From 0d252f34bbbfefcb027a291f2614d51901a20381 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 28 Mar 2024 20:10:51 +0900 Subject: [PATCH 001/122] fix(hesai_hw_interface): add error handling * check PTC command error codes, throw exception if necessary * perform size checks before parsing responses * emit errors on too-large payload size --- .../include/nebula_common/util/expected.hpp | 53 ++ .../hesai_cmd_response.hpp | 401 ++++++------ .../hesai_hw_interface.hpp | 28 +- .../hesai_hw_interface.cpp | 587 +++++++----------- .../hesai/hesai_hw_monitor_ros_wrapper.hpp | 1 + .../hesai/hesai_hw_monitor_ros_wrapper.cpp | 20 +- 6 files changed, 509 insertions(+), 581 deletions(-) create mode 100644 nebula_common/include/nebula_common/util/expected.hpp diff --git a/nebula_common/include/nebula_common/util/expected.hpp b/nebula_common/include/nebula_common/util/expected.hpp new file mode 100644 index 000000000..4fc35b3fa --- /dev/null +++ b/nebula_common/include/nebula_common/util/expected.hpp @@ -0,0 +1,53 @@ +#pragma once + +#include + +namespace nebula +{ +namespace util +{ + +/// @brief A poor man's backport of C++23's std::expected. +/// +/// At any given time, holds exactly one of: expected value, or error value. +/// Provides functions for easy exception handling. +/// +/// More info here: https://en.cppreference.com/w/cpp/utility/expected +/// +/// @tparam T Type of the expected value +/// @tparam E Error type +template +struct expected +{ + bool has_value() { return std::holds_alternative(value_); } + + T value() { return std::get(value_); } + + T value_or(const T & default_) + { + if (has_value()) return value(); + return default_; + } + + T value_or_throw(const std::string & error_msg) { + if (has_value()) return value(); + throw std::runtime_error(error_msg); + } + + E error() { return std::get(value_); } + + E error_or(const E & default_) { + if (!has_value()) return error(); + return default_; + } + + expected(const T & value) { value_ = value; } + + expected(const E & error) { value_ = error; } + +private: + std::variant value_; +}; + +} // namespace util +} // namespace nebula \ No newline at end of file diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp index 21989bf9b..4af74426c 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp @@ -2,18 +2,27 @@ #define HESAI_CMD_RESPONSE_HPP #include +#include #include +#include +#include #include +#include + +using namespace boost::endian; namespace nebula { + +#pragma pack(push, 1) + /// @brief PTP STATUS struct of PTC_COMMAND_PTP_DIAGNOSTICS struct HesaiPtpDiagStatus { - long long master_offset; - int ptp_state; - int elapsed_millisec; + big_int64_buf_t master_offset; + big_int32_buf_t ptp_state; + big_int32_buf_t elapsed_millisec; friend std::ostream & operator<<(std::ostream & os, nebula::HesaiPtpDiagStatus const & arg) { @@ -30,35 +39,20 @@ struct HesaiPtpDiagStatus /// @brief PTP TLV PORT_DATA_SET struct of PTC_COMMAND_PTP_DIAGNOSTICS struct HesaiPtpDiagPort { - std::vector portIdentity = std::vector(10); - int portState; - int logMinDelayReqInterval; - long long peerMeanPathDelay; - int logAnnounceInterval; - int announceReceiptTimeout; - int logSyncInterval; - int delayMechanism; - int logMinPdelayReqInterval; - int versionNumber; - - HesaiPtpDiagPort() {} - HesaiPtpDiagPort(const HesaiPtpDiagPort & arg) - { - std::copy(arg.portIdentity.begin(), arg.portIdentity.end(), portIdentity.begin()); - portState = arg.portState; - logMinDelayReqInterval = arg.logMinDelayReqInterval; - peerMeanPathDelay = arg.peerMeanPathDelay; - logAnnounceInterval = arg.logAnnounceInterval; - announceReceiptTimeout = arg.announceReceiptTimeout; - logSyncInterval = arg.logSyncInterval; - delayMechanism = arg.delayMechanism; - logMinPdelayReqInterval = arg.logMinPdelayReqInterval; - versionNumber = arg.versionNumber; - } + uint8_t portIdentity[10]; + big_int32_buf_t portState; + big_int32_buf_t logMinDelayReqInterval; + big_int64_buf_t peerMeanPathDelay; + big_int32_buf_t logAnnounceInterval; + big_int32_buf_t announceReceiptTimeout; + big_int32_buf_t logSyncInterval; + big_int32_buf_t delayMechanism; + big_int32_buf_t logMinPdelayReqInterval; + big_int32_buf_t versionNumber; friend std::ostream & operator<<(std::ostream & os, nebula::HesaiPtpDiagPort const & arg) { - os << "portIdentity: " << std::string(arg.portIdentity.begin(), arg.portIdentity.end()); + os << "portIdentity: " << std::string(std::begin(arg.portIdentity), std::end(arg.portIdentity)); os << ", "; os << "portState: " << arg.portState; os << ", "; @@ -85,28 +79,14 @@ struct HesaiPtpDiagPort /// @brief LinuxPTP TLV TIME_STATUS_NP struct of PTC_COMMAND_PTP_DIAGNOSTICS struct HesaiPtpDiagTime { - long long master_offset; - long long ingress_time; - int cumulativeScaledRateOffset; - int scaledLastGmPhaseChange; - int gmTimeBaseIndicator; - std::vector lastGmPhaseChange = std::vector(12); - int gmPresent; - long long gmIdentity; - - HesaiPtpDiagTime() {} - HesaiPtpDiagTime(const HesaiPtpDiagTime & arg) - { - master_offset = arg.master_offset; - ingress_time = arg.ingress_time; - cumulativeScaledRateOffset = arg.cumulativeScaledRateOffset; - scaledLastGmPhaseChange = arg.scaledLastGmPhaseChange; - gmTimeBaseIndicator = arg.gmTimeBaseIndicator; - std::copy( - arg.lastGmPhaseChange.begin(), arg.lastGmPhaseChange.end(), lastGmPhaseChange.begin()); - gmPresent = arg.gmPresent; - gmIdentity = arg.gmIdentity; - } + big_int64_buf_t master_offset; + big_int64_buf_t ingress_time; + big_int32_buf_t cumulativeScaledRateOffset; + big_int32_buf_t scaledLastGmPhaseChange; + big_int16_buf_t gmTimeBaseIndicator; + uint8_t lastGmPhaseChange[12]; + big_int32_buf_t gmPresent; + big_int64_buf_t gmIdentity; friend std::ostream & operator<<(std::ostream & os, nebula::HesaiPtpDiagTime const & arg) { @@ -120,8 +100,9 @@ struct HesaiPtpDiagTime os << ", "; os << "gmTimeBaseIndicator: " << arg.gmTimeBaseIndicator; os << ", "; + //FIXME: lastGmPhaseChange is a binary number, displaying it as string is incorrect os << "lastGmPhaseChange: " - << std::string(arg.lastGmPhaseChange.begin(), arg.lastGmPhaseChange.end()); + << std::string(std::begin(arg.lastGmPhaseChange), std::end(arg.lastGmPhaseChange)); os << ", "; os << "gmPresent: " << arg.gmPresent; os << ", "; @@ -134,20 +115,20 @@ struct HesaiPtpDiagTime /// @brief LinuxPTP TLV GRANDMASTER_SETTINGS_NP struct of PTC_COMMAND_PTP_DIAGNOSTICS struct HesaiPtpDiagGrandmaster { - int clockQuality; - int utc_offset; - int time_flags; - int time_source; + big_int32_buf_t clockQuality; + big_int16_buf_t utc_offset; + int8_t time_flags; + int8_t time_source; friend std::ostream & operator<<(std::ostream & os, nebula::HesaiPtpDiagGrandmaster const & arg) { os << "clockQuality: " << arg.clockQuality; os << ", "; - os << "utc_offset: " << arg.utc_offset; + os << "utc_offset: " << static_cast(arg.utc_offset.value()); os << ", "; - os << "time_flags: " << arg.time_flags; + os << "time_flags: " << static_cast(arg.time_flags); os << ", "; - os << "time_source: " << arg.time_source; + os << "time_source: " << static_cast(arg.time_source); return os; } @@ -156,61 +137,45 @@ struct HesaiPtpDiagGrandmaster /// @brief struct of PTC_COMMAND_GET_INVENTORY_INFO struct HesaiInventory { - std::vector sn = std::vector(18); - std::vector date_of_manufacture = std::vector(16); - std::vector mac = std::vector(6); - std::vector sw_ver = std::vector(16); - std::vector hw_ver = std::vector(16); - std::vector control_fw_ver = std::vector(16); - std::vector sensor_fw_ver = std::vector(16); - int angle_offset; - int model; - int motor_type; - int num_of_lines; - std::vector reserved = std::vector(11); - - HesaiInventory() {} - HesaiInventory(const HesaiInventory & arg) - { - std::copy(arg.sn.begin(), arg.sn.end(), sn.begin()); - std::copy( - arg.date_of_manufacture.begin(), arg.date_of_manufacture.end(), date_of_manufacture.begin()); - std::copy(arg.mac.begin(), arg.mac.end(), mac.begin()); - std::copy(arg.sw_ver.begin(), arg.sw_ver.end(), sw_ver.begin()); - std::copy(arg.hw_ver.begin(), arg.hw_ver.end(), hw_ver.begin()); - std::copy(arg.control_fw_ver.begin(), arg.control_fw_ver.end(), control_fw_ver.begin()); - std::copy(arg.sensor_fw_ver.begin(), arg.sensor_fw_ver.end(), sensor_fw_ver.begin()); - angle_offset = arg.angle_offset; - model = arg.model; - motor_type = arg.motor_type; - num_of_lines = arg.num_of_lines; - std::copy(arg.reserved.begin(), arg.reserved.end(), reserved.begin()); - } + uint8_t sn[18]; + uint8_t date_of_manufacture[16]; + uint8_t mac[6]; + uint8_t sw_ver[16]; + uint8_t hw_ver[16]; + uint8_t control_fw_ver[16]; + uint8_t sensor_fw_ver[16]; + big_uint16_buf_t angle_offset; + uint8_t model; + uint8_t motor_type; + uint8_t num_of_lines; + uint8_t reserved[11]; friend std::ostream & operator<<(std::ostream & os, nebula::HesaiInventory const & arg) { - os << "sn: " << std::string(arg.sn.begin(), arg.sn.end()); + os << "sn: " << std::string(std::begin(arg.sn), std::end(arg.sn)); os << ", "; os << "date_of_manufacture: " - << std::string(arg.date_of_manufacture.begin(), arg.date_of_manufacture.end()); + << std::string(std::begin(arg.date_of_manufacture), std::end(arg.date_of_manufacture)); os << ", "; os << "mac: "; - std::stringstream ss; - for (long unsigned int i = 0; i < arg.mac.size() - 1; i++) { - ss << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.mac[i]) & 0xff) - << ":"; + + for (size_t i = 0; i < sizeof(arg.mac); i++) { + if (i != 0) { + os << ':'; + } + os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.mac[i])); } - ss << std::hex << std::setfill('0') << std::setw(2) - << (static_cast(arg.mac[arg.mac.size() - 1]) & 0xff); - os << ss.str(); + os << ", "; - os << "sw_ver: " << std::string(arg.sw_ver.begin(), arg.sw_ver.end()); + os << "sw_ver: " << std::string(std::begin(arg.sw_ver), std::end(arg.sw_ver)); os << ", "; - os << "hw_ver: " << std::string(arg.hw_ver.begin(), arg.hw_ver.end()); + os << "hw_ver: " << std::string(std::begin(arg.hw_ver), std::end(arg.hw_ver)); os << ", "; - os << "control_fw_ver: " << std::string(arg.control_fw_ver.begin(), arg.control_fw_ver.end()); + os << "control_fw_ver: " + << std::string(std::begin(arg.control_fw_ver), std::end(arg.control_fw_ver)); os << ", "; - os << "sensor_fw_ver: " << std::string(arg.sensor_fw_ver.begin(), arg.sensor_fw_ver.end()); + os << "sensor_fw_ver: " + << std::string(std::begin(arg.sensor_fw_ver), std::end(arg.sensor_fw_ver)); os << ", "; os << "angle_offset: " << arg.angle_offset; os << ", "; @@ -220,12 +185,13 @@ struct HesaiInventory os << ", "; os << "num_of_lines: " << arg.num_of_lines; os << ", "; - // os << "reserved: " << boost::algorithm::join(arg.reserved, ","); - os << "reserved: "; - for (long unsigned int i = 0; i < arg.reserved.size() - 1; i++) { - os << arg.reserved[i] << ","; + + for (size_t i = 0; i < sizeof(arg.reserved); i++) { + if (i != 0) { + os << ' '; + } + os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.reserved[i])); } - os << arg.reserved[arg.reserved.size() - 1]; return os; } @@ -258,7 +224,7 @@ struct HesaiInventory case 48: return "PandarAT128"; default: - return "Unknown(" + std::to_string(model) + ")"; + return "Unknown(" + std::to_string(static_cast(model)) + ")"; } } }; @@ -266,42 +232,55 @@ struct HesaiInventory /// @brief struct of PTC_COMMAND_GET_CONFIG_INFO struct HesaiConfig { - int ipaddr[4]; - int mask[4]; - int gateway[4]; - int dest_ipaddr[4]; - int dest_LiDAR_udp_port; - int dest_gps_udp_port; - int spin_rate; - int sync; - int sync_angle; - int start_angle; - int stop_angle; - int clock_source; - int udp_seq; - int trigger_method; - int return_mode; - int standby_mode; - int motor_status; - int vlan_flag; - int vlan_id; - int clock_data_fmt; - int noise_filtering; - int reflectivity_mapping; - unsigned char reserved[6]; + uint8_t ipaddr[4]; + uint8_t mask[4]; + uint8_t gateway[4]; + uint8_t dest_ipaddr[4]; + big_uint16_buf_t dest_LiDAR_udp_port; + big_uint16_buf_t dest_gps_udp_port; + big_uint16_buf_t spin_rate; + uint8_t sync; + big_uint16_buf_t sync_angle; + big_uint16_buf_t start_angle; + big_uint16_buf_t stop_angle; + uint8_t clock_source; + uint8_t udp_seq; + uint8_t trigger_method; + uint8_t return_mode; + uint8_t standby_mode; + uint8_t motor_status; + uint8_t vlan_flag; + big_uint16_buf_t vlan_id; + uint8_t clock_data_fmt; //FIXME: labeled as gps_nmea_sentence in AT128, OT128 datasheets + uint8_t noise_filtering; + uint8_t reflectivity_mapping; + uint8_t reserved[6]; friend std::ostream & operator<<(std::ostream & os, nebula::HesaiConfig const & arg) { - os << "ipaddr: " << arg.ipaddr[0] << "." << arg.ipaddr[1] << "." << arg.ipaddr[2] << "." - << arg.ipaddr[3]; - os << ", "; - os << "mask: " << arg.mask[0] << "." << arg.mask[1] << "." << arg.mask[2] << "." << arg.mask[3]; - os << ", "; - os << "gateway: " << arg.gateway[0] << "." << arg.gateway[1] << "." << arg.gateway[2] << "." - << arg.gateway[3]; - os << ", "; - os << "dest_ipaddr: " << arg.dest_ipaddr[0] << "." << arg.dest_ipaddr[1] << "." - << arg.dest_ipaddr[2] << "." << arg.dest_ipaddr[3]; + os << "ipaddr: " + << static_cast(arg.ipaddr[0]) << "." + << static_cast(arg.ipaddr[1]) << "." + << static_cast(arg.ipaddr[2]) << "." + << static_cast(arg.ipaddr[3]); + os << ", "; + os << "mask: " + << static_cast(arg.mask[0]) << "." + << static_cast(arg.mask[1]) << "." + << static_cast(arg.mask[2]) << "." + << static_cast(arg.mask[3]); + os << ", "; + os << "gateway: " + << static_cast(arg.gateway[0]) << "." + << static_cast(arg.gateway[1]) << "." + << static_cast(arg.gateway[2]) << "." + << static_cast(arg.gateway[3]); + os << ", "; + os << "dest_ipaddr: " + << static_cast(arg.dest_ipaddr[0]) << "." + << static_cast(arg.dest_ipaddr[1]) << "." + << static_cast(arg.dest_ipaddr[2]) << "." + << static_cast(arg.dest_ipaddr[3]); os << ", "; os << "dest_LiDAR_udp_port: " << arg.dest_LiDAR_udp_port; os << ", "; @@ -339,8 +318,14 @@ struct HesaiConfig os << ", "; os << "reflectivity_mapping: " << arg.reflectivity_mapping; os << ", "; - os << "reserved: " << arg.reserved[0] << "," << arg.reserved[1] << "," << arg.reserved[2] << "," - << arg.reserved[3] << "," << arg.reserved[4] << "," << arg.reserved[5]; + os << "reserved: "; + + for (size_t i = 0; i < sizeof(arg.reserved); i++) { + if (i != 0) { + os << ' '; + } + os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.reserved[i])); + } return os; } @@ -349,30 +334,15 @@ struct HesaiConfig /// @brief struct of PTC_COMMAND_GET_LIDAR_STATUS struct HesaiLidarStatus { - int system_uptime; - int motor_speed; - // int temperature[8]; - std::vector temperature = std::vector(8); - int gps_pps_lock; - int gps_gprmc_status; - int startup_times; - int total_operation_time; - int ptp_clock_status; - std::vector reserved = std::vector(5); - - HesaiLidarStatus() {} - HesaiLidarStatus(const HesaiLidarStatus & arg) - { - system_uptime = arg.system_uptime; - motor_speed = arg.motor_speed; - std::copy(arg.temperature.begin(), arg.temperature.end(), temperature.begin()); - gps_pps_lock = arg.gps_pps_lock; - gps_gprmc_status = arg.gps_gprmc_status; - startup_times = arg.startup_times; - total_operation_time = arg.total_operation_time; - ptp_clock_status = arg.ptp_clock_status; - std::copy(arg.reserved.begin(), arg.reserved.end(), reserved.begin()); - } + big_uint32_buf_t system_uptime; + big_uint16_buf_t motor_speed; + big_int32_buf_t temperature[8]; + uint8_t gps_pps_lock; + uint8_t gps_gprmc_status; + big_uint32_buf_t startup_times; + big_uint32_buf_t total_operation_time; + uint8_t ptp_clock_status; + uint8_t reserved[5]; // FIXME: 4 bytes labeled as humidity in OT128 datasheet friend std::ostream & operator<<(std::ostream & os, nebula::HesaiLidarStatus const & arg) { @@ -381,26 +351,33 @@ struct HesaiLidarStatus os << "motor_speed: " << arg.motor_speed; os << ", "; os << "temperature: "; - for (long unsigned int i = 0; i < arg.temperature.size() - 1; i++) { - os << arg.temperature[i] << ","; + + for (size_t i = 0; i < sizeof(arg.temperature); i++) { + if (i != 0) { + os << ','; + } + os << arg.temperature[i]; } - os << arg.temperature[arg.temperature.size() - 1]; + os << ", "; - os << "gps_pps_lock: " << arg.gps_pps_lock; + os << "gps_pps_lock: " << static_cast(arg.gps_pps_lock); os << ", "; - os << "gps_gprmc_status: " << arg.gps_gprmc_status; + os << "gps_gprmc_status: " << static_cast(arg.gps_gprmc_status); os << ", "; os << "startup_times: " << arg.startup_times; os << ", "; os << "total_operation_time: " << arg.total_operation_time; os << ", "; - os << "ptp_clock_status: " << arg.ptp_clock_status; + os << "ptp_clock_status: " << static_cast(arg.ptp_clock_status); os << ", "; os << "reserved: "; - for (long unsigned int i = 0; i < arg.reserved.size() - 1; i++) { - os << arg.reserved[i] << ","; + + for (size_t i = 0; i < sizeof(arg.reserved); i++) { + if (i != 0) { + os << ' '; + } + os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.reserved[i])); } - os << arg.reserved[arg.reserved.size() - 1]; return os; } @@ -410,13 +387,10 @@ struct HesaiLidarStatus switch (gps_pps_lock) { case 1: return "Lock"; - break; case 0: return "Unlock"; - break; default: return "Unknown"; - break; } } std::string get_str_gps_gprmc_status() @@ -424,13 +398,10 @@ struct HesaiLidarStatus switch (gps_gprmc_status) { case 1: return "Lock"; - break; case 0: return "Unlock"; - break; default: return "Unknown"; - break; } } std::string get_str_ptp_clock_status() @@ -438,19 +409,14 @@ struct HesaiLidarStatus switch (ptp_clock_status) { case 0: return "free run"; - break; case 1: return "tracking"; - break; case 2: return "locked"; - break; case 3: return "frozen"; - break; default: return "Unknown"; - break; } } }; @@ -458,17 +424,17 @@ struct HesaiLidarStatus /// @brief struct of PTC_COMMAND_GET_LIDAR_RANGE struct HesaiLidarRangeAll { - int method; - int start; - int end; + uint8_t method; + big_uint16_buf_t start; + big_uint16_buf_t end; friend std::ostream & operator<<(std::ostream & os, nebula::HesaiLidarRangeAll const & arg) { - os << "method: " << arg.method; + os << "method: " << static_cast(arg.method); os << ", "; - os << "start: " << arg.start; + os << "start: " << static_cast(arg.start.value()); os << ", "; - os << "end: " << arg.end; + os << "end: " << static_cast(arg.end.value()); return os; } @@ -477,30 +443,31 @@ struct HesaiLidarRangeAll /// @brief struct of PTC_COMMAND_GET_PTP_CONFIG struct HesaiPtpConfig { - int status; - int profile; - int domain; - int network; - int logAnnounceInterval; - int logSyncInterval; - int logMinDelayReqInterval; + int8_t status; + int8_t profile; + int8_t domain; + int8_t network; + int8_t logAnnounceInterval; + int8_t logSyncInterval; + int8_t logMinDelayReqInterval; + //FIXME: this format is not correct for OT128, or for AT128 on 802.1AS friend std::ostream & operator<<(std::ostream & os, nebula::HesaiPtpConfig const & arg) { - os << "status: " << arg.status; + os << "status: " << static_cast(arg.status); os << ", "; - os << "profile: " << arg.profile; + os << "profile: " << static_cast(arg.profile); os << ", "; - os << "domain: " << arg.domain; + os << "domain: " << static_cast(arg.domain); os << ", "; - os << "network: " << arg.network; + os << "network: " << static_cast(arg.network); if (arg.status == 0) { os << ", "; - os << "logAnnounceInterval: " << arg.logAnnounceInterval; + os << "logAnnounceInterval: " << static_cast(arg.logAnnounceInterval); os << ", "; - os << "logSyncInterval: " << arg.logSyncInterval; + os << "logSyncInterval: " << static_cast(arg.logSyncInterval); os << ", "; - os << "logMinDelayReqInterval: " << arg.logMinDelayReqInterval; + os << "logMinDelayReqInterval: " << static_cast(arg.logMinDelayReqInterval); } return os; } @@ -509,10 +476,11 @@ struct HesaiPtpConfig /// @brief struct of PTC_COMMAND_LIDAR_MONITOR struct HesaiLidarMonitor { - int input_voltage; - int input_current; - int input_power; - std::vector reserved = std::vector(52); + //FIXME: this format is not correct for OT128 + big_int32_buf_t input_voltage; + big_int32_buf_t input_current; + big_int32_buf_t input_power; + uint8_t reserved[52]; friend std::ostream & operator<<(std::ostream & os, nebula::HesaiLidarMonitor const & arg) { @@ -523,14 +491,19 @@ struct HesaiLidarMonitor os << "input_power: " << arg.input_power; os << ", "; os << "reserved: "; - for (long unsigned int i = 0; i < arg.reserved.size() - 1; i++) { - os << arg.reserved[i] << ","; + + for (size_t i = 0; i < sizeof(arg.reserved); i++) { + if (i != 0) { + os << ' '; + } + os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.reserved[i])); } - os << arg.reserved[arg.reserved.size() - 1]; return os; } }; +#pragma pack(pop) + } // namespace nebula #endif // HESAI_CMD_RESPONSE_HPP diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index 2f5639373..c60107ab2 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -15,6 +15,7 @@ #include "boost_udp_driver/udp_driver.hpp" #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/hesai/hesai_status.hpp" +#include "nebula_common/util/expected.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp" @@ -29,6 +30,7 @@ #include #include +#include namespace nebula { @@ -63,6 +65,20 @@ const uint8_t PTC_COMMAND_RESET = 0x25; const uint8_t PTC_COMMAND_SET_ROTATE_DIRECTION = 0x2a; const uint8_t PTC_COMMAND_LIDAR_MONITOR = 0x27; +const uint8_t PTC_ERROR_CODE_NO_ERROR = 0x00; +const uint8_t PTC_ERROR_CODE_INVALID_INPUT_PARAM = 0x01; +const uint8_t PTC_ERROR_CODE_SERVER_CONN_FAILED = 0x02; +const uint8_t PTC_ERROR_CODE_INVALID_DATA = 0x03; +const uint8_t PTC_ERROR_CODE_OUT_OF_MEMORY = 0x04; +const uint8_t PTC_ERROR_CODE_UNSUPPORTED_CMD = 0x05; +const uint8_t PTC_ERROR_CODE_FPGA_COMM_FAILED = 0x06; +const uint8_t PTC_ERROR_CODE_OTHER = 0x07; + +const uint8_t TCP_ERROR_UNRELATED_RESPONSE = 1; +const uint8_t TCP_ERROR_UNEXPECTED_PAYLOAD = 2; +const uint8_t TCP_ERROR_TIMEOUT = 4; +const uint8_t TCP_ERROR_INCOMPLETE_RESPONSE = 8; + const uint16_t PANDARQT64_PACKET_SIZE = 1072; const uint16_t PANDARQT128_PACKET_SIZE = 1127; const uint16_t PANDARXT32_PACKET_SIZE = 1080; @@ -74,7 +90,6 @@ const uint16_t PANDAR40_PACKET_SIZE = 1262; const uint16_t PANDAR40P_EXTENDED_PACKET_SIZE = 1266; const uint16_t PANDAR128_E4X_PACKET_SIZE = 861; const uint16_t PANDAR128_E4X_EXTENDED_PACKET_SIZE = 1117; - const uint16_t MTU_SIZE = 1500; // Time interval between Announce messages, in units of log seconds (default: 1) @@ -87,10 +102,13 @@ const int PTP_LOG_MIN_DELAY_INTERVAL = 0; const int HESAI_LIDAR_GPS_CLOCK_SOURCE = 0; const int HESAI_LIDAR_PTP_CLOCK_SOURCE = 1; + /// @brief Hardware interface of hesai driver class HesaiHwInterface : NebulaHwInterfaceBase { private: + typedef nebula::util::expected, uint32_t> ptc_cmd_result_t; + std::unique_ptr<::drivers::common::IoContext> cloud_io_context_; std::shared_ptr m_owned_ctx; std::unique_ptr<::drivers::udp_driver::UdpDriver> cloud_udp_driver_; @@ -141,12 +159,18 @@ class HesaiHwInterface : NebulaHwInterfaceBase /// @param bytes Target byte vector void PrintDebug(const std::vector & bytes); + /// @brief Convert an error code to a human-readable string + /// @param error_code The error code (lowest byte is Hesai PTC error code, higher bytes nebula flags) + /// such as TCP_ERROR_UNRELATED_RESPONSE etc. + /// @return A string description of all errors in this code + std::string PrettyPrintPTCError(uint32_t error_code); + /// @brief Send a PTC request with an optional payload, and return the full response payload. /// Blocking. /// @param command_id PTC command number. /// @param payload Payload bytes of the PTC command. Not including the 8-byte PTC header. /// @return The returned payload, if successful, or nullptr. - std::shared_ptr> SendReceive( + ptc_cmd_result_t SendReceive( const uint8_t command_id, const std::vector & payload = {}); public: diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index a5e5bd068..3d068173f 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -48,7 +48,7 @@ HesaiHwInterface::~HesaiHwInterface() #endif } -std::shared_ptr> HesaiHwInterface::SendReceive( +HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( const uint8_t command_id, const std::vector & payload) { uint32_t len = payload.size(); @@ -64,8 +64,12 @@ std::shared_ptr> HesaiHwInterface::SendReceive( send_buf.emplace_back(len & 0xff); send_buf.insert(send_buf.end(), payload.begin(), payload.end()); + // These are shared_ptrs so that in case of request timeout, the callback (if ever called) can access valid memory auto recv_buf = std::make_shared>(); - bool success = false; + auto response_complete = std::make_shared(false); + + // Low byte is for PTC error code, the rest is nebula-specific + auto error_code = std::make_shared(0); std::stringstream ss; ss << "0x" << std::setfill('0') << std::setw(2) << std::hex << static_cast(command_id) << " (" << len << ") "; @@ -84,23 +88,32 @@ std::shared_ptr> HesaiHwInterface::SendReceive( PrintDebug(log_tag + "Sending payload"); tcp_driver_->asyncSendReceiveHeaderPayload( send_buf, - [this, log_tag, &success](const std::vector & header_bytes) { + [this, log_tag, command_id, response_complete, error_code](const std::vector & header_bytes) { size_t payload_len = (header_bytes[4] << 24) | (header_bytes[5] << 16) | (header_bytes[6] << 8) | header_bytes[7]; PrintDebug(log_tag + "Received header (expecting " + std::to_string(payload_len) + "B payload)"); - if (payload_len == 0) { success = true; } + // If command_id in the response does not match, we got a response for another command (or rubbish), probably as a + // result of too many simultaneous TCP connections to the sensor (e.g. from GUI, Web UI, another nebula instance, etc.) + if (header_bytes[2] != command_id) { + *error_code = (TCP_ERROR_UNRELATED_RESPONSE << 8); + } + *error_code |= header_bytes[3]; + if (payload_len == 0) { + *response_complete = true; + } }, - [this, log_tag, &recv_buf, &success](const std::vector & payload_bytes) { + [this, log_tag, recv_buf, response_complete, error_code](const std::vector & payload_bytes) { PrintDebug(log_tag + "Received payload"); // Header had payload length 0 (thus, header callback processed request successfully already), // but we still received a payload: invalid state - if (success == true) { - throw std::runtime_error("Received payload despite payload length 0 in header"); + if (*response_complete == true) { + *error_code |= (TCP_ERROR_UNEXPECTED_PAYLOAD << 8); + return; } // Skip 8 header bytes recv_buf->insert(recv_buf->end(), std::next(payload_bytes.begin(), 8), payload_bytes.end()); - success = true; + *response_complete = true; }, [this, log_tag, &tm]() { PrintDebug(log_tag + "Unlocking mutex"); @@ -110,16 +123,19 @@ std::shared_ptr> HesaiHwInterface::SendReceive( this->IOContextRun(); if (!tm.try_lock_for(std::chrono::seconds(1))) { PrintError(log_tag + "Request did not finish within 1s"); - return nullptr; + *error_code |= (TCP_ERROR_TIMEOUT << 8); + return *error_code; } - if (!success) { + if (!response_complete) { PrintError(log_tag + "Did not receive response"); - return nullptr; + *error_code |= (TCP_ERROR_INCOMPLETE_RESPONSE << 8); + return *error_code; } PrintDebug(log_tag + "Received response"); - return recv_buf; + + return *recv_buf; } Status HesaiHwInterface::SetSensorConfiguration( @@ -344,50 +360,29 @@ boost::property_tree::ptree HesaiHwInterface::ParseJson(const std::string & str) std::vector HesaiHwInterface::GetLidarCalibrationBytes() { - auto response_ptr = SendReceive(PTC_COMMAND_GET_LIDAR_CALIBRATION); - return std::vector(*response_ptr); + auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_CALIBRATION); + return response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); } std::string HesaiHwInterface::GetLidarCalibrationString() { - auto response_ptr = SendReceive(PTC_COMMAND_GET_LIDAR_CALIBRATION); - std::string calib_string(response_ptr->begin(), response_ptr->end()); + auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_CALIBRATION); + auto calib_data = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + std::string calib_string(calib_data.begin(), calib_data.end()); return calib_string; } HesaiPtpDiagStatus HesaiHwInterface::GetPtpDiagStatus() { - auto response_ptr = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_STATUS}); - auto & response = *response_ptr; - - HesaiPtpDiagStatus hesai_ptp_diag_status{}; - int payload_pos = 0; - hesai_ptp_diag_status.master_offset = static_cast(response[payload_pos++]) << 56; - hesai_ptp_diag_status.master_offset = - hesai_ptp_diag_status.master_offset | static_cast(response[payload_pos++]) << 48; - hesai_ptp_diag_status.master_offset = - hesai_ptp_diag_status.master_offset | static_cast(response[payload_pos++]) << 40; - hesai_ptp_diag_status.master_offset = - hesai_ptp_diag_status.master_offset | static_cast(response[payload_pos++]) << 32; - hesai_ptp_diag_status.master_offset = - hesai_ptp_diag_status.master_offset | static_cast(response[payload_pos++]) << 24; - hesai_ptp_diag_status.master_offset = - hesai_ptp_diag_status.master_offset | static_cast(response[payload_pos++]) << 16; - hesai_ptp_diag_status.master_offset = - hesai_ptp_diag_status.master_offset | static_cast(response[payload_pos++]) << 8; - hesai_ptp_diag_status.master_offset = - hesai_ptp_diag_status.master_offset | static_cast(response[payload_pos++]); - hesai_ptp_diag_status.ptp_state = response[payload_pos++] << 24; - hesai_ptp_diag_status.ptp_state = hesai_ptp_diag_status.ptp_state | response[payload_pos++] << 16; - hesai_ptp_diag_status.ptp_state = hesai_ptp_diag_status.ptp_state | response[payload_pos++] << 8; - hesai_ptp_diag_status.ptp_state = hesai_ptp_diag_status.ptp_state | response[payload_pos++]; - hesai_ptp_diag_status.elapsed_millisec = response[payload_pos++] << 24; - hesai_ptp_diag_status.elapsed_millisec = - hesai_ptp_diag_status.elapsed_millisec | response[payload_pos++] << 16; - hesai_ptp_diag_status.elapsed_millisec = - hesai_ptp_diag_status.elapsed_millisec | response[payload_pos++] << 8; - hesai_ptp_diag_status.elapsed_millisec = - hesai_ptp_diag_status.elapsed_millisec | response[payload_pos++]; + auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_STATUS}); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + + if (response.size() != sizeof(HesaiPtpDiagStatus)) { + throw std::runtime_error("Unexpected payload size"); + } + + HesaiPtpDiagStatus hesai_ptp_diag_status; + memcpy(&hesai_ptp_diag_status, response.data(), sizeof(HesaiPtpDiagStatus)); std::stringstream ss; ss << "HesaiHwInterface::GetPtpDiagStatus: " << hesai_ptp_diag_status; @@ -398,38 +393,14 @@ HesaiPtpDiagStatus HesaiHwInterface::GetPtpDiagStatus() HesaiPtpDiagPort HesaiHwInterface::GetPtpDiagPort() { - auto response_ptr = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_PORT_DATA_SET}); - auto & response = *response_ptr; - - HesaiPtpDiagPort hesai_ptp_diag_port; - int payload_pos = 0; + auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_PORT_DATA_SET}); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); - for (size_t i = 0; i < hesai_ptp_diag_port.portIdentity.size(); i++) { - hesai_ptp_diag_port.portIdentity[i] = response[payload_pos++]; + if (response.size() != sizeof(HesaiPtpDiagPort)) { + throw std::runtime_error("Unexpected payload size"); } - hesai_ptp_diag_port.portState = static_cast(response[payload_pos++]); - hesai_ptp_diag_port.logMinDelayReqInterval = static_cast(response[payload_pos++]); - hesai_ptp_diag_port.peerMeanPathDelay = static_cast(response[payload_pos++]) << 56; - hesai_ptp_diag_port.peerMeanPathDelay = - hesai_ptp_diag_port.peerMeanPathDelay | static_cast(response[payload_pos++]) << 48; - hesai_ptp_diag_port.peerMeanPathDelay = - hesai_ptp_diag_port.peerMeanPathDelay | static_cast(response[payload_pos++]) << 40; - hesai_ptp_diag_port.peerMeanPathDelay = - hesai_ptp_diag_port.peerMeanPathDelay | static_cast(response[payload_pos++]) << 32; - hesai_ptp_diag_port.peerMeanPathDelay = - hesai_ptp_diag_port.peerMeanPathDelay | static_cast(response[payload_pos++]) << 24; - hesai_ptp_diag_port.peerMeanPathDelay = - hesai_ptp_diag_port.peerMeanPathDelay | static_cast(response[payload_pos++]) << 16; - hesai_ptp_diag_port.peerMeanPathDelay = - hesai_ptp_diag_port.peerMeanPathDelay | static_cast(response[payload_pos++]) << 8; - hesai_ptp_diag_port.peerMeanPathDelay = - hesai_ptp_diag_port.peerMeanPathDelay | static_cast(response[payload_pos++]); - hesai_ptp_diag_port.logAnnounceInterval = static_cast(response[payload_pos++]); - hesai_ptp_diag_port.announceReceiptTimeout = static_cast(response[payload_pos++]); - hesai_ptp_diag_port.logSyncInterval = static_cast(response[payload_pos++]); - hesai_ptp_diag_port.delayMechanism = static_cast(response[payload_pos++]); - hesai_ptp_diag_port.logMinPdelayReqInterval = static_cast(response[payload_pos++]); - hesai_ptp_diag_port.versionNumber = static_cast(response[payload_pos++]); + HesaiPtpDiagPort hesai_ptp_diag_port; + memcpy(&hesai_ptp_diag_port, response.data(), sizeof(HesaiPtpDiagPort)); std::stringstream ss; ss << "HesaiHwInterface::GetPtpDiagPort: " << hesai_ptp_diag_port; @@ -440,80 +411,15 @@ HesaiPtpDiagPort HesaiHwInterface::GetPtpDiagPort() HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() { - auto response_ptr = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_TIME_STATUS_NP}); - auto & response = *response_ptr; + auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_TIME_STATUS_NP}); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); - HesaiPtpDiagTime hesai_ptp_diag_time; - int payload_pos = 0; - hesai_ptp_diag_time.master_offset = static_cast(response[payload_pos++]) << 56; - hesai_ptp_diag_time.master_offset = - hesai_ptp_diag_time.master_offset | static_cast(response[payload_pos++]) << 48; - hesai_ptp_diag_time.master_offset = - hesai_ptp_diag_time.master_offset | static_cast(response[payload_pos++]) << 40; - hesai_ptp_diag_time.master_offset = - hesai_ptp_diag_time.master_offset | static_cast(response[payload_pos++]) << 32; - hesai_ptp_diag_time.master_offset = - hesai_ptp_diag_time.master_offset | static_cast(response[payload_pos++]) << 24; - hesai_ptp_diag_time.master_offset = - hesai_ptp_diag_time.master_offset | static_cast(response[payload_pos++]) << 16; - hesai_ptp_diag_time.master_offset = - hesai_ptp_diag_time.master_offset | static_cast(response[payload_pos++]) << 8; - hesai_ptp_diag_time.master_offset = - hesai_ptp_diag_time.master_offset | static_cast(response[payload_pos++]); - hesai_ptp_diag_time.ingress_time = static_cast(response[payload_pos++]) << 56; - hesai_ptp_diag_time.ingress_time = - hesai_ptp_diag_time.ingress_time | static_cast(response[payload_pos++]) << 48; - hesai_ptp_diag_time.ingress_time = - hesai_ptp_diag_time.ingress_time | static_cast(response[payload_pos++]) << 40; - hesai_ptp_diag_time.ingress_time = - hesai_ptp_diag_time.ingress_time | static_cast(response[payload_pos++]) << 32; - hesai_ptp_diag_time.ingress_time = - hesai_ptp_diag_time.ingress_time | static_cast(response[payload_pos++]) << 24; - hesai_ptp_diag_time.ingress_time = - hesai_ptp_diag_time.ingress_time | static_cast(response[payload_pos++]) << 16; - hesai_ptp_diag_time.ingress_time = - hesai_ptp_diag_time.ingress_time | static_cast(response[payload_pos++]) << 8; - hesai_ptp_diag_time.ingress_time = - hesai_ptp_diag_time.ingress_time | static_cast(response[payload_pos++]); - hesai_ptp_diag_time.cumulativeScaledRateOffset = response[payload_pos++] << 24; - hesai_ptp_diag_time.cumulativeScaledRateOffset = - hesai_ptp_diag_time.cumulativeScaledRateOffset | response[payload_pos++] << 16; - hesai_ptp_diag_time.cumulativeScaledRateOffset = - hesai_ptp_diag_time.cumulativeScaledRateOffset | response[payload_pos++] << 8; - hesai_ptp_diag_time.cumulativeScaledRateOffset = - hesai_ptp_diag_time.cumulativeScaledRateOffset | response[payload_pos++]; - hesai_ptp_diag_time.scaledLastGmPhaseChange = response[payload_pos++] << 24; - hesai_ptp_diag_time.scaledLastGmPhaseChange = - hesai_ptp_diag_time.scaledLastGmPhaseChange | response[payload_pos++] << 16; - hesai_ptp_diag_time.scaledLastGmPhaseChange = - hesai_ptp_diag_time.scaledLastGmPhaseChange | response[payload_pos++] << 8; - hesai_ptp_diag_time.scaledLastGmPhaseChange = - hesai_ptp_diag_time.scaledLastGmPhaseChange | response[payload_pos++]; - hesai_ptp_diag_time.gmTimeBaseIndicator = response[payload_pos++] << 8; - hesai_ptp_diag_time.gmTimeBaseIndicator = - hesai_ptp_diag_time.gmTimeBaseIndicator | response[payload_pos++]; - for (size_t i = 0; i < hesai_ptp_diag_time.lastGmPhaseChange.size(); i++) { - hesai_ptp_diag_time.lastGmPhaseChange[i] = response[payload_pos++]; + if (response.size() != sizeof(HesaiPtpDiagTime)) { + throw std::runtime_error("Unexpected payload size"); } - hesai_ptp_diag_time.gmPresent = response[payload_pos++] << 24; - hesai_ptp_diag_time.gmPresent = hesai_ptp_diag_time.gmPresent | response[payload_pos++] << 16; - hesai_ptp_diag_time.gmPresent = hesai_ptp_diag_time.gmPresent | response[payload_pos++] << 8; - hesai_ptp_diag_time.gmPresent = hesai_ptp_diag_time.gmPresent | response[payload_pos++]; - hesai_ptp_diag_time.gmIdentity = static_cast(response[payload_pos++]) << 56; - hesai_ptp_diag_time.gmIdentity = - hesai_ptp_diag_time.gmIdentity | static_cast(response[payload_pos++]) << 48; - hesai_ptp_diag_time.gmIdentity = - hesai_ptp_diag_time.gmIdentity | static_cast(response[payload_pos++]) << 40; - hesai_ptp_diag_time.gmIdentity = - hesai_ptp_diag_time.gmIdentity | static_cast(response[payload_pos++]) << 32; - hesai_ptp_diag_time.gmIdentity = - hesai_ptp_diag_time.gmIdentity | static_cast(response[payload_pos++]) << 24; - hesai_ptp_diag_time.gmIdentity = - hesai_ptp_diag_time.gmIdentity | static_cast(response[payload_pos++]) << 16; - hesai_ptp_diag_time.gmIdentity = - hesai_ptp_diag_time.gmIdentity | static_cast(response[payload_pos++]) << 8; - hesai_ptp_diag_time.gmIdentity = - hesai_ptp_diag_time.gmIdentity | static_cast(response[payload_pos++]); + + HesaiPtpDiagTime hesai_ptp_diag_time; + memcpy(&hesai_ptp_diag_time, response.data(), sizeof(HesaiPtpDiagTime)); std::stringstream ss; ss << "HesaiHwInterface::GetPtpDiagTime: " << hesai_ptp_diag_time; @@ -524,25 +430,15 @@ HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() { - auto response_ptr = - SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); - auto & response = *response_ptr; + auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + + if (response.size() != sizeof(HesaiPtpDiagGrandmaster)) { + throw std::runtime_error("Unexpected payload size"); + } HesaiPtpDiagGrandmaster hesai_ptp_diag_grandmaster; - int payload_pos = 0; - - hesai_ptp_diag_grandmaster.clockQuality = response[payload_pos++] << 24; - hesai_ptp_diag_grandmaster.clockQuality = - hesai_ptp_diag_grandmaster.clockQuality | response[payload_pos++] << 16; - hesai_ptp_diag_grandmaster.clockQuality = - hesai_ptp_diag_grandmaster.clockQuality | response[payload_pos++] << 8; - hesai_ptp_diag_grandmaster.clockQuality = - hesai_ptp_diag_grandmaster.clockQuality | response[payload_pos++]; - hesai_ptp_diag_grandmaster.utc_offset = response[payload_pos++] << 8; - hesai_ptp_diag_grandmaster.utc_offset = - hesai_ptp_diag_grandmaster.utc_offset | response[payload_pos++]; - hesai_ptp_diag_grandmaster.time_flags = static_cast(response[payload_pos++]); - hesai_ptp_diag_grandmaster.time_source = static_cast(response[payload_pos++]); + memcpy(&hesai_ptp_diag_grandmaster, response.data(), sizeof(HesaiPtpDiagGrandmaster)); std::stringstream ss; ss << "HesaiHwInterface::GetPtpDiagGrandmaster: " << hesai_ptp_diag_grandmaster; @@ -553,98 +449,32 @@ HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() HesaiInventory HesaiHwInterface::GetInventory() { - auto response_ptr = SendReceive(PTC_COMMAND_GET_INVENTORY_INFO); - auto & response = *response_ptr; + auto response_or_err = SendReceive(PTC_COMMAND_GET_INVENTORY_INFO); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); - HesaiInventory hesai_inventory; - int payload_pos = 0; - for (size_t i = 0; i < hesai_inventory.sn.size(); i++) { - hesai_inventory.sn[i] = response[payload_pos++]; - } - for (size_t i = 0; i < hesai_inventory.date_of_manufacture.size(); i++) { - hesai_inventory.date_of_manufacture[i] = response[payload_pos++]; - } - for (size_t i = 0; i < hesai_inventory.mac.size(); i++) { - hesai_inventory.mac[i] = response[payload_pos++]; - } - for (size_t i = 0; i < hesai_inventory.sw_ver.size(); i++) { - hesai_inventory.sw_ver[i] = response[payload_pos++]; - } - for (size_t i = 0; i < hesai_inventory.hw_ver.size(); i++) { - hesai_inventory.hw_ver[i] = response[payload_pos++]; - } - for (size_t i = 0; i < hesai_inventory.control_fw_ver.size(); i++) { - hesai_inventory.control_fw_ver[i] = response[payload_pos++]; - } - for (size_t i = 0; i < hesai_inventory.sensor_fw_ver.size(); i++) { - hesai_inventory.sensor_fw_ver[i] = response[payload_pos++]; - } - hesai_inventory.angle_offset = response[payload_pos++] << 8; - hesai_inventory.angle_offset = hesai_inventory.angle_offset | response[payload_pos++]; - hesai_inventory.model = static_cast(response[payload_pos++]); - hesai_inventory.motor_type = static_cast(response[payload_pos++]); - hesai_inventory.num_of_lines = static_cast(response[payload_pos++]); - for (size_t i = 0; i < hesai_inventory.reserved.size(); i++) { - hesai_inventory.reserved[i] = static_cast(response[payload_pos++]); + if (response.size() < sizeof(HesaiInventory)) { + throw std::runtime_error("Unexpected payload size"); + } else if (response.size() > sizeof(HesaiInventory)) { + PrintError("HesaiInventory from Sensor has unknown format. Will parse anyway."); } + HesaiInventory hesai_inventory; + memcpy(&hesai_inventory, response.data(), sizeof(HesaiInventory)); + return hesai_inventory; } HesaiConfig HesaiHwInterface::GetConfig() { - auto response_ptr = SendReceive(PTC_COMMAND_GET_CONFIG_INFO); - auto & response = *response_ptr; - - HesaiConfig hesai_config{}; - int payload_pos = 0; - hesai_config.ipaddr[0] = static_cast(response[payload_pos++]); - hesai_config.ipaddr[1] = static_cast(response[payload_pos++]); - hesai_config.ipaddr[2] = static_cast(response[payload_pos++]); - hesai_config.ipaddr[3] = static_cast(response[payload_pos++]); - hesai_config.mask[0] = static_cast(response[payload_pos++]); - hesai_config.mask[1] = static_cast(response[payload_pos++]); - hesai_config.mask[2] = static_cast(response[payload_pos++]); - hesai_config.mask[3] = static_cast(response[payload_pos++]); - hesai_config.gateway[0] = static_cast(response[payload_pos++]); - hesai_config.gateway[1] = static_cast(response[payload_pos++]); - hesai_config.gateway[2] = static_cast(response[payload_pos++]); - hesai_config.gateway[3] = static_cast(response[payload_pos++]); - hesai_config.dest_ipaddr[0] = static_cast(response[payload_pos++]); - hesai_config.dest_ipaddr[1] = static_cast(response[payload_pos++]); - hesai_config.dest_ipaddr[2] = static_cast(response[payload_pos++]); - hesai_config.dest_ipaddr[3] = static_cast(response[payload_pos++]); - hesai_config.dest_LiDAR_udp_port = response[payload_pos++] << 8; - hesai_config.dest_LiDAR_udp_port = hesai_config.dest_LiDAR_udp_port | response[payload_pos++]; - hesai_config.dest_gps_udp_port = response[payload_pos++] << 8; - hesai_config.dest_gps_udp_port = hesai_config.dest_gps_udp_port | response[payload_pos++]; - hesai_config.spin_rate = response[payload_pos++] << 8; - hesai_config.spin_rate = hesai_config.spin_rate | response[payload_pos++]; - hesai_config.sync = static_cast(response[payload_pos++]); - hesai_config.sync_angle = response[payload_pos++] << 8; - hesai_config.sync_angle = hesai_config.sync_angle | response[payload_pos++]; - hesai_config.start_angle = response[payload_pos++] << 8; - hesai_config.start_angle = hesai_config.start_angle | response[payload_pos++]; - hesai_config.stop_angle = response[payload_pos++] << 8; - hesai_config.stop_angle = hesai_config.stop_angle | response[payload_pos++]; - hesai_config.clock_source = static_cast(response[payload_pos++]); - hesai_config.udp_seq = static_cast(response[payload_pos++]); - hesai_config.trigger_method = static_cast(response[payload_pos++]); - hesai_config.return_mode = static_cast(response[payload_pos++]); - hesai_config.standby_mode = static_cast(response[payload_pos++]); - hesai_config.motor_status = static_cast(response[payload_pos++]); - hesai_config.vlan_flag = static_cast(response[payload_pos++]); - hesai_config.vlan_id = response[payload_pos++] << 8; - hesai_config.vlan_id = hesai_config.vlan_id | response[payload_pos++]; - hesai_config.clock_data_fmt = static_cast(response[payload_pos++]); - hesai_config.noise_filtering = static_cast(response[payload_pos++]); - hesai_config.reflectivity_mapping = static_cast(response[payload_pos++]); - hesai_config.reserved[0] = static_cast(response[payload_pos++]); - hesai_config.reserved[1] = static_cast(response[payload_pos++]); - hesai_config.reserved[2] = static_cast(response[payload_pos++]); - hesai_config.reserved[3] = static_cast(response[payload_pos++]); - hesai_config.reserved[4] = static_cast(response[payload_pos++]); - hesai_config.reserved[5] = static_cast(response[payload_pos++]); + auto response_or_err = SendReceive(PTC_COMMAND_GET_CONFIG_INFO); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + + if (response.size() != sizeof(HesaiConfig)) { + throw std::runtime_error("Unexpected payload size"); + } + + HesaiConfig hesai_config; + memcpy(&hesai_config, response.data(), sizeof(HesaiConfig)); std::cout << "Config: " << hesai_config << std::endl; return hesai_config; @@ -652,40 +482,16 @@ HesaiConfig HesaiHwInterface::GetConfig() HesaiLidarStatus HesaiHwInterface::GetLidarStatus() { - auto response_ptr = SendReceive(PTC_COMMAND_GET_LIDAR_STATUS); - auto & response = *response_ptr; + auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_STATUS); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); - HesaiLidarStatus hesai_status; - int payload_pos = 0; - hesai_status.system_uptime = response[payload_pos++] << 24; - hesai_status.system_uptime = hesai_status.system_uptime | response[payload_pos++] << 16; - hesai_status.system_uptime = hesai_status.system_uptime | response[payload_pos++] << 8; - hesai_status.system_uptime = hesai_status.system_uptime | response[payload_pos++]; - hesai_status.motor_speed = response[payload_pos++] << 8; - hesai_status.motor_speed = hesai_status.motor_speed | response[payload_pos++]; - for (size_t i = 0; i < hesai_status.temperature.size(); i++) { - hesai_status.temperature[i] = response[payload_pos++] << 24; - hesai_status.temperature[i] = hesai_status.temperature[i] | response[payload_pos++] << 16; - hesai_status.temperature[i] = hesai_status.temperature[i] | response[payload_pos++] << 8; - hesai_status.temperature[i] = hesai_status.temperature[i] | response[payload_pos++]; - } - hesai_status.gps_pps_lock = static_cast(response[payload_pos++]); - hesai_status.gps_gprmc_status = static_cast(response[payload_pos++]); - hesai_status.startup_times = response[payload_pos++] << 24; - hesai_status.startup_times = hesai_status.startup_times | response[payload_pos++] << 16; - hesai_status.startup_times = hesai_status.startup_times | response[payload_pos++] << 8; - hesai_status.startup_times = hesai_status.startup_times | response[payload_pos++]; - hesai_status.total_operation_time = response[payload_pos++] << 24; - hesai_status.total_operation_time = hesai_status.total_operation_time | response[payload_pos++] - << 16; - hesai_status.total_operation_time = hesai_status.total_operation_time | response[payload_pos++] - << 8; - hesai_status.total_operation_time = hesai_status.total_operation_time | response[payload_pos++]; - hesai_status.ptp_clock_status = static_cast(response[payload_pos++]); - for (size_t i = 0; i < hesai_status.reserved.size(); i++) { - hesai_status.reserved[i] = static_cast(response[payload_pos++]); + if (response.size() != sizeof(HesaiLidarStatus)) { + throw std::runtime_error("Unexpected payload size"); } + HesaiLidarStatus hesai_status; + memcpy(&hesai_status, response.data(), sizeof(HesaiLidarStatus)); + return hesai_status; } @@ -695,7 +501,8 @@ Status HesaiHwInterface::SetSpinRate(uint16_t rpm) request_payload.emplace_back((rpm >> 8) & 0xff); request_payload.emplace_back(rpm & 0xff); - SendReceive(PTC_COMMAND_SET_SPIN_RATE, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_SPIN_RATE, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -706,7 +513,8 @@ Status HesaiHwInterface::SetSyncAngle(int sync_angle, int angle) request_payload.emplace_back((angle >> 8) & 0xff); request_payload.emplace_back(angle & 0xff); - SendReceive(PTC_COMMAND_SET_SYNC_ANGLE, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_SYNC_ANGLE, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -715,7 +523,8 @@ Status HesaiHwInterface::SetTriggerMethod(int trigger_method) std::vector request_payload; request_payload.emplace_back(trigger_method & 0xff); - SendReceive(PTC_COMMAND_SET_TRIGGER_METHOD, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_TRIGGER_METHOD, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -724,7 +533,8 @@ Status HesaiHwInterface::SetStandbyMode(int standby_mode) std::vector request_payload; request_payload.emplace_back(standby_mode & 0xff); - SendReceive(PTC_COMMAND_SET_STANDBY_MODE, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_STANDBY_MODE, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -733,7 +543,8 @@ Status HesaiHwInterface::SetReturnMode(int return_mode) std::vector request_payload; request_payload.emplace_back(return_mode & 0xff); - SendReceive(PTC_COMMAND_SET_RETURN_MODE, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_RETURN_MODE, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -750,7 +561,8 @@ Status HesaiHwInterface::SetDestinationIp( request_payload.emplace_back((gps_port >> 8) & 0xff); request_payload.emplace_back(gps_port & 0xff); - SendReceive(PTC_COMMAND_SET_DESTINATION_IP, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_DESTINATION_IP, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -775,7 +587,8 @@ Status HesaiHwInterface::SetControlPort( request_payload.emplace_back((vlan_id >> 8) & 0xff); request_payload.emplace_back(vlan_id & 0xff); - SendReceive(PTC_COMMAND_SET_CONTROL_PORT, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_CONTROL_PORT, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -788,7 +601,8 @@ Status HesaiHwInterface::SetLidarRange(int method, std::vector da request_payload.emplace_back(method & 0xff); request_payload.insert(request_payload.end(), data.begin(), data.end()); - SendReceive(PTC_COMMAND_SET_LIDAR_RANGE, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_LIDAR_RANGE, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -805,31 +619,36 @@ Status HesaiHwInterface::SetLidarRange(int start, int end) request_payload.emplace_back((end >> 8) & 0xff); request_payload.emplace_back(end & 0xff); - SendReceive(PTC_COMMAND_SET_LIDAR_RANGE, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_LIDAR_RANGE, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } HesaiLidarRangeAll HesaiHwInterface::GetLidarRange() { - auto response_ptr = SendReceive(PTC_COMMAND_GET_LIDAR_RANGE); - auto & response = *response_ptr; + auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_RANGE); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + + if (response.size() < 1) { + throw std::runtime_error("Response payload too short"); + } HesaiLidarRangeAll hesai_range_all; - int payload_pos = 0; - int method = static_cast(response[payload_pos++]); - switch (method) { + hesai_range_all.method = response[0]; + switch (hesai_range_all.method) { case 0: // for all channels - hesai_range_all.method = method; - hesai_range_all.start = response[payload_pos++] << 8; - hesai_range_all.start = hesai_range_all.start | response[payload_pos++]; - hesai_range_all.end = response[payload_pos++] << 8; - hesai_range_all.end = hesai_range_all.end | response[payload_pos++]; + if (response.size() != 5) { + throw std::runtime_error("Unexpected response payload"); + } + + memcpy(&hesai_range_all.start, &response[1], 2); + memcpy(&hesai_range_all.end, &response[3], 2); break; case 1: // for each channel - hesai_range_all.method = method; + //TODO break; case 2: // multi-section FOV - hesai_range_all.method = method; + //TODO break; } @@ -841,7 +660,8 @@ Status HesaiHwInterface::SetClockSource(int clock_source) std::vector request_payload; request_payload.emplace_back(clock_source & 0xff); - SendReceive(PTC_COMMAND_SET_CLOCK_SOURCE, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_CLOCK_SOURCE, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -874,28 +694,28 @@ Status HesaiHwInterface::SetPtpConfig( request_payload.emplace_back(switch_type & 0xff); } - SendReceive(PTC_COMMAND_SET_PTP_CONFIG, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_PTP_CONFIG, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } HesaiPtpConfig HesaiHwInterface::GetPtpConfig() { - auto response_ptr = SendReceive(PTC_COMMAND_GET_PTP_CONFIG); - auto & response = *response_ptr; - - HesaiPtpConfig hesai_ptp_config{}; + auto response_or_err = SendReceive(PTC_COMMAND_GET_PTP_CONFIG); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); - int payload_pos = 0; - hesai_ptp_config.status = static_cast(response[payload_pos++]); - hesai_ptp_config.profile = static_cast(response[payload_pos++]); - hesai_ptp_config.domain = static_cast(response[payload_pos++]); - hesai_ptp_config.network = static_cast(response[payload_pos++]); - if (hesai_ptp_config.status == 0) { - hesai_ptp_config.logAnnounceInterval = static_cast(response[payload_pos++]); - hesai_ptp_config.logSyncInterval = static_cast(response[payload_pos++]); - hesai_ptp_config.logMinDelayReqInterval = static_cast(response[payload_pos++]); + if (response.size() < sizeof(HesaiPtpConfig)) { + throw std::runtime_error("Unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpConfig)) { + PrintError("HesaiPtpConfig from Sensor has unknown format. Will parse anyway."); } + HesaiPtpConfig hesai_ptp_config; + memcpy(&hesai_ptp_config.status, response.data(), 1); + + size_t bytes_to_parse = (hesai_ptp_config.status == 0) ? sizeof(HesaiPtpConfig) : 4; + memcpy(&hesai_ptp_config, response.data(), bytes_to_parse); + std::stringstream ss; ss << "HesaiHwInterface::GetPtpConfig: " << hesai_ptp_config; PrintInfo(ss.str()); @@ -905,7 +725,8 @@ HesaiPtpConfig HesaiHwInterface::GetPtpConfig() Status HesaiHwInterface::SendReset() { - SendReceive(PTC_COMMAND_RESET); + auto response_or_err = SendReceive(PTC_COMMAND_RESET); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } @@ -914,38 +735,23 @@ Status HesaiHwInterface::SetRotDir(int mode) std::vector request_payload; request_payload.emplace_back(mode & 0xff); - SendReceive(PTC_COMMAND_SET_ROTATE_DIRECTION, request_payload); + auto response_or_err = SendReceive(PTC_COMMAND_SET_ROTATE_DIRECTION, request_payload); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); return Status::OK; } HesaiLidarMonitor HesaiHwInterface::GetLidarMonitor() { - auto response_ptr = SendReceive(PTC_COMMAND_LIDAR_MONITOR); - auto & response = *response_ptr; + auto response_or_err = SendReceive(PTC_COMMAND_LIDAR_MONITOR); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); - HesaiLidarMonitor hesai_lidar_monitor; - int payload_pos = 0; - hesai_lidar_monitor.input_voltage = response[payload_pos++] << 24; - hesai_lidar_monitor.input_voltage = hesai_lidar_monitor.input_voltage | response[payload_pos++] - << 16; - hesai_lidar_monitor.input_voltage = hesai_lidar_monitor.input_voltage | response[payload_pos++] - << 8; - hesai_lidar_monitor.input_voltage = hesai_lidar_monitor.input_voltage | response[payload_pos++]; - hesai_lidar_monitor.input_current = response[payload_pos++] << 24; - hesai_lidar_monitor.input_current = hesai_lidar_monitor.input_current | response[payload_pos++] - << 16; - hesai_lidar_monitor.input_current = hesai_lidar_monitor.input_current | response[payload_pos++] - << 8; - hesai_lidar_monitor.input_current = hesai_lidar_monitor.input_current | response[payload_pos++]; - hesai_lidar_monitor.input_power = response[payload_pos++] << 24; - hesai_lidar_monitor.input_power = hesai_lidar_monitor.input_power | response[payload_pos++] << 16; - hesai_lidar_monitor.input_power = hesai_lidar_monitor.input_power | response[payload_pos++] << 8; - hesai_lidar_monitor.input_power = hesai_lidar_monitor.input_power | response[payload_pos++]; - - for (size_t i = 0; i < hesai_lidar_monitor.reserved.size(); i++) { - hesai_lidar_monitor.reserved[i] = static_cast(response[payload_pos++]); + if (response.size() != sizeof(HesaiLidarMonitor)) { + throw std::runtime_error("Unexpected payload size"); } + HesaiLidarMonitor hesai_lidar_monitor; + memcpy(&hesai_lidar_monitor, response.data(), sizeof(HesaiLidarMonitor)); + return hesai_lidar_monitor; } @@ -1153,8 +959,8 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( } auto current_rotation_speed = hesai_config.spin_rate; - if (sensor_configuration->rotation_speed != current_rotation_speed) { - PrintInfo("current lidar rotation_speed: " + std::to_string(current_rotation_speed)); + if (sensor_configuration->rotation_speed != current_rotation_speed.value()) { + PrintInfo("current lidar rotation_speed: " + std::to_string(static_cast(current_rotation_speed.value()))); PrintInfo( "current configuration rotation_speed: " + std::to_string(sensor_configuration->rotation_speed)); @@ -1172,8 +978,8 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( bool set_flg = false; std::stringstream ss; - ss << hesai_config.dest_ipaddr[0] << "." << hesai_config.dest_ipaddr[1] << "." - << hesai_config.dest_ipaddr[2] << "." << hesai_config.dest_ipaddr[3]; + ss << static_cast(hesai_config.dest_ipaddr[0]) << "." << static_cast(hesai_config.dest_ipaddr[1]) << "." + << static_cast(hesai_config.dest_ipaddr[2]) << "." << static_cast(hesai_config.dest_ipaddr[3]); auto current_host_addr = ss.str(); if (sensor_configuration->host_ip != current_host_addr) { set_flg = true; @@ -1182,17 +988,17 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( } auto current_host_dport = hesai_config.dest_LiDAR_udp_port; - if (sensor_configuration->data_port != current_host_dport) { + if (sensor_configuration->data_port != current_host_dport.value()) { set_flg = true; - PrintInfo("current lidar dest_LiDAR_udp_port: " + std::to_string(current_host_dport)); + PrintInfo("current lidar dest_LiDAR_udp_port: " + std::to_string(static_cast(current_host_dport.value()))); PrintInfo( "current configuration data_port: " + std::to_string(sensor_configuration->data_port)); } auto current_host_tport = hesai_config.dest_gps_udp_port; - if (sensor_configuration->gnss_port != current_host_tport) { + if (sensor_configuration->gnss_port != current_host_tport.value()) { set_flg = true; - PrintInfo("current lidar dest_gps_udp_port: " + std::to_string(current_host_tport)); + PrintInfo("current lidar dest_gps_udp_port: " + std::to_string(static_cast(current_host_tport.value()))); PrintInfo( "current configuration gnss_port: " + std::to_string(sensor_configuration->gnss_port)); } @@ -1212,7 +1018,7 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( if (sensor_configuration->sensor_model != SensorModel::HESAI_PANDARAT128) { set_flg = true; - auto sync_angle = static_cast(hesai_config.sync_angle / 100); + auto sync_angle = static_cast(hesai_config.sync_angle.value() / 100); auto scan_phase = static_cast(sensor_configuration->scan_phase); int sync_flg = 1; if (scan_phase != sync_angle) { @@ -1296,18 +1102,18 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( set_flg = true; } else { auto current_cloud_min_angle = hesai_lidar_range_all.start; - if (static_cast(sensor_configuration->cloud_min_angle * 10) != current_cloud_min_angle) { + if (static_cast(sensor_configuration->cloud_min_angle * 10) != current_cloud_min_angle.value()) { set_flg = true; - PrintInfo("current lidar range.start: " + std::to_string(current_cloud_min_angle)); + PrintInfo("current lidar range.start: " + std::to_string(static_cast(current_cloud_min_angle.value()))); PrintInfo( "current configuration cloud_min_angle: " + std::to_string(sensor_configuration->cloud_min_angle)); } auto current_cloud_max_angle = hesai_lidar_range_all.end; - if (static_cast(sensor_configuration->cloud_max_angle * 10) != current_cloud_max_angle) { + if (static_cast(sensor_configuration->cloud_max_angle * 10) != current_cloud_max_angle.value()) { set_flg = true; - PrintInfo("current lidar range.end: " + std::to_string(current_cloud_max_angle)); + PrintInfo("current lidar range.end: " + std::to_string(static_cast(current_cloud_max_angle.value()))); PrintInfo( "current configuration cloud_max_angle: " + std::to_string(sensor_configuration->cloud_max_angle)); @@ -1547,5 +1353,76 @@ void HesaiHwInterface::PrintDebug(const std::vector & bytes) PrintDebug(ss.str()); } +std::string HesaiHwInterface::PrettyPrintPTCError(uint32_t error_code) { + if (error_code == 0) { + return "No error"; + } + + uint8_t hesai_error = error_code & 0xFF; + uint32_t nebula_error_flags = (error_code >> 8); + std::stringstream ss; + + if (hesai_error) { + ss << "Sensor error: 0x" << std::setfill('0') << std::setw(2) << std::hex << static_cast(hesai_error) << ' '; + } + + switch(hesai_error) { + case PTC_ERROR_CODE_NO_ERROR: + break; + case PTC_ERROR_CODE_INVALID_INPUT_PARAM: + ss << "Invalid input parameter"; + break; + case PTC_ERROR_CODE_SERVER_CONN_FAILED: + ss << "Failure to connect to server"; + break; + case PTC_ERROR_CODE_INVALID_DATA: + ss << "No valid data returned"; + break; + case PTC_ERROR_CODE_OUT_OF_MEMORY: + ss << "Server does not have enough memory"; + break; + case PTC_ERROR_CODE_UNSUPPORTED_CMD: + ss << "Server does not support this command yet"; + break; + case PTC_ERROR_CODE_FPGA_COMM_FAILED: + ss << "Server failed to communicate with FPGA"; + break; + case PTC_ERROR_CODE_OTHER: + ss << "Unspecified internal error"; + break; + default: + ss << "Unknown error"; + break; + } + + if (!nebula_error_flags) { + return ss.str(); + } + + if (hesai_error) { + ss << ", "; + } + + ss << "Communication error: "; + std::vector nebula_errors; + + if (nebula_error_flags & TCP_ERROR_INCOMPLETE_RESPONSE) { + nebula_errors.push_back("Incomplete response payload"); + } + if (nebula_error_flags & TCP_ERROR_TIMEOUT) { + nebula_errors.push_back("Request timeout"); + } + if (nebula_error_flags & TCP_ERROR_UNEXPECTED_PAYLOAD) { + nebula_errors.push_back("Received payload but expected payload length 0"); + } + if (nebula_error_flags & TCP_ERROR_UNRELATED_RESPONSE) { + nebula_errors.push_back("Received unrelated response"); + } + + ss << boost::algorithm::join(nebula_errors, ", "); + + return ss.str(); +} + } // namespace drivers } // namespace nebula diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp index 857f638cd..aee7e3284 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp @@ -20,6 +20,7 @@ #include #include +#include namespace nebula { diff --git a/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp index 239f6b8b0..d1c0beec9 100644 --- a/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp @@ -73,7 +73,7 @@ HesaiHwMonitorRosWrapper::HesaiHwMonitorRosWrapper(const rclcpp::NodeOptions & o std::cout << "HesaiInventory" << std::endl; std::cout << result << std::endl; info_model = result.get_str_model(); - info_serial = std::string(result.sn.begin(), result.sn.end()); + info_serial = std::string(std::begin(result.sn), std::begin(result.sn)); hw_interface_.SetTargetModel(result.model); RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); @@ -479,9 +479,9 @@ void HesaiHwMonitorRosWrapper::HesaiCheckStatus( uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - diagnostics.add("system_uptime", std::to_string(current_status->system_uptime)); - diagnostics.add("startup_times", std::to_string(current_status->startup_times)); - diagnostics.add("total_operation_time", std::to_string(current_status->total_operation_time)); + diagnostics.add("system_uptime", std::to_string(current_status->system_uptime.value())); + diagnostics.add("startup_times", std::to_string(current_status->startup_times.value())); + diagnostics.add("total_operation_time", std::to_string(current_status->total_operation_time.value())); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -530,9 +530,9 @@ void HesaiHwMonitorRosWrapper::HesaiCheckTemperature( if (current_status) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - for (size_t i = 0; i < current_status->temperature.size(); i++) { + for (size_t i = 0; i < std::size(current_status->temperature); i++) { diagnostics.add( - temperature_names[i], GetFixedPrecisionString(current_status->temperature[i] * 0.01)); + temperature_names[i], GetFixedPrecisionString(current_status->temperature[i].value() * 0.01)); } diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -547,7 +547,7 @@ void HesaiHwMonitorRosWrapper::HesaiCheckRpm( if (current_status) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - diagnostics.add("motor_speed", std::to_string(current_status->motor_speed)); + diagnostics.add("motor_speed", std::to_string(current_status->motor_speed.value())); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -596,11 +596,11 @@ void HesaiHwMonitorRosWrapper::HesaiCheckVoltage( uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; diagnostics.add( - "input_voltage", GetFixedPrecisionString(current_monitor->input_voltage * 0.01) + " V"); + "input_voltage", GetFixedPrecisionString(current_monitor->input_voltage.value() * 0.01) + " V"); diagnostics.add( - "input_current", GetFixedPrecisionString(current_monitor->input_current * 0.01) + " mA"); + "input_current", GetFixedPrecisionString(current_monitor->input_current.value() * 0.01) + " mA"); diagnostics.add( - "input_power", GetFixedPrecisionString(current_monitor->input_power * 0.01) + " W"); + "input_power", GetFixedPrecisionString(current_monitor->input_power.value() * 0.01) + " W"); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { From aff27331c53d80f443b2e29cbc2edcc2e0a90bb8 Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Thu, 21 Mar 2024 16:58:45 +0900 Subject: [PATCH 002/122] fix(hesai_decoder): print config instead of config address --- .../nebula_decoders_hesai/decoders/hesai_decoder.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index 7bdfd069e..b81b45d44 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -213,7 +213,7 @@ class HesaiDecoder : public HesaiScanDecoder logger_(rclcpp::get_logger("HesaiDecoder")) { logger_.set_level(rclcpp::Logger::Level::Debug); - RCLCPP_INFO_STREAM(logger_, sensor_configuration_); + RCLCPP_INFO_STREAM(logger_, *sensor_configuration_); decode_pc_.reset(new NebulaPointCloud); output_pc_.reset(new NebulaPointCloud); From e9e05a65348c7950f2089f49b57cf5a159cffd99 Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Thu, 21 Mar 2024 17:01:34 +0900 Subject: [PATCH 003/122] refactor(nebula_ros): combine Hesai wrapper nodes into one This is step one of the single node refactoring of Nebula. In this step, only the three Hesai wrapper nodes were combined into one, and no optimizations have been done that are made possible by this refactoring. The next step is to do those optimizations (e.g. get rid of unnecessary pointcloud copying). --- nebula_common/CMakeLists.txt | 2 + nebula_ros/CMakeLists.txt | 31 +- .../common/nebula_ros_wrapper_base.hpp | 68 + .../hesai/hesai_decoder_ros_wrapper.hpp | 106 -- .../hesai/hesai_hw_interface_ros_wrapper.hpp | 100 -- ..._ros_wrapper.hpp => hesai_ros_wrapper.hpp} | 194 ++- nebula_ros/launch/hesai_launch_all_hw.xml | 68 +- .../launch/hesai_launch_component.launch.xml | 115 -- .../src/hesai/hesai_decoder_ros_wrapper.cpp | 488 ------- .../hesai/hesai_hw_interface_ros_wrapper.cpp | 510 ------- .../hesai/hesai_hw_monitor_ros_wrapper.cpp | 620 --------- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 1234 +++++++++++++++++ 12 files changed, 1475 insertions(+), 2061 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp delete mode 100644 nebula_ros/include/nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp delete mode 100644 nebula_ros/include/nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp rename nebula_ros/include/nebula_ros/hesai/{hesai_hw_monitor_ros_wrapper.hpp => hesai_ros_wrapper.hpp} (52%) delete mode 100644 nebula_ros/launch/hesai_launch_component.launch.xml delete mode 100644 nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp delete mode 100644 nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp delete mode 100644 nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp create mode 100644 nebula_ros/src/hesai/hesai_ros_wrapper.cpp diff --git a/nebula_common/CMakeLists.txt b/nebula_common/CMakeLists.txt index 4c146736c..154f8e453 100644 --- a/nebula_common/CMakeLists.txt +++ b/nebula_common/CMakeLists.txt @@ -40,6 +40,8 @@ ament_auto_add_library(nebula_common SHARED src/velodyne/velodyne_calibration_decoder.cpp ) +target_link_libraries(nebula_common yaml-cpp) + ament_auto_package() # Set ROS_DISTRO macros diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index dd81e1ac0..18ce06aad 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -33,34 +33,13 @@ include_directories( ) link_libraries(${YAML_CPP_LIBRARIES} ${PCL_LIBRARIES}) ## Hesai -# Hw Interface -ament_auto_add_library(hesai_hw_ros_wrapper SHARED - src/hesai/hesai_hw_interface_ros_wrapper.cpp - ) - -rclcpp_components_register_node(hesai_hw_ros_wrapper - PLUGIN "HesaiHwInterfaceRosWrapper" - EXECUTABLE hesai_hw_interface_ros_wrapper_node - ) - -# Monitor -ament_auto_add_library(hesai_hw_monitor_ros_wrapper SHARED - src/hesai/hesai_hw_monitor_ros_wrapper.cpp - ) - -rclcpp_components_register_node(hesai_hw_monitor_ros_wrapper - PLUGIN "HesaiHwMonitorRosWrapper" - EXECUTABLE hesai_hw_monitor_ros_wrapper_node - ) - -# DriverDecoder -ament_auto_add_library(hesai_driver_ros_wrapper SHARED - src/hesai/hesai_decoder_ros_wrapper.cpp +ament_auto_add_library(hesai_ros_wrapper SHARED + src/hesai/hesai_ros_wrapper.cpp ) -rclcpp_components_register_node(hesai_driver_ros_wrapper - PLUGIN "HesaiDriverRosWrapper" - EXECUTABLE hesai_driver_ros_wrapper_node +rclcpp_components_register_node(hesai_ros_wrapper + PLUGIN "HesaiRosWrapper" + EXECUTABLE hesai_ros_wrapper_node ) ## Velodyne diff --git a/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp b/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp new file mode 100644 index 000000000..5aaeb634b --- /dev/null +++ b/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp @@ -0,0 +1,68 @@ +#pragma once + +#include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" + +#include +#include +#include + +#include + +#include +#include + +namespace nebula +{ +namespace ros +{ +/// @brief Base class for ros wrapper of each sensor driver +class NebulaRosWrapperBase +{ +public: + NebulaRosWrapperBase() = default; + + NebulaRosWrapperBase(NebulaRosWrapperBase && c) = delete; + NebulaRosWrapperBase & operator=(NebulaRosWrapperBase && c) = delete; + NebulaRosWrapperBase(const NebulaRosWrapperBase & c) = delete; + NebulaRosWrapperBase & operator=(const NebulaRosWrapperBase & c) = delete; + + /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) + /// @return Resulting status + virtual Status StreamStart() = 0; + + /// @brief Stop point cloud streaming (not used) + /// @return Resulting status + virtual Status StreamStop() = 0; + + /// @brief Shutdown (not used) + /// @return Resulting status + virtual Status Shutdown() = 0; + +private: + /// @brief Virtual function for initializing hardware interface ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + virtual Status InitializeHwInterface( + const drivers::SensorConfigurationBase & sensor_configuration) = 0; + + /// @brief Virtual function for initializing hardware monitor ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + virtual Status InitializeHwMonitor( + const drivers::SensorConfigurationBase & sensor_configuration) = 0; + + /// @brief Virtual function for initializing ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + /// @return Resulting status + virtual Status InitializeCloudDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) = 0; + + /// @brief Point cloud publisher + rclcpp::Publisher::SharedPtr cloud_pub_; +}; + +} // namespace ros +} // namespace nebula diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp deleted file mode 100644 index 52518fcd0..000000000 --- a/nebula_ros/include/nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp +++ /dev/null @@ -1,106 +0,0 @@ -#ifndef NEBULA_HesaiDriverRosWrapper_H -#define NEBULA_HesaiDriverRosWrapper_H - -#include "nebula_common/hesai/hesai_common.hpp" -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" -#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" -#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" -#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" - -#include -#include -#include -#include - -#include - -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" - -namespace nebula -{ -namespace ros -{ -/// @brief Ros wrapper of hesai driver -class HesaiDriverRosWrapper final : public rclcpp::Node, NebulaDriverRosWrapperBase -{ - std::shared_ptr driver_ptr_; - Status wrapper_status_; - rclcpp::Subscription::SharedPtr pandar_scan_sub_; - rclcpp::Publisher::SharedPtr nebula_points_pub_; - rclcpp::Publisher::SharedPtr aw_points_ex_pub_; - rclcpp::Publisher::SharedPtr aw_points_base_pub_; - - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; - std::shared_ptr correction_cfg_ptr_; - - drivers::HesaiHwInterface hw_interface_; - - /// @brief Initializing ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Initializing ros wrapper for AT - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration); - - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @param calibration_configuration Output of CalibrationConfiguration - /// @param correction_configuration Output of CorrectionConfiguration (for AT) - /// @return Resulting status - Status GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration, - drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration); - - /// @brief Convert seconds to chrono::nanoseconds - /// @param seconds - /// @return chrono::nanoseconds - static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) - { - return std::chrono::duration_cast( - std::chrono::duration(seconds)); - } - - /*** - * Publishes a sensor_msgs::msg::PointCloud2 to the specified publisher - * @param pointcloud unique pointer containing the point cloud to publish - * @param publisher - */ - void PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher); - -public: - explicit HesaiDriverRosWrapper(const rclcpp::NodeOptions & options); - - /// @brief Callback for PandarScan subscriber - /// @param scan_msg Received PandarScan - void ReceiveScanMsgCallback(const pandar_msgs::msg::PandarScan::SharedPtr scan_msg); - - /// @brief Get current status of this driver - /// @return Current status - Status GetStatus(); - -private: - /// @brief File path of Correction data (Only required only for AT) - std::string correction_file_path; -}; - -} // namespace ros -} // namespace nebula - -#endif // NEBULA_HesaiDriverRosWrapper_H diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp deleted file mode 100644 index 1802f87b2..000000000 --- a/nebula_ros/include/nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp +++ /dev/null @@ -1,100 +0,0 @@ -#ifndef NEBULA_HesaiHwInterfaceRosWrapper_H -#define NEBULA_HesaiHwInterfaceRosWrapper_H - -#include "nebula_common/hesai/hesai_common.hpp" -#include "nebula_common/nebula_common.hpp" -#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" -#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" -#include "boost_tcp_driver/tcp_driver.hpp" - -#include -#include -#include - -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" - -#include - -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Get parameter from rclcpp::Parameter -/// @tparam T -/// @param p Parameter from rclcpp parameter callback -/// @param name Target parameter name -/// @param value Corresponding value -/// @return Whether the target name existed -template -bool get_param(const std::vector & p, const std::string & name, T & value) -{ - auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { - return parameter.get_name() == name; - }); - if (it != p.cend()) { - value = it->template get_value(); - return true; - } - return false; -} - -/// @brief Hardware interface ros wrapper of hesai driver -class HesaiHwInterfaceRosWrapper final : public rclcpp::Node, NebulaHwInterfaceWrapperBase -{ - drivers::HesaiHwInterface hw_interface_; - Status interface_status_; - - drivers::HesaiSensorConfiguration sensor_configuration_; - - /// @brief Received Hesai message publisher - rclcpp::Publisher::SharedPtr pandar_scan_pub_; - - /// @brief Initializing hardware interface ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - Status InitializeHwInterface( - const drivers::SensorConfigurationBase & sensor_configuration) override; - /// @brief Callback for receiving PandarScan - /// @param scan_buffer Received PandarScan - void ReceiveScanDataCallback(std::unique_ptr scan_buffer); - -public: - explicit HesaiHwInterfaceRosWrapper(const rclcpp::NodeOptions & options); - ~HesaiHwInterfaceRosWrapper() noexcept override; - /// @brief Start point cloud streaming (Call SensorInterfaceStart of HwInterface) - /// @return Resulting status - Status StreamStart() override; - /// @brief Stop point cloud streaming (not used) - /// @return Resulting status - Status StreamStop() override; - /// @brief Shutdown (not used) - /// @return Resulting status - Status Shutdown() override; - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @return Resulting status - Status GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration); - -private: - uint16_t delay_hw_ms_; - bool retry_hw_; - std::mutex mtx_config_; - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - /// @brief rclcpp parameter callback - /// @param parameters Received parameters - /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); - /// @brief Updating rclcpp parameter - /// @return SetParametersResult - std::vector updateParameters(); -}; - -} // namespace ros -} // namespace nebula - -#endif // NEBULA_HesaiHwInterfaceRosWrapper_H diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp similarity index 52% rename from nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp rename to nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index c23b76c55..f23d1f9c4 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -1,30 +1,36 @@ -#ifndef NEBULA_HesaiHwMonitorRosWrapper_H -#define NEBULA_HesaiHwMonitorRosWrapper_H +#pragma once +#include "boost_tcp_driver/tcp_driver.hpp" #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" +#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" +#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" #include "nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp" -#include "boost_tcp_driver/tcp_driver.hpp" +#include "nebula_ros/common/nebula_ros_wrapper_base.hpp" #include #include #include #include -#include +#include "pandar_msgs/msg/pandar_packet.hpp" +#include "pandar_msgs/msg/pandar_scan.hpp" -#include #include #include #include +#include +#include #include namespace nebula { namespace ros { + /// @brief Get parameter from rclcpp::Parameter /// @tparam T /// @param p Parameter from rclcpp parameter callback @@ -44,39 +50,106 @@ bool get_param(const std::vector & p, const std::string & nam return false; } -/// @brief Hardware monitor ros wrapper of hesai driver -class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapperBase +/// @brief Ros wrapper of hesai driver +class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase { - drivers::HesaiHwInterface hw_interface_; - Status interface_status_; +public: + explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); + ~HesaiRosWrapper(); - drivers::HesaiSensorConfiguration sensor_configuration_; + /// @brief Callback for PandarScan subscriber + /// @param scan_msg Received PandarScan + void ReceiveScanMsgCallback(const pandar_msgs::msg::PandarScan::SharedPtr scan_msg); - /// @brief Initializing hardware monitor ros wrapper + /// @brief Get current status of this driver + /// @return Current status + Status GetStatus(); + + /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) + /// @return Resulting status + Status StreamStart() override; + /// @brief Stop point cloud streaming (not used) + /// @return Resulting status + Status StreamStop() override; + /// @brief Shutdown (not used) + /// @return Resulting status + Status Shutdown() override; + +private: + /// @brief Initializing ros wrapper /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver /// @return Resulting status - Status InitializeHwMonitor( - const drivers::SensorConfigurationBase & sensor_configuration) override; + Status InitializeCloudDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) override; + + /// @brief Initializing ros wrapper for AT + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + /// @param correction_configuration CorrectionConfiguration for this driver + /// @return Resulting status + Status InitializeCloudDriver( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration, + const std::shared_ptr & correction_configuration); -public: - explicit HesaiHwMonitorRosWrapper(const rclcpp::NodeOptions & options); - ~HesaiHwMonitorRosWrapper() noexcept override; - /// @brief Not used - /// @return Current status - Status MonitorStart() override; - /// @brief Not used - /// @return Status::OK - Status MonitorStop() override; - /// @brief Not used - /// @return Status::OK - Status Shutdown() override; /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration /// @return Resulting status - Status GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration); + Status GetParameters( + drivers::HesaiSensorConfiguration & sensor_configuration); + + /// @brief Get calibration data from the sensor + /// @param calibration_configuration Output of CalibrationConfiguration + /// @param correction_configuration Output of CorrectionConfiguration (for AT) + /// @return Resulting status + Status GetCalibrationData( + drivers::HesaiCalibrationConfiguration & calibration_configuration, + drivers::HesaiCorrection & correction_configuration); + + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast( + std::chrono::duration(seconds)); + } + + /*** + * Publishes a sensor_msgs::msg::PointCloud2 to the specified publisher + * @param pointcloud unique pointer containing the point cloud to publish + * @param publisher + */ + void PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher); + + /// @brief Initializing hardware interface ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + Status InitializeHwInterface( + const drivers::SensorConfigurationBase & sensor_configuration) override; + /// @brief Callback for receiving PandarScan + /// @param scan_buffer Received PandarScan + void ReceiveScanDataCallback(std::unique_ptr scan_buffer); + + /// @brief rclcpp parameter callback + /// @param parameters Received parameters + /// @return SetParametersResult + rcl_interfaces::msg::SetParametersResult paramCallback( + const std::vector & parameters); + /// @brief Updating rclcpp parameter + /// @return SetParametersResult + std::vector updateParameters(); + + /// @brief Initializing hardware monitor ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + Status InitializeHwMonitor( + const drivers::SensorConfigurationBase & sensor_configuration) override; -private: - diagnostic_updater::Updater diagnostics_updater_; /// @brief Initializing diagnostics void InitializeHesaiDiagnostics(); /// @brief Callback of the timer for getting the current lidar status @@ -106,6 +179,49 @@ class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapp /// @brief Check voltage information from HesaiLidarStatus for diagnostic_updater via tcp /// @param diagnostics DiagnosticStatusWrapper void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); + /// @brief Get value from property_tree + /// @param pt property_tree + /// @param key Pey string + /// @return Value + std::string GetPtreeValue(boost::property_tree::ptree * pt, const std::string & key); + /// @brief Making fixed precision string + /// @param val Target value + /// @param pre Precision + /// @return Created string + std::string GetFixedPrecisionString(double val, int pre = 2); + + std::shared_ptr driver_ptr_; + Status wrapper_status_; + rclcpp::Subscription::SharedPtr pandar_scan_sub_; + rclcpp::Publisher::SharedPtr nebula_points_pub_; + rclcpp::Publisher::SharedPtr aw_points_ex_pub_; + rclcpp::Publisher::SharedPtr aw_points_base_pub_; + + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; + std::shared_ptr correction_cfg_ptr_; + + Status interface_status_; + + //todo: temporary class member during single node refactoring + bool launch_hw_; + + //todo: temporary class member during single node refactoring + std::string calibration_file_path; + /// @brief File path of Correction data (Only required only for AT) + std::string correction_file_path; + + /// @brief Received Hesai message publisher + rclcpp::Publisher::SharedPtr pandar_scan_pub_; + + drivers::HesaiHwInterface hw_interface_; + + uint16_t delay_hw_ms_; + bool retry_hw_; + std::mutex mtx_config_; + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + + diagnostic_updater::Updater diagnostics_updater_; rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; rclcpp::TimerBase::SharedPtr diagnostics_update_monitor_timer_; @@ -127,24 +243,6 @@ class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapp std::mutex mtx_diag; std::mutex mtx_status; std::mutex mtx_lidar_monitor; - // std::timed_mutex mtx_lidar_monitor; - std::mutex mtx_config_; - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - /// @brief rclcpp parameter callback - /// @param parameters Received parameters - /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); - /// @brief Get value from property_tree - /// @param pt property_tree - /// @param key Pey string - /// @return Value - std::string GetPtreeValue(boost::property_tree::ptree * pt, const std::string & key); - /// @brief Making fixed precision string - /// @param val Target value - /// @param pre Precision - /// @return Created string - std::string GetFixedPrecisionString(double val, int pre = 2); std::string info_model; std::string info_serial; @@ -157,9 +255,9 @@ class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapp std::string message_sep; std::vector temperature_names; + + bool setup_sensor; }; } // namespace ros } // namespace nebula - -#endif // NEBULA_HesaiHwMonitorRosWrapper_H diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index f4a1cd41c..579852fb8 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -35,8 +35,8 @@ - + @@ -45,52 +45,24 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + diff --git a/nebula_ros/launch/hesai_launch_component.launch.xml b/nebula_ros/launch/hesai_launch_component.launch.xml deleted file mode 100644 index 75c7414da..000000000 --- a/nebula_ros/launch/hesai_launch_component.launch.xml +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp deleted file mode 100644 index 6f27d547e..000000000 --- a/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp +++ /dev/null @@ -1,488 +0,0 @@ -#include "nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp" - -namespace nebula -{ -namespace ros -{ -HesaiDriverRosWrapper::HesaiDriverRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_driver_ros_wrapper", options), hw_interface_() -{ - drivers::HesaiCalibrationConfiguration calibration_configuration; - drivers::HesaiSensorConfiguration sensor_configuration; - drivers::HesaiCorrection correction_configuration; - - setvbuf(stdout, NULL, _IONBF, BUFSIZ); - - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - - wrapper_status_ = - GetParameters(sensor_configuration, calibration_configuration, correction_configuration); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return; - } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - - calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); - - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - correction_cfg_ptr_ = std::make_shared(correction_configuration); - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); - } else { - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); - } - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), - qos_profile); - pandar_scan_sub_ = create_subscription( - "pandar_packets", qos, - std::bind(&HesaiDriverRosWrapper::ReceiveScanMsgCallback, this, std::placeholders::_1)); - nebula_points_pub_ = - this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); - aw_points_base_pub_ = - this->create_publisher("aw_points", rclcpp::SensorDataQoS()); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", rclcpp::SensorDataQoS()); -} - -void HesaiDriverRosWrapper::ReceiveScanMsgCallback( - const pandar_msgs::msg::PandarScan::SharedPtr scan_msg) -{ - auto t_start = std::chrono::high_resolution_clock::now(); - std::tuple pointcloud_ts = - driver_ptr_->ConvertScanToPointcloud(scan_msg); - nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - - if (pointcloud == nullptr) { - RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); - return; - }; - if ( - nebula_points_pub_->get_subscription_count() > 0 || - nebula_points_pub_->get_intra_process_subscription_count() > 0) { - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); - } - if ( - aw_points_base_pub_->get_subscription_count() > 0 || - aw_points_base_pub_->get_intra_process_subscription_count() > 0) { - const auto autoware_cloud_xyzi = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); - } - if ( - aw_points_ex_pub_->get_subscription_count() > 0 || - aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - const auto autoware_ex_cloud = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); - } - - auto runtime = std::chrono::high_resolution_clock::now() - t_start; - RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); -} - -void HesaiDriverRosWrapper::PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher) -{ - if (pointcloud->header.stamp.sec < 0) { - RCLCPP_WARN_STREAM(this->get_logger(), "Timestamp error, verify clock source."); - } - pointcloud->header.frame_id = sensor_cfg_ptr_->frame_id; - publisher->publish(std::move(pointcloud)); -} - -Status HesaiDriverRosWrapper::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) -{ - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiDriverRosWrapper::InitializeDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration), - std::static_pointer_cast(correction_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiDriverRosWrapper::GetStatus() { return wrapper_status_; } - -Status HesaiDriverRosWrapper::GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration, - drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("calibration_file", "", descriptor); - calibration_configuration.calibration_file = - this->get_parameter("calibration_file").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("min_range", 0.3, descriptor); - sensor_configuration.min_range = this->get_parameter("min_range").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("max_range", 300., descriptor); - sensor_configuration.max_range = this->get_parameter("max_range").as_double(); - } - if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("correction_file", "", descriptor); - correction_file_path = this->get_parameter("correction_file").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = - this->get_parameter("dual_return_distance_threshold").as_double(); - } - bool launch_hw; - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("launch_hw", "", descriptor); - launch_hw = this->get_parameter("launch_hw").as_bool(); - } - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { - return Status::SENSOR_CONFIG_ERROR; - } - - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration); - - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - - bool run_local = !launch_hw; - if (sensor_configuration.sensor_model != drivers::SensorModel::HESAI_PANDARAT128) { - std::string calibration_file_path_from_sensor; - if (launch_hw && !calibration_configuration.calibration_file.empty()) { - int ext_pos = calibration_configuration.calibration_file.find_last_of('.'); - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(0, ext_pos); - calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(ext_pos, calibration_configuration.calibration_file.size() - ext_pos); - } - if(launch_hw) { - run_local = false; - RCLCPP_INFO_STREAM( - this->get_logger(), "Trying to acquire calibration data from sensor: '" - << sensor_configuration.sensor_ip << "'"); - std::future future = std::async(std::launch::async, - [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { - if (hw_interface_.InitializeTcpDriver() == Status::OK) { - auto str = hw_interface_.GetLidarCalibrationString(); - auto rt = calibration_configuration.SaveFileFromString( - calibration_file_path_from_sensor, str); - RCLCPP_ERROR_STREAM(get_logger(), str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromString success:" - << calibration_file_path_from_sensor << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromString failed:" - << calibration_file_path_from_sensor << "\n"); - } - rt = calibration_configuration.LoadFromString(str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), - "LoadFromString success:" << str << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), - "LoadFromString failed:" << str << "\n"); - } - } else { - run_local = true; - } - }); - std::future_status status; - status = future.wait_for(std::chrono::milliseconds(5000)); - if (status == std::future_status::timeout) { - std::cerr << "# std::future_status::timeout\n"; - RCLCPP_ERROR_STREAM(get_logger(), "GetCalibration Timeout"); - run_local = true; - } else if (status == std::future_status::ready && !run_local) { - RCLCPP_INFO_STREAM( - this->get_logger(), "Acquired calibration data from sensor: '" - << sensor_configuration.sensor_ip << "'"); - RCLCPP_INFO_STREAM( - this->get_logger(), "The calibration has been saved in '" - << calibration_file_path_from_sensor << "'"); - } - } - if(run_local) { - RCLCPP_WARN_STREAM(get_logger(), "Running locally"); - bool run_org = false; - if (calibration_file_path_from_sensor.empty()) { - run_org = true; - } else { - RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_file_path_from_sensor); - auto cal_status = - calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); - - if (cal_status != Status::OK) { - run_org = true; - }else{ - RCLCPP_INFO_STREAM( - this->get_logger(), "Load calibration data from: '" - << calibration_file_path_from_sensor << "'"); - } - } - if(run_org) { - RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_configuration.calibration_file); - if (calibration_configuration.calibration_file.empty()) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = - calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); - - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), - "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); - return cal_status; - }else{ - RCLCPP_INFO_STREAM( - this->get_logger(), "Load calibration data from: '" - << calibration_configuration.calibration_file << "'"); - } - } - } - } - } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 - std::string correction_file_path_from_sensor; - if (launch_hw && !correction_file_path.empty()) { - int ext_pos = correction_file_path.find_last_of('.'); - correction_file_path_from_sensor += correction_file_path.substr(0, ext_pos); - correction_file_path_from_sensor += "_from_sensor"; - correction_file_path_from_sensor += correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); - } - std::future future = std::async(std::launch::async, [this, &correction_configuration, &correction_file_path_from_sensor, &run_local, &launch_hw]() { - if (launch_hw && hw_interface_.InitializeTcpDriver() == Status::OK) { - RCLCPP_INFO_STREAM( - this->get_logger(), "Trying to acquire calibration data from sensor"); - auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); - RCLCPP_INFO_STREAM(get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); - auto rt = correction_configuration.SaveFileFromBinary(correction_file_path_from_sensor, received_bytes); - if(rt == Status::OK) - { - RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromBinary failed:" << correction_file_path_from_sensor << ". Falling back to offline calibration file."); - run_local = true; - } - rt = correction_configuration.LoadFromBinary(received_bytes); - if(rt == Status::OK) - { - RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); - run_local = false; - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "LoadFromBinary failed" << ". Falling back to offline calibration file."); - run_local = true; - } - }else{ - RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); - run_local = true; - } - }); - if (!run_local) { - std::future_status status; - status = future.wait_for(std::chrono::milliseconds(8000)); - if (status == std::future_status::timeout) { - std::cerr << "# std::future_status::timeout\n"; - run_local = true; - } else if (status == std::future_status::ready && !run_local) { - RCLCPP_INFO_STREAM( - this->get_logger(), "Acquired correction data from sensor: '" - << sensor_configuration.sensor_ip << "'"); - RCLCPP_INFO_STREAM( - this->get_logger(), "The correction has been saved in '" - << correction_file_path_from_sensor << "'"); - } - } - if(run_local) { - bool run_org = false; - if (correction_file_path_from_sensor.empty()) { - run_org = true; - } else { - auto cal_status = - correction_configuration.LoadFromFile(correction_file_path_from_sensor); - - if (cal_status != Status::OK) { - run_org = true; - }else{ - RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" - << correction_file_path_from_sensor << "'"); - } - } - if(run_org) { - if (correction_file_path.empty()) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Empty Correction File: '" << correction_file_path << "'"); - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = correction_configuration.LoadFromFile(correction_file_path); - - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Given Correction File: '" << correction_file_path << "'"); - return cal_status; - }else{ - RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" - << correction_file_path << "'"); - } - } - } - } - } // end AT128 - // Do not use outside of this location - hw_interface_.~HesaiHwInterface(); - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); - return Status::OK; -} - -RCLCPP_COMPONENTS_REGISTER_NODE(HesaiDriverRosWrapper) -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp deleted file mode 100644 index 1ac59b55b..000000000 --- a/nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp +++ /dev/null @@ -1,510 +0,0 @@ -#include "nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp" - -namespace nebula -{ -namespace ros -{ -HesaiHwInterfaceRosWrapper::HesaiHwInterfaceRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_hw_interface_ros_wrapper", options), hw_interface_() -{ - if (mtx_config_.try_lock()) { - interface_status_ = GetParameters(sensor_configuration_); - mtx_config_.unlock(); - } - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_hw_ms_)); - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); -#if not defined(TEST_PCAP) - Status rt = hw_interface_.InitializeTcpDriver(); - if(this->retry_hw_) - { - int cnt = 0; - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - while(rt == Status::ERROR_1) - { - cnt++; - std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000 - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - rt = hw_interface_.InitializeTcpDriver(); - } - } - - if(rt != Status::ERROR_1){ - try{ - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto result = hw_interface_.GetInventory(); - RCLCPP_INFO_STREAM(get_logger(), result); - hw_interface_.SetTargetModel(result.model); - }); - for (std::thread & th : thread_pool) { - th.join(); - } - - } - catch (...) - { - std::cout << "catch (...) in parent" << std::endl; - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); - } - if (this->setup_sensor) { - hw_interface_.CheckAndSetConfig(); - updateParameters(); - } - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr->sensor_model); - hw_interface_.SetTargetModel(sensor_cfg_ptr->sensor_model); - } -#endif - - hw_interface_.RegisterScanCallback( - std::bind(&HesaiHwInterfaceRosWrapper::ReceiveScanDataCallback, this, std::placeholders::_1)); - pandar_scan_pub_ = - this->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); - -#if not defined(TEST_PCAP) - if (this->setup_sensor) { - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiHwInterfaceRosWrapper::paramCallback, this, std::placeholders::_1)); - } -#endif - -#ifdef WITH_DEBUG_STDOUT_HesaiHwInterfaceRosWrapper - if (false) { - std::vector thread_pool{}; - thread_pool.emplace_back([this] { hw_interface_.SetStandbyMode(0); }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetLidarCalib(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpDiagStatus(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpDiagPort(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpDiagTime(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpDiagGrandmaster(ios); - }); - // thread_pool.emplace_back([&hw_interface_]{ - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetInventory(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetConfig(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetLidarStatus(ios); - }); - thread_pool.emplace_back([this] { hw_interface_.SetStandbyMode(1); }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpConfig(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetLidarRange(ios); - }); - for (std::thread & th : thread_pool) { - // hw_interface_.IOServiceRun(); - th.join(); - } - } - if (false) { - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - std::cout << "GetLidarCalib" << std::endl; - hw_interface_.GetLidarCalib(ios); - }); - for (std::thread & th : thread_pool) { - th.join(); - } - } -#endif - - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); -} - -HesaiHwInterfaceRosWrapper::~HesaiHwInterfaceRosWrapper() { - RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); - hw_interface_.FinalizeTcpDriver(); -} - -Status HesaiHwInterfaceRosWrapper::StreamStart() -{ - if (Status::OK == interface_status_) { - interface_status_ = hw_interface_.SensorInterfaceStart(); - } - return interface_status_; -} - -Status HesaiHwInterfaceRosWrapper::StreamStop() { return Status::OK; } -Status HesaiHwInterfaceRosWrapper::Shutdown() { return Status::OK; } - -Status HesaiHwInterfaceRosWrapper::InitializeHwInterface( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) -{ - std::stringstream ss; - ss << sensor_configuration; - RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); - return Status::OK; -} - -Status HesaiHwInterfaceRosWrapper::GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { - descriptor.additional_constraints = "200, 300, 400, 500"; - range.set__from_value(200).set__to_value(500).set__step(100); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 200, descriptor); - } else { - descriptor.additional_constraints = "300, 600, 1200"; - range.set__from_value(300).set__to_value(1200).set__step(300); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 600, descriptor); - } - sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = - this->get_parameter("dual_return_distance_threshold").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("setup_sensor", true, descriptor); - this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("delay_hw_ms", 0, descriptor); - this->delay_hw_ms_ = this->get_parameter("delay_hw_ms").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("retry_hw", true, descriptor); - this->retry_hw_ = this->get_parameter("retry_hw").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("ptp_profile", ""); - sensor_configuration.ptp_profile = - nebula::drivers::PtpProfileFromString(this->get_parameter("ptp_profile").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("ptp_transport_type", ""); - sensor_configuration.ptp_transport_type = - nebula::drivers::PtpTransportTypeFromString(this->get_parameter("ptp_transport_type").as_string()); - if(static_cast(sensor_configuration.ptp_profile) > 0) { - sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; - } - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("ptp_switch_type", ""); - sensor_configuration.ptp_switch_type = - nebula::drivers::PtpSwitchTypeFromString(this->get_parameter("ptp_switch_type").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(127).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("ptp_domain", 0, descriptor); - sensor_configuration.ptp_domain = this->get_parameter("ptp_domain").as_int(); - } - - if(sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { - RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); - return Status::SENSOR_CONFIG_ERROR; - } - if(sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when using the '1588v2' PTP Profile"); - return Status::SENSOR_CONFIG_ERROR; - } - if(sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); - return Status::SENSOR_CONFIG_ERROR; - } - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { // || - return Status::SENSOR_CONFIG_ERROR; - } - - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); - return Status::OK; -} - -void HesaiHwInterfaceRosWrapper::ReceiveScanDataCallback( - std::unique_ptr scan_buffer) -{ - // Publish - scan_buffer->header.frame_id = sensor_configuration_.frame_id; - scan_buffer->header.stamp = scan_buffer->packets.front().stamp; - pandar_scan_pub_->publish(std::move(scan_buffer)); -} - -rcl_interfaces::msg::SetParametersResult HesaiHwInterfaceRosWrapper::paramCallback( - const std::vector & p) -{ - std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback"); - RCLCPP_DEBUG_STREAM(this->get_logger(), p); - RCLCPP_DEBUG_STREAM(this->get_logger(), sensor_configuration_); - RCLCPP_INFO_STREAM(this->get_logger(), p); - - drivers::HesaiSensorConfiguration new_param{sensor_configuration_}; - RCLCPP_INFO_STREAM(this->get_logger(), new_param); - std::string sensor_model_str; - std::string return_mode_str; - if ( - get_param(p, "sensor_model", sensor_model_str) || - get_param(p, "return_mode", return_mode_str) || get_param(p, "host_ip", new_param.host_ip) || - get_param(p, "sensor_ip", new_param.sensor_ip) || - get_param(p, "frame_id", new_param.frame_id) || - get_param(p, "data_port", new_param.data_port) || - get_param(p, "gnss_port", new_param.gnss_port) || - get_param(p, "scan_phase", new_param.scan_phase) || - get_param(p, "packet_mtu_size", new_param.packet_mtu_size) || - get_param(p, "rotation_speed", new_param.rotation_speed) || - get_param(p, "cloud_min_angle", new_param.cloud_min_angle) || - get_param(p, "cloud_max_angle", new_param.cloud_max_angle) || - get_param(p, "dual_return_distance_threshold", new_param.dual_return_distance_threshold)) { - if (0 < sensor_model_str.length()) - new_param.sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); - if (0 < return_mode_str.length()) - new_param.return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); - - sensor_configuration_ = new_param; - RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - hw_interface_.CheckAndSetConfig(); - } - - auto result = std::make_shared(); - result->successful = true; - result->reason = "success"; - - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback success"); - - return *result; -} - -std::vector HesaiHwInterfaceRosWrapper::updateParameters() -{ - std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters start"); - std::ostringstream os_sensor_model; - os_sensor_model << sensor_configuration_.sensor_model; - std::ostringstream os_return_mode; - os_return_mode << sensor_configuration_.return_mode; - RCLCPP_INFO_STREAM(this->get_logger(), "set_parameters"); - auto results = set_parameters( - {rclcpp::Parameter("sensor_model", os_sensor_model.str()), - rclcpp::Parameter("return_mode", os_return_mode.str()), - rclcpp::Parameter("host_ip", sensor_configuration_.host_ip), - rclcpp::Parameter("sensor_ip", sensor_configuration_.sensor_ip), - rclcpp::Parameter("frame_id", sensor_configuration_.frame_id), - rclcpp::Parameter("data_port", sensor_configuration_.data_port), - rclcpp::Parameter("gnss_port", sensor_configuration_.gnss_port), - rclcpp::Parameter("scan_phase", sensor_configuration_.scan_phase), - rclcpp::Parameter("packet_mtu_size", sensor_configuration_.packet_mtu_size), - rclcpp::Parameter("rotation_speed", sensor_configuration_.rotation_speed), - rclcpp::Parameter("cloud_min_angle", sensor_configuration_.cloud_min_angle), - rclcpp::Parameter("cloud_max_angle", sensor_configuration_.cloud_max_angle), - rclcpp::Parameter( - "dual_return_distance_threshold", sensor_configuration_.dual_return_distance_threshold)}); - RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters end"); - return results; -} - -RCLCPP_COMPONENTS_REGISTER_NODE(HesaiHwInterfaceRosWrapper) -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp deleted file mode 100644 index 85476075e..000000000 --- a/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp +++ /dev/null @@ -1,620 +0,0 @@ -#include "nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp" - -namespace nebula -{ -namespace ros -{ -HesaiHwMonitorRosWrapper::HesaiHwMonitorRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_hw_monitor_ros_wrapper", options), hw_interface_(), diagnostics_updater_(this) -{ - cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); - cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - if (mtx_config_.try_lock()) { - interface_status_ = GetParameters(sensor_configuration_); - mtx_config_.unlock(); - } - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_monitor_ms_)); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - - message_sep = ": "; - not_supported_message = "Not supported"; - error_message = "Error"; - - switch (sensor_cfg_ptr->sensor_model) { - case nebula::drivers::SensorModel::HESAI_PANDARXT32: - case nebula::drivers::SensorModel::HESAI_PANDARXT32M: - case nebula::drivers::SensorModel::HESAI_PANDARAT128: - temperature_names.emplace_back("Bottom circuit board T1"); - temperature_names.emplace_back("Bottom circuit board T2"); - temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); - temperature_names.emplace_back("Laser emitting board RT_L2"); - temperature_names.emplace_back("Receiving board RT_R"); - temperature_names.emplace_back("Receiving board RT2"); - temperature_names.emplace_back("Top circuit RT3"); - temperature_names.emplace_back("Not used"); - break; - case nebula::drivers::SensorModel::HESAI_PANDAR64: - case nebula::drivers::SensorModel::HESAI_PANDAR40P: - case nebula::drivers::SensorModel::HESAI_PANDAR40M: - case nebula::drivers::SensorModel::HESAI_PANDARQT64: - case nebula::drivers::SensorModel::HESAI_PANDARQT128: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: - default: - temperature_names.emplace_back("Bottom circuit RT1"); - temperature_names.emplace_back("Bottom circuit RT2"); - temperature_names.emplace_back("Internal Temperature"); - temperature_names.emplace_back("Laser emitting board RT1"); - temperature_names.emplace_back("Laser emitting board RT2"); - temperature_names.emplace_back("Receiving board RT1"); - temperature_names.emplace_back("Top circuit RT1"); - temperature_names.emplace_back("Top circuit RT2"); - break; - } - - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - while(hw_interface_.InitializeTcpDriver() == Status::ERROR_1) - { - RCLCPP_WARN(this->get_logger(), "Could not initialize TCP driver, retrying in 8s..."); - std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000 - } - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto result = hw_interface_.GetInventory(); - current_inventory.reset(new HesaiInventory(result)); - current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); - RCLCPP_INFO_STREAM(this->get_logger(), "HesaiInventory"); - RCLCPP_INFO_STREAM(this->get_logger(), result); - info_model = result.get_str_model(); - info_serial = std::string(result.sn.begin(), result.sn.end()); - hw_interface_.SetTargetModel(result.model); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); - InitializeHesaiDiagnostics(); - }); - for (std::thread & th : thread_pool) { - th.join(); - } - - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiHwMonitorRosWrapper::paramCallback, this, std::placeholders::_1)); -} - -Status HesaiHwMonitorRosWrapper::MonitorStart() { return interface_status_; } - -Status HesaiHwMonitorRosWrapper::MonitorStop() { return Status::OK; } -Status HesaiHwMonitorRosWrapper::Shutdown() { return Status::OK; } - -Status HesaiHwMonitorRosWrapper::InitializeHwMonitor( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) -{ - std::stringstream ss; - ss << sensor_configuration; - RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); - return Status::OK; -} - -Status HesaiHwMonitorRosWrapper::GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { - descriptor.additional_constraints = "200, 300, 400, 500"; - range.set__from_value(200).set__to_value(500).set__step(100); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 200, descriptor); - } else { - descriptor.additional_constraints = "300, 600, 1200"; - range.set__from_value(300).set__to_value(1200).set__step(300); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 600, descriptor); - } - sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = - this->get_parameter("dual_return_distance_threshold").as_double(); - } - - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { // || - return Status::SENSOR_CONFIG_ERROR; - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("diag_span", 1000, descriptor); - this->diag_span_ = this->get_parameter("diag_span").as_int(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("delay_monitor_ms", 0, descriptor); - this->delay_monitor_ms_ = this->get_parameter("delay_monitor_ms").as_int(); - } - - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); - return Status::OK; -} - -void HesaiHwMonitorRosWrapper::InitializeHesaiDiagnostics() -{ - RCLCPP_INFO_STREAM(this->get_logger(), "InitializeHesaiDiagnostics"); - using std::chrono_literals::operator""s; - std::ostringstream os; - auto hardware_id = info_model + ": " + info_serial; - diagnostics_updater_.setHardwareID(hardware_id); - RCLCPP_INFO_STREAM(this->get_logger(), "hardware_id: " + hardware_id); - - diagnostics_updater_.add("hesai_status", this, &HesaiHwMonitorRosWrapper::HesaiCheckStatus); - diagnostics_updater_.add("hesai_ptp", this, &HesaiHwMonitorRosWrapper::HesaiCheckPtp); - diagnostics_updater_.add( - "hesai_temperature", this, &HesaiHwMonitorRosWrapper::HesaiCheckTemperature); - diagnostics_updater_.add("hesai_rpm", this, &HesaiHwMonitorRosWrapper::HesaiCheckRpm); - - current_status.reset(); - current_monitor.reset(); - current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - - auto fetch_diag_from_sensor = [this](){ - OnHesaiStatusTimer(); - if (hw_interface_.UseHttpGetLidarMonitor()) { - OnHesaiLidarMonitorTimerHttp(); - } else { - OnHesaiLidarMonitorTimer(); - } - }; - - fetch_diagnostics_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); - - if (hw_interface_.UseHttpGetLidarMonitor()) { - diagnostics_updater_.add( - "hesai_voltage", this, &HesaiHwMonitorRosWrapper::HesaiCheckVoltageHttp); - } else { - diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorRosWrapper::HesaiCheckVoltage); - } - - auto on_timer_update = [this] { - RCLCPP_DEBUG_STREAM(get_logger(), "OnUpdateTimer"); - auto now = this->get_clock()->now(); - auto dif = (now - *current_status_time).seconds(); - - RCLCPP_DEBUG_STREAM(get_logger(), "dif(status): " << dif); - - if (diag_span_ * 2.0 < dif * 1000) { - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); - } else { - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); - } - dif = (now - *current_lidar_monitor_time).seconds(); - RCLCPP_DEBUG_STREAM(get_logger(), "dif(monitor): " << dif); - if (diag_span_ * 2.0 < dif * 1000) { - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); - } else { - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); - } - diagnostics_updater_.force_update(); - }; - diagnostics_update_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(1000), std::move(on_timer_update), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(diagnostics_update_timer_, cbg_r_); - - RCLCPP_DEBUG_STREAM(get_logger(), "add_timer"); -} - -std::string HesaiHwMonitorRosWrapper::GetPtreeValue( - boost::property_tree::ptree * pt, const std::string & key) -{ - boost::optional value = pt->get_optional(key); - if (value) { - return value.get(); - } else { - return not_supported_message; - } -} -std::string HesaiHwMonitorRosWrapper::GetFixedPrecisionString(double val, int pre) -{ - std::stringstream ss; - ss << std::fixed << std::setprecision(pre) << val; - return ss.str(); -} - -rcl_interfaces::msg::SetParametersResult HesaiHwMonitorRosWrapper::paramCallback( - const std::vector & p) -{ - std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback"); - RCLCPP_DEBUG_STREAM(get_logger(), p); - RCLCPP_DEBUG_STREAM(get_logger(), sensor_configuration_); - RCLCPP_INFO_STREAM(this->get_logger(), p); - - drivers::HesaiSensorConfiguration new_param{sensor_configuration_}; - RCLCPP_INFO_STREAM(this->get_logger(), new_param); - uint16_t new_diag_span = 0; - if (get_param(p, "diag_span", new_diag_span)) { - sensor_configuration_ = new_param; - RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); - } - - auto result = std::make_shared(); - result->successful = true; - result->reason = "success"; - - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback success"); - return *result; -} - -void HesaiHwMonitorRosWrapper::OnHesaiStatusTimer() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer" << std::endl); - try { - auto ios = std::make_shared(); - auto result = hw_interface_.GetLidarStatus(); - std::scoped_lock lock(mtx_status); - current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_status.reset(new HesaiLidarStatus(result)); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiHwMonitorRosWrapper::OnHesaiStatusTimer(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiHwMonitorRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), - error.what()); - } - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl); -} - -void HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp"); - try { - hw_interface_.GetLidarMonitorAsyncHttp([this](const std::string & str) { - std::scoped_lock lock(mtx_lidar_monitor); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_tree = - std::make_unique(hw_interface_.ParseJson(str)); - }); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_error)"), - error.what()); - } - - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp END"); -} - -void HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer"); - try { - auto ios = std::make_shared(); - auto result = hw_interface_.GetLidarMonitor(); - std::scoped_lock lock(mtx_lidar_monitor); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_monitor.reset(new HesaiLidarMonitor(result)); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), - error.what()); - } - - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END"); -} - -void HesaiHwMonitorRosWrapper::HesaiCheckStatus( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_status); - if (current_status) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - - diagnostics.add("system_uptime", std::to_string(current_status->system_uptime)); - diagnostics.add("startup_times", std::to_string(current_status->startup_times)); - diagnostics.add("total_operation_time", std::to_string(current_status->total_operation_time)); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckPtp( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_status); - if (current_status) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - auto gps_status = current_status->get_str_gps_pps_lock(); - auto gprmc_status = current_status->get_str_gps_gprmc_status(); - auto ptp_status = current_status->get_str_ptp_clock_status(); - std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); - std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); - std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); - diagnostics.add("gps_pps_lock", gps_status); - diagnostics.add("gps_gprmc_status", gprmc_status); - diagnostics.add("ptp_clock_status", ptp_status); - if (gps_status != "UNKNOWN") { - msg.emplace_back("gps_pps_lock: " + gps_status); - } - if (gprmc_status != "UNKNOWN") { - msg.emplace_back("gprmc_status: " + gprmc_status); - } - if (ptp_status != "UNKNOWN") { - msg.emplace_back("ptp_status: " + ptp_status); - } - if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") { - level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - } - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckTemperature( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_status); - if (current_status) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - for (size_t i = 0; i < current_status->temperature.size(); i++) { - diagnostics.add( - temperature_names[i], GetFixedPrecisionString(current_status->temperature[i] * 0.01)); - } - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckRpm( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_status); - if (current_status) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - diagnostics.add("motor_speed", std::to_string(current_status->motor_speed)); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckVoltageHttp( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_monitor); - if (current_lidar_monitor_tree) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - std::string key = ""; - - std::string mes; - key = "lidarInCur"; - try { - mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); - } catch (boost::bad_lexical_cast & ex) { - level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = error_message + std::string(ex.what()); - } - diagnostics.add(key, mes); - key = "lidarInVol"; - try { - mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); - } catch (boost::bad_lexical_cast & ex) { - level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = error_message + std::string(ex.what()); - } - diagnostics.add(key, mes); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckVoltage( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_monitor); - if (current_monitor) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - diagnostics.add( - "input_voltage", GetFixedPrecisionString(current_monitor->input_voltage * 0.01) + " V"); - diagnostics.add( - "input_current", GetFixedPrecisionString(current_monitor->input_current * 0.01) + " mA"); - diagnostics.add( - "input_power", GetFixedPrecisionString(current_monitor->input_power * 0.01) + " W"); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - - HesaiHwMonitorRosWrapper::~HesaiHwMonitorRosWrapper() { - RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); - hw_interface_.FinalizeTcpDriver(); - } - - RCLCPP_COMPONENTS_REGISTER_NODE(HesaiHwMonitorRosWrapper) -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp new file mode 100644 index 000000000..4fc2a12df --- /dev/null +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -0,0 +1,1234 @@ +#include "nebula_ros/hesai/hesai_ros_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ +HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) +: rclcpp::Node("hesai_ros_wrapper", options), hw_interface_(), diagnostics_updater_(this) +{ + setvbuf(stdout, NULL, _IONBF, BUFSIZ); + + drivers::HesaiSensorConfiguration sensor_configuration; + wrapper_status_ = GetParameters(sensor_configuration); + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + + // hwiface +{ + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return; + } + std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_hw_ms_)); + hw_interface_.SetLogger(std::make_shared(this->get_logger())); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); +#if not defined(TEST_PCAP) + Status rt = hw_interface_.InitializeTcpDriver(); + if(this->retry_hw_) + { + int cnt = 0; + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); + while(rt == Status::ERROR_1) + { + cnt++; + std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000 + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); + rt = hw_interface_.InitializeTcpDriver(); + } + } + + if(rt != Status::ERROR_1){ + try{ + std::vector thread_pool{}; + thread_pool.emplace_back([this] { + auto result = hw_interface_.GetInventory(); + RCLCPP_INFO_STREAM(get_logger(), result); + hw_interface_.SetTargetModel(result.model); + }); + for (std::thread & th : thread_pool) { + th.join(); + } + + } + catch (...) + { + std::cout << "catch (...) in parent" << std::endl; + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); + } + if (this->setup_sensor) { + hw_interface_.CheckAndSetConfig(); + updateParameters(); + } + } + else + { + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); + hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); + } +#endif + + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveScanDataCallback, this, std::placeholders::_1)); + pandar_scan_pub_ = + this->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); + +#if not defined(TEST_PCAP) + if (this->setup_sensor) { + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); + } +#endif + + RCLCPP_DEBUG(this->get_logger(), "Starting stream"); + StreamStart(); +} + // decoder + { + drivers::HesaiCalibrationConfiguration calibration_configuration; + drivers::HesaiCorrection correction_configuration; + + wrapper_status_ = + GetCalibrationData(calibration_configuration, correction_configuration); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return; + } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + + calibration_cfg_ptr_ = + std::make_shared(calibration_configuration); + + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { + correction_cfg_ptr_ = std::make_shared(correction_configuration); + wrapper_status_ = InitializeCloudDriver( + std::static_pointer_cast(sensor_cfg_ptr_), + std::static_pointer_cast(calibration_cfg_ptr_), + std::static_pointer_cast(correction_cfg_ptr_)); + } else { + wrapper_status_ = InitializeCloudDriver( + std::static_pointer_cast(sensor_cfg_ptr_), + std::static_pointer_cast(calibration_cfg_ptr_)); + } + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); + rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; + auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), + qos_profile); + pandar_scan_sub_ = create_subscription( + "pandar_packets", qos, + std::bind(&HesaiRosWrapper::ReceiveScanMsgCallback, this, std::placeholders::_1)); + nebula_points_pub_ = + this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); + aw_points_base_pub_ = + this->create_publisher("aw_points", rclcpp::SensorDataQoS()); + aw_points_ex_pub_ = + this->create_publisher("aw_points_ex", rclcpp::SensorDataQoS()); +} + +//hwmon +{ +cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); + cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return; + } + std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_monitor_ms_)); + + message_sep = ": "; + not_supported_message = "Not supported"; + error_message = "Error"; + + switch (sensor_cfg_ptr_->sensor_model) { + case nebula::drivers::SensorModel::HESAI_PANDARXT32: + case nebula::drivers::SensorModel::HESAI_PANDARXT32M: + case nebula::drivers::SensorModel::HESAI_PANDARAT128: + temperature_names.emplace_back("Bottom circuit board T1"); + temperature_names.emplace_back("Bottom circuit board T2"); + temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names.emplace_back("Laser emitting board RT_L2"); + temperature_names.emplace_back("Receiving board RT_R"); + temperature_names.emplace_back("Receiving board RT2"); + temperature_names.emplace_back("Top circuit RT3"); + temperature_names.emplace_back("Not used"); + break; + case nebula::drivers::SensorModel::HESAI_PANDAR64: + case nebula::drivers::SensorModel::HESAI_PANDAR40P: + case nebula::drivers::SensorModel::HESAI_PANDAR40M: + case nebula::drivers::SensorModel::HESAI_PANDARQT64: + case nebula::drivers::SensorModel::HESAI_PANDARQT128: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: + default: + temperature_names.emplace_back("Bottom circuit RT1"); + temperature_names.emplace_back("Bottom circuit RT2"); + temperature_names.emplace_back("Internal Temperature"); + temperature_names.emplace_back("Laser emitting board RT1"); + temperature_names.emplace_back("Laser emitting board RT2"); + temperature_names.emplace_back("Receiving board RT1"); + temperature_names.emplace_back("Top circuit RT1"); + temperature_names.emplace_back("Top circuit RT2"); + break; + } + + std::vector thread_pool{}; + thread_pool.emplace_back([this] { + auto result = hw_interface_.GetInventory(); + current_inventory.reset(new HesaiInventory(result)); + current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); + RCLCPP_INFO_STREAM(this->get_logger(), "HesaiInventory"); + RCLCPP_INFO_STREAM(this->get_logger(), result); + info_model = result.get_str_model(); + info_serial = std::string(result.sn.begin(), result.sn.end()); + hw_interface_.SetTargetModel(result.model); + RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); + RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); + InitializeHesaiDiagnostics(); + }); + for (std::thread & th : thread_pool) { + th.join(); + } + + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); +} +} + +void HesaiRosWrapper::ReceiveScanMsgCallback( + const pandar_msgs::msg::PandarScan::SharedPtr scan_msg) +{ + auto t_start = std::chrono::high_resolution_clock::now(); + std::tuple pointcloud_ts = + driver_ptr_->ConvertScanToPointcloud(scan_msg); + nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + + if (pointcloud == nullptr) { + RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); + return; + }; + if ( + nebula_points_pub_->get_subscription_count() > 0 || + nebula_points_pub_->get_intra_process_subscription_count() > 0) { + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); + } + if ( + aw_points_base_pub_->get_subscription_count() > 0 || + aw_points_base_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_cloud_xyzi = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); + } + if ( + aw_points_ex_pub_->get_subscription_count() > 0 || + aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_ex_cloud = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); + } + + auto runtime = std::chrono::high_resolution_clock::now() - t_start; + RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); +} + +void HesaiRosWrapper::PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher) +{ + if (pointcloud->header.stamp.sec < 0) { + RCLCPP_WARN_STREAM(this->get_logger(), "Timestamp error, verify clock source."); + } + pointcloud->header.frame_id = sensor_cfg_ptr_->frame_id; + publisher->publish(std::move(pointcloud)); +} + +Status HesaiRosWrapper::InitializeCloudDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) +{ + driver_ptr_ = std::make_shared( + std::static_pointer_cast(sensor_configuration), + std::static_pointer_cast(calibration_configuration)); + return driver_ptr_->GetStatus(); +} + +Status HesaiRosWrapper::InitializeCloudDriver( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration, + const std::shared_ptr & correction_configuration) +{ + // driver should be initialized here with proper decoder + driver_ptr_ = std::make_shared( + std::static_pointer_cast(sensor_configuration), + std::static_pointer_cast(calibration_configuration), + std::static_pointer_cast(correction_configuration)); + return driver_ptr_->GetStatus(); +} + +Status HesaiRosWrapper::GetStatus() { return wrapper_status_; } + +/// decoder +Status HesaiRosWrapper::GetParameters( + drivers::HesaiSensorConfiguration & sensor_configuration) +{ + /////////////////////////////////////////////// + // Define and get ROS parameters + /////////////////////////////////////////////// + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_model", ""); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("return_mode", "", descriptor); + sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( + this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("host_ip", "255.255.255.255", descriptor); + sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); + sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("data_port", 2368, descriptor); + sensor_configuration.data_port = this->get_parameter("data_port").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("gnss_port", 2369, descriptor); + sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("frame_id", "pandar", descriptor); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; + rcl_interfaces::msg::FloatingPointRange range; + range.set__from_value(0).set__to_value(360).set__step(0.01); + descriptor.floating_point_range = {range}; + this->declare_parameter("scan_phase", 0., descriptor); + sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("calibration_file", "", descriptor); + calibration_file_path = + this->get_parameter("calibration_file").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("min_range", 0.3, descriptor); + sensor_configuration.min_range = this->get_parameter("min_range").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("max_range", 300., descriptor); + sensor_configuration.max_range = this->get_parameter("max_range").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("packet_mtu_size", 1500, descriptor); + sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); + } + + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + rcl_interfaces::msg::IntegerRange range; + RCLCPP_DEBUG_STREAM(get_logger(), sensor_configuration.sensor_model); + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { + descriptor.additional_constraints = "200, 300, 400, 500"; + // range.set__from_value(200).set__to_value(500).set__step(100); + // descriptor.integer_range = {range}; //todo + this->declare_parameter("rotation_speed", 200, descriptor); + } else { + descriptor.additional_constraints = "300, 600, 1200"; + // range.set__from_value(300).set__to_value(1200).set__step(300); + // descriptor.integer_range = {range}; //todo + this->declare_parameter("rotation_speed", 600, descriptor); + } + sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + rcl_interfaces::msg::IntegerRange range; + range.set__from_value(0).set__to_value(360).set__step(1); + descriptor.integer_range = {range}; + this->declare_parameter("cloud_min_angle", 0, descriptor); + sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + rcl_interfaces::msg::IntegerRange range; + range.set__from_value(0).set__to_value(360).set__step(1); + descriptor.integer_range = {range}; + this->declare_parameter("cloud_max_angle", 360, descriptor); + sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); + } + if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("correction_file", "", descriptor); + correction_file_path = this->get_parameter("correction_file").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; + rcl_interfaces::msg::FloatingPointRange range; + range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); + descriptor.floating_point_range = {range}; + this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); + sensor_configuration.dual_return_distance_threshold = + this->get_parameter("dual_return_distance_threshold").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("launch_hw", "", descriptor); + launch_hw_ = this->get_parameter("launch_hw").as_bool(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("setup_sensor", true, descriptor); + this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); + } + + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + this->declare_parameter("delay_hw_ms", 0, descriptor); + this->delay_hw_ms_ = this->get_parameter("delay_hw_ms").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("retry_hw", true, descriptor); + this->retry_hw_ = this->get_parameter("retry_hw").as_bool(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("ptp_profile", ""); + sensor_configuration.ptp_profile = + nebula::drivers::PtpProfileFromString(this->get_parameter("ptp_profile").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("ptp_transport_type", ""); + sensor_configuration.ptp_transport_type = + nebula::drivers::PtpTransportTypeFromString(this->get_parameter("ptp_transport_type").as_string()); + if(static_cast(sensor_configuration.ptp_profile) > 0) { + sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; + } + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("ptp_switch_type", ""); + sensor_configuration.ptp_switch_type = + nebula::drivers::PtpSwitchTypeFromString(this->get_parameter("ptp_switch_type").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + rcl_interfaces::msg::IntegerRange range; + range.set__from_value(0).set__to_value(127).set__step(1); + descriptor.integer_range = {range}; + this->declare_parameter("ptp_domain", 0, descriptor); + sensor_configuration.ptp_domain = this->get_parameter("ptp_domain").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + this->declare_parameter("diag_span", 1000, descriptor); + this->diag_span_ = this->get_parameter("diag_span").as_int(); + } + + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + this->declare_parameter("delay_monitor_ms", 0, descriptor); + this->delay_monitor_ms_ = this->get_parameter("delay_monitor_ms").as_int(); + } + + /////////////////////////////////////////////// + // Validate ROS parameters + /////////////////////////////////////////////// + + if(sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { + RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); + return Status::SENSOR_CONFIG_ERROR; + } + if(sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { + RCLCPP_ERROR_STREAM(get_logger(), + "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when using the '1588v2' PTP Profile"); + return Status::SENSOR_CONFIG_ERROR; + } + if(sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { + RCLCPP_ERROR_STREAM(get_logger(), + "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); + return Status::SENSOR_CONFIG_ERROR; + } + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + return Status::INVALID_SENSOR_MODEL; + } + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + return Status::INVALID_ECHO_MODE; + } + if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { + return Status::SENSOR_CONFIG_ERROR; + } + + /////////////////////////////////////////////// + // Decoder-specific setup + /////////////////////////////////////////////// + + std::shared_ptr sensor_cfg_ptr = + std::make_shared(sensor_configuration); + + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr)); + + /////////////////////////////////////////////// + // HW Interface specific setup + /////////////////////////////////////////////// + + /////////////////////////////////////////////// + // HW Monitor specific setup + /////////////////////////////////////////////// + + RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + return Status::OK; +} + +Status HesaiRosWrapper::GetCalibrationData( + drivers::HesaiCalibrationConfiguration & calibration_configuration, + drivers::HesaiCorrection & correction_configuration) { + calibration_configuration.calibration_file = calibration_file_path; //todo + + bool run_local = !launch_hw_; + if (sensor_cfg_ptr_->sensor_model != drivers::SensorModel::HESAI_PANDARAT128) { + std::string calibration_file_path_from_sensor; + if (launch_hw_ && !calibration_configuration.calibration_file.empty()) { + int ext_pos = calibration_configuration.calibration_file.find_last_of('.'); + calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(0, ext_pos); + calibration_file_path_from_sensor += "_from_sensor"; + calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(ext_pos, calibration_configuration.calibration_file.size() - ext_pos); + } + if(launch_hw_) { + run_local = false; + RCLCPP_INFO_STREAM( + this->get_logger(), "Trying to acquire calibration data from sensor: '" + << sensor_cfg_ptr_->sensor_ip << "'"); + std::future future = std::async(std::launch::async, + [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { + auto str = hw_interface_.GetLidarCalibrationString(); + auto rt = calibration_configuration.SaveFileFromString( + calibration_file_path_from_sensor, str); + RCLCPP_ERROR_STREAM(get_logger(), str); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromString success:" + << calibration_file_path_from_sensor << "\n"); + } else { + RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromString failed:" + << calibration_file_path_from_sensor << "\n"); + } + rt = calibration_configuration.LoadFromString(str); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM(get_logger(), + "LoadFromString success:" << str << "\n"); + } else { + RCLCPP_ERROR_STREAM(get_logger(), + "LoadFromString failed:" << str << "\n"); + } + }); + std::future_status status; + status = future.wait_for(std::chrono::milliseconds(5000)); + if (status == std::future_status::timeout) { + std::cerr << "# std::future_status::timeout\n"; + RCLCPP_ERROR_STREAM(get_logger(), "GetCalibration Timeout"); + run_local = true; + } else if (status == std::future_status::ready && !run_local) { + RCLCPP_INFO_STREAM( + this->get_logger(), "Acquired calibration data from sensor: '" + << sensor_cfg_ptr_->sensor_ip << "'"); + RCLCPP_INFO_STREAM( + this->get_logger(), "The calibration has been saved in '" + << calibration_file_path_from_sensor << "'"); + } + } + if(run_local) { + RCLCPP_WARN_STREAM(get_logger(), "Running locally"); + bool run_org = false; + if (calibration_file_path_from_sensor.empty()) { + run_org = true; + } else { + RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_file_path_from_sensor); + auto cal_status = + calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); + + if (cal_status != Status::OK) { + run_org = true; + }else{ + RCLCPP_INFO_STREAM( + this->get_logger(), "Load calibration data from: '" + << calibration_file_path_from_sensor << "'"); + } + } + if(run_org) { + RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_configuration.calibration_file); + if (calibration_configuration.calibration_file.empty()) { + RCLCPP_ERROR_STREAM( + this->get_logger(), "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); + return Status::INVALID_CALIBRATION_FILE; + } else { + auto cal_status = + calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); + + if (cal_status != Status::OK) { + RCLCPP_ERROR_STREAM( + this->get_logger(), + "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); + return cal_status; + }else{ + RCLCPP_INFO_STREAM( + this->get_logger(), "Load calibration data from: '" + << calibration_configuration.calibration_file << "'"); + } + } + } + } + } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 + std::string correction_file_path_from_sensor; + if (launch_hw_ && !correction_file_path.empty()) { + int ext_pos = correction_file_path.find_last_of('.'); + correction_file_path_from_sensor += correction_file_path.substr(0, ext_pos); + correction_file_path_from_sensor += "_from_sensor"; + correction_file_path_from_sensor += correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); + } + std::future future = std::async(std::launch::async, [this, &correction_configuration, &correction_file_path_from_sensor, &run_local]() { + if (launch_hw_) { + RCLCPP_INFO_STREAM( + this->get_logger(), "Trying to acquire calibration data from sensor"); + auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); + RCLCPP_INFO_STREAM(get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); + auto rt = correction_configuration.SaveFileFromBinary(correction_file_path_from_sensor, received_bytes); + if(rt == Status::OK) + { + RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); + } + else + { + RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromBinary failed:" << correction_file_path_from_sensor << ". Falling back to offline calibration file."); + run_local = true; + } + rt = correction_configuration.LoadFromBinary(received_bytes); + if(rt == Status::OK) + { + RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); + run_local = false; + } + else + { + RCLCPP_ERROR_STREAM(get_logger(), "LoadFromBinary failed" << ". Falling back to offline calibration file."); + run_local = true; + } + }else{ + RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); + run_local = true; + } + }); + if (!run_local) { + std::future_status status; + status = future.wait_for(std::chrono::milliseconds(8000)); + if (status == std::future_status::timeout) { + std::cerr << "# std::future_status::timeout\n"; + run_local = true; + } else if (status == std::future_status::ready && !run_local) { + RCLCPP_INFO_STREAM( + this->get_logger(), "Acquired correction data from sensor: '" + << sensor_cfg_ptr_->sensor_ip << "'"); + RCLCPP_INFO_STREAM( + this->get_logger(), "The correction has been saved in '" + << correction_file_path_from_sensor << "'"); + } + } + if(run_local) { + bool run_org = false; + if (correction_file_path_from_sensor.empty()) { + run_org = true; + } else { + auto cal_status = + correction_configuration.LoadFromFile(correction_file_path_from_sensor); + + if (cal_status != Status::OK) { + run_org = true; + }else{ + RCLCPP_INFO_STREAM( + this->get_logger(), "Load correction data from: '" + << correction_file_path_from_sensor << "'"); + } + } + if(run_org) { + if (correction_file_path.empty()) { + RCLCPP_ERROR_STREAM( + this->get_logger(), "Empty Correction File: '" << correction_file_path << "'"); + return Status::INVALID_CALIBRATION_FILE; + } else { + auto cal_status = correction_configuration.LoadFromFile(correction_file_path); + + if (cal_status != Status::OK) { + RCLCPP_ERROR_STREAM( + this->get_logger(), "Given Correction File: '" << correction_file_path << "'"); + return cal_status; + }else{ + RCLCPP_INFO_STREAM( + this->get_logger(), "Load correction data from: '" + << correction_file_path << "'"); + } + } + } + } + } // end AT128 + + return Status::OK; + } + +HesaiRosWrapper::~HesaiRosWrapper() { + RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); + hw_interface_.FinalizeTcpDriver(); +} + +Status HesaiRosWrapper::StreamStart() +{ + if (Status::OK == interface_status_) { + interface_status_ = hw_interface_.CloudInterfaceStart(); + } + return interface_status_; +} + +Status HesaiRosWrapper::StreamStop() { return Status::OK; } +Status HesaiRosWrapper::Shutdown() { return Status::OK; } + +Status HesaiRosWrapper::InitializeHwInterface( // todo: don't think this is needed + const drivers::SensorConfigurationBase & sensor_configuration) +{ + std::stringstream ss; + ss << sensor_configuration; + RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); + return Status::OK; +} + +Status HesaiRosWrapper::InitializeHwMonitor( // todo: don't think this is needed + const drivers::SensorConfigurationBase & sensor_configuration) +{ + return Status::OK; +} + +void HesaiRosWrapper::ReceiveScanDataCallback( + std::unique_ptr scan_buffer) +{ + // Publish + scan_buffer->header.frame_id = sensor_cfg_ptr_->frame_id; + scan_buffer->header.stamp = scan_buffer->packets.front().stamp; + pandar_scan_pub_->publish(std::move(scan_buffer)); +} + +rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( + const std::vector & p) +{ + std::scoped_lock lock(mtx_config_); + RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback"); + RCLCPP_DEBUG_STREAM(this->get_logger(), p); + RCLCPP_DEBUG_STREAM(this->get_logger(), *sensor_cfg_ptr_); + RCLCPP_INFO_STREAM(this->get_logger(), p); + + std::shared_ptr new_param = + std::make_shared(*sensor_cfg_ptr_); + RCLCPP_INFO_STREAM(this->get_logger(), new_param); + std::string sensor_model_str; + std::string return_mode_str; + if ( + get_param(p, "sensor_model", sensor_model_str) | + get_param(p, "return_mode", return_mode_str) | + get_param(p, "host_ip", new_param->host_ip) | + get_param(p, "sensor_ip", new_param->sensor_ip) | + get_param(p, "frame_id", new_param->frame_id) | + get_param(p, "data_port", new_param->data_port) | + get_param(p, "gnss_port", new_param->gnss_port) | + get_param(p, "scan_phase", new_param->scan_phase) | + get_param(p, "packet_mtu_size", new_param->packet_mtu_size) | + get_param(p, "rotation_speed", new_param->rotation_speed) | + get_param(p, "cloud_min_angle", new_param->cloud_min_angle) | + get_param(p, "cloud_max_angle", new_param->cloud_max_angle) | + get_param(p, "dual_return_distance_threshold", new_param->dual_return_distance_threshold)) { + if (0 < sensor_model_str.length()) + new_param->sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); + if (0 < return_mode_str.length()) + new_param->return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); + + sensor_cfg_ptr_.swap(new_param); + RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); + RCLCPP_DEBUG_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); + hw_interface_.CheckAndSetConfig(); + } + + auto result = std::make_shared(); + result->successful = true; + result->reason = "success"; + + RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback success"); + + return *result; +} + +std::vector HesaiRosWrapper::updateParameters() +{ + std::scoped_lock lock(mtx_config_); + RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters start"); + std::ostringstream os_sensor_model; + os_sensor_model << sensor_cfg_ptr_->sensor_model; + std::ostringstream os_return_mode; + os_return_mode << sensor_cfg_ptr_->return_mode; + RCLCPP_INFO_STREAM(this->get_logger(), "set_parameters"); + auto results = set_parameters( + {rclcpp::Parameter("sensor_model", os_sensor_model.str()), + rclcpp::Parameter("return_mode", os_return_mode.str()), + rclcpp::Parameter("host_ip", sensor_cfg_ptr_->host_ip), + rclcpp::Parameter("sensor_ip", sensor_cfg_ptr_->sensor_ip), + rclcpp::Parameter("frame_id", sensor_cfg_ptr_->frame_id), + rclcpp::Parameter("data_port", sensor_cfg_ptr_->data_port), + rclcpp::Parameter("gnss_port", sensor_cfg_ptr_->gnss_port), + rclcpp::Parameter("scan_phase", sensor_cfg_ptr_->scan_phase), + rclcpp::Parameter("packet_mtu_size", sensor_cfg_ptr_->packet_mtu_size), + rclcpp::Parameter("rotation_speed", sensor_cfg_ptr_->rotation_speed), + rclcpp::Parameter("cloud_min_angle", sensor_cfg_ptr_->cloud_min_angle), + rclcpp::Parameter("cloud_max_angle", sensor_cfg_ptr_->cloud_max_angle), + rclcpp::Parameter( + "dual_return_distance_threshold", sensor_cfg_ptr_->dual_return_distance_threshold)}); + RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters end"); + return results; +} + +void HesaiRosWrapper::InitializeHesaiDiagnostics() +{ + RCLCPP_INFO_STREAM(this->get_logger(), "InitializeHesaiDiagnostics"); + using std::chrono_literals::operator""s; + std::ostringstream os; + auto hardware_id = info_model + ": " + info_serial; + diagnostics_updater_.setHardwareID(hardware_id); + RCLCPP_INFO_STREAM(this->get_logger(), "hardware_id: " + hardware_id); + + diagnostics_updater_.add("hesai_status", this, &HesaiRosWrapper::HesaiCheckStatus); + diagnostics_updater_.add("hesai_ptp", this, &HesaiRosWrapper::HesaiCheckPtp); + diagnostics_updater_.add( + "hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); + diagnostics_updater_.add("hesai_rpm", this, &HesaiRosWrapper::HesaiCheckRpm); + + current_status.reset(); + current_monitor.reset(); + current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + + auto fetch_diag_from_sensor = [this](){ + OnHesaiStatusTimer(); + if (hw_interface_.UseHttpGetLidarMonitor()) { + OnHesaiLidarMonitorTimerHttp(); + } else { + OnHesaiLidarMonitorTimer(); + } + }; + + fetch_diagnostics_timer_ = std::make_shared>( + this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); + + if (hw_interface_.UseHttpGetLidarMonitor()) { + diagnostics_updater_.add( + "hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); + } else { + diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltage); + } + + auto on_timer_update = [this] { + RCLCPP_DEBUG_STREAM(get_logger(), "OnUpdateTimer"); + auto now = this->get_clock()->now(); + auto dif = (now - *current_status_time).seconds(); + + RCLCPP_DEBUG_STREAM(get_logger(), "dif(status): " << dif); + + if (diag_span_ * 2.0 < dif * 1000) { + current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); + } else { + current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(get_logger(), "OK"); + } + dif = (now - *current_lidar_monitor_time).seconds(); + RCLCPP_DEBUG_STREAM(get_logger(), "dif(monitor): " << dif); + if (diag_span_ * 2.0 < dif * 1000) { + current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); + } else { + current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(get_logger(), "OK"); + } + diagnostics_updater_.force_update(); + }; + diagnostics_update_timer_ = std::make_shared>( + this->get_clock(), std::chrono::milliseconds(1000), std::move(on_timer_update), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(diagnostics_update_timer_, cbg_r_); + + RCLCPP_DEBUG_STREAM(get_logger(), "add_timer"); +} + +std::string HesaiRosWrapper::GetPtreeValue( + boost::property_tree::ptree * pt, const std::string & key) +{ + boost::optional value = pt->get_optional(key); + if (value) { + return value.get(); + } else { + return not_supported_message; + } +} +std::string HesaiRosWrapper::GetFixedPrecisionString(double val, int pre) +{ + std::stringstream ss; + ss << std::fixed << std::setprecision(pre) << val; + return ss.str(); +} + +void HesaiRosWrapper::OnHesaiStatusTimer() +{ + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer" << std::endl); + try { + auto result = hw_interface_.GetLidarStatus(); + std::scoped_lock lock(mtx_status); + current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_status.reset(new HesaiLidarStatus(result)); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl); +} + +void HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp() +{ + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp"); + try { + hw_interface_.GetLidarMonitorAsyncHttp([this](const std::string & str) { + std::scoped_lock lock(mtx_lidar_monitor); + current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_lidar_monitor_tree = + std::make_unique(hw_interface_.ParseJson(str)); + }); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp END"); +} + +void HesaiRosWrapper::OnHesaiLidarMonitorTimer() +{ + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer"); + try { + auto ios = std::make_shared(); + auto result = hw_interface_.GetLidarMonitor(); + std::scoped_lock lock(mtx_lidar_monitor); + current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_monitor.reset(new HesaiLidarMonitor(result)); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END"); +} + +void HesaiRosWrapper::HesaiCheckStatus( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_status); + if (current_status) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + + diagnostics.add("system_uptime", std::to_string(current_status->system_uptime)); + diagnostics.add("startup_times", std::to_string(current_status->startup_times)); + diagnostics.add("total_operation_time", std::to_string(current_status->total_operation_time)); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckPtp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_status); + if (current_status) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + auto gps_status = current_status->get_str_gps_pps_lock(); + auto gprmc_status = current_status->get_str_gps_gprmc_status(); + auto ptp_status = current_status->get_str_ptp_clock_status(); + std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); + std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); + std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); + diagnostics.add("gps_pps_lock", gps_status); + diagnostics.add("gps_gprmc_status", gprmc_status); + diagnostics.add("ptp_clock_status", ptp_status); + if (gps_status != "UNKNOWN") { + msg.emplace_back("gps_pps_lock: " + gps_status); + } + if (gprmc_status != "UNKNOWN") { + msg.emplace_back("gprmc_status: " + gprmc_status); + } + if (ptp_status != "UNKNOWN") { + msg.emplace_back("ptp_status: " + ptp_status); + } + if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") { + level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + } + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckTemperature( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_status); + if (current_status) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + for (size_t i = 0; i < current_status->temperature.size(); i++) { + diagnostics.add( + temperature_names[i], GetFixedPrecisionString(current_status->temperature[i] * 0.01)); + } + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckRpm( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_status); + if (current_status) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + diagnostics.add("motor_speed", std::to_string(current_status->motor_speed)); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckVoltageHttp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_lidar_monitor); + if (current_lidar_monitor_tree) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + std::string key = ""; + + std::string mes; + key = "lidarInCur"; + try { + mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); + } catch (boost::bad_lexical_cast & ex) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = error_message + std::string(ex.what()); + } + diagnostics.add(key, mes); + key = "lidarInVol"; + try { + mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); + } catch (boost::bad_lexical_cast & ex) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = error_message + std::string(ex.what()); + } + diagnostics.add(key, mes); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckVoltage( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_lidar_monitor); + if (current_monitor) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + diagnostics.add( + "input_voltage", GetFixedPrecisionString(current_monitor->input_voltage * 0.01) + " V"); + diagnostics.add( + "input_current", GetFixedPrecisionString(current_monitor->input_current * 0.01) + " mA"); + diagnostics.add( + "input_power", GetFixedPrecisionString(current_monitor->input_power * 0.01) + " W"); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + + RCLCPP_COMPONENTS_REGISTER_NODE(HesaiRosWrapper) +} // namespace ros +} // namespace nebula From f99755538dbb1c05bb7e1e167d2bcc67dfcd8739 Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Thu, 21 Mar 2024 18:34:02 +0900 Subject: [PATCH 004/122] refactor: remove pandarScan pub/sub, decode one packet at a time --- .../decoders/hesai_decoder.hpp | 14 +++--- .../decoders/hesai_scan_decoder.hpp | 4 +- .../nebula_decoders_hesai/hesai_driver.hpp | 4 +- .../nebula_decoders_hesai/hesai_driver.cpp | 25 +++++----- .../hesai_hw_interface.hpp | 6 +-- .../hesai_hw_interface.cpp | 48 ++----------------- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 6 +-- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 29 +++++------ 8 files changed, 41 insertions(+), 95 deletions(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index b81b45d44..8f28856e8 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -52,17 +52,17 @@ class HesaiDecoder : public HesaiScanDecoder block_firing_offset_ns_; /// @brief Validates and parse PandarPacket. Currently only checks size, not checksums etc. - /// @param pandar_packet The incoming PandarPacket + /// @param packet The incoming PandarPacket /// @return Whether the packet was parsed successfully - bool parsePacket(const pandar_msgs::msg::PandarPacket & pandar_packet) + bool parsePacket(const std::vector & packet) { - if (pandar_packet.size < sizeof(typename SensorT::packet_t)) { + if (packet.size() < sizeof(typename SensorT::packet_t)) { RCLCPP_ERROR_STREAM( - logger_, "Packet size mismatch:" << pandar_packet.size << " | Expected at least:" + logger_, "Packet size mismatch:" << packet.size() << " | Expected at least:" << sizeof(typename SensorT::packet_t)); return false; } - if (std::memcpy(&packet_, pandar_packet.data.data(), sizeof(typename SensorT::packet_t))) { + if (std::memcpy(&packet_, packet.data(), sizeof(typename SensorT::packet_t))) { // FIXME(mojomex) do validation? // RCLCPP_DEBUG(logger_, "Packet parsed successfully"); return true; @@ -222,9 +222,9 @@ class HesaiDecoder : public HesaiScanDecoder output_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); } - int unpack(const pandar_msgs::msg::PandarPacket & pandar_packet) override + int unpack(const std::vector & packet) override { - if (!parsePacket(pandar_packet)) { + if (!parsePacket(packet)) { return -1; } diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp index f0b4e3f8b..9d06c2702 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp @@ -26,9 +26,9 @@ class HesaiScanDecoder HesaiScanDecoder() = default; /// @brief Parses PandarPacket and add its points to the point cloud - /// @param pandar_packet The incoming PandarPacket + /// @param packet The incoming PandarPacket /// @return The last azimuth processed - virtual int unpack(const pandar_msgs::msg::PandarPacket & pandar_packet) = 0; + virtual int unpack(const std::vector & packet) = 0; /// @brief Indicates whether one full scan is ready /// @return Whether a scan is ready diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index c83788965..a3f37cd32 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -54,8 +54,8 @@ class HesaiDriver : NebulaDriverBase /// @brief Convert PandarScan message to point cloud /// @param pandar_scan Message /// @return tuple of Point cloud and timestamp - std::tuple ConvertScanToPointcloud( - const std::shared_ptr & pandar_scan); + std::tuple ParseCloudPacket( + const std::vector & packet); }; } // namespace drivers diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index 49be4adac..61b969ed7 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -72,8 +72,8 @@ HesaiDriver::HesaiDriver( } } -std::tuple HesaiDriver::ConvertScanToPointcloud( - const std::shared_ptr & pandar_scan) +std::tuple HesaiDriver::ParseCloudPacket( + const std::vector & packet) { std::tuple pointcloud; auto logger = rclcpp::get_logger("HesaiDriver"); @@ -83,20 +83,17 @@ std::tuple HesaiDriver::ConvertScanToPoint return pointcloud; } - int cnt = 0, last_azimuth = 0; - for (auto & packet : pandar_scan->packets) { - last_azimuth = scan_decoder_->unpack(packet); - if (scan_decoder_->hasScanned()) { - pointcloud = scan_decoder_->getPointcloud(); - cnt++; - } + scan_decoder_->unpack(packet); + if (scan_decoder_->hasScanned()) { + pointcloud = scan_decoder_->getPointcloud(); } - if (cnt == 0) { - RCLCPP_ERROR_STREAM( - logger, "Scanned " << pandar_scan->packets.size() << " packets, but no " - << "pointclouds were generated. Last azimuth: " << last_azimuth); - } + // todo + // if (cnt == 0) { + // RCLCPP_ERROR_STREAM( + // logger, "Scanned " << pandar_scan->packets.size() << " packets, but no " + // << "pointclouds were generated. Last azimuth: " << last_azimuth); + // } return pointcloud; } diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index 2f5639373..f65daf077 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -102,8 +102,8 @@ class HesaiHwInterface : NebulaHwInterfaceBase std::unique_ptr scan_cloud_ptr_; std::function is_valid_packet_; /*Lambda Function Array to verify proper packet size*/ - std::function buffer)> - scan_reception_callback_; /**This function pointer is called when the scan is complete*/ + std::function & buffer)> + cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ int prev_phase_{}; @@ -192,7 +192,7 @@ class HesaiHwInterface : NebulaHwInterfaceBase /// @param scan_callback Callback function /// @return Resulting status Status RegisterScanCallback( - std::function)> scan_callback); + std::function &)> scan_callback); /// @brief Getting data with PTC_COMMAND_GET_LIDAR_CALIBRATION /// @return Resulting status std::string GetLidarCalibrationString(); diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index a5e5bd068..bf3060afc 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -218,61 +218,19 @@ Status HesaiHwInterface::SensorInterfaceStart() } Status HesaiHwInterface::RegisterScanCallback( - std::function)> scan_callback) + std::function &)> scan_callback) { - scan_reception_callback_ = std::move(scan_callback); + cloud_packet_callback_ = std::move(scan_callback); return Status::OK; } void HesaiHwInterface::ReceiveSensorPacketCallback(const std::vector & buffer) { - int scan_phase = static_cast(sensor_configuration_->scan_phase * 100.0); if (!is_valid_packet_(buffer.size())) { PrintDebug("Invalid Packet: " + std::to_string(buffer.size())); return; } - const uint32_t buffer_size = buffer.size(); - pandar_msgs::msg::PandarPacket pandar_packet; - std::copy_n(std::make_move_iterator(buffer.begin()), buffer_size, pandar_packet.data.begin()); - pandar_packet.size = buffer_size; - auto now = std::chrono::system_clock::now(); - auto now_secs = std::chrono::duration_cast(now.time_since_epoch()).count(); - auto now_nanosecs = - std::chrono::duration_cast(now.time_since_epoch()).count(); - pandar_packet.stamp.sec = static_cast(now_secs); - pandar_packet.stamp.nanosec = static_cast(now_nanosecs % 1'000'000'000); - scan_cloud_ptr_->packets.emplace_back(pandar_packet); - - int current_phase = 0; - bool comp_flg = false; - - const auto & data = scan_cloud_ptr_->packets.back().data; - current_phase = (data[azimuth_index_] & 0xff) + ((data[azimuth_index_ + 1] & 0xff) << 8); - if (is_solid_state) { - current_phase = (static_cast(current_phase) + 36000 - 0) % 12000; - if (current_phase >= prev_phase_ || scan_cloud_ptr_->packets.size() < 2) { - prev_phase_ = current_phase; - } else { - comp_flg = true; - } - } else { - current_phase = (static_cast(current_phase) + 36000 - scan_phase) % 36000; - - if (current_phase >= prev_phase_ || scan_cloud_ptr_->packets.size() < 2) { - prev_phase_ = current_phase; - } else { - comp_flg = true; - } - } - - if (comp_flg) { // Scan complete - if (scan_reception_callback_) { - scan_cloud_ptr_->header.stamp = scan_cloud_ptr_->packets.front().stamp; - // Callback - scan_reception_callback_(std::move(scan_cloud_ptr_)); - scan_cloud_ptr_ = std::make_unique(); - } - } + cloud_packet_callback_(buffer); } Status HesaiHwInterface::SensorInterfaceStop() { diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index f23d1f9c4..adce54b8f 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -57,10 +57,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); ~HesaiRosWrapper(); - /// @brief Callback for PandarScan subscriber - /// @param scan_msg Received PandarScan - void ReceiveScanMsgCallback(const pandar_msgs::msg::PandarScan::SharedPtr scan_msg); - /// @brief Get current status of this driver /// @return Current status Status GetStatus(); @@ -133,7 +129,7 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase const drivers::SensorConfigurationBase & sensor_configuration) override; /// @brief Callback for receiving PandarScan /// @param scan_buffer Received PandarScan - void ReceiveScanDataCallback(std::unique_ptr scan_buffer); + void ReceiveCloudPacketCallback(const std::vector & scan_buffer); /// @brief rclcpp parameter callback /// @param parameters Received parameters diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 4fc2a12df..b809bccf8 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -69,7 +69,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) #endif hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveScanDataCallback, this, std::placeholders::_1)); + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); pandar_scan_pub_ = this->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); @@ -117,9 +117,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - pandar_scan_sub_ = create_subscription( - "pandar_packets", qos, - std::bind(&HesaiRosWrapper::ReceiveScanMsgCallback, this, std::placeholders::_1)); + nebula_points_pub_ = this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); aw_points_base_pub_ = @@ -198,16 +196,22 @@ cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); } } -void HesaiRosWrapper::ReceiveScanMsgCallback( - const pandar_msgs::msg::PandarScan::SharedPtr scan_msg) +void HesaiRosWrapper::ReceiveCloudPacketCallback( + const std::vector & packet) { + // Driver is not initialized yet + if (!driver_ptr_) { + return; + } + auto t_start = std::chrono::high_resolution_clock::now(); std::tuple pointcloud_ts = - driver_ptr_->ConvertScanToPointcloud(scan_msg); + driver_ptr_->ParseCloudPacket(packet); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); if (pointcloud == nullptr) { - RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); + // todo + // RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); return; }; if ( @@ -845,15 +849,6 @@ Status HesaiRosWrapper::InitializeHwMonitor( // todo: don't think this is neede return Status::OK; } -void HesaiRosWrapper::ReceiveScanDataCallback( - std::unique_ptr scan_buffer) -{ - // Publish - scan_buffer->header.frame_id = sensor_cfg_ptr_->frame_id; - scan_buffer->header.stamp = scan_buffer->packets.front().stamp; - pandar_scan_pub_->publish(std::move(scan_buffer)); -} - rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( const std::vector & p) { From 39d050cff12b3e7b3ed4fd39e34b22d204f8c710 Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Tue, 26 Mar 2024 16:31:25 +0900 Subject: [PATCH 005/122] reword later --- nebula_ros/CMakeLists.txt | 1 + .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 28 +- nebula_ros/launch/hesai_launch_all_hw.xml | 4 - nebula_ros/package.xml | 1 + nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 557 +++++++++--------- scripts/plot_times.py | 7 +- 6 files changed, 309 insertions(+), 289 deletions(-) diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index 18ce06aad..1bd697624 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -23,6 +23,7 @@ find_package(nebula_decoders REQUIRED) find_package(nebula_hw_interfaces REQUIRED) find_package(yaml-cpp REQUIRED) find_package(robosense_msgs REQUIRED) +find_package(nebula_msgs REQUIRED) include_directories( include diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index adce54b8f..004c717cd 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -15,8 +15,7 @@ #include #include -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" +#include "nebula_msgs/msg/nebula_packet.hpp" #include #include @@ -72,23 +71,21 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase Status Shutdown() override; private: - /// @brief Initializing ros wrapper + /// @brief Initialize pointcloud decoder /// @param sensor_configuration SensorConfiguration for this driver /// @param calibration_configuration CalibrationConfiguration for this driver - /// @return Resulting status - Status InitializeCloudDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Initializing ros wrapper for AT - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver + /// @param correction_configuration CorrectionConfiguration for this driver (only for AT128, ignored otherwise) /// @return Resulting status Status InitializeCloudDriver( const std::shared_ptr & sensor_configuration, const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration); + const std::shared_ptr & correction_configuration = nullptr); + + Status InitializeCloudDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) { + return InitializeCloudDriver(sensor_configuration, calibration_configuration, nullptr); + } /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration @@ -188,7 +185,10 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::shared_ptr driver_ptr_; Status wrapper_status_; - rclcpp::Subscription::SharedPtr pandar_scan_sub_; + + rclcpp::Publisher::SharedPtr packet_pub_; + rclcpp::Subscription::SharedPtr packet_sub_; + rclcpp::Publisher::SharedPtr nebula_points_pub_; rclcpp::Publisher::SharedPtr aw_points_ex_pub_; rclcpp::Publisher::SharedPtr aw_points_base_pub_; diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index 579852fb8..a74eb9813 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -27,8 +27,6 @@ - - @@ -55,7 +53,6 @@ - @@ -63,6 +60,5 @@ - diff --git a/nebula_ros/package.xml b/nebula_ros/package.xml index 87bc000c9..54df70ea9 100644 --- a/nebula_ros/package.xml +++ b/nebula_ros/package.xml @@ -31,6 +31,7 @@ velodyne_msgs visualization_msgs yaml-cpp + nebula_msgs ament_cmake_gtest ament_lint_auto diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index b809bccf8..ce81d6b3e 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -5,7 +5,9 @@ namespace nebula namespace ros { HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_ros_wrapper", options), hw_interface_(), diagnostics_updater_(this) +: rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), + hw_interface_(), + diagnostics_updater_(this) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); @@ -14,33 +16,29 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) sensor_cfg_ptr_ = std::make_shared(sensor_configuration); // hwiface -{ - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_hw_ms_)); - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); -#if not defined(TEST_PCAP) - Status rt = hw_interface_.InitializeTcpDriver(); - if(this->retry_hw_) { - int cnt = 0; - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - while(rt == Status::ERROR_1) - { - cnt++; - std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000 - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - rt = hw_interface_.InitializeTcpDriver(); + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return; + } + hw_interface_.SetLogger(std::make_shared(this->get_logger())); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); + Status rt = hw_interface_.InitializeTcpDriver(); + if (this->retry_hw_) { + int cnt = 0; + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); + while (rt == Status::ERROR_1) { + cnt++; + std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); + rt = hw_interface_.InitializeTcpDriver(); + } } - } - if(rt != Status::ERROR_1){ - try{ - std::vector thread_pool{}; + if (rt != Status::ERROR_1) { + try { + std::vector thread_pool{}; thread_pool.emplace_back([this] { auto result = hw_interface_.GetInventory(); RCLCPP_INFO_STREAM(get_logger(), result); @@ -50,74 +48,60 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) th.join(); } + } catch (...) { + std::cout << "catch (...) in parent" << std::endl; + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); + } + if (this->setup_sensor) { + hw_interface_.CheckAndSetConfig(); + updateParameters(); + } + } else { + RCLCPP_ERROR_STREAM( + get_logger(), + "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); + hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); } - catch (...) - { - std::cout << "catch (...) in parent" << std::endl; - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); - } - if (this->setup_sensor) { - hw_interface_.CheckAndSetConfig(); - updateParameters(); - } - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); - hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); - } -#endif - - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - pandar_scan_pub_ = - this->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); - -#if not defined(TEST_PCAP) - if (this->setup_sensor) { - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); } -#endif - - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); -} // decoder { - drivers::HesaiCalibrationConfiguration calibration_configuration; - drivers::HesaiCorrection correction_configuration; - - wrapper_status_ = - GetCalibrationData(calibration_configuration, correction_configuration); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return; - } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - - calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); + drivers::HesaiCalibrationConfiguration calibration_configuration; + drivers::HesaiCorrection correction_configuration; + wrapper_status_ = GetCalibrationData(calibration_configuration, correction_configuration); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return; + } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { + calibration_cfg_ptr_ = + std::make_shared(calibration_configuration); + // Will be left empty for AT128, and ignored by all decoders except AT128 correction_cfg_ptr_ = std::make_shared(correction_configuration); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); wrapper_status_ = InitializeCloudDriver( std::static_pointer_cast(sensor_cfg_ptr_), std::static_pointer_cast(calibration_cfg_ptr_), std::static_pointer_cast(correction_cfg_ptr_)); - } else { - wrapper_status_ = InitializeCloudDriver( - std::static_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); - } + + RCLCPP_DEBUG(this->get_logger(), "Starting stream"); + StreamStart(); + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + packet_pub_ = create_publisher( + "hesai_packets", rclcpp::SensorDataQoS()); + + packet_sub_ = create_subscription( + "hesai_packets", rclcpp::SensorDataQoS(), [](nebula_msgs::msg::NebulaPacket::UniquePtr){}); + nebula_points_pub_ = this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); aw_points_base_pub_ = @@ -194,11 +178,18 @@ cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); set_param_res_ = this->add_on_set_parameters_callback( std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); } -} -void HesaiRosWrapper::ReceiveCloudPacketCallback( - const std::vector & packet) +void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) { + auto t_received = std::chrono::high_resolution_clock::now().time_since_epoch().count(); + auto msg_ptr = std::make_unique(packet.size()); + msg_ptr->stamp.sec = t_received / 1'000'000'000; + msg_ptr->stamp.nanosec = t_received % 1'000'000'000; + // TODO(mojomex) this copy could be avoided if transport_drivers would give us a non-const vector + std::copy(packet.begin(), packet.end(), msg_ptr->data.begin()); + packet_pub_->publish(std::move(msg_ptr)); + + //todo // Driver is not initialized yet if (!driver_ptr_) { return; @@ -209,6 +200,12 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback( driver_ptr_->ParseCloudPacket(packet); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + auto t_end = std::chrono::high_resolution_clock::now(); + auto runtime = t_end - t_start; + t_start = t_end; + RCLCPP_DEBUG( + get_logger(), "PROFILING {'d_decode_packet': %lu}", runtime.count()); + if (pointcloud == nullptr) { // todo // RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); @@ -237,8 +234,8 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback( if ( aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - const auto autoware_ex_cloud = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( + pointcloud, std::get<1>(pointcloud_ts)); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = @@ -246,8 +243,9 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback( PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); } - auto runtime = std::chrono::high_resolution_clock::now() - t_start; - RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); + runtime = std::chrono::high_resolution_clock::now() - t_start; + RCLCPP_DEBUG( + get_logger(), "PROFILING {'d_convert_pc': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); } void HesaiRosWrapper::PublishCloud( @@ -261,22 +259,11 @@ void HesaiRosWrapper::PublishCloud( publisher->publish(std::move(pointcloud)); } -Status HesaiRosWrapper::InitializeCloudDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) -{ - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - Status HesaiRosWrapper::InitializeCloudDriver( const std::shared_ptr & sensor_configuration, const std::shared_ptr & calibration_configuration, const std::shared_ptr & correction_configuration) { - // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), std::static_pointer_cast(calibration_configuration), @@ -284,11 +271,12 @@ Status HesaiRosWrapper::InitializeCloudDriver( return driver_ptr_->GetStatus(); } -Status HesaiRosWrapper::GetStatus() { return wrapper_status_; } +Status HesaiRosWrapper::GetStatus() +{ + return wrapper_status_; +} -/// decoder -Status HesaiRosWrapper::GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration) +Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration) { /////////////////////////////////////////////// // Define and get ROS parameters @@ -377,8 +365,7 @@ Status HesaiRosWrapper::GetParameters( descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; this->declare_parameter("calibration_file", "", descriptor); - calibration_file_path = - this->get_parameter("calibration_file").as_string(); + calibration_file_path = this->get_parameter("calibration_file").as_string(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -492,16 +479,6 @@ Status HesaiRosWrapper::GetParameters( this->declare_parameter("setup_sensor", true, descriptor); this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("delay_hw_ms", 0, descriptor); - this->delay_hw_ms_ = this->get_parameter("delay_hw_ms").as_int(); - } { rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; @@ -528,9 +505,9 @@ Status HesaiRosWrapper::GetParameters( descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; this->declare_parameter("ptp_transport_type", ""); - sensor_configuration.ptp_transport_type = - nebula::drivers::PtpTransportTypeFromString(this->get_parameter("ptp_transport_type").as_string()); - if(static_cast(sensor_configuration.ptp_profile) > 0) { + sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportTypeFromString( + this->get_parameter("ptp_transport_type").as_string()); + if (static_cast(sensor_configuration.ptp_profile) > 0) { sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; } } @@ -565,32 +542,27 @@ Status HesaiRosWrapper::GetParameters( this->diag_span_ = this->get_parameter("diag_span").as_int(); } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("delay_monitor_ms", 0, descriptor); - this->delay_monitor_ms_ = this->get_parameter("delay_monitor_ms").as_int(); - } - /////////////////////////////////////////////// // Validate ROS parameters /////////////////////////////////////////////// - if(sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { - RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); + if (sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { + RCLCPP_ERROR_STREAM( + get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); return Status::SENSOR_CONFIG_ERROR; } - if(sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when using the '1588v2' PTP Profile"); + if ( + sensor_configuration.ptp_transport_type == + nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { + RCLCPP_ERROR_STREAM( + get_logger(), + "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " + "using the '1588v2' PTP Profile"); return Status::SENSOR_CONFIG_ERROR; } - if(sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); + if (sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { + RCLCPP_ERROR_STREAM( + get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); return Status::SENSOR_CONFIG_ERROR; } if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { @@ -603,69 +575,61 @@ Status HesaiRosWrapper::GetParameters( return Status::SENSOR_CONFIG_ERROR; } - /////////////////////////////////////////////// - // Decoder-specific setup - /////////////////////////////////////////////// - std::shared_ptr sensor_cfg_ptr = std::make_shared(sensor_configuration); hw_interface_.SetSensorConfiguration( std::static_pointer_cast(sensor_cfg_ptr)); - /////////////////////////////////////////////// - // HW Interface specific setup - /////////////////////////////////////////////// - - /////////////////////////////////////////////// - // HW Monitor specific setup - /////////////////////////////////////////////// - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); return Status::OK; } Status HesaiRosWrapper::GetCalibrationData( drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration) { - calibration_configuration.calibration_file = calibration_file_path; //todo + drivers::HesaiCorrection & correction_configuration) +{ + calibration_configuration.calibration_file = calibration_file_path; // todo - bool run_local = !launch_hw_; + bool run_local = !launch_hw_; if (sensor_cfg_ptr_->sensor_model != drivers::SensorModel::HESAI_PANDARAT128) { std::string calibration_file_path_from_sensor; if (launch_hw_ && !calibration_configuration.calibration_file.empty()) { int ext_pos = calibration_configuration.calibration_file.find_last_of('.'); - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(0, ext_pos); + calibration_file_path_from_sensor += + calibration_configuration.calibration_file.substr(0, ext_pos); calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(ext_pos, calibration_configuration.calibration_file.size() - ext_pos); + calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr( + ext_pos, calibration_configuration.calibration_file.size() - ext_pos); } - if(launch_hw_) { + if (launch_hw_) { run_local = false; RCLCPP_INFO_STREAM( - this->get_logger(), "Trying to acquire calibration data from sensor: '" - << sensor_cfg_ptr_->sensor_ip << "'"); - std::future future = std::async(std::launch::async, - [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { - auto str = hw_interface_.GetLidarCalibrationString(); - auto rt = calibration_configuration.SaveFileFromString( - calibration_file_path_from_sensor, str); - RCLCPP_ERROR_STREAM(get_logger(), str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromString success:" - << calibration_file_path_from_sensor << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromString failed:" - << calibration_file_path_from_sensor << "\n"); - } - rt = calibration_configuration.LoadFromString(str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), - "LoadFromString success:" << str << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), - "LoadFromString failed:" << str << "\n"); - } - }); + this->get_logger(), + "Trying to acquire calibration data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); + std::future future = std::async( + std::launch::async, + [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { + auto str = hw_interface_.GetLidarCalibrationString(); + auto rt = + calibration_configuration.SaveFileFromString(calibration_file_path_from_sensor, str); + RCLCPP_ERROR_STREAM(get_logger(), str); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM( + get_logger(), + "SaveFileFromString success:" << calibration_file_path_from_sensor << "\n"); + } else { + RCLCPP_ERROR_STREAM( + get_logger(), + "SaveFileFromString failed:" << calibration_file_path_from_sensor << "\n"); + } + rt = calibration_configuration.LoadFromString(str); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM(get_logger(), "LoadFromString success:" << str << "\n"); + } else { + RCLCPP_ERROR_STREAM(get_logger(), "LoadFromString failed:" << str << "\n"); + } + }); std::future_status status; status = future.wait_for(std::chrono::milliseconds(5000)); if (status == std::future_status::timeout) { @@ -674,36 +638,38 @@ Status HesaiRosWrapper::GetCalibrationData( run_local = true; } else if (status == std::future_status::ready && !run_local) { RCLCPP_INFO_STREAM( - this->get_logger(), "Acquired calibration data from sensor: '" - << sensor_cfg_ptr_->sensor_ip << "'"); + this->get_logger(), + "Acquired calibration data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); RCLCPP_INFO_STREAM( - this->get_logger(), "The calibration has been saved in '" - << calibration_file_path_from_sensor << "'"); + this->get_logger(), + "The calibration has been saved in '" << calibration_file_path_from_sensor << "'"); } } - if(run_local) { + if (run_local) { RCLCPP_WARN_STREAM(get_logger(), "Running locally"); bool run_org = false; if (calibration_file_path_from_sensor.empty()) { run_org = true; } else { - RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_file_path_from_sensor); - auto cal_status = - calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); + RCLCPP_INFO_STREAM( + get_logger(), "Trying to load file: " << calibration_file_path_from_sensor); + auto cal_status = calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); if (cal_status != Status::OK) { run_org = true; - }else{ + } else { RCLCPP_INFO_STREAM( - this->get_logger(), "Load calibration data from: '" - << calibration_file_path_from_sensor << "'"); + this->get_logger(), + "Load calibration data from: '" << calibration_file_path_from_sensor << "'"); } } - if(run_org) { - RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_configuration.calibration_file); + if (run_org) { + RCLCPP_INFO_STREAM( + get_logger(), "Trying to load file: " << calibration_configuration.calibration_file); if (calibration_configuration.calibration_file.empty()) { RCLCPP_ERROR_STREAM( - this->get_logger(), "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); + this->get_logger(), + "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); return Status::INVALID_CALIBRATION_FILE; } else { auto cal_status = @@ -714,54 +680,61 @@ Status HesaiRosWrapper::GetCalibrationData( this->get_logger(), "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); return cal_status; - }else{ + } else { RCLCPP_INFO_STREAM( - this->get_logger(), "Load calibration data from: '" - << calibration_configuration.calibration_file << "'"); + this->get_logger(), + "Load calibration data from: '" << calibration_configuration.calibration_file << "'"); } } } } - } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 + } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 std::string correction_file_path_from_sensor; if (launch_hw_ && !correction_file_path.empty()) { int ext_pos = correction_file_path.find_last_of('.'); correction_file_path_from_sensor += correction_file_path.substr(0, ext_pos); correction_file_path_from_sensor += "_from_sensor"; - correction_file_path_from_sensor += correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); + correction_file_path_from_sensor += + correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); } - std::future future = std::async(std::launch::async, [this, &correction_configuration, &correction_file_path_from_sensor, &run_local]() { - if (launch_hw_) { - RCLCPP_INFO_STREAM( - this->get_logger(), "Trying to acquire calibration data from sensor"); - auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); - RCLCPP_INFO_STREAM(get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); - auto rt = correction_configuration.SaveFileFromBinary(correction_file_path_from_sensor, received_bytes); - if(rt == Status::OK) - { - RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromBinary failed:" << correction_file_path_from_sensor << ". Falling back to offline calibration file."); - run_local = true; - } - rt = correction_configuration.LoadFromBinary(received_bytes); - if(rt == Status::OK) - { - RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); - run_local = false; - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "LoadFromBinary failed" << ". Falling back to offline calibration file."); + std::future future = std::async( + std::launch::async, + [this, &correction_configuration, &correction_file_path_from_sensor, &run_local]() { + if (launch_hw_) { + RCLCPP_INFO_STREAM(this->get_logger(), "Trying to acquire calibration data from sensor"); + auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); + RCLCPP_INFO_STREAM( + get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); + auto rt = correction_configuration.SaveFileFromBinary( + correction_file_path_from_sensor, received_bytes); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM( + get_logger(), + "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); + } else { + RCLCPP_ERROR_STREAM( + get_logger(), + "SaveFileFromBinary failed:" << correction_file_path_from_sensor + << ". Falling back to offline calibration file."); + run_local = true; + } + rt = correction_configuration.LoadFromBinary(received_bytes); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM( + get_logger(), "LoadFromBinary success" + << "\n"); + run_local = false; + } else { + RCLCPP_ERROR_STREAM( + get_logger(), "LoadFromBinary failed" + << ". Falling back to offline calibration file."); + run_local = true; + } + } else { + RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); run_local = true; } - }else{ - RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); - run_local = true; - } - }); + }); if (!run_local) { std::future_status status; status = future.wait_for(std::chrono::milliseconds(8000)); @@ -770,30 +743,29 @@ Status HesaiRosWrapper::GetCalibrationData( run_local = true; } else if (status == std::future_status::ready && !run_local) { RCLCPP_INFO_STREAM( - this->get_logger(), "Acquired correction data from sensor: '" - << sensor_cfg_ptr_->sensor_ip << "'"); + this->get_logger(), + "Acquired correction data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); RCLCPP_INFO_STREAM( - this->get_logger(), "The correction has been saved in '" - << correction_file_path_from_sensor << "'"); + this->get_logger(), + "The correction has been saved in '" << correction_file_path_from_sensor << "'"); } } - if(run_local) { + if (run_local) { bool run_org = false; if (correction_file_path_from_sensor.empty()) { run_org = true; } else { - auto cal_status = - correction_configuration.LoadFromFile(correction_file_path_from_sensor); + auto cal_status = correction_configuration.LoadFromFile(correction_file_path_from_sensor); if (cal_status != Status::OK) { run_org = true; - }else{ + } else { RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" - << correction_file_path_from_sensor << "'"); + this->get_logger(), + "Load correction data from: '" << correction_file_path_from_sensor << "'"); } } - if(run_org) { + if (run_org) { if (correction_file_path.empty()) { RCLCPP_ERROR_STREAM( this->get_logger(), "Empty Correction File: '" << correction_file_path << "'"); @@ -805,20 +777,20 @@ Status HesaiRosWrapper::GetCalibrationData( RCLCPP_ERROR_STREAM( this->get_logger(), "Given Correction File: '" << correction_file_path << "'"); return cal_status; - }else{ + } else { RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" - << correction_file_path << "'"); + this->get_logger(), "Load correction data from: '" << correction_file_path << "'"); } } } } - } // end AT128 + } // end AT128 return Status::OK; - } +} -HesaiRosWrapper::~HesaiRosWrapper() { +HesaiRosWrapper::~HesaiRosWrapper() +{ RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); hw_interface_.FinalizeTcpDriver(); } @@ -831,8 +803,14 @@ Status HesaiRosWrapper::StreamStart() return interface_status_; } -Status HesaiRosWrapper::StreamStop() { return Status::OK; } -Status HesaiRosWrapper::Shutdown() { return Status::OK; } +Status HesaiRosWrapper::StreamStop() +{ + return Status::OK; +} +Status HesaiRosWrapper::Shutdown() +{ + return Status::OK; +} Status HesaiRosWrapper::InitializeHwInterface( // todo: don't think this is needed const drivers::SensorConfigurationBase & sensor_configuration) @@ -844,8 +822,63 @@ Status HesaiRosWrapper::InitializeHwInterface( // todo: don't think this is nee } Status HesaiRosWrapper::InitializeHwMonitor( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) + const drivers::SensorConfigurationBase & /* sensor_configuration */) { + cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); + cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return Status::ERROR_1; + } + + message_sep = ": "; + not_supported_message = "Not supported"; + error_message = "Error"; + + switch (sensor_cfg_ptr_->sensor_model) { + case nebula::drivers::SensorModel::HESAI_PANDARXT32: + case nebula::drivers::SensorModel::HESAI_PANDARXT32M: + case nebula::drivers::SensorModel::HESAI_PANDARAT128: + temperature_names.emplace_back("Bottom circuit board T1"); + temperature_names.emplace_back("Bottom circuit board T2"); + temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names.emplace_back("Laser emitting board RT_L2"); + temperature_names.emplace_back("Receiving board RT_R"); + temperature_names.emplace_back("Receiving board RT2"); + temperature_names.emplace_back("Top circuit RT3"); + temperature_names.emplace_back("Not used"); + break; + case nebula::drivers::SensorModel::HESAI_PANDAR64: + case nebula::drivers::SensorModel::HESAI_PANDAR40P: + case nebula::drivers::SensorModel::HESAI_PANDAR40M: + case nebula::drivers::SensorModel::HESAI_PANDARQT64: + case nebula::drivers::SensorModel::HESAI_PANDARQT128: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: + default: + temperature_names.emplace_back("Bottom circuit RT1"); + temperature_names.emplace_back("Bottom circuit RT2"); + temperature_names.emplace_back("Internal Temperature"); + temperature_names.emplace_back("Laser emitting board RT1"); + temperature_names.emplace_back("Laser emitting board RT2"); + temperature_names.emplace_back("Receiving board RT1"); + temperature_names.emplace_back("Top circuit RT1"); + temperature_names.emplace_back("Top circuit RT2"); + break; + } + + auto result = hw_interface_.GetInventory(); + current_inventory.reset(new HesaiInventory(result)); + current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); + std::cout << "HesaiInventory" << std::endl; + std::cout << result << std::endl; + info_model = result.get_str_model(); + info_serial = std::string(result.sn.begin(), result.sn.end()); + hw_interface_.SetTargetModel(result.model); + RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); + RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); + InitializeHesaiDiagnostics(); return Status::OK; } @@ -858,16 +891,14 @@ rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( RCLCPP_DEBUG_STREAM(this->get_logger(), *sensor_cfg_ptr_); RCLCPP_INFO_STREAM(this->get_logger(), p); - std::shared_ptr new_param = + std::shared_ptr new_param = std::make_shared(*sensor_cfg_ptr_); RCLCPP_INFO_STREAM(this->get_logger(), new_param); std::string sensor_model_str; std::string return_mode_str; if ( - get_param(p, "sensor_model", sensor_model_str) | - get_param(p, "return_mode", return_mode_str) | - get_param(p, "host_ip", new_param->host_ip) | - get_param(p, "sensor_ip", new_param->sensor_ip) | + get_param(p, "sensor_model", sensor_model_str) | get_param(p, "return_mode", return_mode_str) | + get_param(p, "host_ip", new_param->host_ip) | get_param(p, "sensor_ip", new_param->sensor_ip) | get_param(p, "frame_id", new_param->frame_id) | get_param(p, "data_port", new_param->data_port) | get_param(p, "gnss_port", new_param->gnss_port) | @@ -938,8 +969,7 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() diagnostics_updater_.add("hesai_status", this, &HesaiRosWrapper::HesaiCheckStatus); diagnostics_updater_.add("hesai_ptp", this, &HesaiRosWrapper::HesaiCheckPtp); - diagnostics_updater_.add( - "hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); + diagnostics_updater_.add("hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); diagnostics_updater_.add("hesai_rpm", this, &HesaiRosWrapper::HesaiCheckRpm); current_status.reset(); @@ -964,8 +994,7 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); if (hw_interface_.UseHttpGetLidarMonitor()) { - diagnostics_updater_.add( - "hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); + diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); } else { diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltage); } @@ -1030,12 +1059,10 @@ void HesaiRosWrapper::OnHesaiStatusTimer() current_status.reset(new HesaiLidarStatus(result)); } catch (const std::system_error & error) { RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), - error.what()); + rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), error.what()); } catch (const boost::system::system_error & error) { RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), + rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), error.what()); } RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl); @@ -1053,8 +1080,7 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp() }); } catch (const std::system_error & error) { RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), + rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), error.what()); } catch (const boost::system::system_error & error) { RCLCPP_ERROR_STREAM( @@ -1080,15 +1106,13 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimer() error.what()); } catch (const boost::system::system_error & error) { RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), + rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), error.what()); } RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END"); } -void HesaiRosWrapper::HesaiCheckStatus( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_status); if (current_status) { @@ -1105,8 +1129,7 @@ void HesaiRosWrapper::HesaiCheckStatus( } } -void HesaiRosWrapper::HesaiCheckPtp( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_status); if (current_status) { @@ -1156,8 +1179,7 @@ void HesaiRosWrapper::HesaiCheckTemperature( } } -void HesaiRosWrapper::HesaiCheckRpm( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_status); if (current_status) { @@ -1204,8 +1226,7 @@ void HesaiRosWrapper::HesaiCheckVoltageHttp( } } -void HesaiRosWrapper::HesaiCheckVoltage( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_lidar_monitor); if (current_monitor) { @@ -1224,6 +1245,6 @@ void HesaiRosWrapper::HesaiCheckVoltage( } } - RCLCPP_COMPONENTS_REGISTER_NODE(HesaiRosWrapper) +RCLCPP_COMPONENTS_REGISTER_NODE(HesaiRosWrapper) } // namespace ros } // namespace nebula diff --git a/scripts/plot_times.py b/scripts/plot_times.py index 521dfd347..3cbf93f61 100644 --- a/scripts/plot_times.py +++ b/scripts/plot_times.py @@ -24,7 +24,6 @@ def parse_logs(run_name): for col in [c for c in df.columns if c.startswith("d_")]: df[col] /= 1e6 # ns to ms - df['d_total'] = sum([df[c] for c in df.columns if c.startswith("d_")]) # type: ignore return df def plot_timing_comparison(run_names): @@ -41,11 +40,13 @@ def plot_timing_comparison(run_names): boxes = axs[1:] for i, (label, df) in enumerate(scenario_dfs.items()): - durations = df['d_total'] + # durations = df['d_total'] - ax_d.plot(durations.index, durations, label=label, linestyle='', marker='.') + # ax_d.plot(durations.index, durations, label=label, linestyle='', marker='.') for col in filter(lambda col: col.startswith("n_"), df.columns): ax_n.plot(df.index, df[col], label=f"{label}::{col}", linestyle='', marker='.', color='black') + for col in filter(lambda col: col.startswith("d_"), df.columns): + ax_d.plot(df.index, df[col], label=f"{label}::{col}", linestyle='', marker='.') d_columns = [col for col in df.columns if col.startswith("d_")] n_cols = len(d_columns) From d83932939b44c5d171744e423d27c68e2d0da0b4 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 26 Mar 2024 22:02:51 +0900 Subject: [PATCH 006/122] temporary progress --- nebula_messages/nebula_msgs/CMakeLists.txt | 2 +- .../nebula_msgs/msg/NebulaPacket.msg | 2 +- nebula_messages/nebula_msgs/package.xml | 2 +- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 6 +- nebula_ros/launch/hesai_launch_all_hw.xml | 59 ++++---- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 134 +++++------------- 6 files changed, 78 insertions(+), 127 deletions(-) diff --git a/nebula_messages/nebula_msgs/CMakeLists.txt b/nebula_messages/nebula_msgs/CMakeLists.txt index 2ffa068a5..e2b798d9d 100644 --- a/nebula_messages/nebula_msgs/CMakeLists.txt +++ b/nebula_messages/nebula_msgs/CMakeLists.txt @@ -21,4 +21,4 @@ rosidl_generate_interfaces(${PROJECT_NAME} std_msgs ) -ament_package() +ament_package() \ No newline at end of file diff --git a/nebula_messages/nebula_msgs/msg/NebulaPacket.msg b/nebula_messages/nebula_msgs/msg/NebulaPacket.msg index f6ba285d8..be5898eb1 100644 --- a/nebula_messages/nebula_msgs/msg/NebulaPacket.msg +++ b/nebula_messages/nebula_msgs/msg/NebulaPacket.msg @@ -1,2 +1,2 @@ builtin_interfaces/Time stamp -uint8[] data +uint8[] data \ No newline at end of file diff --git a/nebula_messages/nebula_msgs/package.xml b/nebula_messages/nebula_msgs/package.xml index 146e14d07..6b626c025 100644 --- a/nebula_messages/nebula_msgs/package.xml +++ b/nebula_messages/nebula_msgs/package.xml @@ -22,4 +22,4 @@ ament_cmake - + \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 004c717cd..8361aedfc 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -124,10 +124,14 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase /// @return Resulting status Status InitializeHwInterface( const drivers::SensorConfigurationBase & sensor_configuration) override; - /// @brief Callback for receiving PandarScan + /// @brief Callback for receiving a raw UDP packet /// @param scan_buffer Received PandarScan void ReceiveCloudPacketCallback(const std::vector & scan_buffer); + /// @brief Decodes a nebula packet and, if it completes the scan, publishes the pointcloud. + /// @param packet_msg The received packet message + void ProcessCloudPacket(std::unique_ptr packet_msg); + /// @brief rclcpp parameter callback /// @param parameters Received parameters /// @return SetParametersResult diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index a74eb9813..b7c1459ec 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -33,32 +33,35 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index ce81d6b3e..8957a30d2 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -86,94 +86,31 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) std::static_pointer_cast(calibration_cfg_ptr_), std::static_pointer_cast(correction_cfg_ptr_)); - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), - qos_profile); - - packet_pub_ = create_publisher( - "hesai_packets", rclcpp::SensorDataQoS()); - - packet_sub_ = create_subscription( - "hesai_packets", rclcpp::SensorDataQoS(), [](nebula_msgs::msg::NebulaPacket::UniquePtr){}); - - nebula_points_pub_ = - this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); - aw_points_base_pub_ = - this->create_publisher("aw_points", rclcpp::SensorDataQoS()); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", rclcpp::SensorDataQoS()); -} - -//hwmon -{ -cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); - cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); + rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; + auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), + qos_profile); + + packet_pub_ = create_publisher( + "hesai_packets", rclcpp::SensorDataQoS()); + + packet_sub_ = create_subscription( + "hesai_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); + + nebula_points_pub_ = this->create_publisher( + "pandar_points", rclcpp::SensorDataQoS()); + aw_points_base_pub_ = + this->create_publisher("aw_points", rclcpp::SensorDataQoS()); + aw_points_ex_pub_ = this->create_publisher( + "aw_points_ex", rclcpp::SensorDataQoS()); } - std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_monitor_ms_)); - message_sep = ": "; - not_supported_message = "Not supported"; - error_message = "Error"; + RCLCPP_DEBUG(this->get_logger(), "Starting stream"); + StreamStart(); + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - switch (sensor_cfg_ptr_->sensor_model) { - case nebula::drivers::SensorModel::HESAI_PANDARXT32: - case nebula::drivers::SensorModel::HESAI_PANDARXT32M: - case nebula::drivers::SensorModel::HESAI_PANDARAT128: - temperature_names.emplace_back("Bottom circuit board T1"); - temperature_names.emplace_back("Bottom circuit board T2"); - temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); - temperature_names.emplace_back("Laser emitting board RT_L2"); - temperature_names.emplace_back("Receiving board RT_R"); - temperature_names.emplace_back("Receiving board RT2"); - temperature_names.emplace_back("Top circuit RT3"); - temperature_names.emplace_back("Not used"); - break; - case nebula::drivers::SensorModel::HESAI_PANDAR64: - case nebula::drivers::SensorModel::HESAI_PANDAR40P: - case nebula::drivers::SensorModel::HESAI_PANDAR40M: - case nebula::drivers::SensorModel::HESAI_PANDARQT64: - case nebula::drivers::SensorModel::HESAI_PANDARQT128: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: - default: - temperature_names.emplace_back("Bottom circuit RT1"); - temperature_names.emplace_back("Bottom circuit RT2"); - temperature_names.emplace_back("Internal Temperature"); - temperature_names.emplace_back("Laser emitting board RT1"); - temperature_names.emplace_back("Laser emitting board RT2"); - temperature_names.emplace_back("Receiving board RT1"); - temperature_names.emplace_back("Top circuit RT1"); - temperature_names.emplace_back("Top circuit RT2"); - break; - } - - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto result = hw_interface_.GetInventory(); - current_inventory.reset(new HesaiInventory(result)); - current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); - RCLCPP_INFO_STREAM(this->get_logger(), "HesaiInventory"); - RCLCPP_INFO_STREAM(this->get_logger(), result); - info_model = result.get_str_model(); - info_serial = std::string(result.sn.begin(), result.sn.end()); - hw_interface_.SetTargetModel(result.model); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); - InitializeHesaiDiagnostics(); - }); - for (std::thread & th : thread_pool) { - th.join(); - } + InitializeHwMonitor(*sensor_cfg_ptr_); set_param_res_ = this->add_on_set_parameters_callback( std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); @@ -181,23 +118,30 @@ cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) { - auto t_received = std::chrono::high_resolution_clock::now().time_since_epoch().count(); - auto msg_ptr = std::make_unique(packet.size()); - msg_ptr->stamp.sec = t_received / 1'000'000'000; - msg_ptr->stamp.nanosec = t_received % 1'000'000'000; - // TODO(mojomex) this copy could be avoided if transport_drivers would give us a non-const vector - std::copy(packet.begin(), packet.end(), msg_ptr->data.begin()); - packet_pub_->publish(std::move(msg_ptr)); - - //todo // Driver is not initialized yet if (!driver_ptr_) { return; } + const auto now = std::chrono::system_clock::now(); + const auto timestamp_ns = + std::chrono::duration_cast(now.time_since_epoch()).count(); + + auto msg_ptr = std::make_unique(); + msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); + msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); + std::copy(packet.begin(), packet.end(), std::back_inserter(msg_ptr->data)); + + packet_pub_->publish(std::move(msg_ptr)); +} + +void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) +{ + std::lock_guard lock(mtx_decode_); + auto t_start = std::chrono::high_resolution_clock::now(); std::tuple pointcloud_ts = - driver_ptr_->ParseCloudPacket(packet); + driver_ptr_->ParseCloudPacket(packet_msg->data); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); auto t_end = std::chrono::high_resolution_clock::now(); From fdbeb45e2cb04ddb3a032c9c9d39c34143a3fb14 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 19:35:25 +0900 Subject: [PATCH 007/122] fix(hesai_ros_wrapper): remove changes wrongly merged during rebase --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 8957a30d2..9aef30110 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -91,6 +91,8 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + //TODO(mojomex): create high-frequency QoS with large buffer to prevent packet loss + packet_pub_ = create_publisher( "hesai_packets", rclcpp::SensorDataQoS()); @@ -137,8 +139,6 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { - std::lock_guard lock(mtx_decode_); - auto t_start = std::chrono::high_resolution_clock::now(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); @@ -742,7 +742,7 @@ HesaiRosWrapper::~HesaiRosWrapper() Status HesaiRosWrapper::StreamStart() { if (Status::OK == interface_status_) { - interface_status_ = hw_interface_.CloudInterfaceStart(); + interface_status_ = hw_interface_.SensorInterfaceStart(); } return interface_status_; } From cc26aeb9e71ebeecbe44b2647638c3cef9baf6cb Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 20:16:36 +0900 Subject: [PATCH 008/122] fix(hesai_ros_wrapper): increase packet buffering to stop internal packet loss --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 43 +++++++++++----------- 1 file changed, 21 insertions(+), 22 deletions(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 9aef30110..15f7eca09 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -88,23 +88,23 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), - qos_profile); + auto pointcloud_qos = + rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - //TODO(mojomex): create high-frequency QoS with large buffer to prevent packet loss - - packet_pub_ = create_publisher( - "hesai_packets", rclcpp::SensorDataQoS()); + auto packet_qos = + rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 1000), qos_profile); + packet_pub_ = create_publisher("hesai_packets", packet_qos); packet_sub_ = create_subscription( - "hesai_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); + "hesai_packets", packet_qos, + std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); - nebula_points_pub_ = this->create_publisher( - "pandar_points", rclcpp::SensorDataQoS()); + nebula_points_pub_ = + this->create_publisher("pandar_points", pointcloud_qos); aw_points_base_pub_ = - this->create_publisher("aw_points", rclcpp::SensorDataQoS()); - aw_points_ex_pub_ = this->create_publisher( - "aw_points_ex", rclcpp::SensorDataQoS()); + this->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = + this->create_publisher("aw_points_ex", pointcloud_qos); } RCLCPP_DEBUG(this->get_logger(), "Starting stream"); @@ -664,14 +664,12 @@ Status HesaiRosWrapper::GetCalibrationData( } rt = correction_configuration.LoadFromBinary(received_bytes); if (rt == Status::OK) { - RCLCPP_INFO_STREAM( - get_logger(), "LoadFromBinary success" - << "\n"); + RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); run_local = false; } else { RCLCPP_ERROR_STREAM( - get_logger(), "LoadFromBinary failed" - << ". Falling back to offline calibration file."); + get_logger(), + "LoadFromBinary failed" << ". Falling back to offline calibration file."); run_local = true; } } else { @@ -923,8 +921,8 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - auto fetch_diag_from_sensor = [this](){ - OnHesaiStatusTimer(); + auto fetch_diag_from_sensor = [this]() { + OnHesaiStatusTimer(); if (hw_interface_.UseHttpGetLidarMonitor()) { OnHesaiLidarMonitorTimerHttp(); } else { @@ -932,9 +930,10 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() } }; - fetch_diagnostics_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), - this->get_node_base_interface()->get_context()); + fetch_diagnostics_timer_ = + std::make_shared>( + this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), + this->get_node_base_interface()->get_context()); this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); if (hw_interface_.UseHttpGetLidarMonitor()) { From a1b9f5bce148fef55153211dc077846e1ede2628 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 20:17:59 +0900 Subject: [PATCH 009/122] feat(nebula_common): add instrumentation tools --- .../nebula_common/util/instrumentation.hpp | 109 ++++++++++++++++++ 1 file changed, 109 insertions(+) create mode 100644 nebula_common/include/nebula_common/util/instrumentation.hpp diff --git a/nebula_common/include/nebula_common/util/instrumentation.hpp b/nebula_common/include/nebula_common/util/instrumentation.hpp new file mode 100644 index 000000000..ab9357286 --- /dev/null +++ b/nebula_common/include/nebula_common/util/instrumentation.hpp @@ -0,0 +1,109 @@ +#pragma once + +#include +#include +#include + +namespace nebula +{ +namespace util +{ + +using namespace std::chrono_literals; + +class Instrumentation +{ + using clock = std::chrono::high_resolution_clock; + using time_point = clock::time_point; + using duration = std::chrono::nanoseconds; + +public: + Instrumentation(std::string tag) : tag(tag), last_print(clock::now()) {} + + void tick() + { + auto now = clock::now(); + + if (last_tick != time_point::min()) { + auto rtt = now - last_tick; + rtts_.update(rtt); + } + + last_tick = now; + } + + void tock() + { + auto now = clock::now(); + auto delay = now - last_tick; + delays_.update(delay); + + if (now - last_print >= PRINT_INTERVAL) { + auto del = delays_.reset(); + auto rtt = rtts_.reset(); + + last_print = now; + + std::cout << "{\"tag\": \"" << tag << "\", \"del_min\": " << del.min.count() * 1e-9 + << ", \"del_avg\": " << del.avg.count() * 1e-9 + << ", \"del_max\": " << del.max.count() * 1e-9 + << ", \"rtt_min\": " << rtt.min.count() * 1e-9 + << ", \"rtt_avg\": " << rtt.avg.count() * 1e-9 + << ", \"rtt_max\": " << rtt.max.count() * 1e-9 << ", \"window\": " << rtt.count + << '}' << std::endl; + } + } + +private: + class Counter + { + public: + struct Stats + { + duration min; + duration avg; + duration max; + uint64_t count; + }; + + Stats reset() + { + auto avg_measurement = sum_measurements / num_measurements; + + Stats result{min_measurement, avg_measurement, max_measurement, num_measurements}; + + sum_measurements = duration::zero(); + num_measurements = 0; + min_measurement = duration::zero(); + max_measurement = duration::max(); + } + + void update(duration measurement) + { + sum_measurements += measurement; + num_measurements++; + + min_measurement = std::min(min_measurement, measurement); + max_measurement = std::max(max_measurement, measurement); + } + + private: + duration sum_measurements{duration::zero()}; + uint64_t num_measurements{0}; + duration min_measurement{duration::max()}; + duration max_measurement{duration::zero()}; + }; + + std::string tag; + + time_point last_tick{time_point::min()}; + time_point last_print{time_point::min()}; + + Counter delays_; + Counter rtts_; + + const duration PRINT_INTERVAL = 1s; +}; + +} // namespace util +} // namespace nebula \ No newline at end of file From 1131201545bc2f5475f6c55cd90c494d9c5a8acb Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 20:18:20 +0900 Subject: [PATCH 010/122] feat(hesai_ros_wrapper): instrument code on critical path --- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 1 + nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 37 +++++++++++++------ 2 files changed, 27 insertions(+), 11 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 8361aedfc..68fc5948c 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -4,6 +4,7 @@ #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" +#include "nebula_common/util/instrumentation.hpp" #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" #include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 15f7eca09..1835e1de6 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -120,11 +120,14 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) { + static nebula::util::Instrumentation convert{"ReceiveCloudPacketCallback.convert"}; + static nebula::util::Instrumentation publish{"ReceiveCloudPacketCallback.publish"}; // Driver is not initialized yet if (!driver_ptr_) { return; } + convert.tick(); const auto now = std::chrono::system_clock::now(); const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); @@ -133,22 +136,24 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); std::copy(packet.begin(), packet.end(), std::back_inserter(msg_ptr->data)); + convert.tock(); + publish.tick(); packet_pub_->publish(std::move(msg_ptr)); + publish.tock(); } void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { - auto t_start = std::chrono::high_resolution_clock::now(); + static nebula::util::Instrumentation parse{"ProcessCloudPacket.parse"}; + static nebula::util::Instrumentation convert{"ProcessCloudPacket.convert"}; + static nebula::util::Instrumentation publish{"ProcessCloudPacket.publish"}; + + parse.tick(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - - auto t_end = std::chrono::high_resolution_clock::now(); - auto runtime = t_end - t_start; - t_start = t_end; - RCLCPP_DEBUG( - get_logger(), "PROFILING {'d_decode_packet': %lu}", runtime.count()); + parse.tock(); if (pointcloud == nullptr) { // todo @@ -158,38 +163,48 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrget_subscription_count() > 0 || nebula_points_pub_->get_intra_process_subscription_count() > 0) { + convert.tick(); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + convert.tock(); + publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); + publish.tock(); } if ( aw_points_base_pub_->get_subscription_count() > 0 || aw_points_base_pub_->get_intra_process_subscription_count() > 0) { + convert.tick(); + const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + convert.tock(); + publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); + publish.tock(); } if ( aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { + convert.tick(); + const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( pointcloud, std::get<1>(pointcloud_ts)); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + convert.tock(); + publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); + publish.tock(); } - - runtime = std::chrono::high_resolution_clock::now() - t_start; - RCLCPP_DEBUG( - get_logger(), "PROFILING {'d_convert_pc': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); } void HesaiRosWrapper::PublishCloud( From 174bd1cbcfc75c81924f09ea5283db4865567569 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:18:57 +0900 Subject: [PATCH 011/122] disable instrumentation --- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 3 +- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 55 ++++++++++--------- 2 files changed, 32 insertions(+), 26 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 68fc5948c..a52b3903f 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -4,7 +4,8 @@ #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" -#include "nebula_common/util/instrumentation.hpp" +// #include "nebula_common/util/instrumentation.hpp" +// #include "nebula_common/util/topic_delay.hpp" #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" #include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 1835e1de6..533c3cf49 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -120,14 +120,15 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) { - static nebula::util::Instrumentation convert{"ReceiveCloudPacketCallback.convert"}; - static nebula::util::Instrumentation publish{"ReceiveCloudPacketCallback.publish"}; + // static auto convert = nebula::util::Instrumentation("ReceiveCloudPacketCallback.convert"); + // static auto publish = nebula::util::Instrumentation("ReceiveCloudPacketCallback.publish"); + // static auto delay = nebula::util::TopicDelay("ReceiveCloudPacketCallback"); // Driver is not initialized yet if (!driver_ptr_) { return; } - convert.tick(); + // convert.tick(); const auto now = std::chrono::system_clock::now(); const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); @@ -135,25 +136,29 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa auto msg_ptr = std::make_unique(); msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); - std::copy(packet.begin(), packet.end(), std::back_inserter(msg_ptr->data)); - convert.tock(); + msg_ptr->data.swap(packet); + // convert.tock(); - publish.tick(); - packet_pub_->publish(std::move(msg_ptr)); - publish.tock(); + // delay.tick(msg_ptr->stamp); + + // publish.tick(); + // publish.tock(); } void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { - static nebula::util::Instrumentation parse{"ProcessCloudPacket.parse"}; - static nebula::util::Instrumentation convert{"ProcessCloudPacket.convert"}; - static nebula::util::Instrumentation publish{"ProcessCloudPacket.publish"}; + // static auto parse = nebula::util::Instrumentation("ProcessCloudPacket.parse"); + // static auto convert = nebula::util::Instrumentation("ProcessCloudPacket.convert"); + // static auto publish = nebula::util::Instrumentation("ProcessCloudPacket.publish"); + // static auto delay = nebula::util::TopicDelay("ProcessCloudPacket"); + + // delay.tick(packet_msg->stamp); - parse.tick(); + // parse.tick(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - parse.tock(); + // parse.tock(); if (pointcloud == nullptr) { // todo @@ -163,20 +168,20 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrget_subscription_count() > 0 || nebula_points_pub_->get_intra_process_subscription_count() > 0) { - convert.tick(); + // convert.tick(); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - convert.tock(); - publish.tick(); + // convert.tock(); + // publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); - publish.tock(); + // publish.tock(); } if ( aw_points_base_pub_->get_subscription_count() > 0 || aw_points_base_pub_->get_intra_process_subscription_count() > 0) { - convert.tick(); + // convert.tick(); const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); @@ -184,15 +189,15 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrheader.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - convert.tock(); - publish.tick(); + // convert.tock(); + // publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); - publish.tock(); + // publish.tock(); } if ( aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - convert.tick(); + // convert.tick(); const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( pointcloud, std::get<1>(pointcloud_ts)); @@ -200,10 +205,10 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrheader.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - convert.tock(); - publish.tick(); + // convert.tock(); + // publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); - publish.tock(); + // publish.tock(); } } From 195eb10eff585860d54bfba345b21a5c6110586e Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:20:44 +0900 Subject: [PATCH 012/122] feat(hesai): move received buffer into ros message instead of copy --- .../hesai_hw_interface.hpp | 6 +++--- .../hesai_hw_interface.cpp | 12 ++++++------ .../include/nebula_ros/hesai/hesai_ros_wrapper.hpp | 2 +- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 3 ++- 4 files changed, 12 insertions(+), 11 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index f65daf077..362ca3be0 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -102,7 +102,7 @@ class HesaiHwInterface : NebulaHwInterfaceBase std::unique_ptr scan_cloud_ptr_; std::function is_valid_packet_; /*Lambda Function Array to verify proper packet size*/ - std::function & buffer)> + std::function & buffer)> cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ int prev_phase_{}; @@ -168,7 +168,7 @@ class HesaiHwInterface : NebulaHwInterfaceBase /// @brief Callback function to receive the Cloud Packet data from the UDP Driver /// @param buffer Buffer containing the data received from the UDP socket - void ReceiveSensorPacketCallback(const std::vector & buffer) final; + void ReceiveSensorPacketCallback(std::vector & buffer); /// @brief Starting the interface that handles UDP streams /// @return Resulting status Status SensorInterfaceStart() final; @@ -192,7 +192,7 @@ class HesaiHwInterface : NebulaHwInterfaceBase /// @param scan_callback Callback function /// @return Resulting status Status RegisterScanCallback( - std::function &)> scan_callback); + std::function &)> scan_callback); /// @brief Getting data with PTC_COMMAND_GET_LIDAR_CALIBRATION /// @return Resulting status std::string GetLidarCalibrationString(); diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index bf3060afc..a0fcbf184 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -218,18 +218,18 @@ Status HesaiHwInterface::SensorInterfaceStart() } Status HesaiHwInterface::RegisterScanCallback( - std::function &)> scan_callback) + std::function &)> scan_callback) { cloud_packet_callback_ = std::move(scan_callback); return Status::OK; } -void HesaiHwInterface::ReceiveSensorPacketCallback(const std::vector & buffer) +void HesaiHwInterface::ReceiveSensorPacketCallback(std::vector & buffer) { - if (!is_valid_packet_(buffer.size())) { - PrintDebug("Invalid Packet: " + std::to_string(buffer.size())); - return; - } + // if (!is_valid_packet_(buffer.size())) { + // PrintDebug("Invalid Packet: " + std::to_string(buffer.size())); + // return; + // } TODO cloud_packet_callback_(buffer); } Status HesaiHwInterface::SensorInterfaceStop() diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index a52b3903f..896fec094 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -128,7 +128,7 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase const drivers::SensorConfigurationBase & sensor_configuration) override; /// @brief Callback for receiving a raw UDP packet /// @param scan_buffer Received PandarScan - void ReceiveCloudPacketCallback(const std::vector & scan_buffer); + void ReceiveCloudPacketCallback(std::vector & scan_buffer); /// @brief Decodes a nebula packet and, if it completes the scan, publishes the pointcloud. /// @param packet_msg The received packet message diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 533c3cf49..c113f1f04 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -118,7 +118,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); } -void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) +void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) { // static auto convert = nebula::util::Instrumentation("ReceiveCloudPacketCallback.convert"); // static auto publish = nebula::util::Instrumentation("ReceiveCloudPacketCallback.publish"); @@ -142,6 +142,7 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa // delay.tick(msg_ptr->stamp); // publish.tick(); + packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); } From 295d501e5f552bf2d47ed27b914e3fff9aee2248 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:21:46 +0900 Subject: [PATCH 013/122] feat(hesai_ros_wrapper: add thread-safe queue between udp receiver and decoder, decode in separate thread --- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 5 +++ .../include/nebula_ros/hesai/mt_queue.hpp | 41 +++++++++++++++++++ nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 27 ++++++++---- 3 files changed, 65 insertions(+), 8 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/hesai/mt_queue.hpp diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 896fec094..67c2b537d 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -27,6 +27,8 @@ #include #include +#include "nebula_ros/hesai/mt_queue.hpp" + namespace nebula { namespace ros @@ -203,6 +205,9 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::shared_ptr sensor_cfg_ptr_; std::shared_ptr correction_cfg_ptr_; + mt_queue> packet_queue_; + std::thread decoder_thread_; + Status interface_status_; //todo: temporary class member during single node refactoring diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp new file mode 100644 index 000000000..49c08b957 --- /dev/null +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -0,0 +1,41 @@ +#pragma once + +#include +#include +#include + +template +class mt_queue +{ +private: + std::mutex d_mutex; + std::condition_variable d_condition; + std::deque d_queue; + + size_t capacity_; + +public: + mt_queue(size_t capacity) : capacity_(capacity) {} + + bool push(T && value) + { + { + std::unique_lock lock(this->d_mutex); + if (d_queue.size() == capacity_) { + return false; + } + + d_queue.push_front(std::move(value)); + } + this->d_condition.notify_one(); + return true; + } + T pop() + { + std::unique_lock lock(this->d_mutex); + this->d_condition.wait(lock, [=] { return !this->d_queue.empty(); }); + T rc(std::move(this->d_queue.back())); + this->d_queue.pop_back(); + return rc; + } +}; \ No newline at end of file diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index c113f1f04..b86c05199 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -7,7 +7,8 @@ namespace ros HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), hw_interface_(), - diagnostics_updater_(this) + diagnostics_updater_(this), + packet_queue_(300) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); @@ -91,13 +92,20 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - auto packet_qos = - rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 1000), qos_profile); + // auto packet_qos = + // rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 300), qos_profile); - packet_pub_ = create_publisher("hesai_packets", packet_qos); - packet_sub_ = create_subscription( - "hesai_packets", packet_qos, - std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); + // packet_pub_ = create_publisher("hesai_packets", packet_qos); + // packet_sub_ = create_subscription( + // "hesai_packets", packet_qos, + // std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); + + decoder_thread_ = std::thread([this](){ + while(true) { + auto pkt = packet_queue_.pop(); + this->ProcessCloudPacket(std::move(pkt)); + } + }); nebula_points_pub_ = this->create_publisher("pandar_points", pointcloud_qos); @@ -142,7 +150,10 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) // delay.tick(msg_ptr->stamp); // publish.tick(); - packet_pub_->publish(std::move(msg_ptr)); + if (!packet_queue_.push(std::move(msg_ptr))) { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packets dropped"); + } + // packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); } From bdec15dcc3d435b5b6bb847c8e15fa38cb1287e9 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:22:12 +0900 Subject: [PATCH 014/122] feat(nebula_common): more instrumentation tools --- .../nebula_common/util/instrumentation.hpp | 87 +++++++------------ .../util/performance_counter.hpp | 43 +++++++++ .../nebula_common/util/topic_delay.hpp | 68 +++++++++++++++ scripts/plot_instrumentation.py | 77 ++++++++++++++++ 4 files changed, 220 insertions(+), 55 deletions(-) create mode 100644 nebula_common/include/nebula_common/util/performance_counter.hpp create mode 100644 nebula_common/include/nebula_common/util/topic_delay.hpp create mode 100755 scripts/plot_instrumentation.py diff --git a/nebula_common/include/nebula_common/util/instrumentation.hpp b/nebula_common/include/nebula_common/util/instrumentation.hpp index ab9357286..ccce705d8 100644 --- a/nebula_common/include/nebula_common/util/instrumentation.hpp +++ b/nebula_common/include/nebula_common/util/instrumentation.hpp @@ -1,5 +1,7 @@ #pragma once +#include "nebula_common/util/performance_counter.hpp" + #include #include #include @@ -18,86 +20,61 @@ class Instrumentation using duration = std::chrono::nanoseconds; public: - Instrumentation(std::string tag) : tag(tag), last_print(clock::now()) {} + Instrumentation(std::string tag) + : tag_(std::move(tag)), last_print_(clock::now()), delays_(), rtts_() + { + } void tick() { auto now = clock::now(); - if (last_tick != time_point::min()) { - auto rtt = now - last_tick; + if (last_tick_ != time_point::min()) { + auto rtt = now - last_tick_; rtts_.update(rtt); } - last_tick = now; + last_tick_ = now; } void tock() { auto now = clock::now(); - auto delay = now - last_tick; + auto delay = now - last_tick_; delays_.update(delay); - if (now - last_print >= PRINT_INTERVAL) { + if (now - last_print_ >= PRINT_INTERVAL) { auto del = delays_.reset(); auto rtt = rtts_.reset(); - last_print = now; + last_print_ = now; - std::cout << "{\"tag\": \"" << tag << "\", \"del_min\": " << del.min.count() * 1e-9 - << ", \"del_avg\": " << del.avg.count() * 1e-9 - << ", \"del_max\": " << del.max.count() * 1e-9 - << ", \"rtt_min\": " << rtt.min.count() * 1e-9 - << ", \"rtt_avg\": " << rtt.avg.count() * 1e-9 - << ", \"rtt_max\": " << rtt.max.count() * 1e-9 << ", \"window\": " << rtt.count - << '}' << std::endl; - } - } + std::stringstream ss; -private: - class Counter - { - public: - struct Stats - { - duration min; - duration avg; - duration max; - uint64_t count; - }; - - Stats reset() - { - auto avg_measurement = sum_measurements / num_measurements; - - Stats result{min_measurement, avg_measurement, max_measurement, num_measurements}; - - sum_measurements = duration::zero(); - num_measurements = 0; - min_measurement = duration::zero(); - max_measurement = duration::max(); - } + ss << "{\"type\": \"instrumentation\", \"tag\": \"" << tag_ + << "\", \"del\": ["; + + for (duration & dt : *del) { + ss << dt.count() << ','; + } - void update(duration measurement) - { - sum_measurements += measurement; - num_measurements++; + ss <<"null], \"rtt\": ["; - min_measurement = std::min(min_measurement, measurement); - max_measurement = std::max(max_measurement, measurement); - } + for (duration & dt : *rtt) { + ss << dt.count() << ','; + } + + ss << "null]}" << std::endl; - private: - duration sum_measurements{duration::zero()}; - uint64_t num_measurements{0}; - duration min_measurement{duration::max()}; - duration max_measurement{duration::zero()}; - }; + std::cout << ss.str(); + } + } - std::string tag; +private: + std::string tag_; - time_point last_tick{time_point::min()}; - time_point last_print{time_point::min()}; + time_point last_tick_{time_point::min()}; + time_point last_print_{time_point::min()}; Counter delays_; Counter rtts_; diff --git a/nebula_common/include/nebula_common/util/performance_counter.hpp b/nebula_common/include/nebula_common/util/performance_counter.hpp new file mode 100644 index 000000000..cd6b618f1 --- /dev/null +++ b/nebula_common/include/nebula_common/util/performance_counter.hpp @@ -0,0 +1,43 @@ +#pragma once + +#include +#include +#include + +namespace nebula +{ +namespace util +{ + +class Counter +{ + using clock = std::chrono::high_resolution_clock; + using time_point = clock::time_point; + using duration = std::chrono::nanoseconds; + +public: + Counter() + : buf_record_(), buf_output_() + { + buf_record_.resize(100000); + buf_output_.resize(100000); + } + + std::vector * reset() + { + buf_record_.swap(buf_output_); + buf_record_.clear(); + return &buf_output_; + } + + void update(duration measurement) + { + buf_record_.push_back(measurement); + } + +private: + std::vector buf_record_; + std::vector buf_output_; +}; +} // namespace util +} // namespace nebula \ No newline at end of file diff --git a/nebula_common/include/nebula_common/util/topic_delay.hpp b/nebula_common/include/nebula_common/util/topic_delay.hpp new file mode 100644 index 000000000..a92ce29a2 --- /dev/null +++ b/nebula_common/include/nebula_common/util/topic_delay.hpp @@ -0,0 +1,68 @@ +#pragma once + +#include + +#include "nebula_common/util/performance_counter.hpp" + + +#include +#include +#include + +namespace nebula +{ +namespace util +{ + +using namespace std::chrono_literals; + +class TopicDelay +{ + using clock = std::chrono::high_resolution_clock; + using time_point = clock::time_point; + using duration = std::chrono::nanoseconds; + +public: + TopicDelay(std::string tag) : tag_(std::move(tag)), last_print_(clock::now()), delays_() {} + + void tick(builtin_interfaces::msg::Time & stamp) + { + auto now = clock::now(); + + time_point t_msg = time_point(duration(static_cast(stamp.sec) * 1'000'000'000ULL + stamp.nanosec)); + auto delay = now - t_msg; + + delays_.update(delay); + + if (now - last_print_ >= PRINT_INTERVAL) { + auto del = delays_.reset(); + + last_print_ = now; + + std::stringstream ss; + + ss << "{\"type\": \"topic_delay\", \"tag\": \"" << tag_ + << "\", \"del\": ["; + + for (duration & dt : *del) { + ss << dt.count() << ','; + } + + ss << "null]}" << std::endl; + + std::cout << ss.str(); + } + } + +private: + std::string tag_; + + time_point last_print_{time_point::min()}; + + Counter delays_; + + const duration PRINT_INTERVAL = 1s; +}; + +} // namespace util +} // namespace nebula \ No newline at end of file diff --git a/scripts/plot_instrumentation.py b/scripts/plot_instrumentation.py new file mode 100755 index 000000000..fe9c12fda --- /dev/null +++ b/scripts/plot_instrumentation.py @@ -0,0 +1,77 @@ +#!/usr/bin/python3 + +import argparse +from matplotlib import pyplot as plt +import numpy as np +import pandas as pd +import re +import json +import os +from collections import defaultdict + +def condition_data(log_file: str): + with open(log_file, 'r') as f: + lines = f.readlines() + lines = [re.search(r'(\{"type":.*?"tag":.*?\})', l) for l in lines] + lines = [re.sub(r'([0-9])"', r'\1', l[1]) for l in lines if l] + lines = [json.loads(l) for l in lines if l] + + cols = defaultdict(list) + + for record in lines: + for key in record.keys(): + if key in ["tag", "type"]: + continue + + colname = f"{record['type']}.{key}.{record['tag']}" + cols[colname] += [num for num in record[key] if num is not None] + + def quantile_filter(series, quantile): + q = series.quantile(quantile) + return series[series <= q] + + cols = {k: pd.Series(v, name=k) / 1e3 for k, v in cols.items()} + cols = {k: quantile_filter(v, .999) for k, v in cols.items()} + + for v in cols.values(): + v: pd.Series + v.attrs['file'] = os.path.basename(os.path.splitext(log_file)[0]) + + return cols + +def plot(conditioned_logs): + + conditioned_logs = {k: [dic[k] for dic in conditioned_logs] for k in conditioned_logs[0]} + + fig, axs = plt.subplots(1, len(conditioned_logs), figsize=(15, 8), dpi=120) + + handles, labels = [], [] + + for i, k in enumerate(sorted(conditioned_logs.keys())): + k: str + v = conditioned_logs[k] + ax: plt.Axes = axs[i] + art = ax.boxplot(v) + handles.append(art) + labels.append(k) + ax.set_ylabel("dt [µs]") + ax.set_title(k.replace(".", "\n")) + ax.set_xticks([1 + i for i in range(len(v))], [ser.attrs['file'] for ser in v]) + ax.tick_params(axis='x', labelrotation=90) + + + + fig.tight_layout() + plt.savefig("instrumentation.png") + plt.show() + +def main(args): + conditioned_logs = [condition_data(f) for f in args.log_files] + plot(conditioned_logs) + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("log_files", nargs="+") + args = parser.parse_args() + + main(args) \ No newline at end of file From 017cfadabe38d0f69576f584503fc9fb14a8e15f Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:23:02 +0900 Subject: [PATCH 015/122] fix: update link to transport_drivers fork --- build_depends.repos | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/build_depends.repos b/build_depends.repos index e28379f1a..e9278685a 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -2,5 +2,5 @@ repositories: # TCP version of transport drivers transport_drivers: type: git - url: https://github.com/MapIV/transport_drivers - version: boost + url: https://github.com/mojomex/transport_drivers + version: mutable-buffer-in-udp-callback From 6713b0d7d5b8386f002d169e29b7b9c5463b52ec Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 15:14:44 +0900 Subject: [PATCH 016/122] fix(hesai_hw_monitor_ros_wrapper): fixed wrong range given for S/N copy --- nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp index a7d6e5b11..e64bf443b 100644 --- a/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp @@ -74,7 +74,7 @@ HesaiHwMonitorRosWrapper::HesaiHwMonitorRosWrapper(const rclcpp::NodeOptions & o RCLCPP_INFO_STREAM(this->get_logger(), "HesaiInventory"); RCLCPP_INFO_STREAM(this->get_logger(), result); info_model = result.get_str_model(); - info_serial = std::string(std::begin(result.sn), std::begin(result.sn)); + info_serial = std::string(std::begin(result.sn), std::end(result.sn)); hw_interface_.SetTargetModel(result.model); RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); From cd6ad8e4c78b36f270581f7483e815fb6ee5ed2c Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 15:36:49 +0900 Subject: [PATCH 017/122] update GitHub PR view From decf1ac207142e818d6c6b4cb3193fd3c271dae0 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 16:26:42 +0900 Subject: [PATCH 018/122] fix(hesai): print uint8, uint16 as numbers --- .../hesai_cmd_response.hpp | 109 ++++++++++-------- 1 file changed, 61 insertions(+), 48 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp index 4af74426c..a6d78c45e 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp @@ -124,11 +124,11 @@ struct HesaiPtpDiagGrandmaster { os << "clockQuality: " << arg.clockQuality; os << ", "; - os << "utc_offset: " << static_cast(arg.utc_offset.value()); + os << "utc_offset: " << arg.utc_offset; os << ", "; - os << "time_flags: " << static_cast(arg.time_flags); + os << "time_flags: " << +arg.time_flags; os << ", "; - os << "time_source: " << static_cast(arg.time_source); + os << "time_source: " << +arg.time_source; return os; } @@ -137,13 +137,13 @@ struct HesaiPtpDiagGrandmaster /// @brief struct of PTC_COMMAND_GET_INVENTORY_INFO struct HesaiInventory { - uint8_t sn[18]; - uint8_t date_of_manufacture[16]; + char sn[18]; + char date_of_manufacture[16]; uint8_t mac[6]; - uint8_t sw_ver[16]; - uint8_t hw_ver[16]; - uint8_t control_fw_ver[16]; - uint8_t sensor_fw_ver[16]; + char sw_ver[16]; + char hw_ver[16]; + char control_fw_ver[16]; + char sensor_fw_ver[16]; big_uint16_buf_t angle_offset; uint8_t model; uint8_t motor_type; @@ -152,10 +152,13 @@ struct HesaiInventory friend std::ostream & operator<<(std::ostream & os, nebula::HesaiInventory const & arg) { - os << "sn: " << std::string(std::begin(arg.sn), std::end(arg.sn)); + std::ios initial_format(nullptr); + initial_format.copyfmt(os); + + os << "sn: " << std::string(arg.sn, strnlen(arg.sn, sizeof(arg.sn))); os << ", "; os << "date_of_manufacture: " - << std::string(std::begin(arg.date_of_manufacture), std::end(arg.date_of_manufacture)); + << std::string(arg.date_of_manufacture, strnlen(arg.date_of_manufacture, sizeof(arg.date_of_manufacture))); os << ", "; os << "mac: "; @@ -163,35 +166,37 @@ struct HesaiInventory if (i != 0) { os << ':'; } - os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.mac[i])); + os << std::hex << std::setfill('0') << std::setw(2) << (+arg.mac[i]); } + os.copyfmt(initial_format); os << ", "; - os << "sw_ver: " << std::string(std::begin(arg.sw_ver), std::end(arg.sw_ver)); + os << "sw_ver: " << std::string(arg.sw_ver, strnlen(arg.sw_ver, sizeof(arg.sw_ver))); os << ", "; - os << "hw_ver: " << std::string(std::begin(arg.hw_ver), std::end(arg.hw_ver)); + os << "hw_ver: " << std::string(arg.hw_ver, strnlen(arg.hw_ver, sizeof(arg.hw_ver))); os << ", "; os << "control_fw_ver: " - << std::string(std::begin(arg.control_fw_ver), std::end(arg.control_fw_ver)); + << std::string(arg.control_fw_ver, strnlen(arg.control_fw_ver, sizeof(arg.control_fw_ver))); os << ", "; os << "sensor_fw_ver: " - << std::string(std::begin(arg.sensor_fw_ver), std::end(arg.sensor_fw_ver)); + << std::string(arg.sensor_fw_ver, strnlen(arg.sensor_fw_ver, sizeof(arg.sensor_fw_ver))); os << ", "; os << "angle_offset: " << arg.angle_offset; os << ", "; - os << "model: " << arg.model; + os << "model: " << +arg.model; os << ", "; - os << "motor_type: " << arg.motor_type; + os << "motor_type: " << +arg.motor_type; os << ", "; - os << "num_of_lines: " << arg.num_of_lines; + os << "num_of_lines: " << +arg.num_of_lines; os << ", "; for (size_t i = 0; i < sizeof(arg.reserved); i++) { if (i != 0) { os << ' '; } - os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.reserved[i])); + os << std::hex << std::setfill('0') << std::setw(2) << (+arg.reserved[i]); } + os.copyfmt(initial_format); return os; } @@ -258,29 +263,32 @@ struct HesaiConfig friend std::ostream & operator<<(std::ostream & os, nebula::HesaiConfig const & arg) { + std::ios initial_format(nullptr); + initial_format.copyfmt(os); + os << "ipaddr: " - << static_cast(arg.ipaddr[0]) << "." - << static_cast(arg.ipaddr[1]) << "." - << static_cast(arg.ipaddr[2]) << "." - << static_cast(arg.ipaddr[3]); + << +arg.ipaddr[0] << "." + << +arg.ipaddr[1] << "." + << +arg.ipaddr[2] << "." + << +arg.ipaddr[3]; os << ", "; os << "mask: " - << static_cast(arg.mask[0]) << "." - << static_cast(arg.mask[1]) << "." - << static_cast(arg.mask[2]) << "." - << static_cast(arg.mask[3]); + << +arg.mask[0] << "." + << +arg.mask[1] << "." + << +arg.mask[2] << "." + << +arg.mask[3]; os << ", "; os << "gateway: " - << static_cast(arg.gateway[0]) << "." - << static_cast(arg.gateway[1]) << "." - << static_cast(arg.gateway[2]) << "." - << static_cast(arg.gateway[3]); + << +arg.gateway[0] << "." + << +arg.gateway[1] << "." + << +arg.gateway[2] << "." + << +arg.gateway[3]; os << ", "; os << "dest_ipaddr: " - << static_cast(arg.dest_ipaddr[0]) << "." - << static_cast(arg.dest_ipaddr[1]) << "." - << static_cast(arg.dest_ipaddr[2]) << "." - << static_cast(arg.dest_ipaddr[3]); + << +arg.dest_ipaddr[0] << "." + << +arg.dest_ipaddr[1] << "." + << +arg.dest_ipaddr[2] << "." + << +arg.dest_ipaddr[3]; os << ", "; os << "dest_LiDAR_udp_port: " << arg.dest_LiDAR_udp_port; os << ", "; @@ -288,7 +296,7 @@ struct HesaiConfig os << ", "; os << "spin_rate: " << arg.spin_rate; os << ", "; - os << "sync: " << arg.sync; + os << "sync: " << +arg.sync; os << ", "; os << "sync_angle: " << arg.sync_angle; os << ", "; @@ -296,27 +304,27 @@ struct HesaiConfig os << ", "; os << "stop_angle: " << arg.stop_angle; os << ", "; - os << "clock_source: " << arg.clock_source; + os << "clock_source: " << +arg.clock_source; os << ", "; - os << "udp_seq: " << arg.udp_seq; + os << "udp_seq: " << +arg.udp_seq; os << ", "; - os << "trigger_method: " << arg.trigger_method; + os << "trigger_method: " << +arg.trigger_method; os << ", "; - os << "return_mode: " << arg.return_mode; + os << "return_mode: " << +arg.return_mode; os << ", "; - os << "standby_mode: " << arg.standby_mode; + os << "standby_mode: " << +arg.standby_mode; os << ", "; - os << "motor_status: " << arg.motor_status; + os << "motor_status: " << +arg.motor_status; os << ", "; - os << "vlan_flag: " << arg.vlan_flag; + os << "vlan_flag: " << +arg.vlan_flag; os << ", "; os << "vlan_id: " << arg.vlan_id; os << ", "; - os << "clock_data_fmt: " << arg.clock_data_fmt; + os << "clock_data_fmt: " << +arg.clock_data_fmt; os << ", "; - os << "noise_filtering: " << arg.noise_filtering; + os << "noise_filtering: " << +arg.noise_filtering; os << ", "; - os << "reflectivity_mapping: " << arg.reflectivity_mapping; + os << "reflectivity_mapping: " << +arg.reflectivity_mapping; os << ", "; os << "reserved: "; @@ -324,8 +332,9 @@ struct HesaiConfig if (i != 0) { os << ' '; } - os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.reserved[i])); + os << std::hex << std::setfill('0') << std::setw(2) << (+arg.reserved[i]); } + os.copyfmt(initial_format); return os; } @@ -346,6 +355,9 @@ struct HesaiLidarStatus friend std::ostream & operator<<(std::ostream & os, nebula::HesaiLidarStatus const & arg) { + std::ios initial_format(nullptr); + initial_format.copyfmt(os); + os << "system_uptime: " << arg.system_uptime; os << ", "; os << "motor_speed: " << arg.motor_speed; @@ -378,6 +390,7 @@ struct HesaiLidarStatus } os << std::hex << std::setfill('0') << std::setw(2) << (static_cast(arg.reserved[i])); } + os.copyfmt(initial_format); return os; } From da8fd64a1144e0ef020d2245f10b4599c9e27871 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 16:43:51 +0900 Subject: [PATCH 019/122] refactor(mt_queue): make variables more readable --- .../include/nebula_ros/hesai/mt_queue.hpp | 25 +++++++++---------- 1 file changed, 12 insertions(+), 13 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp index 49c08b957..730b54f7c 100644 --- a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -8,10 +8,9 @@ template class mt_queue { private: - std::mutex d_mutex; - std::condition_variable d_condition; - std::deque d_queue; - + std::mutex mutex_; + std::condition_variable condition_variable_; + std::deque queue_; size_t capacity_; public: @@ -20,22 +19,22 @@ class mt_queue bool push(T && value) { { - std::unique_lock lock(this->d_mutex); - if (d_queue.size() == capacity_) { + std::unique_lock lock(this->mutex_); + if (queue_.size() == capacity_) { return false; } - d_queue.push_front(std::move(value)); + queue_.push_front(std::move(value)); } - this->d_condition.notify_one(); + this->condition_variable_.notify_one(); return true; } T pop() { - std::unique_lock lock(this->d_mutex); - this->d_condition.wait(lock, [=] { return !this->d_queue.empty(); }); - T rc(std::move(this->d_queue.back())); - this->d_queue.pop_back(); - return rc; + std::unique_lock lock(this->mutex_); + this->condition_variable_.wait(lock, [=] { return !this->queue_.empty(); }); + T return_value(std::move(this->queue_.back())); + this->queue_.pop_back(); + return return_value; } }; \ No newline at end of file From dc850fbd90defc83bacf18e96fd86bbee22e1dec Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 16:45:48 +0900 Subject: [PATCH 020/122] perf(hesai_ros_wrapper): update queue capacity to alleviate packet drops on ECU --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index b86c05199..f84371a36 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -8,7 +8,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), hw_interface_(), diagnostics_updater_(this), - packet_queue_(300) + packet_queue_(3000) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); From d5d98a25d5787c9525fa0bc7fe2b403b0f3da1f6 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 16:46:11 +0900 Subject: [PATCH 021/122] chore(hesai_ros_wrapper): remove unused pub/sub --- .../include/nebula_ros/hesai/hesai_ros_wrapper.hpp | 3 --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 11 ----------- 2 files changed, 14 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 67c2b537d..4038565c4 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -194,9 +194,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::shared_ptr driver_ptr_; Status wrapper_status_; - rclcpp::Publisher::SharedPtr packet_pub_; - rclcpp::Subscription::SharedPtr packet_sub_; - rclcpp::Publisher::SharedPtr nebula_points_pub_; rclcpp::Publisher::SharedPtr aw_points_ex_pub_; rclcpp::Publisher::SharedPtr aw_points_base_pub_; diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index f84371a36..1540df3fa 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -92,14 +92,6 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - // auto packet_qos = - // rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 300), qos_profile); - - // packet_pub_ = create_publisher("hesai_packets", packet_qos); - // packet_sub_ = create_subscription( - // "hesai_packets", packet_qos, - // std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); - decoder_thread_ = std::thread([this](){ while(true) { auto pkt = packet_queue_.pop(); @@ -254,9 +246,6 @@ Status HesaiRosWrapper::GetStatus() Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration) { - /////////////////////////////////////////////// - // Define and get ROS parameters - /////////////////////////////////////////////// { rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; From 1403984996b9c137e7ce7c80653d04448b70be88 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 18:07:03 +0900 Subject: [PATCH 022/122] refactor(hesai_ros_wrapper): clean up control flow, member variables --- .../common/nebula_ros_wrapper_base.hpp | 68 --- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 110 ++--- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 436 ++++++++---------- 3 files changed, 230 insertions(+), 384 deletions(-) delete mode 100644 nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp diff --git a/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp b/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp deleted file mode 100644 index 5aaeb634b..000000000 --- a/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp +++ /dev/null @@ -1,68 +0,0 @@ -#pragma once - -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" - -#include -#include -#include - -#include - -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Base class for ros wrapper of each sensor driver -class NebulaRosWrapperBase -{ -public: - NebulaRosWrapperBase() = default; - - NebulaRosWrapperBase(NebulaRosWrapperBase && c) = delete; - NebulaRosWrapperBase & operator=(NebulaRosWrapperBase && c) = delete; - NebulaRosWrapperBase(const NebulaRosWrapperBase & c) = delete; - NebulaRosWrapperBase & operator=(const NebulaRosWrapperBase & c) = delete; - - /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) - /// @return Resulting status - virtual Status StreamStart() = 0; - - /// @brief Stop point cloud streaming (not used) - /// @return Resulting status - virtual Status StreamStop() = 0; - - /// @brief Shutdown (not used) - /// @return Resulting status - virtual Status Shutdown() = 0; - -private: - /// @brief Virtual function for initializing hardware interface ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - virtual Status InitializeHwInterface( - const drivers::SensorConfigurationBase & sensor_configuration) = 0; - - /// @brief Virtual function for initializing hardware monitor ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - virtual Status InitializeHwMonitor( - const drivers::SensorConfigurationBase & sensor_configuration) = 0; - - /// @brief Virtual function for initializing ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @return Resulting status - virtual Status InitializeCloudDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) = 0; - - /// @brief Point cloud publisher - rclcpp::Publisher::SharedPtr cloud_pub_; -}; - -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 4038565c4..456e49e11 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -8,9 +8,7 @@ // #include "nebula_common/util/topic_delay.hpp" #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" -#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" -#include "nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp" -#include "nebula_ros/common/nebula_ros_wrapper_base.hpp" +#include "nebula_ros/hesai/mt_queue.hpp" #include #include @@ -27,8 +25,6 @@ #include #include -#include "nebula_ros/hesai/mt_queue.hpp" - namespace nebula { namespace ros @@ -54,7 +50,7 @@ bool get_param(const std::vector & p, const std::string & nam } /// @brief Ros wrapper of hesai driver -class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase +class HesaiRosWrapper final : public rclcpp::Node { public: explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); @@ -66,36 +62,17 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) /// @return Resulting status - Status StreamStart() override; - /// @brief Stop point cloud streaming (not used) - /// @return Resulting status - Status StreamStop() override; - /// @brief Shutdown (not used) - /// @return Resulting status - Status Shutdown() override; + Status StreamStart(); private: - /// @brief Initialize pointcloud decoder - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver (only for AT128, ignored otherwise) - /// @return Resulting status - Status InitializeCloudDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration = nullptr); - - Status InitializeCloudDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) { - return InitializeCloudDriver(sensor_configuration, calibration_configuration, nullptr); - } + Status InitializeHwInterface(); + Status InitializeDecoder(); + Status InitializeHwMonitor(); /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration /// @return Resulting status - Status GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration); + Status GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration); /// @brief Get calibration data from the sensor /// @param calibration_configuration Output of CalibrationConfiguration @@ -123,11 +100,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::unique_ptr pointcloud, const rclcpp::Publisher::SharedPtr & publisher); - /// @brief Initializing hardware interface ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - Status InitializeHwInterface( - const drivers::SensorConfigurationBase & sensor_configuration) override; /// @brief Callback for receiving a raw UDP packet /// @param scan_buffer Received PandarScan void ReceiveCloudPacketCallback(std::vector & scan_buffer); @@ -145,12 +117,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase /// @return SetParametersResult std::vector updateParameters(); - /// @brief Initializing hardware monitor ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - Status InitializeHwMonitor( - const drivers::SensorConfigurationBase & sensor_configuration) override; - /// @brief Initializing diagnostics void InitializeHesaiDiagnostics(); /// @brief Callback of the timer for getting the current lidar status @@ -192,7 +158,10 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::string GetFixedPrecisionString(double val, int pre = 2); std::shared_ptr driver_ptr_; + drivers::HesaiHwInterface hw_interface_; + Status wrapper_status_; + Status interface_status_; rclcpp::Publisher::SharedPtr nebula_points_pub_; rclcpp::Publisher::SharedPtr aw_points_ex_pub_; @@ -202,15 +171,15 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::shared_ptr sensor_cfg_ptr_; std::shared_ptr correction_cfg_ptr_; + /// @brief Stores received packets that have not been processed yet by the decoder thread mt_queue> packet_queue_; + /// @brief Thread to isolate decoding from receiving std::thread decoder_thread_; - Status interface_status_; - - //todo: temporary class member during single node refactoring + // todo: temporary class member during single node refactoring bool launch_hw_; - //todo: temporary class member during single node refactoring + // todo: temporary class member during single node refactoring std::string calibration_file_path; /// @brief File path of Correction data (Only required only for AT) std::string correction_file_path; @@ -218,9 +187,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase /// @brief Received Hesai message publisher rclcpp::Publisher::SharedPtr pandar_scan_pub_; - drivers::HesaiHwInterface hw_interface_; - - uint16_t delay_hw_ms_; bool retry_hw_; std::mutex mtx_config_; OnSetParametersCallbackHandle::SharedPtr set_param_res_; @@ -228,39 +194,35 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase diagnostic_updater::Updater diagnostics_updater_; rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; - rclcpp::TimerBase::SharedPtr diagnostics_update_monitor_timer_; rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_; - std::unique_ptr current_status; - std::unique_ptr current_monitor; - std::unique_ptr current_config; - std::unique_ptr current_inventory; - std::unique_ptr current_lidar_monitor_tree; - std::unique_ptr current_status_time; - std::unique_ptr current_config_time; - std::unique_ptr current_inventory_time; - std::unique_ptr current_lidar_monitor_time; - uint8_t current_diag_status; - uint8_t current_monitor_status; - uint16_t diag_span_; - uint16_t delay_monitor_ms_; - std::mutex mtx_diag; - std::mutex mtx_status; - std::mutex mtx_lidar_monitor; + std::unique_ptr current_status_; + std::unique_ptr current_monitor_; + std::unique_ptr current_config_; + std::unique_ptr current_inventory_; + std::unique_ptr current_lidar_monitor_tree_; + + std::unique_ptr current_status_time_; + std::unique_ptr current_config_time_; + std::unique_ptr current_inventory_time_; + std::unique_ptr current_lidar_monitor_time_; - std::string info_model; - std::string info_serial; - rclcpp::CallbackGroup::SharedPtr cbg_r_; - rclcpp::CallbackGroup::SharedPtr cbg_m_; - rclcpp::CallbackGroup::SharedPtr cbg_m2_; + uint8_t current_diag_status_; + uint8_t current_monitor_status_; + + uint16_t diag_span_; + std::mutex mtx_lidar_status_; + std::mutex mtx_lidar_monitor_; - const char * not_supported_message; - const char * error_message; - std::string message_sep; + std::string info_model_; + std::string info_serial_; - std::vector temperature_names; + std::vector temperature_names_; bool setup_sensor; + const std::string MSG_NOT_SUPPORTED = "Not supported"; + const std::string MSG_ERROR = "Error"; + const std::string MSG_SEP = ": "; }; } // namespace ros diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 1540df3fa..f0e6c121a 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -7,115 +7,164 @@ namespace ros HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), hw_interface_(), - diagnostics_updater_(this), - packet_queue_(3000) + packet_queue_(3000), + diagnostics_updater_(this) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); drivers::HesaiSensorConfiguration sensor_configuration; wrapper_status_ = GetParameters(sensor_configuration); sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + // DeclareRosParameters(); + // auto sensor_cfg_ptr = GetRosParameters(); + InitializeHwInterface(); + InitializeDecoder(); + InitializeHwMonitor(); + // StreamStart(); - // hwiface - { - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - Status rt = hw_interface_.InitializeTcpDriver(); - if (this->retry_hw_) { - int cnt = 0; - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - while (rt == Status::ERROR_1) { - cnt++; - std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - rt = hw_interface_.InitializeTcpDriver(); - } + + RCLCPP_DEBUG(this->get_logger(), "Starting stream"); + StreamStart(); + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); +} + +Status HesaiRosWrapper::InitializeHwInterface() +{ + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return interface_status_; + } + hw_interface_.SetLogger(std::make_shared(this->get_logger())); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); + + Status status; + int retry_count = 0; + + while (true) { + status = hw_interface_.InitializeTcpDriver(); + if (status == Status::OK || !retry_hw_) { + break; } - if (rt != Status::ERROR_1) { - try { - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto result = hw_interface_.GetInventory(); - RCLCPP_INFO_STREAM(get_logger(), result); - hw_interface_.SetTargetModel(result.model); - }); - for (std::thread & th : thread_pool) { - th.join(); - } + retry_count++; + std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << retry_count); + }; - } catch (...) { - std::cout << "catch (...) in parent" << std::endl; - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); - } - if (this->setup_sensor) { - hw_interface_.CheckAndSetConfig(); - updateParameters(); - } - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); - hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); + if (status == Status::OK) { + try { + auto inventory = hw_interface_.GetInventory(); + RCLCPP_INFO_STREAM(get_logger(), inventory); + hw_interface_.SetTargetModel(inventory.model); + } catch (...) { + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); } + if (this->setup_sensor) { + hw_interface_.CheckAndSetConfig(); + updateParameters(); + } + } else { + RCLCPP_ERROR_STREAM( + get_logger(), + "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); + hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); } - // decoder - { - drivers::HesaiCalibrationConfiguration calibration_configuration; - drivers::HesaiCorrection correction_configuration; - wrapper_status_ = GetCalibrationData(calibration_configuration, correction_configuration); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return; - } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - - calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); - // Will be left empty for AT128, and ignored by all decoders except AT128 - correction_cfg_ptr_ = std::make_shared(correction_configuration); - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - wrapper_status_ = InitializeCloudDriver( - std::static_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto pointcloud_qos = - rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - - decoder_thread_ = std::thread([this](){ - while(true) { - auto pkt = packet_queue_.pop(); - this->ProcessCloudPacket(std::move(pkt)); - } - }); + return Status::OK; +} + +Status HesaiRosWrapper::InitializeDecoder() +{ + calibration_cfg_ptr_ = std::make_shared(); + correction_cfg_ptr_ = std::make_shared(); - nebula_points_pub_ = - this->create_publisher("pandar_points", pointcloud_qos); - aw_points_base_pub_ = - this->create_publisher("aw_points", pointcloud_qos); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", pointcloud_qos); + wrapper_status_ = GetCalibrationData(*calibration_cfg_ptr_, *correction_cfg_ptr_); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return wrapper_status_; } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); + rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; + auto pointcloud_qos = + rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + + decoder_thread_ = std::thread([this]() { + while (true) { + auto pkt = packet_queue_.pop(); + this->ProcessCloudPacket(std::move(pkt)); + } + }); - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + nebula_points_pub_ = + this->create_publisher("pandar_points", pointcloud_qos); + aw_points_base_pub_ = + this->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = + this->create_publisher("aw_points_ex", pointcloud_qos); - InitializeHwMonitor(*sensor_cfg_ptr_); + driver_ptr_ = std::make_shared( + sensor_cfg_ptr_, calibration_cfg_ptr_, correction_cfg_ptr_); + return driver_ptr_->GetStatus(); +} - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); +Status HesaiRosWrapper::InitializeHwMonitor() +{ + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return Status::ERROR_1; + } + + switch (sensor_cfg_ptr_->sensor_model) { + case nebula::drivers::SensorModel::HESAI_PANDARXT32: + case nebula::drivers::SensorModel::HESAI_PANDARXT32M: + case nebula::drivers::SensorModel::HESAI_PANDARAT128: + temperature_names_.emplace_back("Bottom circuit board T1"); + temperature_names_.emplace_back("Bottom circuit board T2"); + temperature_names_.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names_.emplace_back("Laser emitting board RT_L2"); + temperature_names_.emplace_back("Receiving board RT_R"); + temperature_names_.emplace_back("Receiving board RT2"); + temperature_names_.emplace_back("Top circuit RT3"); + temperature_names_.emplace_back("Not used"); + break; + case nebula::drivers::SensorModel::HESAI_PANDAR64: + case nebula::drivers::SensorModel::HESAI_PANDAR40P: + case nebula::drivers::SensorModel::HESAI_PANDAR40M: + case nebula::drivers::SensorModel::HESAI_PANDARQT64: + case nebula::drivers::SensorModel::HESAI_PANDARQT128: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: + default: + temperature_names_.emplace_back("Bottom circuit RT1"); + temperature_names_.emplace_back("Bottom circuit RT2"); + temperature_names_.emplace_back("Internal Temperature"); + temperature_names_.emplace_back("Laser emitting board RT1"); + temperature_names_.emplace_back("Laser emitting board RT2"); + temperature_names_.emplace_back("Receiving board RT1"); + temperature_names_.emplace_back("Top circuit RT1"); + temperature_names_.emplace_back("Top circuit RT2"); + break; + } + + auto result = hw_interface_.GetInventory(); + current_inventory_.reset(new HesaiInventory(result)); + current_inventory_time_.reset(new rclcpp::Time(this->get_clock()->now())); + std::cout << "HesaiInventory" << std::endl; + std::cout << result << std::endl; + info_model_ = result.get_str_model(); + info_serial_ = std::string(result.sn.begin(), result.sn.end()); + hw_interface_.SetTargetModel(result.model); + RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model_); + RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial_); + InitializeHesaiDiagnostics(); + return Status::OK; } void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) @@ -227,18 +276,6 @@ void HesaiRosWrapper::PublishCloud( publisher->publish(std::move(pointcloud)); } -Status HesaiRosWrapper::InitializeCloudDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) -{ - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration), - std::static_pointer_cast(correction_configuration)); - return driver_ptr_->GetStatus(); -} - Status HesaiRosWrapper::GetStatus() { return wrapper_status_; @@ -766,85 +803,6 @@ Status HesaiRosWrapper::StreamStart() return interface_status_; } -Status HesaiRosWrapper::StreamStop() -{ - return Status::OK; -} -Status HesaiRosWrapper::Shutdown() -{ - return Status::OK; -} - -Status HesaiRosWrapper::InitializeHwInterface( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) -{ - std::stringstream ss; - ss << sensor_configuration; - RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); - return Status::OK; -} - -Status HesaiRosWrapper::InitializeHwMonitor( // todo: don't think this is needed - const drivers::SensorConfigurationBase & /* sensor_configuration */) -{ - cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); - cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return Status::ERROR_1; - } - - message_sep = ": "; - not_supported_message = "Not supported"; - error_message = "Error"; - - switch (sensor_cfg_ptr_->sensor_model) { - case nebula::drivers::SensorModel::HESAI_PANDARXT32: - case nebula::drivers::SensorModel::HESAI_PANDARXT32M: - case nebula::drivers::SensorModel::HESAI_PANDARAT128: - temperature_names.emplace_back("Bottom circuit board T1"); - temperature_names.emplace_back("Bottom circuit board T2"); - temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); - temperature_names.emplace_back("Laser emitting board RT_L2"); - temperature_names.emplace_back("Receiving board RT_R"); - temperature_names.emplace_back("Receiving board RT2"); - temperature_names.emplace_back("Top circuit RT3"); - temperature_names.emplace_back("Not used"); - break; - case nebula::drivers::SensorModel::HESAI_PANDAR64: - case nebula::drivers::SensorModel::HESAI_PANDAR40P: - case nebula::drivers::SensorModel::HESAI_PANDAR40M: - case nebula::drivers::SensorModel::HESAI_PANDARQT64: - case nebula::drivers::SensorModel::HESAI_PANDARQT128: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: - default: - temperature_names.emplace_back("Bottom circuit RT1"); - temperature_names.emplace_back("Bottom circuit RT2"); - temperature_names.emplace_back("Internal Temperature"); - temperature_names.emplace_back("Laser emitting board RT1"); - temperature_names.emplace_back("Laser emitting board RT2"); - temperature_names.emplace_back("Receiving board RT1"); - temperature_names.emplace_back("Top circuit RT1"); - temperature_names.emplace_back("Top circuit RT2"); - break; - } - - auto result = hw_interface_.GetInventory(); - current_inventory.reset(new HesaiInventory(result)); - current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); - std::cout << "HesaiInventory" << std::endl; - std::cout << result << std::endl; - info_model = result.get_str_model(); - info_serial = std::string(result.sn.begin(), result.sn.end()); - hw_interface_.SetTargetModel(result.model); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); - InitializeHesaiDiagnostics(); - return Status::OK; -} - rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( const std::vector & p) { @@ -926,7 +884,7 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() RCLCPP_INFO_STREAM(this->get_logger(), "InitializeHesaiDiagnostics"); using std::chrono_literals::operator""s; std::ostringstream os; - auto hardware_id = info_model + ": " + info_serial; + auto hardware_id = info_model_ + ": " + info_serial_; diagnostics_updater_.setHardwareID(hardware_id); RCLCPP_INFO_STREAM(this->get_logger(), "hardware_id: " + hardware_id); @@ -935,12 +893,12 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() diagnostics_updater_.add("hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); diagnostics_updater_.add("hesai_rpm", this, &HesaiRosWrapper::HesaiCheckRpm); - current_status.reset(); - current_monitor.reset(); - current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_status_.reset(); + current_monitor_.reset(); + current_status_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; auto fetch_diag_from_sensor = [this]() { OnHesaiStatusTimer(); @@ -952,10 +910,7 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() }; fetch_diagnostics_timer_ = - std::make_shared>( - this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); + create_wall_timer(std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor)); if (hw_interface_.UseHttpGetLidarMonitor()) { diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); @@ -966,32 +921,30 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() auto on_timer_update = [this] { RCLCPP_DEBUG_STREAM(get_logger(), "OnUpdateTimer"); auto now = this->get_clock()->now(); - auto dif = (now - *current_status_time).seconds(); + auto dif = (now - *current_status_time_).seconds(); RCLCPP_DEBUG_STREAM(get_logger(), "dif(status): " << dif); if (diag_span_ * 2.0 < dif * 1000) { - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); } else { - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::OK; + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; RCLCPP_DEBUG_STREAM(get_logger(), "OK"); } - dif = (now - *current_lidar_monitor_time).seconds(); + dif = (now - *current_lidar_monitor_time_).seconds(); RCLCPP_DEBUG_STREAM(get_logger(), "dif(monitor): " << dif); if (diag_span_ * 2.0 < dif * 1000) { - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); } else { - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::OK; + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; RCLCPP_DEBUG_STREAM(get_logger(), "OK"); } diagnostics_updater_.force_update(); }; - diagnostics_update_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(1000), std::move(on_timer_update), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(diagnostics_update_timer_, cbg_r_); + diagnostics_update_timer_ = + create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); RCLCPP_DEBUG_STREAM(get_logger(), "add_timer"); } @@ -1003,7 +956,7 @@ std::string HesaiRosWrapper::GetPtreeValue( if (value) { return value.get(); } else { - return not_supported_message; + return MSG_NOT_SUPPORTED; } } std::string HesaiRosWrapper::GetFixedPrecisionString(double val, int pre) @@ -1018,9 +971,9 @@ void HesaiRosWrapper::OnHesaiStatusTimer() RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer" << std::endl); try { auto result = hw_interface_.GetLidarStatus(); - std::scoped_lock lock(mtx_status); - current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_status.reset(new HesaiLidarStatus(result)); + std::scoped_lock lock(mtx_lidar_status_); + current_status_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_status_.reset(new HesaiLidarStatus(result)); } catch (const std::system_error & error) { RCLCPP_ERROR_STREAM( rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), error.what()); @@ -1037,9 +990,9 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp() RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp"); try { hw_interface_.GetLidarMonitorAsyncHttp([this](const std::string & str) { - std::scoped_lock lock(mtx_lidar_monitor); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_tree = + std::scoped_lock lock(mtx_lidar_monitor_); + current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_lidar_monitor_tree_ = std::make_unique(hw_interface_.ParseJson(str)); }); } catch (const std::system_error & error) { @@ -1059,11 +1012,10 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimer() { RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer"); try { - auto ios = std::make_shared(); auto result = hw_interface_.GetLidarMonitor(); - std::scoped_lock lock(mtx_lidar_monitor); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_monitor.reset(new HesaiLidarMonitor(result)); + std::scoped_lock lock(mtx_lidar_monitor_); + current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_monitor_.reset(new HesaiLidarMonitor(result)); } catch (const std::system_error & error) { RCLCPP_ERROR_STREAM( rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), @@ -1078,14 +1030,14 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimer() void HesaiRosWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_status); - if (current_status) { + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - diagnostics.add("system_uptime", std::to_string(current_status->system_uptime)); - diagnostics.add("startup_times", std::to_string(current_status->startup_times)); - diagnostics.add("total_operation_time", std::to_string(current_status->total_operation_time)); + diagnostics.add("system_uptime", std::to_string(current_status_->system_uptime)); + diagnostics.add("startup_times", std::to_string(current_status_->startup_times)); + diagnostics.add("total_operation_time", std::to_string(current_status_->total_operation_time)); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -1095,13 +1047,13 @@ void HesaiRosWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapp void HesaiRosWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_status); - if (current_status) { + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - auto gps_status = current_status->get_str_gps_pps_lock(); - auto gprmc_status = current_status->get_str_gps_gprmc_status(); - auto ptp_status = current_status->get_str_ptp_clock_status(); + auto gps_status = current_status_->get_str_gps_pps_lock(); + auto gprmc_status = current_status_->get_str_gps_gprmc_status(); + auto ptp_status = current_status_->get_str_ptp_clock_status(); std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); @@ -1129,13 +1081,13 @@ void HesaiRosWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper void HesaiRosWrapper::HesaiCheckTemperature( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_status); - if (current_status) { + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - for (size_t i = 0; i < current_status->temperature.size(); i++) { + for (size_t i = 0; i < current_status_->temperature.size(); i++) { diagnostics.add( - temperature_names[i], GetFixedPrecisionString(current_status->temperature[i] * 0.01)); + temperature_names_[i], GetFixedPrecisionString(current_status_->temperature[i] * 0.01)); } diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -1145,11 +1097,11 @@ void HesaiRosWrapper::HesaiCheckTemperature( void HesaiRosWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_status); - if (current_status) { + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - diagnostics.add("motor_speed", std::to_string(current_status->motor_speed)); + diagnostics.add("motor_speed", std::to_string(current_status_->motor_speed)); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -1160,8 +1112,8 @@ void HesaiRosWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper void HesaiRosWrapper::HesaiCheckVoltageHttp( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_lidar_monitor); - if (current_lidar_monitor_tree) { + std::scoped_lock lock(mtx_lidar_monitor_); + if (current_lidar_monitor_tree_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; std::string key = ""; @@ -1169,18 +1121,18 @@ void HesaiRosWrapper::HesaiCheckVoltageHttp( std::string mes; key = "lidarInCur"; try { - mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); + mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); } catch (boost::bad_lexical_cast & ex) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = error_message + std::string(ex.what()); + mes = MSG_ERROR + std::string(ex.what()); } diagnostics.add(key, mes); key = "lidarInVol"; try { - mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); + mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); } catch (boost::bad_lexical_cast & ex) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = error_message + std::string(ex.what()); + mes = MSG_ERROR + std::string(ex.what()); } diagnostics.add(key, mes); @@ -1192,16 +1144,16 @@ void HesaiRosWrapper::HesaiCheckVoltageHttp( void HesaiRosWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_lidar_monitor); - if (current_monitor) { + std::scoped_lock lock(mtx_lidar_monitor_); + if (current_monitor_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; diagnostics.add( - "input_voltage", GetFixedPrecisionString(current_monitor->input_voltage * 0.01) + " V"); + "input_voltage", GetFixedPrecisionString(current_monitor_->input_voltage * 0.01) + " V"); diagnostics.add( - "input_current", GetFixedPrecisionString(current_monitor->input_current * 0.01) + " mA"); + "input_current", GetFixedPrecisionString(current_monitor_->input_current * 0.01) + " mA"); diagnostics.add( - "input_power", GetFixedPrecisionString(current_monitor->input_power * 0.01) + " W"); + "input_power", GetFixedPrecisionString(current_monitor_->input_power * 0.01) + " W"); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { From b20317630dc33c4eb941a723b31d687068fff639 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 9 Apr 2024 18:45:41 +0900 Subject: [PATCH 023/122] feat(hesai_ros_wrapper): publish/subscribe to legacy pandar_packets on demand --- .../hesai_hw_interface.hpp | 8 +- .../hesai_hw_interface.cpp | 70 ++---------- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 52 +++++---- .../include/nebula_ros/hesai/mt_queue.hpp | 13 ++- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 101 +++++++++++++----- 5 files changed, 124 insertions(+), 120 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index b5635d933..e58705e63 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -104,7 +104,7 @@ const int HESAI_LIDAR_PTP_CLOCK_SOURCE = 1; /// @brief Hardware interface of hesai driver -class HesaiHwInterface : NebulaHwInterfaceBase +class HesaiHwInterface : public NebulaHwInterfaceBase { private: typedef nebula::util::expected, uint32_t> ptc_cmd_result_t; @@ -114,12 +114,6 @@ class HesaiHwInterface : NebulaHwInterfaceBase std::unique_ptr<::drivers::udp_driver::UdpDriver> cloud_udp_driver_; std::shared_ptr<::drivers::tcp_driver::TcpDriver> tcp_driver_; std::shared_ptr sensor_configuration_; - std::shared_ptr calibration_configuration_; - size_t azimuth_index_{}; - size_t mtu_size_{}; - std::unique_ptr scan_cloud_ptr_; - std::function - is_valid_packet_; /*Lambda Function Array to verify proper packet size*/ std::function & buffer)> cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 7ec3f73a8..a54c5dc40 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -17,8 +17,7 @@ HesaiHwInterface::HesaiHwInterface() : cloud_io_context_{new ::drivers::common::IoContext(1)}, m_owned_ctx{new boost::asio::io_context(1)}, cloud_udp_driver_{new ::drivers::udp_driver::UdpDriver(*cloud_io_context_)}, - tcp_driver_{new ::drivers::tcp_driver::TcpDriver(m_owned_ctx)}, - scan_cloud_ptr_{std::make_unique()} + tcp_driver_{new ::drivers::tcp_driver::TcpDriver(m_owned_ctx)} { } HesaiHwInterface::~HesaiHwInterface() @@ -141,63 +140,8 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( Status HesaiHwInterface::SetSensorConfiguration( std::shared_ptr sensor_configuration) { - HesaiStatus status = Status::OK; - mtu_size_ = MTU_SIZE; - is_solid_state = false; - try { - sensor_configuration_ = - std::static_pointer_cast(sensor_configuration); - if ( - sensor_configuration_->sensor_model == SensorModel::HESAI_PANDAR40P || - sensor_configuration_->sensor_model == SensorModel::HESAI_PANDAR40P) { - azimuth_index_ = 2; - is_valid_packet_ = [](size_t packet_size) { - return ( - packet_size == PANDAR40_PACKET_SIZE || packet_size == PANDAR40P_EXTENDED_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARQT64) { - azimuth_index_ = 12; // 12 + 258 * [0-3] - is_valid_packet_ = [](size_t packet_size) { return (packet_size == PANDARQT64_PACKET_SIZE); }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARQT128) { - azimuth_index_ = 12; // 12 + 514 * [0-1] - is_valid_packet_ = [](size_t packet_size) { - return (packet_size == PANDARQT128_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARXT32) { - azimuth_index_ = 12; // 12 + 130 * [0-7] - is_valid_packet_ = [](size_t packet_size) { return (packet_size == PANDARXT32_PACKET_SIZE); }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARXT32M) { - azimuth_index_ = 12; // 12 + 130 * [0-7] - is_valid_packet_ = [](size_t packet_size) { - return (packet_size == PANDARXT32M_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARAT128) { - azimuth_index_ = 12; // 12 + 4 * 128 * [0-1] - is_solid_state = true; - is_valid_packet_ = [](size_t packet_size) { - return (packet_size == PANDARAT128_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDAR64) { - azimuth_index_ = 8; // 8 + 192 * [0-5] - is_valid_packet_ = [](size_t packet_size) { - return ( - packet_size == PANDAR64_PACKET_SIZE || packet_size == PANDAR64_EXTENDED_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDAR128_E4X) { - azimuth_index_ = 12; // 12 - is_valid_packet_ = [](size_t packet_size) { - return ( - packet_size == PANDAR128_E4X_EXTENDED_PACKET_SIZE || - packet_size == PANDAR128_E4X_PACKET_SIZE); - }; - } else { - status = Status::INVALID_SENSOR_MODEL; - } - } catch (const std::exception & ex) { - status = Status::SENSOR_CONFIG_ERROR; - std::cerr << status << std::endl; - return status; - } + sensor_configuration_ = + std::static_pointer_cast(sensor_configuration); return Status::OK; } @@ -242,10 +186,6 @@ Status HesaiHwInterface::RegisterScanCallback( void HesaiHwInterface::ReceiveSensorPacketCallback(std::vector & buffer) { - // if (!is_valid_packet_(buffer.size())) { - // PrintDebug("Invalid Packet: " + std::to_string(buffer.size())); - // return; - // } TODO cloud_packet_callback_(buffer); } Status HesaiHwInterface::SensorInterfaceStop() @@ -297,7 +237,9 @@ Status HesaiHwInterface::InitializeTcpDriver() Status HesaiHwInterface::FinalizeTcpDriver() { try { - tcp_driver_->close(); + if (tcp_driver_) { + tcp_driver_->close(); + } } catch (std::exception & e) { PrintError("Error while finalizing the TcpDriver"); return Status::UDP_CONNECTION_ERROR; diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 2ba2e2407..9c50e20eb 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -16,6 +16,8 @@ #include #include "nebula_msgs/msg/nebula_packet.hpp" +#include "pandar_msgs/msg/pandar_packet.hpp" +#include "pandar_msgs/msg/pandar_scan.hpp" #include #include @@ -105,6 +107,10 @@ class HesaiRosWrapper final : public rclcpp::Node /// @param scan_buffer Received PandarScan void ReceiveCloudPacketCallback(std::vector & scan_buffer); + /// @brief Callback for receiving replayed, aggregated packets (= scan messages) + /// @param scan_msg + void ReceiveScanMessageCallback(std::unique_ptr scan_msg); + /// @brief Decodes a nebula packet and, if it completes the scan, publishes the pointcloud. /// @param packet_msg The received packet message void ProcessCloudPacket(std::unique_ptr packet_msg); @@ -158,19 +164,23 @@ class HesaiRosWrapper final : public rclcpp::Node /// @return Created string std::string GetFixedPrecisionString(double val, int pre = 2); - std::shared_ptr driver_ptr_; - drivers::HesaiHwInterface hw_interface_; + std::shared_ptr driver_ptr_{}; + drivers::HesaiHwInterface hw_interface_{}; Status wrapper_status_; Status interface_status_; - rclcpp::Publisher::SharedPtr nebula_points_pub_; - rclcpp::Publisher::SharedPtr aw_points_ex_pub_; - rclcpp::Publisher::SharedPtr aw_points_base_pub_; + rclcpp::Subscription::SharedPtr packets_sub_{}; + rclcpp::Publisher::SharedPtr packets_pub_{}; + pandar_msgs::msg::PandarScan::UniquePtr current_scan_msg_{}; + + rclcpp::Publisher::SharedPtr nebula_points_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; - std::shared_ptr correction_cfg_ptr_; + std::shared_ptr calibration_cfg_ptr_{}; + std::shared_ptr sensor_cfg_ptr_{}; + std::shared_ptr correction_cfg_ptr_{}; /// @brief Stores received packets that have not been processed yet by the decoder thread mt_queue> packet_queue_; @@ -186,27 +196,27 @@ class HesaiRosWrapper final : public rclcpp::Node std::string correction_file_path; /// @brief Received Hesai message publisher - rclcpp::Publisher::SharedPtr pandar_scan_pub_; + rclcpp::Publisher::SharedPtr pandar_scan_pub_{}; bool retry_hw_; std::mutex mtx_config_; - OnSetParametersCallbackHandle::SharedPtr set_param_res_; + OnSetParametersCallbackHandle::SharedPtr set_param_res_{}; diagnostic_updater::Updater diagnostics_updater_; - rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; - rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_; + rclcpp::TimerBase::SharedPtr diagnostics_update_timer_{}; + rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_{}; - std::unique_ptr current_status_; - std::unique_ptr current_monitor_; - std::unique_ptr current_config_; - std::unique_ptr current_inventory_; - std::unique_ptr current_lidar_monitor_tree_; + std::unique_ptr current_status_{}; + std::unique_ptr current_monitor_{}; + std::unique_ptr current_config_{}; + std::unique_ptr current_inventory_{}; + std::unique_ptr current_lidar_monitor_tree_{}; - std::unique_ptr current_status_time_; - std::unique_ptr current_config_time_; - std::unique_ptr current_inventory_time_; - std::unique_ptr current_lidar_monitor_time_; + std::unique_ptr current_status_time_{}; + std::unique_ptr current_config_time_{}; + std::unique_ptr current_inventory_time_{}; + std::unique_ptr current_lidar_monitor_time_{}; uint8_t current_diag_status_; uint8_t current_monitor_status_; diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp index 730b54f7c..67b287ddc 100644 --- a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -16,7 +16,7 @@ class mt_queue public: mt_queue(size_t capacity) : capacity_(capacity) {} - bool push(T && value) + bool try_push(T && value) { { std::unique_lock lock(this->mutex_); @@ -29,6 +29,17 @@ class mt_queue this->condition_variable_.notify_one(); return true; } + + void push(T && value) + { + { + std::unique_lock lock(this->mutex_); + this->condition_variable_.wait(lock, [=] { return this->queue_.size() < this->capacity_; }); + queue_.push_front(std::move(value)); + } + this->condition_variable_.notify_one(); + } + T pop() { std::unique_lock lock(this->mutex_); diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 2c9bc7ef0..847039a9b 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -7,26 +7,29 @@ namespace ros HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), hw_interface_(), + wrapper_status_(Status::NOT_INITIALIZED), + interface_status_(Status::NOT_INITIALIZED), packet_queue_(3000), diagnostics_updater_(this) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); - drivers::HesaiSensorConfiguration sensor_configuration; - wrapper_status_ = GetParameters(sensor_configuration); - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); - // DeclareRosParameters(); - // auto sensor_cfg_ptr = GetRosParameters(); + sensor_cfg_ptr_ = std::make_shared(); + wrapper_status_ = GetParameters(*sensor_cfg_ptr_); + InitializeHwInterface(); InitializeDecoder(); - InitializeHwMonitor(); - // StreamStart(); - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + + if (launch_hw_) { + InitializeHwMonitor(); + StreamStart(); + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + } else { + packets_sub_ = create_subscription("pandar_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); + } set_param_res_ = this->add_on_set_parameters_callback( std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); @@ -34,29 +37,31 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) Status HesaiRosWrapper::InitializeHwInterface() { - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return interface_status_; - } + interface_status_ = Status::OK; + hw_interface_.SetLogger(std::make_shared(this->get_logger())); hw_interface_.SetSensorConfiguration( std::static_pointer_cast(sensor_cfg_ptr_)); - - Status status; + hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); + + if (!launch_hw_) { + return interface_status_; + } + int retry_count = 0; while (true) { - status = hw_interface_.InitializeTcpDriver(); - if (status == Status::OK || !retry_hw_) { + interface_status_ = hw_interface_.InitializeTcpDriver(); + if (interface_status_ == Status::OK || !retry_hw_) { break; } retry_count++; std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << retry_count); - }; + } - if (status == Status::OK) { + if (interface_status_ == Status::OK) { try { auto inventory = hw_interface_.GetInventory(); RCLCPP_INFO_STREAM(get_logger(), inventory); @@ -72,9 +77,12 @@ Status HesaiRosWrapper::InitializeHwInterface() RCLCPP_ERROR_STREAM( get_logger(), "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); - hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); } + pandar_scan_pub_ = + create_publisher("pandar_packets", rclcpp::SensorDataQoS()); + current_scan_msg_ = std::make_unique(); + return Status::OK; } @@ -191,13 +199,32 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) // delay.tick(msg_ptr->stamp); // publish.tick(); - if (!packet_queue_.push(std::move(msg_ptr))) { + if (!packet_queue_.try_push(std::move(msg_ptr))) { RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packets dropped"); } // packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); } +void HesaiRosWrapper::ReceiveScanMessageCallback( + std::unique_ptr scan_msg) +{ + if (launch_hw_) { + RCLCPP_ERROR_THROTTLE( + get_logger(), *get_clock(), 1000, + "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); + return; + } + + for (auto & pkt : scan_msg->packets) { + auto nebula_pkt_ptr = std::make_unique(); + nebula_pkt_ptr->stamp = pkt.stamp; + std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); + + packet_queue_.push(std::move(nebula_pkt_ptr)); + } +} + void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { // static auto parse = nebula::util::Instrumentation("ProcessCloudPacket.parse"); @@ -207,6 +234,22 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrstamp); + // Accumulate packets for recording only if someone is subscribed to the topic (for performance) + if ( + pandar_scan_pub_ && + (pandar_scan_pub_->get_subscription_count() > 0 || + pandar_scan_pub_->get_intra_process_subscription_count() > 0)) { + if (current_scan_msg_->packets.size() == 0) { + current_scan_msg_->header.stamp = packet_msg->stamp; + } + + pandar_msgs::msg::PandarPacket pandar_packet_msg{}; + pandar_packet_msg.stamp = packet_msg->stamp; + pandar_packet_msg.size = packet_msg->data.size(); + std::copy(packet_msg->data.begin(), packet_msg->data.end(), pandar_packet_msg.data.begin()); + current_scan_msg_->packets.emplace_back(std::move(pandar_packet_msg)); + } + // parse.tick(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); @@ -218,6 +261,13 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrpackets.empty()) { + pandar_scan_pub_->publish(std::move(current_scan_msg_)); + current_scan_msg_ = std::make_unique(); + } + if ( nebula_points_pub_->get_subscription_count() > 0 || nebula_points_pub_->get_intra_process_subscription_count() > 0) { @@ -577,11 +627,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor return Status::SENSOR_CONFIG_ERROR; } - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); + std::static_pointer_cast(sensor_cfg_ptr_)); RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); return Status::OK; From bebae29160ccc3dc83bc66dded4dddb0ab097c28 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 9 Apr 2024 18:46:05 +0900 Subject: [PATCH 024/122] change launch file back to single-threaded container --- nebula_ros/launch/hesai_launch_all_hw.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index b7c1459ec..1bd285766 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -33,7 +33,7 @@ - From 38072d4f8a8c930b02fd942c73dd1f2615c3c42e Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 10 Apr 2024 12:23:36 +0900 Subject: [PATCH 025/122] attempt to make queue contention less bad --- .../include/nebula_ros/hesai/mt_queue.hpp | 37 +++++++++++-------- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 12 ++++-- 2 files changed, 30 insertions(+), 19 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp index 67b287ddc..a259a80ba 100644 --- a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -9,7 +9,7 @@ class mt_queue { private: std::mutex mutex_; - std::condition_variable condition_variable_; + std::condition_variable cv_not_empty_, cv_not_full_; std::deque queue_; size_t capacity_; @@ -18,34 +18,39 @@ class mt_queue bool try_push(T && value) { - { - std::unique_lock lock(this->mutex_); - if (queue_.size() == capacity_) { - return false; - } - + std::unique_lock lock(this->mutex_); + bool can_push = queue_.size() < capacity_; + if (can_push) { queue_.push_front(std::move(value)); } - this->condition_variable_.notify_one(); - return true; + this->cv_not_empty_.notify_all(); + return can_push; } void push(T && value) { - { - std::unique_lock lock(this->mutex_); - this->condition_variable_.wait(lock, [=] { return this->queue_.size() < this->capacity_; }); - queue_.push_front(std::move(value)); - } - this->condition_variable_.notify_one(); + std::unique_lock lock(this->mutex_); + this->cv_not_full_.wait(lock, [=] { return this->queue_.size() < this->capacity_; }); + queue_.push_front(std::move(value)); + this->cv_not_empty_.notify_all(); } T pop() { std::unique_lock lock(this->mutex_); - this->condition_variable_.wait(lock, [=] { return !this->queue_.empty(); }); + this->cv_not_empty_.wait(lock, [=] { return !this->queue_.empty(); }); T return_value(std::move(this->queue_.back())); this->queue_.pop_back(); + this->cv_not_full_.notify_all(); + return return_value; } + + void pop_all(std::deque & dest) { + std::unique_lock lock(this->mutex_); + this->cv_not_empty_.wait(lock, [=] { return !this->queue_.empty(); }); + dest.insert(dest.end(), std::make_move_iterator(queue_.begin()), std::make_move_iterator(queue_.end())); + this->queue_.clear(); + this->cv_not_full_.notify_all(); + } }; \ No newline at end of file diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 847039a9b..27ad7b3b3 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -104,9 +104,15 @@ Status HesaiRosWrapper::InitializeDecoder() rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); decoder_thread_ = std::thread([this]() { + std::deque> received{}; while (true) { - auto pkt = packet_queue_.pop(); - this->ProcessCloudPacket(std::move(pkt)); + packet_queue_.pop_all(received); + + while (!received.empty()) { + auto pkt = std::move(received.back()); + received.pop_back(); + this->ProcessCloudPacket(std::move(pkt)); + } } }); @@ -200,7 +206,7 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) // publish.tick(); if (!packet_queue_.try_push(std::move(msg_ptr))) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packets dropped"); + RCLCPP_ERROR(get_logger(), "Packet dropped"); } // packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); From 0215d7cca3939cd7e96fbda8696e56e47475269f Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 11 Apr 2024 19:00:25 +0900 Subject: [PATCH 026/122] chore(hesai_ros_wrapper): reduce logging output --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 27ad7b3b3..56ed46ca4 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -206,7 +206,7 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) // publish.tick(); if (!packet_queue_.try_push(std::move(msg_ptr))) { - RCLCPP_ERROR(get_logger(), "Packet dropped"); + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); } // packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); From d0f10cbd5686c19b45bdc48c2eb9dc93fd49dfb1 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 11 Apr 2024 19:18:35 +0900 Subject: [PATCH 027/122] feat(hesai_ros_wrapper): print warning when connected to HW and receiving /pandar_packets --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 16 +++++----------- 1 file changed, 5 insertions(+), 11 deletions(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 56ed46ca4..38b224fb3 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -27,10 +27,11 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) StreamStart(); hw_interface_.RegisterScanCallback( std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - } else { - packets_sub_ = create_subscription("pandar_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); } + packets_sub_ = create_subscription("pandar_packets", rclcpp::SensorDataQoS(), + std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); + set_param_res_ = this->add_on_set_parameters_callback( std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); } @@ -104,15 +105,8 @@ Status HesaiRosWrapper::InitializeDecoder() rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); decoder_thread_ = std::thread([this]() { - std::deque> received{}; while (true) { - packet_queue_.pop_all(received); - - while (!received.empty()) { - auto pkt = std::move(received.back()); - received.pop_back(); - this->ProcessCloudPacket(std::move(pkt)); - } + this->ProcessCloudPacket(std::move(packet_queue_.pop())); } }); @@ -242,7 +236,7 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrget_subscription_count() > 0 || pandar_scan_pub_->get_intra_process_subscription_count() > 0)) { if (current_scan_msg_->packets.size() == 0) { From 7fd450b5d3504612a6edce1425e726244c0bc106 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 12 Apr 2024 14:43:27 +0900 Subject: [PATCH 028/122] feat(nebula_launch.py): throw error when trying to launch Hesai sensor and refer to hesai_launch_all_hw.xml --- nebula_ros/launch/nebula_launch.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/nebula_ros/launch/nebula_launch.py b/nebula_ros/launch/nebula_launch.py index b394498fb..74d3eb475 100644 --- a/nebula_ros/launch/nebula_launch.py +++ b/nebula_ros/launch/nebula_launch.py @@ -41,8 +41,11 @@ def launch_setup(context, *args, **kwargs): # Model and make sensor_model = LaunchConfiguration("sensor_model").perform(context) calibration_file = LaunchConfiguration("calibration_file").perform(context) - correction_file = LaunchConfiguration("correction_file").perform(context) sensor_make, sensor_extension = get_sensor_make(sensor_model) + + if sensor_make.lower() == "hesai": + raise ValueError("\n `nebula_launch.py` is deprecated. For Hesai sensors, use `hesai_launch_all_hw.xml` instead.") + nebula_decoders_share_dir = get_package_share_directory("nebula_decoders") nebula_ros_share_dir = get_package_share_directory("nebula_ros") @@ -84,7 +87,6 @@ def launch_setup(context, *args, **kwargs): "sensor_ip": LaunchConfiguration("sensor_ip"), "return_mode": LaunchConfiguration("return_mode"), "calibration_file": calibration_file or sensor_calib_fp, - "correction_file": correction_file or sensor_corr_fp, "setup_sensor": LaunchConfiguration("setup_sensor"), "ptp_profile": LaunchConfiguration("ptp_profile"), "ptp_domain": LaunchConfiguration("ptp_domain"), @@ -110,7 +112,6 @@ def launch_setup(context, *args, **kwargs): "sensor_ip": LaunchConfiguration("sensor_ip"), "return_mode": LaunchConfiguration("return_mode"), "calibration_file": calibration_file or sensor_calib_fp, - "correction_file": correction_file or sensor_corr_fp, }, ], ) @@ -127,7 +128,6 @@ def launch_setup(context, *args, **kwargs): "sensor_ip": LaunchConfiguration("sensor_ip"), "return_mode": LaunchConfiguration("return_mode"), "calibration_file": calibration_file or sensor_calib_fp, - "correction_file": correction_file or sensor_corr_fp, "launch_hw": LaunchConfiguration("launch_hw"), "ptp_profile": LaunchConfiguration("ptp_profile"), "ptp_domain": LaunchConfiguration("ptp_domain"), From a857d50b2827752074bf243a33a4860fe1afba80 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 16 Apr 2024 17:57:28 +0900 Subject: [PATCH 029/122] chore: update cspell ignore --- nebula_common/src/velodyne/velodyne_calibration_decoder.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index 0c03c3c9e..954da496b 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,3 +1,4 @@ +// cspell:ignore piyush, fout /** * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, From 77b933f56c82d90bf38d515aad257c3ca0fce730 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 16:38:39 +0900 Subject: [PATCH 030/122] refactor(nebula_ros): split single wrapper file into 3 sub-wrappers --- .cspell.json | 29 +- .../nebula_common/hesai/hesai_common.hpp | 35 +- .../include/nebula_common/util/expected.hpp | 3 + .../decoders/hesai_packet.hpp | 2 +- .../nebula_decoders_hesai/hesai_driver.hpp | 15 +- .../nebula_decoders_hesai/hesai_driver.cpp | 55 +- .../hesai_hw_interface.cpp | 24 +- nebula_ros/CMakeLists.txt | 4 + .../nebula_ros/hesai/decoder_wrapper.hpp | 66 + .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 181 +-- .../nebula_ros/hesai/hw_interface_wrapper.hpp | 32 + .../nebula_ros/hesai/hw_monitor_wrapper.hpp | 95 ++ .../include/nebula_ros/hesai/mt_queue.hpp | 9 +- nebula_ros/package.xml | 1 + nebula_ros/src/hesai/decoder_wrapper.cpp | 255 ++++ nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 1159 +++-------------- nebula_ros/src/hesai/hw_interface_wrapper.cpp | 94 ++ nebula_ros/src/hesai/hw_monitor_wrapper.cpp | 412 ++++++ 18 files changed, 1269 insertions(+), 1202 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp create mode 100644 nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp create mode 100644 nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp create mode 100644 nebula_ros/src/hesai/decoder_wrapper.cpp create mode 100644 nebula_ros/src/hesai/hw_interface_wrapper.cpp create mode 100644 nebula_ros/src/hesai/hw_monitor_wrapper.cpp diff --git a/.cspell.json b/.cspell.json index 4f17f7ddd..7b1d6b2be 100644 --- a/.cspell.json +++ b/.cspell.json @@ -6,14 +6,26 @@ "adctp", "Adctp", "AT", + "autosar", "block_id", + "Bpearl", + "calib", + "DHAVE", + "Difop", "extrinsics", "gprmc", + "gptp", + "Helios", "Hesai", + "Idat", + "ipaddr", + "manc", "memcpy", "mkdoxy", + "Msop", "nohup", "nproc", + "ntoa", "pandar", "PANDAR", "PANDARAT", @@ -23,6 +35,7 @@ "QT", "rclcpp", "schedutil", + "srvs", "STD_COUT", "stds", "struct", @@ -30,20 +43,8 @@ "UDP_SEQ", "vccint", "Vccint", - "XT", - "XTM", - "DHAVE", - "Bpearl", - "Helios", - "Msop", - "Difop", - "gptp", - "Idat", "Vdat", - "autosar", - "srvs", - "manc", - "ipaddr", - "ntoa" + "XT", + "XTM" ] } diff --git a/nebula_common/include/nebula_common/hesai/hesai_common.hpp b/nebula_common/include/nebula_common/hesai/hesai_common.hpp index 9c6e5d555..0c7ae1c1b 100644 --- a/nebula_common/include/nebula_common/hesai/hesai_common.hpp +++ b/nebula_common/include/nebula_common/hesai/hesai_common.hpp @@ -14,7 +14,7 @@ namespace nebula namespace drivers { /// @brief struct for Hesai sensor configuration -struct HesaiSensorConfiguration : LidarConfigurationBase +struct HesaiSensorConfiguration : public LidarConfigurationBase { uint16_t gnss_port{}; double scan_phase{}; @@ -43,13 +43,20 @@ inline std::ostream & operator<<(std::ostream & os, HesaiSensorConfiguration con return os; } +struct HesaiCalibrationConfigurationBase : public CalibrationConfigurationBase +{ + virtual nebula::Status LoadFromBytes(const std::vector & buf) = 0; + virtual nebula::Status LoadFromFile(const std::string & calibration_file) = 0; + virtual nebula::Status SaveToFileFromBytes(const std::string & calibration_file, const std::vector & buf) = 0; +}; + /// @brief struct for Hesai calibration configuration -struct HesaiCalibrationConfiguration : CalibrationConfigurationBase +struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase { std::map elev_angle_map; std::map azimuth_offset_map; - inline nebula::Status LoadFromFile(const std::string & calibration_file) + inline nebula::Status LoadFromFile(const std::string & calibration_file) override { std::ifstream ifs(calibration_file); if (!ifs) { @@ -61,6 +68,11 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase return LoadFromString(ss.str()); } + nebula::Status LoadFromBytes(const std::vector & buf) { + std::string calibration_string = std::string(buf.begin(), buf.end()); + return LoadFromString(calibration_string); + } + /// @brief Loading calibration data /// @param calibration_content /// @return Resulting status @@ -99,7 +111,7 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase /// @brief Saving calibration data (not used) /// @param calibration_file /// @return Resulting status - inline nebula::Status SaveFile(const std::string & calibration_file) + inline nebula::Status SaveToFile(const std::string & calibration_file) { std::ofstream ofs(calibration_file); if (!ofs) { @@ -117,6 +129,11 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase return Status::OK; } + nebula::Status SaveToFileFromBytes(const std::string & calibration_file, const std::vector & buf) override { + std::string calibration_string = std::string(buf.begin(), buf.end()); + return SaveFileFromString(calibration_file, calibration_string); + } + /// @brief Saving calibration data from string /// @param calibration_file path /// @param calibration_string calibration string @@ -134,7 +151,7 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase }; /// @brief struct for Hesai correction configuration (for AT) -struct HesaiCorrection +struct HesaiCorrection : public HesaiCalibrationConfigurationBase { uint16_t delimiter; uint8_t versionMajor; @@ -156,7 +173,7 @@ struct HesaiCorrection /// @brief Load correction data from file /// @param buf Binary buffer /// @return Resulting status - inline nebula::Status LoadFromBinary(const std::vector & buf) + inline nebula::Status LoadFromBytes(const std::vector & buf) override { size_t index; for (index = 0; index < buf.size()-1; index++) { @@ -258,7 +275,7 @@ struct HesaiCorrection /// @brief Load correction data from file /// @param correction_file path /// @return Resulting status - inline nebula::Status LoadFromFile(const std::string & correction_file) + inline nebula::Status LoadFromFile(const std::string & correction_file) override { std::ifstream ifs(correction_file, std::ios::in | std::ios::binary); if (!ifs) { @@ -271,7 +288,7 @@ struct HesaiCorrection ifs.read((char *)&c, sizeof(unsigned char)); buf.emplace_back(c); } - LoadFromBinary(buf); + LoadFromBytes(buf); ifs.close(); return Status::OK; @@ -281,7 +298,7 @@ struct HesaiCorrection /// @param correction_file path /// @param buf correction binary /// @return Resulting status - inline nebula::Status SaveFileFromBinary(const std::string & correction_file, const std::vector & buf) + inline nebula::Status SaveToFileFromBytes(const std::string & correction_file, const std::vector & buf) override { std::cerr << "Saving in:" << correction_file << "\n"; std::ofstream ofs(correction_file, std::ios::trunc | std::ios::binary); diff --git a/nebula_common/include/nebula_common/util/expected.hpp b/nebula_common/include/nebula_common/util/expected.hpp index 4fc35b3fa..795e1f43e 100644 --- a/nebula_common/include/nebula_common/util/expected.hpp +++ b/nebula_common/include/nebula_common/util/expected.hpp @@ -29,6 +29,9 @@ struct expected return default_; } + /// @brief If the instance has a value, return the value, else throw std::runtime_error(error_msg) + /// @param error_msg The message to be included in the thrown exception + /// @return The value T value_or_throw(const std::string & error_msg) { if (has_value()) return value(); throw std::runtime_error(error_msg); diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp index 730888c91..0280f1ff7 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp @@ -190,7 +190,7 @@ struct PacketBase /// @brief Get the number of returns for a given return mode /// @param return_mode The return mode /// @return The number of returns -int get_n_returns(uint8_t return_mode) +inline int get_n_returns(uint8_t return_mode) { switch (return_mode) { case return_mode::SINGLE_FIRST: diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index a3f37cd32..5ee9892d4 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -34,12 +34,11 @@ class HesaiDriver : NebulaDriverBase HesaiDriver() = delete; /// @brief Constructor /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver (for AT) + /// @param calibration_configuration CalibrationConfiguration for this driver (either HesaiCalibrationConfiguration + /// for sensors other than AT128 or HesaiCorrection for AT128) explicit HesaiDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration = nullptr); + const std::shared_ptr& sensor_configuration, + const std::shared_ptr& calibration_configuration = nullptr); /// @brief Get current status of this driver /// @return Current status @@ -48,14 +47,12 @@ class HesaiDriver : NebulaDriverBase /// @brief Setting CalibrationConfiguration (not used) /// @param calibration_configuration /// @return Resulting status - Status SetCalibrationConfiguration( - const CalibrationConfigurationBase & calibration_configuration) override; + Status SetCalibrationConfiguration(const CalibrationConfigurationBase& calibration_configuration) override; /// @brief Convert PandarScan message to point cloud /// @param pandar_scan Message /// @return tuple of Point cloud and timestamp - std::tuple ParseCloudPacket( - const std::vector & packet); + std::tuple ParseCloudPacket(const std::vector& packet); }; } // namespace drivers diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index 61b969ed7..27624a469 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -17,53 +17,56 @@ namespace nebula { namespace drivers { -HesaiDriver::HesaiDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) +HesaiDriver::HesaiDriver(const std::shared_ptr& sensor_configuration, + const std::shared_ptr& calibration_configuration) { // initialize proper parser from cloud config's model and echo mode driver_status_ = nebula::Status::OK; - switch (sensor_configuration->sensor_model) { + + std::shared_ptr calibration = nullptr; + std::shared_ptr correction = nullptr; + + if (sensor_configuration->sensor_model == SensorModel::HESAI_PANDARAT128) + { + correction = std::static_pointer_cast(calibration_configuration); + } + else + { + calibration = std::static_pointer_cast(calibration_configuration); + } + + switch (sensor_configuration->sensor_model) + { case SensorModel::UNKNOWN: driver_status_ = nebula::Status::INVALID_SENSOR_MODEL; break; case SensorModel::HESAI_PANDAR64: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDAR40P: case SensorModel::HESAI_PANDAR40M: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARQT64: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARQT128: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARXT32: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARXT32M: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARAT128: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDAR128_E3X: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDAR128_E4X: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; default: driver_status_ = nebula::Status::NOT_INITIALIZED; @@ -78,13 +81,15 @@ std::tuple HesaiDriver::ParseCloudPacket( std::tuple pointcloud; auto logger = rclcpp::get_logger("HesaiDriver"); - if (driver_status_ != nebula::Status::OK) { + if (driver_status_ != nebula::Status::OK) + { RCLCPP_ERROR(logger, "Driver not OK."); return pointcloud; } scan_decoder_->unpack(packet); - if (scan_decoder_->hasScanned()) { + if (scan_decoder_->hasScanned()) + { pointcloud = scan_decoder_->getPointcloud(); } diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index a54c5dc40..c522969a0 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -22,29 +22,7 @@ HesaiHwInterface::HesaiHwInterface() } HesaiHwInterface::~HesaiHwInterface() { -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................st: HesaiHwInterface::~HesaiHwInterface()" << std::endl; -#endif - if (tcp_driver_) { -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................tcp_driver_ is available" << std::endl; -#endif - if (tcp_driver_ && tcp_driver_->isOpen()) { -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................st: tcp_driver_->close();" << std::endl; -#endif - tcp_driver_->close(); -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................ed: tcp_driver_->close();" << std::endl; -#endif - } -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................ed: if(tcp_driver_)" << std::endl; -#endif - } -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................ed: HesaiHwInterface::~HesaiHwInterface()" << std::endl; -#endif + FinalizeTcpDriver(); } HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index 1bd697624..b11339765 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -24,6 +24,7 @@ find_package(nebula_hw_interfaces REQUIRED) find_package(yaml-cpp REQUIRED) find_package(robosense_msgs REQUIRED) find_package(nebula_msgs REQUIRED) +find_package(pandar_msgs REQUIRED) include_directories( include @@ -36,6 +37,9 @@ link_libraries(${YAML_CPP_LIBRARIES} ${PCL_LIBRARIES}) ## Hesai ament_auto_add_library(hesai_ros_wrapper SHARED src/hesai/hesai_ros_wrapper.cpp + src/hesai/decoder_wrapper.cpp + src/hesai/hw_interface_wrapper.cpp + src/hesai/hw_monitor_wrapper.cpp ) rclcpp_components_register_node(hesai_ros_wrapper diff --git a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp new file mode 100644 index 000000000..262c16839 --- /dev/null +++ b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp @@ -0,0 +1,66 @@ +#pragma once + +#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" +#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" + +#include +#include +#include + +#include "nebula_msgs/msg/nebula_packet.hpp" +#include "pandar_msgs/msg/pandar_packet.hpp" +#include "pandar_msgs/msg/pandar_scan.hpp" + +#include +#include + +namespace nebula +{ +namespace ros +{ +class HesaiDecoderWrapper +{ +public: + HesaiDecoderWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config); + + nebula::util::expected, nebula::Status> + GetCalibrationData(); + + void ProcessCloudPacket(std::unique_ptr packet_msg); + + void PublishCloud(std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr& publisher); + + nebula::Status Status(); + +private: + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast(std::chrono::duration(seconds)); + } + + nebula::Status status_; + rclcpp::Logger logger_; + + const std::shared_ptr hw_interface_; + std::shared_ptr sensor_cfg_; + + std::string calibration_file_path_{}; + std::shared_ptr calibration_cfg_ptr_{}; + + std::shared_ptr driver_ptr_; + + rclcpp::Publisher::SharedPtr packets_pub_{}; + pandar_msgs::msg::PandarScan::UniquePtr current_scan_msg_{}; + + rclcpp::Publisher::SharedPtr nebula_points_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 9c50e20eb..e037bce40 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -4,29 +4,27 @@ #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" -// #include "nebula_common/util/instrumentation.hpp" -// #include "nebula_common/util/topic_delay.hpp" -#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" +#include "nebula_ros/hesai/decoder_wrapper.hpp" +#include "nebula_ros/hesai/hw_interface_wrapper.hpp" +#include "nebula_ros/hesai/hw_monitor_wrapper.hpp" #include "nebula_ros/hesai/mt_queue.hpp" #include -#include #include #include #include "nebula_msgs/msg/nebula_packet.hpp" -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" #include #include #include +#include #include #include +#include #include -#include namespace nebula { @@ -40,12 +38,12 @@ namespace ros /// @param value Corresponding value /// @return Whether the target name existed template -bool get_param(const std::vector & p, const std::string & name, T & value) +bool get_param(const std::vector& p, const std::string& name, T& value) { - auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { - return parameter.get_name() == name; - }); - if (it != p.cend()) { + auto it = std::find_if(p.cbegin(), p.cend(), + [&name](const rclcpp::Parameter& parameter) { return parameter.get_name() == name; }); + if (it != p.cend()) + { value = it->template get_value(); return true; } @@ -56,8 +54,8 @@ bool get_param(const std::vector & p, const std::string & nam class HesaiRosWrapper final : public rclcpp::Node { public: - explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); - ~HesaiRosWrapper(); + explicit HesaiRosWrapper(const rclcpp::NodeOptions& options); + ~HesaiRosWrapper() noexcept; /// @brief Get current status of this driver /// @return Current status @@ -68,172 +66,45 @@ class HesaiRosWrapper final : public rclcpp::Node Status StreamStart(); private: - Status InitializeHwInterface(); - Status InitializeDecoder(); - Status InitializeHwMonitor(); + void ReceiveCloudPacketCallback(std::vector& packet); + + void ReceiveScanMessageCallback(std::unique_ptr scan_msg); + + Status DeclareAndGetSensorConfigParams(); /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration /// @return Resulting status - Status GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration); - - /// @brief Get calibration data from the sensor - /// @param calibration_configuration Output of CalibrationConfiguration - /// @param correction_configuration Output of CorrectionConfiguration (for AT) - /// @return Resulting status - Status GetCalibrationData( - drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration); - - /// @brief Convert seconds to chrono::nanoseconds - /// @param seconds - /// @return chrono::nanoseconds - static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) - { - return std::chrono::duration_cast( - std::chrono::duration(seconds)); - } - - /*** - * Publishes a sensor_msgs::msg::PointCloud2 to the specified publisher - * @param pointcloud unique pointer containing the point cloud to publish - * @param publisher - */ - void PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher); - - /// @brief Callback for receiving a raw UDP packet - /// @param scan_buffer Received PandarScan - void ReceiveCloudPacketCallback(std::vector & scan_buffer); - - /// @brief Callback for receiving replayed, aggregated packets (= scan messages) - /// @param scan_msg - void ReceiveScanMessageCallback(std::unique_ptr scan_msg); - - /// @brief Decodes a nebula packet and, if it completes the scan, publishes the pointcloud. - /// @param packet_msg The received packet message - void ProcessCloudPacket(std::unique_ptr packet_msg); + Status DeclareAndGetWrapperParams(); /// @brief rclcpp parameter callback /// @param parameters Received parameters /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); + rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector& parameters); + /// @brief Updating rclcpp parameter /// @return SetParametersResult std::vector updateParameters(); - /// @brief Initializing diagnostics - void InitializeHesaiDiagnostics(); - /// @brief Callback of the timer for getting the current lidar status - void OnHesaiStatusTimer(); - /// @brief Callback of the timer for getting the current lidar monitor via http - void OnHesaiLidarMonitorTimerHttp(); - /// @brief Callback of the timer for getting the current lidar monitor via tcp - void OnHesaiLidarMonitorTimer(); - // void OnHesaiDiagnosticsTimer(); - // void OnHesaiStatusTimer(); - - /// @brief Check status information from HesaiLidarStatus for diagnostic_updater - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check ptp information from HesaiLidarStatus for diagnostic_updater - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check temperature information from HesaiLidarStatus for diagnostic_updater - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check rpm information from HesaiLidarStatus for diagnostic_updater - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check voltage information from HesaiLidarStatus for diagnostic_updater via http - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check voltage information from HesaiLidarStatus for diagnostic_updater via tcp - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Get value from property_tree - /// @param pt property_tree - /// @param key Pey string - /// @return Value - std::string GetPtreeValue(boost::property_tree::ptree * pt, const std::string & key); - /// @brief Making fixed precision string - /// @param val Target value - /// @param pre Precision - /// @return Created string - std::string GetFixedPrecisionString(double val, int pre = 2); - - std::shared_ptr driver_ptr_{}; - drivers::HesaiHwInterface hw_interface_{}; - Status wrapper_status_; - Status interface_status_; - rclcpp::Subscription::SharedPtr packets_sub_{}; - rclcpp::Publisher::SharedPtr packets_pub_{}; - pandar_msgs::msg::PandarScan::UniquePtr current_scan_msg_{}; - - rclcpp::Publisher::SharedPtr nebula_points_pub_{}; - rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; - rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; - - std::shared_ptr calibration_cfg_ptr_{}; - std::shared_ptr sensor_cfg_ptr_{}; - std::shared_ptr correction_cfg_ptr_{}; + std::shared_ptr sensor_cfg_ptr_{}; /// @brief Stores received packets that have not been processed yet by the decoder thread mt_queue> packet_queue_; /// @brief Thread to isolate decoding from receiving std::thread decoder_thread_; - // todo: temporary class member during single node refactoring - bool launch_hw_; + rclcpp::Subscription::SharedPtr packets_sub_{}; - // todo: temporary class member during single node refactoring - std::string calibration_file_path; - /// @brief File path of Correction data (Only required only for AT) - std::string correction_file_path; + bool launch_hw_; - /// @brief Received Hesai message publisher - rclcpp::Publisher::SharedPtr pandar_scan_pub_{}; + std::optional hw_interface_wrapper_; + std::optional hw_monitor_wrapper_; + std::optional decoder_wrapper_; - bool retry_hw_; std::mutex mtx_config_; OnSetParametersCallbackHandle::SharedPtr set_param_res_{}; - - diagnostic_updater::Updater diagnostics_updater_; - - rclcpp::TimerBase::SharedPtr diagnostics_update_timer_{}; - rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_{}; - - std::unique_ptr current_status_{}; - std::unique_ptr current_monitor_{}; - std::unique_ptr current_config_{}; - std::unique_ptr current_inventory_{}; - std::unique_ptr current_lidar_monitor_tree_{}; - - std::unique_ptr current_status_time_{}; - std::unique_ptr current_config_time_{}; - std::unique_ptr current_inventory_time_{}; - std::unique_ptr current_lidar_monitor_time_{}; - - uint8_t current_diag_status_; - uint8_t current_monitor_status_; - - uint16_t diag_span_; - std::mutex mtx_lidar_status_; - std::mutex mtx_lidar_monitor_; - - std::string info_model_; - std::string info_serial_; - - std::vector temperature_names_; - - bool setup_sensor; - const std::string MSG_NOT_SUPPORTED = "Not supported"; - const std::string MSG_ERROR = "Error"; - const std::string MSG_SEP = ": "; }; } // namespace ros diff --git a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp new file mode 100644 index 000000000..30f069c99 --- /dev/null +++ b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp @@ -0,0 +1,32 @@ +#pragma once + +#include +#include + +#include + +#include + +namespace nebula +{ +namespace ros +{ +class HesaiHwInterfaceWrapper +{ +public: + HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, + std::shared_ptr& config); + + nebula::Status InitializeHwInterface(); + + nebula::Status Status(); + + std::shared_ptr HwInterface() const; + +private: + std::shared_ptr hw_interface_; + rclcpp::Logger logger_; + nebula::Status status_; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp new file mode 100644 index 000000000..5ddfc9e79 --- /dev/null +++ b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp @@ -0,0 +1,95 @@ +#pragma once + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +namespace nebula +{ +namespace ros +{ +class HesaiHwMonitorWrapper +{ +public: + HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config); + + nebula::Status InitializeHwMonitor(); + + void InitializeHesaiDiagnostics(); + + std::string GetPtreeValue(boost::property_tree::ptree* pt, const std::string& key); + + std::string GetFixedPrecisionString(double val, int pre); + + void OnHesaiStatusTimer(); + + void OnHesaiLidarMonitorTimerHttp(); + + void OnHesaiLidarMonitorTimer(); + + void HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + nebula::Status Status(); + +private: + rclcpp::Logger logger_; + diagnostic_updater::Updater diagnostics_updater_; + nebula::Status status_; + + const std::shared_ptr hw_interface_; + rclcpp::Node* const parent_node_; + + uint16_t diag_span_; + rclcpp::TimerBase::SharedPtr diagnostics_update_timer_{}; + rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_{}; + + std::unique_ptr current_status_{}; + std::unique_ptr current_monitor_{}; + std::unique_ptr current_config_{}; + std::unique_ptr current_inventory_{}; + std::unique_ptr current_lidar_monitor_tree_{}; + + std::unique_ptr current_status_time_{}; + std::unique_ptr current_config_time_{}; + std::unique_ptr current_inventory_time_{}; + std::unique_ptr current_lidar_monitor_time_{}; + + uint8_t current_diag_status_; + uint8_t current_monitor_status_; + + std::mutex mtx_lidar_status_; + std::mutex mtx_lidar_monitor_; + + std::string info_model_; + std::string info_serial_; + + std::vector temperature_names_; + + bool setup_sensor; + const std::string MSG_NOT_SUPPORTED = "Not supported"; + const std::string MSG_ERROR = "Error"; + const std::string MSG_SEP = ": "; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp index a259a80ba..d60b7b4db 100644 --- a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -3,6 +3,7 @@ #include #include #include +#include template class mt_queue @@ -45,12 +46,4 @@ class mt_queue return return_value; } - - void pop_all(std::deque & dest) { - std::unique_lock lock(this->mutex_); - this->cv_not_empty_.wait(lock, [=] { return !this->queue_.empty(); }); - dest.insert(dest.end(), std::make_move_iterator(queue_.begin()), std::make_move_iterator(queue_.end())); - this->queue_.clear(); - this->cv_not_full_.notify_all(); - } }; \ No newline at end of file diff --git a/nebula_ros/package.xml b/nebula_ros/package.xml index 54df70ea9..e918afdc7 100644 --- a/nebula_ros/package.xml +++ b/nebula_ros/package.xml @@ -32,6 +32,7 @@ visualization_msgs yaml-cpp nebula_msgs + pandar_msgs ament_cmake_gtest ament_lint_auto diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp new file mode 100644 index 000000000..1ae6d2837 --- /dev/null +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -0,0 +1,255 @@ +#include "nebula_ros/hesai/decoder_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ + +HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config) + : status_(nebula::Status::NOT_INITIALIZED) + , logger_(parent_node->get_logger().get_child("HesaiDecoder")) + , hw_interface_(hw_interface) + , sensor_cfg_(config) +{ + if (!config) + { + throw std::runtime_error("HesaiDecoderWrapper cannot be instantiated without a valid config!"); + } + + if (config->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + parent_node->declare_parameter("correction_file", "", descriptor); + calibration_file_path_ = parent_node->get_parameter("correction_file").as_string(); + } + else + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + parent_node->declare_parameter("calibration_file", "", descriptor); + calibration_file_path_ = parent_node->get_parameter("calibration_file").as_string(); + } + + auto calibration_result = GetCalibrationData(); + + if (!calibration_result.has_value()) + { + throw std::runtime_error( + (std::stringstream() << "No valid calibration found: " << calibration_result.error()).str()); + } + + calibration_cfg_ptr_ = calibration_result.value(); + RCLCPP_INFO_STREAM(logger_, "Using calibration data from " << calibration_cfg_ptr_->calibration_file); + + RCLCPP_INFO(logger_, "Starting Decoder"); + + driver_ptr_ = std::make_shared(config, calibration_cfg_ptr_); + status_ = driver_ptr_->GetStatus(); + + if (Status::OK != status_) + { + throw std::runtime_error((std::stringstream() << "Error instantiating decoder: " << status_).str()); + } + + // Publish packets only if HW interface is connected + if (hw_interface_) + { + current_scan_msg_ = std::make_unique(); + packets_pub_ = + parent_node->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); + } + + auto qos_profile = rmw_qos_profile_sensor_data; + auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + + nebula_points_pub_ = parent_node->create_publisher("pandar_points", pointcloud_qos); + aw_points_base_pub_ = parent_node->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = parent_node->create_publisher("aw_points_ex", pointcloud_qos); + + RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); +} + +nebula::util::expected, nebula::Status> +HesaiDecoderWrapper::GetCalibrationData() +{ + std::shared_ptr calib; + + if (sensor_cfg_->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) + { + calib = std::make_shared(); + } + else + { + calib = std::make_shared(); + } + + bool hw_connected = hw_interface_ != nullptr; + std::string calibration_file_path_from_sensor; + + { + int ext_pos = calibration_file_path_.find_last_of('.'); + calibration_file_path_from_sensor = calibration_file_path_.substr(0, ext_pos); + // TODO: if multiple different sensors of the same type are used, this will mix up their calibration data + calibration_file_path_from_sensor += "_from_sensor"; + calibration_file_path_from_sensor += + calibration_file_path_.substr(ext_pos, calibration_file_path_.size() - ext_pos); + } + + // If a sensor is connected, try to download and save its calibration data + if (hw_connected) + { + try + { + auto raw_data = hw_interface_->GetLidarCalibrationBytes(); + RCLCPP_INFO(logger_, "Downloaded calibration data from sensor."); + auto status = calib->SaveToFileFromBytes(calibration_file_path_from_sensor, raw_data); + if (status != Status::OK) + { + RCLCPP_ERROR_STREAM(logger_, "Could not save calibration data: " << status); + } + else + { + RCLCPP_INFO_STREAM(logger_, "Saved downloaded data to " << calibration_file_path_from_sensor); + } + } + catch (std::runtime_error& e) + { + RCLCPP_ERROR_STREAM(logger_, "Could not download calibration data: " << e.what()); + } + } + + // If saved calibration data from a sensor exists (either just downloaded above, or previously), try to load it + if (std::filesystem::exists(calibration_file_path_from_sensor)) + { + auto status = calib->LoadFromFile(calibration_file_path_from_sensor); + if (status == Status::OK) + { + calib->calibration_file = calibration_file_path_from_sensor; + return calib; + } + + RCLCPP_ERROR_STREAM(logger_, "Could not load downloaded calibration data: " << status); + } + else + { + RCLCPP_ERROR(logger_, "No downloaded calibration data found."); + } + + RCLCPP_WARN(logger_, "Falling back to generic calibration file."); + + // If downloaded data did not exist or could not be loaded, fall back to a generic file. + // If that file does not exist either, return an error code + if (!std::filesystem::exists(calibration_file_path_)) + { + RCLCPP_ERROR(logger_, "No calibration data found."); + return nebula::Status(Status::INVALID_CALIBRATION_FILE); + } + + // Try to load the existing fallback calibration file. Return an error if this fails + auto status = calib->LoadFromFile(calibration_file_path_); + if (status != Status::OK) + { + RCLCPP_ERROR(logger_, "Could not load fallback calibration file."); + return status; + } + + // Return the fallback calibration file + calib->calibration_file = calibration_file_path_; + return calib; +} + +void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) +{ + // Accumulate packets for recording only if someone is subscribed to the topic (for performance) + if (hw_interface_ && + (packets_pub_->get_subscription_count() > 0 || packets_pub_->get_intra_process_subscription_count() > 0)) + { + if (current_scan_msg_->packets.size() == 0) + { + current_scan_msg_->header.stamp = packet_msg->stamp; + } + + pandar_msgs::msg::PandarPacket pandar_packet_msg{}; + pandar_packet_msg.stamp = packet_msg->stamp; + pandar_packet_msg.size = packet_msg->data.size(); + std::copy(packet_msg->data.begin(), packet_msg->data.end(), pandar_packet_msg.data.begin()); + current_scan_msg_->packets.emplace_back(std::move(pandar_packet_msg)); + } + + std::tuple pointcloud_ts = + driver_ptr_->ParseCloudPacket(packet_msg->data); + nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + + if (pointcloud == nullptr) + { + // todo + // RCLCPP_WARN_STREAM(logger_, "Empty cloud parsed."); + return; + }; + + // Publish scan message only if it has been written to + if (current_scan_msg_ && !current_scan_msg_->packets.empty()) + { + packets_pub_->publish(std::move(current_scan_msg_)); + current_scan_msg_ = std::make_unique(); + } + + if (nebula_points_pub_->get_subscription_count() > 0 || + nebula_points_pub_->get_intra_process_subscription_count() > 0) + { + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); + } + if (aw_points_base_pub_->get_subscription_count() > 0 || + aw_points_base_pub_->get_intra_process_subscription_count() > 0) + { + const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); + } + if (aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) + { + const auto autoware_ex_cloud = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); + } +} + +void HesaiDecoderWrapper::PublishCloud(std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr& publisher) +{ + if (pointcloud->header.stamp.sec < 0) + { + RCLCPP_WARN_STREAM(logger_, "Timestamp error, verify clock source."); + } + pointcloud->header.frame_id = sensor_cfg_->frame_id; + publisher->publish(std::move(pointcloud)); +} + +nebula::Status HesaiDecoderWrapper::Status() +{ + if (!driver_ptr_) + { + return nebula::Status::NOT_INITIALIZED; + } + + return driver_ptr_->GetStatus(); +} +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 38b224fb3..e99e5c6d9 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -4,344 +4,70 @@ namespace nebula { namespace ros { -HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), - hw_interface_(), - wrapper_status_(Status::NOT_INITIALIZED), - interface_status_(Status::NOT_INITIALIZED), - packet_queue_(3000), - diagnostics_updater_(this) +HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions& options) + : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)) + , wrapper_status_(Status::NOT_INITIALIZED) + , sensor_cfg_ptr_(nullptr) + , packet_queue_(3000) + , hw_interface_wrapper_() + , hw_monitor_wrapper_() + , decoder_wrapper_() { setvbuf(stdout, NULL, _IONBF, BUFSIZ); - sensor_cfg_ptr_ = std::make_shared(); - wrapper_status_ = GetParameters(*sensor_cfg_ptr_); + wrapper_status_ = DeclareAndGetSensorConfigParams(); + wrapper_status_ = DeclareAndGetWrapperParams(); - InitializeHwInterface(); - InitializeDecoder(); - - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - - if (launch_hw_) { - InitializeHwMonitor(); - StreamStart(); - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - } - - packets_sub_ = create_subscription("pandar_packets", rclcpp::SensorDataQoS(), - std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); - - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); -} - -Status HesaiRosWrapper::InitializeHwInterface() -{ - interface_status_ = Status::OK; - - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); - - if (!launch_hw_) { - return interface_status_; - } - - int retry_count = 0; - - while (true) { - interface_status_ = hw_interface_.InitializeTcpDriver(); - if (interface_status_ == Status::OK || !retry_hw_) { - break; - } - - retry_count++; - std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << retry_count); - } - - if (interface_status_ == Status::OK) { - try { - auto inventory = hw_interface_.GetInventory(); - RCLCPP_INFO_STREAM(get_logger(), inventory); - hw_interface_.SetTargetModel(inventory.model); - } catch (...) { - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); - } - if (this->setup_sensor) { - hw_interface_.CheckAndSetConfig(); - updateParameters(); - } - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); + if (launch_hw_) + { + hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_); + hw_monitor_wrapper_.emplace(this, hw_interface_wrapper_->HwInterface(), sensor_cfg_ptr_); } - pandar_scan_pub_ = - create_publisher("pandar_packets", rclcpp::SensorDataQoS()); - current_scan_msg_ = std::make_unique(); - - return Status::OK; -} + decoder_wrapper_.emplace(this, hw_interface_wrapper_ ? hw_interface_wrapper_->HwInterface() : nullptr, + sensor_cfg_ptr_); -Status HesaiRosWrapper::InitializeDecoder() -{ - calibration_cfg_ptr_ = std::make_shared(); - correction_cfg_ptr_ = std::make_shared(); + RCLCPP_INFO_STREAM(get_logger(), "SensorConfig:" << *sensor_cfg_ptr_); + set_param_res_ = + add_on_set_parameters_callback(std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); - wrapper_status_ = GetCalibrationData(*calibration_cfg_ptr_, *correction_cfg_ptr_); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return wrapper_status_; - } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto pointcloud_qos = - rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + RCLCPP_DEBUG(get_logger(), "Starting stream"); decoder_thread_ = std::thread([this]() { - while (true) { - this->ProcessCloudPacket(std::move(packet_queue_.pop())); + while (true) + { + decoder_wrapper_->ProcessCloudPacket(std::move(packet_queue_.pop())); } }); - nebula_points_pub_ = - this->create_publisher("pandar_points", pointcloud_qos); - aw_points_base_pub_ = - this->create_publisher("aw_points", pointcloud_qos); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", pointcloud_qos); - - driver_ptr_ = std::make_shared( - sensor_cfg_ptr_, calibration_cfg_ptr_, correction_cfg_ptr_); - return driver_ptr_->GetStatus(); -} - -Status HesaiRosWrapper::InitializeHwMonitor() -{ - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return Status::ERROR_1; - } - - switch (sensor_cfg_ptr_->sensor_model) { - case nebula::drivers::SensorModel::HESAI_PANDARXT32: - case nebula::drivers::SensorModel::HESAI_PANDARXT32M: - case nebula::drivers::SensorModel::HESAI_PANDARAT128: - temperature_names_.emplace_back("Bottom circuit board T1"); - temperature_names_.emplace_back("Bottom circuit board T2"); - temperature_names_.emplace_back("Laser emitting board RT_L1(Internal)"); - temperature_names_.emplace_back("Laser emitting board RT_L2"); - temperature_names_.emplace_back("Receiving board RT_R"); - temperature_names_.emplace_back("Receiving board RT2"); - temperature_names_.emplace_back("Top circuit RT3"); - temperature_names_.emplace_back("Not used"); - break; - case nebula::drivers::SensorModel::HESAI_PANDAR64: - case nebula::drivers::SensorModel::HESAI_PANDAR40P: - case nebula::drivers::SensorModel::HESAI_PANDAR40M: - case nebula::drivers::SensorModel::HESAI_PANDARQT64: - case nebula::drivers::SensorModel::HESAI_PANDARQT128: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: - default: - temperature_names_.emplace_back("Bottom circuit RT1"); - temperature_names_.emplace_back("Bottom circuit RT2"); - temperature_names_.emplace_back("Internal Temperature"); - temperature_names_.emplace_back("Laser emitting board RT1"); - temperature_names_.emplace_back("Laser emitting board RT2"); - temperature_names_.emplace_back("Receiving board RT1"); - temperature_names_.emplace_back("Top circuit RT1"); - temperature_names_.emplace_back("Top circuit RT2"); - break; - } - - auto result = hw_interface_.GetInventory(); - current_inventory_.reset(new HesaiInventory(result)); - current_inventory_time_.reset(new rclcpp::Time(this->get_clock()->now())); - std::cout << "HesaiInventory" << std::endl; - std::cout << result << std::endl; - info_model_ = result.get_str_model(); - info_serial_ = std::string(std::begin(result.sn), std::end(result.sn)); - hw_interface_.SetTargetModel(result.model); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model_); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial_); - InitializeHesaiDiagnostics(); - return Status::OK; -} - -void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) -{ - // static auto convert = nebula::util::Instrumentation("ReceiveCloudPacketCallback.convert"); - // static auto publish = nebula::util::Instrumentation("ReceiveCloudPacketCallback.publish"); - // static auto delay = nebula::util::TopicDelay("ReceiveCloudPacketCallback"); - // Driver is not initialized yet - if (!driver_ptr_) { - return; - } - - // convert.tick(); - const auto now = std::chrono::system_clock::now(); - const auto timestamp_ns = - std::chrono::duration_cast(now.time_since_epoch()).count(); - - auto msg_ptr = std::make_unique(); - msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); - msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); - msg_ptr->data.swap(packet); - // convert.tock(); - - // delay.tick(msg_ptr->stamp); - - // publish.tick(); - if (!packet_queue_.try_push(std::move(msg_ptr))) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); - } - // packet_pub_->publish(std::move(msg_ptr)); - // publish.tock(); -} - -void HesaiRosWrapper::ReceiveScanMessageCallback( - std::unique_ptr scan_msg) -{ - if (launch_hw_) { - RCLCPP_ERROR_THROTTLE( - get_logger(), *get_clock(), 1000, - "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); - return; - } - - for (auto & pkt : scan_msg->packets) { - auto nebula_pkt_ptr = std::make_unique(); - nebula_pkt_ptr->stamp = pkt.stamp; - std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); - - packet_queue_.push(std::move(nebula_pkt_ptr)); - } -} - -void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) -{ - // static auto parse = nebula::util::Instrumentation("ProcessCloudPacket.parse"); - // static auto convert = nebula::util::Instrumentation("ProcessCloudPacket.convert"); - // static auto publish = nebula::util::Instrumentation("ProcessCloudPacket.publish"); - // static auto delay = nebula::util::TopicDelay("ProcessCloudPacket"); - - // delay.tick(packet_msg->stamp); - - // Accumulate packets for recording only if someone is subscribed to the topic (for performance) - if ( - launch_hw_ && - (pandar_scan_pub_->get_subscription_count() > 0 || - pandar_scan_pub_->get_intra_process_subscription_count() > 0)) { - if (current_scan_msg_->packets.size() == 0) { - current_scan_msg_->header.stamp = packet_msg->stamp; - } - - pandar_msgs::msg::PandarPacket pandar_packet_msg{}; - pandar_packet_msg.stamp = packet_msg->stamp; - pandar_packet_msg.size = packet_msg->data.size(); - std::copy(packet_msg->data.begin(), packet_msg->data.end(), pandar_packet_msg.data.begin()); - current_scan_msg_->packets.emplace_back(std::move(pandar_packet_msg)); - } - - // parse.tick(); - std::tuple pointcloud_ts = - driver_ptr_->ParseCloudPacket(packet_msg->data); - nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - // parse.tock(); - - if (pointcloud == nullptr) { - // todo - // RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); - return; - }; - - // Publish scan message only if it has been written to - if (current_scan_msg_ && !current_scan_msg_->packets.empty()) { - pandar_scan_pub_->publish(std::move(current_scan_msg_)); - current_scan_msg_ = std::make_unique(); - } - - if ( - nebula_points_pub_->get_subscription_count() > 0 || - nebula_points_pub_->get_intra_process_subscription_count() > 0) { - // convert.tick(); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - // convert.tock(); - // publish.tick(); - PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); - // publish.tock(); - } - if ( - aw_points_base_pub_->get_subscription_count() > 0 || - aw_points_base_pub_->get_intra_process_subscription_count() > 0) { - // convert.tick(); - - const auto autoware_cloud_xyzi = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - // convert.tock(); - // publish.tick(); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); - // publish.tock(); + if (launch_hw_) + { + StreamStart(); + hw_interface_wrapper_->HwInterface()->RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); } - if ( - aw_points_ex_pub_->get_subscription_count() > 0 || - aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - // convert.tick(); - - const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( - pointcloud, std::get<1>(pointcloud_ts)); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - // convert.tock(); - // publish.tick(); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); - // publish.tock(); + else + { + packets_sub_ = create_subscription( + "pandar_packets", rclcpp::SensorDataQoS(), + std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); + RCLCPP_INFO_STREAM(get_logger(), "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); } } -void HesaiRosWrapper::PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher) +nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() { - if (pointcloud->header.stamp.sec < 0) { - RCLCPP_WARN_STREAM(this->get_logger(), "Timestamp error, verify clock source."); - } - pointcloud->header.frame_id = sensor_cfg_ptr_->frame_id; - publisher->publish(std::move(pointcloud)); -} + nebula::drivers::HesaiSensorConfiguration sensor_configuration; -Status HesaiRosWrapper::GetStatus() -{ - return wrapper_status_; -} - -Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration) -{ { rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); + declare_parameter("sensor_model", ""); sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + nebula::drivers::SensorModelFromString(get_parameter("sensor_model").as_string()); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -349,9 +75,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); + declare_parameter("return_mode", "", descriptor); sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); + get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -359,8 +85,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); + declare_parameter("host_ip", "255.255.255.255", descriptor); + sensor_configuration.host_ip = get_parameter("host_ip").as_string(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -368,8 +94,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); + declare_parameter("sensor_ip", "192.168.1.201", descriptor); + sensor_configuration.sensor_ip = get_parameter("sensor_ip").as_string(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -377,8 +103,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); + declare_parameter("data_port", 2368, descriptor); + sensor_configuration.data_port = get_parameter("data_port").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -386,8 +112,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); + declare_parameter("gnss_port", 2369, descriptor); + sensor_configuration.gnss_port = get_parameter("gnss_port").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -395,8 +121,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + declare_parameter("frame_id", "pandar", descriptor); + sensor_configuration.frame_id = get_parameter("frame_id").as_string(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -406,18 +132,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; rcl_interfaces::msg::FloatingPointRange range; range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("calibration_file", "", descriptor); - calibration_file_path = this->get_parameter("calibration_file").as_string(); + descriptor.floating_point_range = { range }; + declare_parameter("scan_phase", 0., descriptor); + sensor_configuration.scan_phase = get_parameter("scan_phase").as_double(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -425,8 +142,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("min_range", 0.3, descriptor); - sensor_configuration.min_range = this->get_parameter("min_range").as_double(); + declare_parameter("min_range", 0.3, descriptor); + sensor_configuration.min_range = get_parameter("min_range").as_double(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -434,8 +151,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("max_range", 300., descriptor); - sensor_configuration.max_range = this->get_parameter("max_range").as_double(); + declare_parameter("max_range", 300., descriptor); + sensor_configuration.max_range = get_parameter("max_range").as_double(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -443,10 +160,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); + declare_parameter("packet_mtu_size", 1500, descriptor); + sensor_configuration.packet_mtu_size = get_parameter("packet_mtu_size").as_int(); } - { rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; @@ -454,18 +170,21 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.dynamic_typing = false; rcl_interfaces::msg::IntegerRange range; RCLCPP_DEBUG_STREAM(get_logger(), sensor_configuration.sensor_model); - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) + { descriptor.additional_constraints = "200, 300, 400, 500"; // range.set__from_value(200).set__to_value(500).set__step(100); // descriptor.integer_range = {range}; //todo - this->declare_parameter("rotation_speed", 200, descriptor); - } else { + declare_parameter("rotation_speed", 200, descriptor); + } + else + { descriptor.additional_constraints = "300, 600, 1200"; // range.set__from_value(300).set__to_value(1200).set__step(300); // descriptor.integer_range = {range}; //todo - this->declare_parameter("rotation_speed", 600, descriptor); + declare_parameter("rotation_speed", 600, descriptor); } - sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); + sensor_configuration.rotation_speed = get_parameter("rotation_speed").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -475,9 +194,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.additional_constraints = ""; rcl_interfaces::msg::IntegerRange range; range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); + descriptor.integer_range = { range }; + declare_parameter("cloud_min_angle", 0, descriptor); + sensor_configuration.cloud_min_angle = get_parameter("cloud_min_angle").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -487,18 +206,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.additional_constraints = ""; rcl_interfaces::msg::IntegerRange range; range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("correction_file", "", descriptor); - correction_file_path = this->get_parameter("correction_file").as_string(); + descriptor.integer_range = { range }; + declare_parameter("cloud_max_angle", 360, descriptor); + sensor_configuration.cloud_max_angle = get_parameter("cloud_max_angle").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -508,37 +218,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; rcl_interfaces::msg::FloatingPointRange range; range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = - this->get_parameter("dual_return_distance_threshold").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("launch_hw", "", descriptor); - launch_hw_ = this->get_parameter("launch_hw").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("setup_sensor", true, descriptor); - this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("retry_hw", true, descriptor); - this->retry_hw_ = this->get_parameter("retry_hw").as_bool(); + descriptor.floating_point_range = { range }; + declare_parameter("dual_return_distance_threshold", 0.1, descriptor); + sensor_configuration.dual_return_distance_threshold = get_parameter("dual_return_distance_threshold").as_double(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -546,9 +228,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("ptp_profile", ""); - sensor_configuration.ptp_profile = - nebula::drivers::PtpProfileFromString(this->get_parameter("ptp_profile").as_string()); + declare_parameter("ptp_profile", ""); + sensor_configuration.ptp_profile = nebula::drivers::PtpProfileFromString(get_parameter("ptp_profile").as_string()); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -556,10 +237,11 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("ptp_transport_type", ""); - sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportTypeFromString( - this->get_parameter("ptp_transport_type").as_string()); - if (static_cast(sensor_configuration.ptp_profile) > 0) { + declare_parameter("ptp_transport_type", ""); + sensor_configuration.ptp_transport_type = + nebula::drivers::PtpTransportTypeFromString(get_parameter("ptp_transport_type").as_string()); + if (static_cast(sensor_configuration.ptp_profile) > 0) + { sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; } } @@ -569,9 +251,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("ptp_switch_type", ""); + declare_parameter("ptp_switch_type", ""); sensor_configuration.ptp_switch_type = - nebula::drivers::PtpSwitchTypeFromString(this->get_parameter("ptp_switch_type").as_string()); + nebula::drivers::PtpSwitchTypeFromString(get_parameter("ptp_switch_type").as_string()); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -580,320 +262,144 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.dynamic_typing = false; rcl_interfaces::msg::IntegerRange range; range.set__from_value(0).set__to_value(127).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("ptp_domain", 0, descriptor); - sensor_configuration.ptp_domain = this->get_parameter("ptp_domain").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("diag_span", 1000, descriptor); - this->diag_span_ = this->get_parameter("diag_span").as_int(); + descriptor.integer_range = { range }; + declare_parameter("ptp_domain", 0, descriptor); + sensor_configuration.ptp_domain = get_parameter("ptp_domain").as_int(); } - /////////////////////////////////////////////// - // Validate ROS parameters - /////////////////////////////////////////////// - - if (sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { - RCLCPP_ERROR_STREAM( - get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); + if (sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) + { + RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); return Status::SENSOR_CONFIG_ERROR; } - if ( - sensor_configuration.ptp_transport_type == - nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { - RCLCPP_ERROR_STREAM( - get_logger(), - "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " - "using the '1588v2' PTP Profile"); + if (sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) + { + RCLCPP_ERROR_STREAM(get_logger(), + "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " + "using the '1588v2' PTP Profile"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { - RCLCPP_ERROR_STREAM( - get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); + if (sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) + { + RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) + { return Status::INVALID_SENSOR_MODEL; } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) + { return Status::INVALID_ECHO_MODE; } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { + if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) + { return Status::SENSOR_CONFIG_ERROR; } - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + auto new_cfg_ptr_ = std::make_shared(sensor_configuration); + sensor_cfg_ptr_.swap(new_cfg_ptr_); return Status::OK; } -Status HesaiRosWrapper::GetCalibrationData( - drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration) +void HesaiRosWrapper::ReceiveScanMessageCallback(std::unique_ptr scan_msg) { - calibration_configuration.calibration_file = calibration_file_path; // todo - - bool run_local = !launch_hw_; - if (sensor_cfg_ptr_->sensor_model != drivers::SensorModel::HESAI_PANDARAT128) { - std::string calibration_file_path_from_sensor; - if (launch_hw_ && !calibration_configuration.calibration_file.empty()) { - int ext_pos = calibration_configuration.calibration_file.find_last_of('.'); - calibration_file_path_from_sensor += - calibration_configuration.calibration_file.substr(0, ext_pos); - calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr( - ext_pos, calibration_configuration.calibration_file.size() - ext_pos); - } - if (launch_hw_) { - run_local = false; - RCLCPP_INFO_STREAM( - this->get_logger(), - "Trying to acquire calibration data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); - std::future future = std::async( - std::launch::async, - [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { - auto str = hw_interface_.GetLidarCalibrationString(); - auto rt = - calibration_configuration.SaveFileFromString(calibration_file_path_from_sensor, str); - RCLCPP_ERROR_STREAM(get_logger(), str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM( - get_logger(), - "SaveFileFromString success:" << calibration_file_path_from_sensor << "\n"); - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "SaveFileFromString failed:" << calibration_file_path_from_sensor << "\n"); - } - rt = calibration_configuration.LoadFromString(str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "LoadFromString success:" << str << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), "LoadFromString failed:" << str << "\n"); - } - }); - std::future_status status; - status = future.wait_for(std::chrono::milliseconds(5000)); - if (status == std::future_status::timeout) { - std::cerr << "# std::future_status::timeout\n"; - RCLCPP_ERROR_STREAM(get_logger(), "GetCalibration Timeout"); - run_local = true; - } else if (status == std::future_status::ready && !run_local) { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Acquired calibration data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); - RCLCPP_INFO_STREAM( - this->get_logger(), - "The calibration has been saved in '" << calibration_file_path_from_sensor << "'"); - } - } - if (run_local) { - RCLCPP_WARN_STREAM(get_logger(), "Running locally"); - bool run_org = false; - if (calibration_file_path_from_sensor.empty()) { - run_org = true; - } else { - RCLCPP_INFO_STREAM( - get_logger(), "Trying to load file: " << calibration_file_path_from_sensor); - auto cal_status = calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); + if (hw_interface_wrapper_) + { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 1000, + "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); + return; + } - if (cal_status != Status::OK) { - run_org = true; - } else { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Load calibration data from: '" << calibration_file_path_from_sensor << "'"); - } - } - if (run_org) { - RCLCPP_INFO_STREAM( - get_logger(), "Trying to load file: " << calibration_configuration.calibration_file); - if (calibration_configuration.calibration_file.empty()) { - RCLCPP_ERROR_STREAM( - this->get_logger(), - "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = - calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); + for (auto& pkt : scan_msg->packets) + { + auto nebula_pkt_ptr = std::make_unique(); + nebula_pkt_ptr->stamp = pkt.stamp; + std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), - "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); - return cal_status; - } else { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Load calibration data from: '" << calibration_configuration.calibration_file << "'"); - } - } - } - } - } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 - std::string correction_file_path_from_sensor; - if (launch_hw_ && !correction_file_path.empty()) { - int ext_pos = correction_file_path.find_last_of('.'); - correction_file_path_from_sensor += correction_file_path.substr(0, ext_pos); - correction_file_path_from_sensor += "_from_sensor"; - correction_file_path_from_sensor += - correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); - } - std::future future = std::async( - std::launch::async, - [this, &correction_configuration, &correction_file_path_from_sensor, &run_local]() { - if (launch_hw_) { - RCLCPP_INFO_STREAM(this->get_logger(), "Trying to acquire calibration data from sensor"); - auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); - RCLCPP_INFO_STREAM( - get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); - auto rt = correction_configuration.SaveFileFromBinary( - correction_file_path_from_sensor, received_bytes); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM( - get_logger(), - "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "SaveFileFromBinary failed:" << correction_file_path_from_sensor - << ". Falling back to offline calibration file."); - run_local = true; - } - rt = correction_configuration.LoadFromBinary(received_bytes); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); - run_local = false; - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "LoadFromBinary failed" << ". Falling back to offline calibration file."); - run_local = true; - } - } else { - RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); - run_local = true; - } - }); - if (!run_local) { - std::future_status status; - status = future.wait_for(std::chrono::milliseconds(8000)); - if (status == std::future_status::timeout) { - std::cerr << "# std::future_status::timeout\n"; - run_local = true; - } else if (status == std::future_status::ready && !run_local) { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Acquired correction data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); - RCLCPP_INFO_STREAM( - this->get_logger(), - "The correction has been saved in '" << correction_file_path_from_sensor << "'"); - } - } - if (run_local) { - bool run_org = false; - if (correction_file_path_from_sensor.empty()) { - run_org = true; - } else { - auto cal_status = correction_configuration.LoadFromFile(correction_file_path_from_sensor); + packet_queue_.push(std::move(nebula_pkt_ptr)); + } +} - if (cal_status != Status::OK) { - run_org = true; - } else { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Load correction data from: '" << correction_file_path_from_sensor << "'"); - } - } - if (run_org) { - if (correction_file_path.empty()) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Empty Correction File: '" << correction_file_path << "'"); - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = correction_configuration.LoadFromFile(correction_file_path); +Status HesaiRosWrapper::GetStatus() +{ + return wrapper_status_; +} - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Given Correction File: '" << correction_file_path << "'"); - return cal_status; - } else { - RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" << correction_file_path << "'"); - } - } - } - } - } // end AT128 +Status HesaiRosWrapper::DeclareAndGetWrapperParams() +{ + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + declare_parameter("launch_hw", "", descriptor); + launch_hw_ = get_parameter("launch_hw").as_bool(); + } return Status::OK; } HesaiRosWrapper::~HesaiRosWrapper() { - RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); - hw_interface_.FinalizeTcpDriver(); } Status HesaiRosWrapper::StreamStart() { - if (Status::OK == interface_status_) { - interface_status_ = hw_interface_.SensorInterfaceStart(); + if (!hw_interface_wrapper_) + { + return Status::UDP_CONNECTION_ERROR; } - return interface_status_; + + if (hw_interface_wrapper_->Status() != Status::OK) + { + return hw_interface_wrapper_->Status(); + } + + return hw_interface_wrapper_->HwInterface()->SensorInterfaceStart(); } -rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( - const std::vector & p) +rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback(const std::vector& p) { std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback"); - RCLCPP_DEBUG_STREAM(this->get_logger(), p); - RCLCPP_DEBUG_STREAM(this->get_logger(), *sensor_cfg_ptr_); - RCLCPP_INFO_STREAM(this->get_logger(), p); + RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback"); + RCLCPP_DEBUG_STREAM(get_logger(), p); + RCLCPP_DEBUG_STREAM(get_logger(), *sensor_cfg_ptr_); + + drivers::HesaiSensorConfiguration new_cfg(*sensor_cfg_ptr_); - std::shared_ptr new_param = - std::make_shared(*sensor_cfg_ptr_); - RCLCPP_INFO_STREAM(this->get_logger(), new_param); std::string sensor_model_str; std::string return_mode_str; - if ( - get_param(p, "sensor_model", sensor_model_str) | get_param(p, "return_mode", return_mode_str) | - get_param(p, "host_ip", new_param->host_ip) | get_param(p, "sensor_ip", new_param->sensor_ip) | - get_param(p, "frame_id", new_param->frame_id) | - get_param(p, "data_port", new_param->data_port) | - get_param(p, "gnss_port", new_param->gnss_port) | - get_param(p, "scan_phase", new_param->scan_phase) | - get_param(p, "packet_mtu_size", new_param->packet_mtu_size) | - get_param(p, "rotation_speed", new_param->rotation_speed) | - get_param(p, "cloud_min_angle", new_param->cloud_min_angle) | - get_param(p, "cloud_max_angle", new_param->cloud_max_angle) | - get_param(p, "dual_return_distance_threshold", new_param->dual_return_distance_threshold)) { + if (get_param(p, "sensor_model", sensor_model_str) | get_param(p, "return_mode", return_mode_str) | + get_param(p, "host_ip", new_cfg.host_ip) | get_param(p, "sensor_ip", new_cfg.sensor_ip) | + get_param(p, "frame_id", new_cfg.frame_id) | get_param(p, "data_port", new_cfg.data_port) | + get_param(p, "gnss_port", new_cfg.gnss_port) | get_param(p, "scan_phase", new_cfg.scan_phase) | + get_param(p, "packet_mtu_size", new_cfg.packet_mtu_size) | + get_param(p, "rotation_speed", new_cfg.rotation_speed) | + get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | + get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle) | + get_param(p, "dual_return_distance_threshold", new_cfg.dual_return_distance_threshold)) + { if (0 < sensor_model_str.length()) - new_param->sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); + new_cfg.sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); if (0 < return_mode_str.length()) - new_param->return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); + new_cfg.return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); - sensor_cfg_ptr_.swap(new_param); - RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); - RCLCPP_DEBUG_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - hw_interface_.CheckAndSetConfig(); + auto new_cfg_ptr = std::make_shared(new_cfg); + sensor_cfg_ptr_.swap(new_cfg_ptr); + RCLCPP_INFO_STREAM(get_logger(), "Update sensor_configuration"); + RCLCPP_DEBUG_STREAM(get_logger(), "hw_interface_.SetSensorConfiguration"); + hw_interface_wrapper_->HwInterface()->SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); + hw_interface_wrapper_->HwInterface()->CheckAndSetConfig(); } auto result = std::make_shared(); result->successful = true; result->reason = "success"; - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback success"); + RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback success"); return *result; } @@ -901,310 +407,47 @@ rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( std::vector HesaiRosWrapper::updateParameters() { std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters start"); + RCLCPP_DEBUG_STREAM(get_logger(), "updateParameters start"); std::ostringstream os_sensor_model; os_sensor_model << sensor_cfg_ptr_->sensor_model; std::ostringstream os_return_mode; os_return_mode << sensor_cfg_ptr_->return_mode; - RCLCPP_INFO_STREAM(this->get_logger(), "set_parameters"); + RCLCPP_INFO_STREAM(get_logger(), "set_parameters"); auto results = set_parameters( - {rclcpp::Parameter("sensor_model", os_sensor_model.str()), - rclcpp::Parameter("return_mode", os_return_mode.str()), - rclcpp::Parameter("host_ip", sensor_cfg_ptr_->host_ip), - rclcpp::Parameter("sensor_ip", sensor_cfg_ptr_->sensor_ip), - rclcpp::Parameter("frame_id", sensor_cfg_ptr_->frame_id), - rclcpp::Parameter("data_port", sensor_cfg_ptr_->data_port), - rclcpp::Parameter("gnss_port", sensor_cfg_ptr_->gnss_port), - rclcpp::Parameter("scan_phase", sensor_cfg_ptr_->scan_phase), - rclcpp::Parameter("packet_mtu_size", sensor_cfg_ptr_->packet_mtu_size), - rclcpp::Parameter("rotation_speed", sensor_cfg_ptr_->rotation_speed), - rclcpp::Parameter("cloud_min_angle", sensor_cfg_ptr_->cloud_min_angle), - rclcpp::Parameter("cloud_max_angle", sensor_cfg_ptr_->cloud_max_angle), - rclcpp::Parameter( - "dual_return_distance_threshold", sensor_cfg_ptr_->dual_return_distance_threshold)}); - RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters end"); + { rclcpp::Parameter("sensor_model", os_sensor_model.str()), + rclcpp::Parameter("return_mode", os_return_mode.str()), rclcpp::Parameter("host_ip", sensor_cfg_ptr_->host_ip), + rclcpp::Parameter("sensor_ip", sensor_cfg_ptr_->sensor_ip), + rclcpp::Parameter("frame_id", sensor_cfg_ptr_->frame_id), + rclcpp::Parameter("data_port", sensor_cfg_ptr_->data_port), + rclcpp::Parameter("gnss_port", sensor_cfg_ptr_->gnss_port), + rclcpp::Parameter("scan_phase", sensor_cfg_ptr_->scan_phase), + rclcpp::Parameter("packet_mtu_size", sensor_cfg_ptr_->packet_mtu_size), + rclcpp::Parameter("rotation_speed", sensor_cfg_ptr_->rotation_speed), + rclcpp::Parameter("cloud_min_angle", sensor_cfg_ptr_->cloud_min_angle), + rclcpp::Parameter("cloud_max_angle", sensor_cfg_ptr_->cloud_max_angle), + rclcpp::Parameter("dual_return_distance_threshold", sensor_cfg_ptr_->dual_return_distance_threshold) }); + RCLCPP_DEBUG_STREAM(get_logger(), "updateParameters end"); return results; } -void HesaiRosWrapper::InitializeHesaiDiagnostics() -{ - RCLCPP_INFO_STREAM(this->get_logger(), "InitializeHesaiDiagnostics"); - using std::chrono_literals::operator""s; - std::ostringstream os; - auto hardware_id = info_model_ + ": " + info_serial_; - diagnostics_updater_.setHardwareID(hardware_id); - RCLCPP_INFO_STREAM(this->get_logger(), "hardware_id: " + hardware_id); - - diagnostics_updater_.add("hesai_status", this, &HesaiRosWrapper::HesaiCheckStatus); - diagnostics_updater_.add("hesai_ptp", this, &HesaiRosWrapper::HesaiCheckPtp); - diagnostics_updater_.add("hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); - diagnostics_updater_.add("hesai_rpm", this, &HesaiRosWrapper::HesaiCheckRpm); - - current_status_.reset(); - current_monitor_.reset(); - current_status_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; - current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; - - auto fetch_diag_from_sensor = [this]() { - OnHesaiStatusTimer(); - if (hw_interface_.UseHttpGetLidarMonitor()) { - OnHesaiLidarMonitorTimerHttp(); - } else { - OnHesaiLidarMonitorTimer(); - } - }; - - fetch_diagnostics_timer_ = - create_wall_timer(std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor)); - - if (hw_interface_.UseHttpGetLidarMonitor()) { - diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); - } else { - diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltage); - } - - auto on_timer_update = [this] { - RCLCPP_DEBUG_STREAM(get_logger(), "OnUpdateTimer"); - auto now = this->get_clock()->now(); - auto dif = (now - *current_status_time_).seconds(); - - RCLCPP_DEBUG_STREAM(get_logger(), "dif(status): " << dif); - - if (diag_span_ * 2.0 < dif * 1000) { - current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); - } else { - current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); - } - dif = (now - *current_lidar_monitor_time_).seconds(); - RCLCPP_DEBUG_STREAM(get_logger(), "dif(monitor): " << dif); - if (diag_span_ * 2.0 < dif * 1000) { - current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); - } else { - current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); - } - diagnostics_updater_.force_update(); - }; - diagnostics_update_timer_ = - create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); - - RCLCPP_DEBUG_STREAM(get_logger(), "add_timer"); -} - -std::string HesaiRosWrapper::GetPtreeValue( - boost::property_tree::ptree * pt, const std::string & key) -{ - boost::optional value = pt->get_optional(key); - if (value) { - return value.get(); - } else { - return MSG_NOT_SUPPORTED; - } -} -std::string HesaiRosWrapper::GetFixedPrecisionString(double val, int pre) -{ - std::stringstream ss; - ss << std::fixed << std::setprecision(pre) << val; - return ss.str(); -} - -void HesaiRosWrapper::OnHesaiStatusTimer() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer" << std::endl); - try { - auto result = hw_interface_.GetLidarStatus(); - std::scoped_lock lock(mtx_lidar_status_); - current_status_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_status_.reset(new HesaiLidarStatus(result)); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), - error.what()); - } - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl); -} - -void HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp"); - try { - hw_interface_.GetLidarMonitorAsyncHttp([this](const std::string & str) { - std::scoped_lock lock(mtx_lidar_monitor_); - current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_tree_ = - std::make_unique(hw_interface_.ParseJson(str)); - }); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_error)"), - error.what()); - } - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp END"); -} - -void HesaiRosWrapper::OnHesaiLidarMonitorTimer() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer"); - try { - auto result = hw_interface_.GetLidarMonitor(); - std::scoped_lock lock(mtx_lidar_monitor_); - current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_monitor_.reset(new HesaiLidarMonitor(result)); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), - error.what()); - } - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END"); -} - -void HesaiRosWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - - diagnostics.add("system_uptime", std::to_string(current_status_->system_uptime.value())); - diagnostics.add("startup_times", std::to_string(current_status_->startup_times.value())); - diagnostics.add("total_operation_time", std::to_string(current_status_->total_operation_time.value())); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiRosWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - auto gps_status = current_status_->get_str_gps_pps_lock(); - auto gprmc_status = current_status_->get_str_gps_gprmc_status(); - auto ptp_status = current_status_->get_str_ptp_clock_status(); - std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); - std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); - std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); - diagnostics.add("gps_pps_lock", gps_status); - diagnostics.add("gps_gprmc_status", gprmc_status); - diagnostics.add("ptp_clock_status", ptp_status); - if (gps_status != "UNKNOWN") { - msg.emplace_back("gps_pps_lock: " + gps_status); - } - if (gprmc_status != "UNKNOWN") { - msg.emplace_back("gprmc_status: " + gprmc_status); - } - if (ptp_status != "UNKNOWN") { - msg.emplace_back("ptp_status: " + ptp_status); - } - if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") { - level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - } - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiRosWrapper::HesaiCheckTemperature( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - for (size_t i = 0; i < std::size(current_status_->temperature); i++) { - diagnostics.add( - temperature_names_[i], GetFixedPrecisionString(current_status_->temperature[i].value() * 0.01)); - } - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiRosWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector& packet) { - std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - diagnostics.add("motor_speed", std::to_string(current_status_->motor_speed.value())); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + if (!decoder_wrapper_ || decoder_wrapper_->Status() != Status::OK) + { + return; } -} -void HesaiRosWrapper::HesaiCheckVoltageHttp( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_monitor_); - if (current_lidar_monitor_tree_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - std::string key = ""; - - std::string mes; - key = "lidarInCur"; - try { - mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); - } catch (boost::bad_lexical_cast & ex) { - level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = MSG_ERROR + std::string(ex.what()); - } - diagnostics.add(key, mes); - key = "lidarInVol"; - try { - mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); - } catch (boost::bad_lexical_cast & ex) { - level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = MSG_ERROR + std::string(ex.what()); - } - diagnostics.add(key, mes); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} + const auto now = std::chrono::system_clock::now(); + const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); -void HesaiRosWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_monitor_); - if (current_monitor_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - diagnostics.add( - "input_voltage", GetFixedPrecisionString(current_monitor_->input_voltage.value() * 0.01) + " V"); - diagnostics.add( - "input_current", GetFixedPrecisionString(current_monitor_->input_current.value() * 0.01) + " mA"); - diagnostics.add( - "input_power", GetFixedPrecisionString(current_monitor_->input_power.value() * 0.01) + " W"); + auto msg_ptr = std::make_unique(); + msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); + msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); + msg_ptr->data.swap(packet); - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + if (!packet_queue_.try_push(std::move(msg_ptr))) + { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); } } diff --git a/nebula_ros/src/hesai/hw_interface_wrapper.cpp b/nebula_ros/src/hesai/hw_interface_wrapper.cpp new file mode 100644 index 000000000..e38f6b181 --- /dev/null +++ b/nebula_ros/src/hesai/hw_interface_wrapper.cpp @@ -0,0 +1,94 @@ +#include "nebula_ros/hesai/hw_interface_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ + +HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, + std::shared_ptr& config) + : hw_interface_(new nebula::drivers::HesaiHwInterface()) + , logger_(parent_node->get_logger().get_child("HwInterface")) + , status_(Status::NOT_INITIALIZED) +{ + bool setup_sensor, retry_connect; + + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + parent_node->declare_parameter("setup_sensor", true, descriptor); + setup_sensor = parent_node->get_parameter("setup_sensor").as_bool(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + parent_node->declare_parameter("retry_hw", true, descriptor); + retry_connect = parent_node->get_parameter("retry_hw").as_bool(); + } + + hw_interface_->SetSensorConfiguration(std::static_pointer_cast(config)); + + status_ = Status::OK; + + hw_interface_->SetLogger(std::make_shared(parent_node->get_logger())); + hw_interface_->SetTargetModel(config->sensor_model); + + int retry_count = 0; + + while (true) + { + status_ = hw_interface_->InitializeTcpDriver(); + if (status_ == Status::OK || !retry_connect) + { + break; + } + + retry_count++; + std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 + RCLCPP_WARN_STREAM(logger_, "Retry: " << retry_count); + } + + if (status_ == Status::OK) + { + try + { + auto inventory = hw_interface_->GetInventory(); + RCLCPP_INFO_STREAM(logger_, inventory); + hw_interface_->SetTargetModel(inventory.model); + } + catch (...) + { + RCLCPP_ERROR_STREAM(logger_, "Failed to get model from sensor..."); + } + if (setup_sensor) + { + hw_interface_->CheckAndSetConfig(); + // updateParameters(); TODO + } + } + else + { + RCLCPP_ERROR_STREAM(logger_, "Failed to get model from sensor... Set from config: " << config->sensor_model); + } + + status_ = Status::OK; +} + +Status HesaiHwInterfaceWrapper::Status() +{ + return status_; +} + +std::shared_ptr HesaiHwInterfaceWrapper::HwInterface() const +{ + return hw_interface_; +} + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp new file mode 100644 index 000000000..579e32a4e --- /dev/null +++ b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp @@ -0,0 +1,412 @@ +#include "nebula_ros/hesai/hw_monitor_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ +HesaiHwMonitorWrapper::HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config) + : logger_(parent_node->get_logger().get_child("HwMonitor")) + , diagnostics_updater_(parent_node) + , status_(Status::OK) + , hw_interface_(hw_interface) + , parent_node_(parent_node) +{ + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + parent_node->declare_parameter("diag_span", 1000, descriptor); + diag_span_ = parent_node->get_parameter("diag_span").as_int(); + } + + switch (config->sensor_model) + { + case nebula::drivers::SensorModel::HESAI_PANDARXT32: + case nebula::drivers::SensorModel::HESAI_PANDARXT32M: + case nebula::drivers::SensorModel::HESAI_PANDARAT128: + temperature_names_.emplace_back("Bottom circuit board T1"); + temperature_names_.emplace_back("Bottom circuit board T2"); + temperature_names_.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names_.emplace_back("Laser emitting board RT_L2"); + temperature_names_.emplace_back("Receiving board RT_R"); + temperature_names_.emplace_back("Receiving board RT2"); + temperature_names_.emplace_back("Top circuit RT3"); + temperature_names_.emplace_back("Not used"); + break; + case nebula::drivers::SensorModel::HESAI_PANDAR64: + case nebula::drivers::SensorModel::HESAI_PANDAR40P: + case nebula::drivers::SensorModel::HESAI_PANDAR40M: + case nebula::drivers::SensorModel::HESAI_PANDARQT64: + case nebula::drivers::SensorModel::HESAI_PANDARQT128: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: + default: + temperature_names_.emplace_back("Bottom circuit RT1"); + temperature_names_.emplace_back("Bottom circuit RT2"); + temperature_names_.emplace_back("Internal Temperature"); + temperature_names_.emplace_back("Laser emitting board RT1"); + temperature_names_.emplace_back("Laser emitting board RT2"); + temperature_names_.emplace_back("Receiving board RT1"); + temperature_names_.emplace_back("Top circuit RT1"); + temperature_names_.emplace_back("Top circuit RT2"); + break; + } + + auto result = hw_interface->GetInventory(); + current_inventory_.reset(new HesaiInventory(result)); + current_inventory_time_.reset(new rclcpp::Time(parent_node->get_clock()->now())); + std::cout << "HesaiInventory" << std::endl; + std::cout << result << std::endl; + info_model_ = result.get_str_model(); + info_serial_ = std::string(std::begin(result.sn), std::end(result.sn)); + RCLCPP_INFO_STREAM(logger_, "Model:" << info_model_); + RCLCPP_INFO_STREAM(logger_, "Serial:" << info_serial_); + InitializeHesaiDiagnostics(); + + if (Status::OK != status_) + { + throw std::runtime_error((std::stringstream() << "Error getting calibration data: " << status_).str()); + } +} + +void HesaiHwMonitorWrapper::InitializeHesaiDiagnostics() +{ + RCLCPP_INFO_STREAM(logger_, "InitializeHesaiDiagnostics"); + using std::chrono_literals::operator""s; + std::ostringstream os; + auto hardware_id = info_model_ + ": " + info_serial_; + diagnostics_updater_.setHardwareID(hardware_id); + RCLCPP_INFO_STREAM(logger_, "hardware_id: " + hardware_id); + + diagnostics_updater_.add("hesai_status", this, &HesaiHwMonitorWrapper::HesaiCheckStatus); + diagnostics_updater_.add("hesai_ptp", this, &HesaiHwMonitorWrapper::HesaiCheckPtp); + diagnostics_updater_.add("hesai_temperature", this, &HesaiHwMonitorWrapper::HesaiCheckTemperature); + diagnostics_updater_.add("hesai_rpm", this, &HesaiHwMonitorWrapper::HesaiCheckRpm); + + current_status_.reset(); + current_monitor_.reset(); + current_status_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_lidar_monitor_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + + auto fetch_diag_from_sensor = [this]() { + OnHesaiStatusTimer(); + if (hw_interface_->UseHttpGetLidarMonitor()) + { + OnHesaiLidarMonitorTimerHttp(); + } + else + { + OnHesaiLidarMonitorTimer(); + } + }; + + fetch_diagnostics_timer_ = + parent_node_->create_wall_timer(std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor)); + + if (hw_interface_->UseHttpGetLidarMonitor()) + { + diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorWrapper::HesaiCheckVoltageHttp); + } + else + { + diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorWrapper::HesaiCheckVoltage); + } + + auto on_timer_update = [this] { + RCLCPP_DEBUG_STREAM(logger_, "OnUpdateTimer"); + auto now = parent_node_->get_clock()->now(); + auto dif = (now - *current_status_time_).seconds(); + + RCLCPP_DEBUG_STREAM(logger_, "dif(status): " << dif); + + if (diag_span_ * 2.0 < dif * 1000) + { + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(logger_, "STALE"); + } + else + { + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(logger_, "OK"); + } + dif = (now - *current_lidar_monitor_time_).seconds(); + RCLCPP_DEBUG_STREAM(logger_, "dif(monitor): " << dif); + if (diag_span_ * 2.0 < dif * 1000) + { + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(logger_, "STALE"); + } + else + { + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(logger_, "OK"); + } + diagnostics_updater_.force_update(); + }; + diagnostics_update_timer_ = + parent_node_->create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); + + RCLCPP_DEBUG_STREAM(logger_, "add_timer"); +} + +std::string HesaiHwMonitorWrapper::GetPtreeValue(boost::property_tree::ptree* pt, const std::string& key) +{ + boost::optional value = pt->get_optional(key); + if (value) + { + return value.get(); + } + else + { + return MSG_NOT_SUPPORTED; + } +} +std::string HesaiHwMonitorWrapper::GetFixedPrecisionString(double val, int pre) +{ + std::stringstream ss; + ss << std::fixed << std::setprecision(pre) << val; + return ss.str(); +} + +void HesaiHwMonitorWrapper::OnHesaiStatusTimer() +{ + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiStatusTimer" << std::endl); + try + { + auto result = hw_interface_->GetLidarStatus(); + std::scoped_lock lock(mtx_lidar_status_); + current_status_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_status_.reset(new HesaiLidarStatus(result)); + } + catch (const std::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiStatusTimer(std::system_error)"), + error.what()); + } + catch (const boost::system::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiStatusTimer(boost::system::system_error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiStatusTimer END" << std::endl); +} + +void HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp() +{ + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimerHttp"); + try + { + hw_interface_->GetLidarMonitorAsyncHttp([this](const std::string& str) { + std::scoped_lock lock(mtx_lidar_monitor_); + current_lidar_monitor_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_lidar_monitor_tree_ = std::make_unique(hw_interface_->ParseJson(str)); + }); + } + catch (const std::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), + error.what()); + } + catch (const boost::system::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_" + "error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimerHttp END"); +} + +void HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer() +{ + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimer"); + try + { + auto result = hw_interface_->GetLidarMonitor(); + std::scoped_lock lock(mtx_lidar_monitor_); + current_lidar_monitor_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_monitor_.reset(new HesaiLidarMonitor(result)); + } + catch (const std::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), + error.what()); + } + catch (const boost::system::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer(boost::system::system_" + "error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimer END"); +} + +void HesaiHwMonitorWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + + diagnostics.add("system_uptime", std::to_string(current_status_->system_uptime.value())); + diagnostics.add("startup_times", std::to_string(current_status_->startup_times.value())); + diagnostics.add("total_operation_time", std::to_string(current_status_->total_operation_time.value())); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + auto gps_status = current_status_->get_str_gps_pps_lock(); + auto gprmc_status = current_status_->get_str_gps_gprmc_status(); + auto ptp_status = current_status_->get_str_ptp_clock_status(); + std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); + std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); + std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); + diagnostics.add("gps_pps_lock", gps_status); + diagnostics.add("gps_gprmc_status", gprmc_status); + diagnostics.add("ptp_clock_status", ptp_status); + if (gps_status != "UNKNOWN") + { + msg.emplace_back("gps_pps_lock: " + gps_status); + } + if (gprmc_status != "UNKNOWN") + { + msg.emplace_back("gprmc_status: " + gprmc_status); + } + if (ptp_status != "UNKNOWN") + { + msg.emplace_back("ptp_status: " + ptp_status); + } + if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") + { + level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + } + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + for (size_t i = 0; i < std::size(current_status_->temperature); i++) + { + diagnostics.add(temperature_names_[i], + GetFixedPrecisionString(current_status_->temperature[i].value() * 0.01, 3)); + } + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + diagnostics.add("motor_speed", std::to_string(current_status_->motor_speed.value())); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_monitor_); + if (current_lidar_monitor_tree_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + std::string key = ""; + + std::string mes; + key = "lidarInCur"; + try + { + mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); + } + catch (boost::bad_lexical_cast& ex) + { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = MSG_ERROR + std::string(ex.what()); + } + diagnostics.add(key, mes); + key = "lidarInVol"; + try + { + mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); + } + catch (boost::bad_lexical_cast& ex) + { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = MSG_ERROR + std::string(ex.what()); + } + diagnostics.add(key, mes); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_monitor_); + if (current_monitor_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + diagnostics.add("input_voltage", GetFixedPrecisionString(current_monitor_->input_voltage.value() * 0.01, 3) + " V"); + diagnostics.add("input_current", GetFixedPrecisionString(current_monitor_->input_current.value() * 0.01, 3) + " m" + "A"); + diagnostics.add("input_power", GetFixedPrecisionString(current_monitor_->input_power.value() * 0.01, 3) + " W"); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +Status HesaiHwMonitorWrapper::Status() +{ + return Status::NOT_IMPLEMENTED; // TODO +} +} // namespace ros +} // namespace nebula \ No newline at end of file From 19e8101da705fdd6d50b25fecfeb5c9be226c0ba Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 16:40:54 +0900 Subject: [PATCH 031/122] chore(velodyne_calibration_decoder): fix spelling --- nebula_common/src/velodyne/velodyne_calibration_decoder.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index 954da496b..0016e8208 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,4 +1,3 @@ -// cspell:ignore piyush, fout /** * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, @@ -7,6 +6,8 @@ * License: Modified BSD License */ +// cspell:ignore piyush, piyushk, fout + #include #ifdef HAVE_NEW_YAMLCPP From f0a85992a8b6c5745d83625450a89db5b8037073 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 16:43:32 +0900 Subject: [PATCH 032/122] chore(nebula_common): remove debug code --- .../nebula_common/util/instrumentation.hpp | 86 ------------------- .../util/performance_counter.hpp | 43 ---------- .../nebula_common/util/topic_delay.hpp | 68 --------------- 3 files changed, 197 deletions(-) delete mode 100644 nebula_common/include/nebula_common/util/instrumentation.hpp delete mode 100644 nebula_common/include/nebula_common/util/performance_counter.hpp delete mode 100644 nebula_common/include/nebula_common/util/topic_delay.hpp diff --git a/nebula_common/include/nebula_common/util/instrumentation.hpp b/nebula_common/include/nebula_common/util/instrumentation.hpp deleted file mode 100644 index ccce705d8..000000000 --- a/nebula_common/include/nebula_common/util/instrumentation.hpp +++ /dev/null @@ -1,86 +0,0 @@ -#pragma once - -#include "nebula_common/util/performance_counter.hpp" - -#include -#include -#include - -namespace nebula -{ -namespace util -{ - -using namespace std::chrono_literals; - -class Instrumentation -{ - using clock = std::chrono::high_resolution_clock; - using time_point = clock::time_point; - using duration = std::chrono::nanoseconds; - -public: - Instrumentation(std::string tag) - : tag_(std::move(tag)), last_print_(clock::now()), delays_(), rtts_() - { - } - - void tick() - { - auto now = clock::now(); - - if (last_tick_ != time_point::min()) { - auto rtt = now - last_tick_; - rtts_.update(rtt); - } - - last_tick_ = now; - } - - void tock() - { - auto now = clock::now(); - auto delay = now - last_tick_; - delays_.update(delay); - - if (now - last_print_ >= PRINT_INTERVAL) { - auto del = delays_.reset(); - auto rtt = rtts_.reset(); - - last_print_ = now; - - std::stringstream ss; - - ss << "{\"type\": \"instrumentation\", \"tag\": \"" << tag_ - << "\", \"del\": ["; - - for (duration & dt : *del) { - ss << dt.count() << ','; - } - - ss <<"null], \"rtt\": ["; - - for (duration & dt : *rtt) { - ss << dt.count() << ','; - } - - ss << "null]}" << std::endl; - - std::cout << ss.str(); - } - } - -private: - std::string tag_; - - time_point last_tick_{time_point::min()}; - time_point last_print_{time_point::min()}; - - Counter delays_; - Counter rtts_; - - const duration PRINT_INTERVAL = 1s; -}; - -} // namespace util -} // namespace nebula \ No newline at end of file diff --git a/nebula_common/include/nebula_common/util/performance_counter.hpp b/nebula_common/include/nebula_common/util/performance_counter.hpp deleted file mode 100644 index cd6b618f1..000000000 --- a/nebula_common/include/nebula_common/util/performance_counter.hpp +++ /dev/null @@ -1,43 +0,0 @@ -#pragma once - -#include -#include -#include - -namespace nebula -{ -namespace util -{ - -class Counter -{ - using clock = std::chrono::high_resolution_clock; - using time_point = clock::time_point; - using duration = std::chrono::nanoseconds; - -public: - Counter() - : buf_record_(), buf_output_() - { - buf_record_.resize(100000); - buf_output_.resize(100000); - } - - std::vector * reset() - { - buf_record_.swap(buf_output_); - buf_record_.clear(); - return &buf_output_; - } - - void update(duration measurement) - { - buf_record_.push_back(measurement); - } - -private: - std::vector buf_record_; - std::vector buf_output_; -}; -} // namespace util -} // namespace nebula \ No newline at end of file diff --git a/nebula_common/include/nebula_common/util/topic_delay.hpp b/nebula_common/include/nebula_common/util/topic_delay.hpp deleted file mode 100644 index a92ce29a2..000000000 --- a/nebula_common/include/nebula_common/util/topic_delay.hpp +++ /dev/null @@ -1,68 +0,0 @@ -#pragma once - -#include - -#include "nebula_common/util/performance_counter.hpp" - - -#include -#include -#include - -namespace nebula -{ -namespace util -{ - -using namespace std::chrono_literals; - -class TopicDelay -{ - using clock = std::chrono::high_resolution_clock; - using time_point = clock::time_point; - using duration = std::chrono::nanoseconds; - -public: - TopicDelay(std::string tag) : tag_(std::move(tag)), last_print_(clock::now()), delays_() {} - - void tick(builtin_interfaces::msg::Time & stamp) - { - auto now = clock::now(); - - time_point t_msg = time_point(duration(static_cast(stamp.sec) * 1'000'000'000ULL + stamp.nanosec)); - auto delay = now - t_msg; - - delays_.update(delay); - - if (now - last_print_ >= PRINT_INTERVAL) { - auto del = delays_.reset(); - - last_print_ = now; - - std::stringstream ss; - - ss << "{\"type\": \"topic_delay\", \"tag\": \"" << tag_ - << "\", \"del\": ["; - - for (duration & dt : *del) { - ss << dt.count() << ','; - } - - ss << "null]}" << std::endl; - - std::cout << ss.str(); - } - } - -private: - std::string tag_; - - time_point last_print_{time_point::min()}; - - Counter delays_; - - const duration PRINT_INTERVAL = 1s; -}; - -} // namespace util -} // namespace nebula \ No newline at end of file From 4f022cda35da7b27d38394b0a18c271e6164ab09 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 16:40:54 +0900 Subject: [PATCH 033/122] chore(velodyne_calibration_decoder): fix spelling --- nebula_common/src/velodyne/velodyne_calibration_decoder.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index 954da496b..8e3766b7b 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,5 +1,5 @@ -// cspell:ignore piyush, fout /** + * cspell:ignore piyush, piyushk, fout * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, * The University of Texas at Austin From bd08a1abe465a52c0aa4beb8b53242ef05bb735f Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:25:11 +0900 Subject: [PATCH 034/122] fix(hesai_decoder): initialize last_phase to prevent empty pointcloud published on startup --- .../nebula_decoders_hesai/decoders/hesai_decoder.hpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index 8f28856e8..daf9406cc 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -174,6 +174,10 @@ class HesaiDecoder : public HesaiScanDecoder /// @return Whether the scan has completed bool checkScanCompleted(uint32_t current_phase, uint32_t sync_phase) { + if (last_phase_ == -1) { + return false; + } + return angle_corrector_.hasScanned(current_phase, last_phase_, sync_phase); } @@ -220,6 +224,8 @@ class HesaiDecoder : public HesaiScanDecoder decode_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); output_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); + + last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet } int unpack(const std::vector & packet) override @@ -247,7 +253,7 @@ class HesaiDecoder : public HesaiScanDecoder sensor_configuration_->scan_phase * SensorT::packet_t::DEGREE_SUBDIVISIONS); if (scan_completed) { - std::swap(decode_pc_, output_pc_); + std::swap(decode_pc_, output_pc_); decode_pc_->clear(); has_scanned_ = true; output_scan_timestamp_ns_ = decode_scan_timestamp_ns_; From 68227d10bf708eccf7a0851298ba7ffe1a126950 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:25:36 +0900 Subject: [PATCH 035/122] fix(nebula_tests): make Hesai tests compile again --- nebula_tests/hesai/hesai_ros_decoder_test.cpp | 42 ++++++++----------- nebula_tests/hesai/hesai_ros_decoder_test.hpp | 30 +++++++------ .../hesai/hesai_ros_decoder_test_main.cpp | 2 + 3 files changed, 37 insertions(+), 37 deletions(-) diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.cpp b/nebula_tests/hesai/hesai_ros_decoder_test.cpp index a07a4dabd..00f33fa1a 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.cpp @@ -46,12 +46,11 @@ HesaiRosDecoderTest::HesaiRosDecoderTest( correction_cfg_ptr_ = std::make_shared(correction_configuration); wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); + correction_cfg_ptr_); } else { wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + calibration_cfg_ptr_); } RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); @@ -59,26 +58,12 @@ HesaiRosDecoderTest::HesaiRosDecoderTest( Status HesaiRosDecoderTest::InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiRosDecoderTest::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast( - calibration_configuration), //); - std::static_pointer_cast(correction_configuration)); + calibration_configuration); return driver_ptr_->GetStatus(); } @@ -291,7 +276,6 @@ void HesaiRosDecoderTest::ReadBag( storage_options.storage_id = params_.storage_id; converter_options.output_serialization_format = params_.format; //"cdr"; rclcpp::Serialization serialization; - nebula::drivers::NebulaPointCloudPtr pointcloud(new nebula::drivers::NebulaPointCloud); rosbag2_cpp::Reader bag_reader(std::make_unique()); bag_reader.open(storage_options, converter_options); @@ -310,12 +294,20 @@ void HesaiRosDecoderTest::ReadBag( "Found data in topic " << bag_message->topic_name << ": " << bag_message->time_stamp); auto extracted_msg_ptr = std::make_shared(extracted_msg); - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud(extracted_msg_ptr); - auto scan_timestamp = std::get<1>(pointcloud_ts); - pointcloud = std::get<0>(pointcloud_ts); - scan_callback(bag_message->time_stamp, scan_timestamp, pointcloud); - pointcloud.reset(new nebula::drivers::NebulaPointCloud); + for (auto & pkt : extracted_msg_ptr->packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); + auto pointcloud = std::get<0>(pointcloud_ts); + auto scan_timestamp = std::get<1>(pointcloud_ts); + + if (!pointcloud) { + continue; + } + + std::cerr << "PC size: " << pointcloud->size() << std::endl; + + scan_callback(bag_message->time_stamp, scan_timestamp, pointcloud); + } } } } diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.hpp b/nebula_tests/hesai/hesai_ros_decoder_test.hpp index a0477a366..43996b9ac 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.hpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.hpp @@ -48,9 +48,25 @@ struct HesaiRosDecoderTestParams double dual_return_distance_threshold = 0.1; }; +inline std::ostream & operator<<(std::ostream & os, nebula::ros::HesaiRosDecoderTestParams const & arg) { + return os << "sensor_model=" << arg.sensor_model << ", " + << "return_mode=" << arg.return_mode << ", " + << "calibration_file=" << arg.calibration_file << ", " + << "bag_path=" << arg.bag_path << ", " + << "correction_file=" << arg.correction_file << ", " + << "frame_id=" << arg.frame_id << ", " + << "scan_phase=" << arg.scan_phase << ", " + << "min_range=" << arg.min_range << ", " + << "max_range=" << arg.max_range << ", " + << "storage_id=" << arg.storage_id << ", " + << "format=" << arg.format << ", " + << "target_topic=" << arg.target_topic << ", " + << "dual_return_distance_threshold=" << arg.dual_return_distance_threshold << ", "; +} + /// @brief Testing decoder of pandar 40p (Keeps HesaiDriverRosWrapper structure as much as /// possible) -class HesaiRosDecoderTest final : public rclcpp::Node, NebulaDriverRosWrapperBase //, testing::Test +class HesaiRosDecoderTest final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; @@ -65,17 +81,7 @@ class HesaiRosDecoderTest final : public rclcpp::Node, NebulaDriverRosWrapperBas /// @return Resulting status Status InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Initializing ros wrapper for AT - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration); + std::shared_ptr calibration_configuration); /// @brief Get configurations (Magic numbers for Pandar40P is described, each function can be /// integrated if the ros parameter can be passed to Google Test) diff --git a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp index 96ff00c3c..d6574ccd4 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp @@ -142,6 +142,8 @@ TEST_P(DecoderTest, TestTimezone) auto gmt = timezone; hesai_driver_->ReadBag(scan_callback); + ASSERT_GT(decoded_timestamps.size(), 0U); + // Then, reset driver and timestamps vector for the next decode run TearDown(); SetUp(); From e3c297ac22fd15326556f1891e13043c057b4547 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:25:52 +0900 Subject: [PATCH 036/122] fix(nebula_examples): make Hesai examples compile again --- .../hesai_ros_offline_extract_bag_pcd.hpp | 9 +- .../hesai/hesai_ros_offline_extract_pcd.hpp | 14 +-- .../hesai_ros_offline_extract_bag_pcd.cpp | 91 +++++++++---------- .../hesai/hesai_ros_offline_extract_pcd.cpp | 41 ++++----- 4 files changed, 61 insertions(+), 94 deletions(-) diff --git a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp index a7681323c..5136cbb12 100644 --- a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp +++ b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp @@ -35,7 +35,7 @@ namespace nebula { namespace ros { -class HesaiRosOfflineExtractBag final : public rclcpp::Node, NebulaDriverRosWrapperBase +class HesaiRosOfflineExtractBag final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; @@ -46,12 +46,7 @@ class HesaiRosOfflineExtractBag final : public rclcpp::Node, NebulaDriverRosWrap Status InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration); + std::shared_ptr calibration_configuration); Status GetParameters( drivers::HesaiSensorConfiguration & sensor_configuration, diff --git a/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp b/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp index 711502e6a..8e26515bf 100644 --- a/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp +++ b/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp @@ -36,7 +36,7 @@ namespace nebula namespace ros { /// @brief Offline hesai driver usage example (Output PCD data) -class HesaiRosOfflineExtractSample final : public rclcpp::Node, NebulaDriverRosWrapperBase +class HesaiRosOfflineExtractSample final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; @@ -51,17 +51,7 @@ class HesaiRosOfflineExtractSample final : public rclcpp::Node, NebulaDriverRosW /// @return Resulting status Status InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Initializing ros wrapper for AT - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration); + std::shared_ptr calibration_configuration); /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration diff --git a/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp b/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp index 9c1266347..02cc84c72 100644 --- a/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp +++ b/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp @@ -56,12 +56,11 @@ HesaiRosOfflineExtractBag::HesaiRosOfflineExtractBag( correction_cfg_ptr_ = std::make_shared(correction_configuration); wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); + correction_cfg_ptr_); } else { wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + calibration_cfg_ptr_); } RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); @@ -69,26 +68,12 @@ HesaiRosOfflineExtractBag::HesaiRosOfflineExtractBag( Status HesaiRosOfflineExtractBag::InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiRosOfflineExtractBag::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast( - calibration_configuration), //); - std::static_pointer_cast(correction_configuration)); + calibration_configuration); return driver_ptr_->GetStatus(); } @@ -328,39 +313,45 @@ Status HesaiRosOfflineExtractBag::ReadBag() std::cout << "Found data in topic " << bag_message->topic_name << ": " << bag_message->time_stamp << std::endl; - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud( - std::make_shared(extracted_msg)); - auto pointcloud = std::get<0>(pointcloud_ts); - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); + for (auto & pkt : extracted_msg.packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); + auto pointcloud = std::get<0>(pointcloud_ts); - if (needs_open) { - const rosbag2_storage::StorageOptions storage_options_w( - {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); - const rosbag2_cpp::ConverterOptions converter_options_w( - {rmw_get_serialization_format(), rmw_get_serialization_format()}); - writer_ = std::make_unique(); - writer_->open(storage_options_w, converter_options_w); - writer_->create_topic( - {bag_message->topic_name, "pandar_msgs/msg/PandarScan", rmw_get_serialization_format(), - ""}); - needs_open = false; - } - writer_->write(bag_message); - cnt++; - if (skip_num < cnt) { - out_cnt++; - if (only_xyz) { - pcl::PointCloud cloud_xyz; - pcl::copyPointCloud(*pointcloud, cloud_xyz); - writer.writeBinary((o_dir / fn).string(), cloud_xyz); - } else { - writer.writeBinary((o_dir / fn).string(), *pointcloud); + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); + + if (needs_open) { + const rosbag2_storage::StorageOptions storage_options_w( + {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); + const rosbag2_cpp::ConverterOptions converter_options_w( + {rmw_get_serialization_format(), rmw_get_serialization_format()}); + writer_ = std::make_unique(); + writer_->open(storage_options_w, converter_options_w); + writer_->create_topic( + {bag_message->topic_name, "pandar_msgs/msg/PandarScan", rmw_get_serialization_format(), + ""}); + needs_open = false; + } + writer_->write(bag_message); + cnt++; + if (skip_num < cnt) { + out_cnt++; + if (only_xyz) { + pcl::PointCloud cloud_xyz; + pcl::copyPointCloud(*pointcloud, cloud_xyz); + writer.writeBinary((o_dir / fn).string(), cloud_xyz); + } else { + writer.writeBinary((o_dir / fn).string(), *pointcloud); + } + // writer.writeASCII((o_dir / fn).string(), *pointcloud); + } + if (out_num <= out_cnt) { + break; } - // writer.writeASCII((o_dir / fn).string(), *pointcloud); - } - if (out_num <= out_cnt) { - break; } } } diff --git a/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp b/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp index a57d9b96e..bd992ee19 100644 --- a/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp +++ b/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp @@ -56,12 +56,11 @@ HesaiRosOfflineExtractSample::HesaiRosOfflineExtractSample( correction_cfg_ptr_ = std::make_shared(correction_configuration); wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); + correction_cfg_ptr_); } else { wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + calibration_cfg_ptr_); } RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); @@ -69,26 +68,12 @@ HesaiRosOfflineExtractSample::HesaiRosOfflineExtractSample( Status HesaiRosOfflineExtractSample::InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiRosOfflineExtractSample::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast( - calibration_configuration), //); - std::static_pointer_cast(correction_configuration)); + calibration_configuration); return driver_ptr_->GetStatus(); } @@ -296,12 +281,18 @@ Status HesaiRosOfflineExtractSample::ReadBag() // nebula::drivers::NebulaPointCloudPtr pointcloud = // driver_ptr_->ConvertScanToPointcloud( // std::make_shared(extracted_msg)); - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud( - std::make_shared(extracted_msg)); - auto pointcloud = std::get<0>(pointcloud_ts); - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); - writer.writeBinary((o_dir / fn).string(), *pointcloud); + for (auto & pkt : extracted_msg.packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); + auto pointcloud = std::get<0>(pointcloud_ts); + + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); + writer.writeBinary((o_dir / fn).string(), *pointcloud); + } } } // close on scope exit From d9e6fa3ffa0e6deccd75c5b8c9ae7c48fbc28467 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:29:03 +0900 Subject: [PATCH 037/122] chore(velodyne_calibration_decoder): fix spelling once and for all --- .cspell.json | 7 +++++-- .../src/velodyne/velodyne_calibration_decoder.cpp | 3 --- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/.cspell.json b/.cspell.json index 7b1d6b2be..228d7f45e 100644 --- a/.cspell.json +++ b/.cspell.json @@ -45,6 +45,9 @@ "Vccint", "Vdat", "XT", - "XTM" + "XTM", + "piyushk", + "Piyush", + "fout" ] -} +} \ No newline at end of file diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index bfea254b7..0c03c3c9e 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,5 +1,4 @@ /** - * cspell:ignore piyush, piyushk, fout * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, * The University of Texas at Austin @@ -7,8 +6,6 @@ * License: Modified BSD License */ -// cspell:ignore piyush, piyushk, fout - #include #ifdef HAVE_NEW_YAMLCPP From 187ad04aebcc997ff0116843c1254e63eef029bb Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:30:25 +0900 Subject: [PATCH 038/122] chore(velodyne_calibration_decoder): fix spelling once and for all --- .cspell.json | 5 ++++- nebula_common/src/velodyne/velodyne_calibration_decoder.cpp | 1 - 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.cspell.json b/.cspell.json index 4f17f7ddd..75b26f454 100644 --- a/.cspell.json +++ b/.cspell.json @@ -44,6 +44,9 @@ "srvs", "manc", "ipaddr", - "ntoa" + "ntoa", + "piyushk", + "Piyush", + "fout" ] } diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index 8e3766b7b..0c03c3c9e 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,5 +1,4 @@ /** - * cspell:ignore piyush, piyushk, fout * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, * The University of Texas at Austin From 1bfba051faa44fbd6c155a949a8c215dc198c861 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 20:21:56 +0900 Subject: [PATCH 039/122] fix(nebula_examples): fix test failure (remove ament_lint_common) --- nebula_examples/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_examples/package.xml b/nebula_examples/package.xml index 6f1163279..f63847cca 100644 --- a/nebula_examples/package.xml +++ b/nebula_examples/package.xml @@ -28,8 +28,8 @@ velodyne_msgs yaml-cpp + ament_cmake_gtest ament_lint_auto - ament_lint_common ament_cmake From 4d3bf5b7f44f5dd3e9691b87e892ad027ae49450 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 22 Apr 2024 11:30:28 +0900 Subject: [PATCH 040/122] fix(hesai_hw_interface): add missing check for PTC error, make error type more readable --- .../hesai_hw_interface.hpp | 24 +++-- .../hesai_hw_interface.cpp | 93 ++++++++++--------- 2 files changed, 64 insertions(+), 53 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index c60107ab2..1b21ddae2 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -93,21 +93,28 @@ const uint16_t PANDAR128_E4X_EXTENDED_PACKET_SIZE = 1117; const uint16_t MTU_SIZE = 1500; // Time interval between Announce messages, in units of log seconds (default: 1) -const int PTP_LOG_ANNOUNCE_INTERVAL = 1; +const int PTP_LOG_ANNOUNCE_INTERVAL = 1; // Time interval between Sync messages, in units of log seconds (default: 1) -const int PTP_SYNC_INTERVAL = 1; +const int PTP_SYNC_INTERVAL = 1; // Minimum permitted mean time between Delay_Req messages, in units of log seconds (default: 0) const int PTP_LOG_MIN_DELAY_INTERVAL = 0; const int HESAI_LIDAR_GPS_CLOCK_SOURCE = 0; const int HESAI_LIDAR_PTP_CLOCK_SOURCE = 1; - /// @brief Hardware interface of hesai driver class HesaiHwInterface : NebulaHwInterfaceBase { private: - typedef nebula::util::expected, uint32_t> ptc_cmd_result_t; + struct ptc_error_t + { + uint8_t error_flags = 0; + uint8_t ptc_error_code = 0; + + bool ok() { return !error_flags && !ptc_error_code; } + }; + + typedef nebula::util::expected, ptc_error_t> ptc_cmd_result_t; std::unique_ptr<::drivers::common::IoContext> cloud_io_context_; std::shared_ptr m_owned_ctx; @@ -160,18 +167,17 @@ class HesaiHwInterface : NebulaHwInterfaceBase void PrintDebug(const std::vector & bytes); /// @brief Convert an error code to a human-readable string - /// @param error_code The error code (lowest byte is Hesai PTC error code, higher bytes nebula flags) - /// such as TCP_ERROR_UNRELATED_RESPONSE etc. + /// @param error_code The error code, containing the sensor's error code (if any), along with + /// flags such as TCP_ERROR_UNRELATED_RESPONSE etc. /// @return A string description of all errors in this code - std::string PrettyPrintPTCError(uint32_t error_code); + std::string PrettyPrintPTCError(ptc_error_t error_code); /// @brief Send a PTC request with an optional payload, and return the full response payload. /// Blocking. /// @param command_id PTC command number. /// @param payload Payload bytes of the PTC command. Not including the 8-byte PTC header. /// @return The returned payload, if successful, or nullptr. - ptc_cmd_result_t SendReceive( - const uint8_t command_id, const std::vector & payload = {}); + ptc_cmd_result_t SendReceive(const uint8_t command_id, const std::vector & payload = {}); public: /// @brief Constructor diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 3d068173f..fccb2a622 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -69,7 +69,7 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( auto response_complete = std::make_shared(false); // Low byte is for PTC error code, the rest is nebula-specific - auto error_code = std::make_shared(0); + auto error_code = std::make_shared(); std::stringstream ss; ss << "0x" << std::setfill('0') << std::setw(2) << std::hex << static_cast(command_id) << " (" << len << ") "; @@ -89,14 +89,15 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( tcp_driver_->asyncSendReceiveHeaderPayload( send_buf, [this, log_tag, command_id, response_complete, error_code](const std::vector & header_bytes) { + error_code->ptc_error_code = header_bytes[3]; + size_t payload_len = (header_bytes[4] << 24) | (header_bytes[5] << 16) | (header_bytes[6] << 8) | header_bytes[7]; PrintDebug(log_tag + "Received header (expecting " + std::to_string(payload_len) + "B payload)"); // If command_id in the response does not match, we got a response for another command (or rubbish), probably as a // result of too many simultaneous TCP connections to the sensor (e.g. from GUI, Web UI, another nebula instance, etc.) if (header_bytes[2] != command_id) { - *error_code = (TCP_ERROR_UNRELATED_RESPONSE << 8); + error_code->error_flags |= TCP_ERROR_UNRELATED_RESPONSE; } - *error_code |= header_bytes[3]; if (payload_len == 0) { *response_complete = true; } @@ -107,7 +108,7 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( // Header had payload length 0 (thus, header callback processed request successfully already), // but we still received a payload: invalid state if (*response_complete == true) { - *error_code |= (TCP_ERROR_UNEXPECTED_PAYLOAD << 8); + error_code->error_flags |= TCP_ERROR_UNEXPECTED_PAYLOAD; return; } @@ -123,13 +124,17 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( this->IOContextRun(); if (!tm.try_lock_for(std::chrono::seconds(1))) { PrintError(log_tag + "Request did not finish within 1s"); - *error_code |= (TCP_ERROR_TIMEOUT << 8); + error_code->error_flags |= TCP_ERROR_TIMEOUT; return *error_code; } if (!response_complete) { PrintError(log_tag + "Did not receive response"); - *error_code |= (TCP_ERROR_INCOMPLETE_RESPONSE << 8); + error_code->error_flags |= TCP_ERROR_INCOMPLETE_RESPONSE; + return *error_code; + } + + if (!error_code->ok()) { return *error_code; } @@ -361,13 +366,13 @@ boost::property_tree::ptree HesaiHwInterface::ParseJson(const std::string & str) std::vector HesaiHwInterface::GetLidarCalibrationBytes() { auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_CALIBRATION); - return response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + return response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); } std::string HesaiHwInterface::GetLidarCalibrationString() { auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_CALIBRATION); - auto calib_data = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto calib_data = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); std::string calib_string(calib_data.begin(), calib_data.end()); return calib_string; } @@ -375,7 +380,7 @@ std::string HesaiHwInterface::GetLidarCalibrationString() HesaiPtpDiagStatus HesaiHwInterface::GetPtpDiagStatus() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_STATUS}); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() != sizeof(HesaiPtpDiagStatus)) { throw std::runtime_error("Unexpected payload size"); @@ -394,7 +399,7 @@ HesaiPtpDiagStatus HesaiHwInterface::GetPtpDiagStatus() HesaiPtpDiagPort HesaiHwInterface::GetPtpDiagPort() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_PORT_DATA_SET}); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() != sizeof(HesaiPtpDiagPort)) { throw std::runtime_error("Unexpected payload size"); @@ -412,7 +417,7 @@ HesaiPtpDiagPort HesaiHwInterface::GetPtpDiagPort() HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_TIME_STATUS_NP}); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() != sizeof(HesaiPtpDiagTime)) { throw std::runtime_error("Unexpected payload size"); @@ -431,7 +436,7 @@ HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() != sizeof(HesaiPtpDiagGrandmaster)) { throw std::runtime_error("Unexpected payload size"); @@ -450,7 +455,7 @@ HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() HesaiInventory HesaiHwInterface::GetInventory() { auto response_or_err = SendReceive(PTC_COMMAND_GET_INVENTORY_INFO); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() < sizeof(HesaiInventory)) { throw std::runtime_error("Unexpected payload size"); @@ -467,7 +472,7 @@ HesaiInventory HesaiHwInterface::GetInventory() HesaiConfig HesaiHwInterface::GetConfig() { auto response_or_err = SendReceive(PTC_COMMAND_GET_CONFIG_INFO); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() != sizeof(HesaiConfig)) { throw std::runtime_error("Unexpected payload size"); @@ -483,7 +488,7 @@ HesaiConfig HesaiHwInterface::GetConfig() HesaiLidarStatus HesaiHwInterface::GetLidarStatus() { auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_STATUS); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() != sizeof(HesaiLidarStatus)) { throw std::runtime_error("Unexpected payload size"); @@ -502,7 +507,7 @@ Status HesaiHwInterface::SetSpinRate(uint16_t rpm) request_payload.emplace_back(rpm & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_SPIN_RATE, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -514,7 +519,7 @@ Status HesaiHwInterface::SetSyncAngle(int sync_angle, int angle) request_payload.emplace_back(angle & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_SYNC_ANGLE, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -524,7 +529,7 @@ Status HesaiHwInterface::SetTriggerMethod(int trigger_method) request_payload.emplace_back(trigger_method & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_TRIGGER_METHOD, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -534,7 +539,7 @@ Status HesaiHwInterface::SetStandbyMode(int standby_mode) request_payload.emplace_back(standby_mode & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_STANDBY_MODE, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -544,7 +549,7 @@ Status HesaiHwInterface::SetReturnMode(int return_mode) request_payload.emplace_back(return_mode & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_RETURN_MODE, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -562,7 +567,7 @@ Status HesaiHwInterface::SetDestinationIp( request_payload.emplace_back(gps_port & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_DESTINATION_IP, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -588,7 +593,7 @@ Status HesaiHwInterface::SetControlPort( request_payload.emplace_back(vlan_id & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_CONTROL_PORT, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -602,7 +607,7 @@ Status HesaiHwInterface::SetLidarRange(int method, std::vector da request_payload.insert(request_payload.end(), data.begin(), data.end()); auto response_or_err = SendReceive(PTC_COMMAND_SET_LIDAR_RANGE, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -620,14 +625,14 @@ Status HesaiHwInterface::SetLidarRange(int start, int end) request_payload.emplace_back(end & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_LIDAR_RANGE, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } HesaiLidarRangeAll HesaiHwInterface::GetLidarRange() { auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_RANGE); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() < 1) { throw std::runtime_error("Response payload too short"); @@ -661,7 +666,7 @@ Status HesaiHwInterface::SetClockSource(int clock_source) request_payload.emplace_back(clock_source & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_CLOCK_SOURCE, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -695,14 +700,14 @@ Status HesaiHwInterface::SetPtpConfig( } auto response_or_err = SendReceive(PTC_COMMAND_SET_PTP_CONFIG, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } HesaiPtpConfig HesaiHwInterface::GetPtpConfig() { auto response_or_err = SendReceive(PTC_COMMAND_GET_PTP_CONFIG); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() < sizeof(HesaiPtpConfig)) { throw std::runtime_error("Unexpected payload size"); @@ -726,7 +731,7 @@ HesaiPtpConfig HesaiHwInterface::GetPtpConfig() Status HesaiHwInterface::SendReset() { auto response_or_err = SendReceive(PTC_COMMAND_RESET); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } @@ -736,14 +741,14 @@ Status HesaiHwInterface::SetRotDir(int mode) request_payload.emplace_back(mode & 0xff); auto response_or_err = SendReceive(PTC_COMMAND_SET_ROTATE_DIRECTION, request_payload); - response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); return Status::OK; } HesaiLidarMonitor HesaiHwInterface::GetLidarMonitor() { auto response_or_err = SendReceive(PTC_COMMAND_LIDAR_MONITOR); - auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or(0))); + auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() != sizeof(HesaiLidarMonitor)) { throw std::runtime_error("Unexpected payload size"); @@ -1353,20 +1358,20 @@ void HesaiHwInterface::PrintDebug(const std::vector & bytes) PrintDebug(ss.str()); } -std::string HesaiHwInterface::PrettyPrintPTCError(uint32_t error_code) { - if (error_code == 0) { +std::string HesaiHwInterface::PrettyPrintPTCError(ptc_error_t error_code) { + if (error_code.ok()) { return "No error"; } - uint8_t hesai_error = error_code & 0xFF; - uint32_t nebula_error_flags = (error_code >> 8); + auto ptc_error = error_code.ptc_error_code; + auto error_flags = error_code.error_flags; std::stringstream ss; - if (hesai_error) { - ss << "Sensor error: 0x" << std::setfill('0') << std::setw(2) << std::hex << static_cast(hesai_error) << ' '; + if (ptc_error) { + ss << "Sensor error: 0x" << std::setfill('0') << std::setw(2) << std::hex << static_cast(ptc_error) << ' '; } - switch(hesai_error) { + switch(ptc_error) { case PTC_ERROR_CODE_NO_ERROR: break; case PTC_ERROR_CODE_INVALID_INPUT_PARAM: @@ -1395,27 +1400,27 @@ std::string HesaiHwInterface::PrettyPrintPTCError(uint32_t error_code) { break; } - if (!nebula_error_flags) { + if (!error_flags) { return ss.str(); } - if (hesai_error) { + if (ptc_error) { ss << ", "; } ss << "Communication error: "; std::vector nebula_errors; - if (nebula_error_flags & TCP_ERROR_INCOMPLETE_RESPONSE) { + if (error_flags & TCP_ERROR_INCOMPLETE_RESPONSE) { nebula_errors.push_back("Incomplete response payload"); } - if (nebula_error_flags & TCP_ERROR_TIMEOUT) { + if (error_flags & TCP_ERROR_TIMEOUT) { nebula_errors.push_back("Request timeout"); } - if (nebula_error_flags & TCP_ERROR_UNEXPECTED_PAYLOAD) { + if (error_flags & TCP_ERROR_UNEXPECTED_PAYLOAD) { nebula_errors.push_back("Received payload but expected payload length 0"); } - if (nebula_error_flags & TCP_ERROR_UNRELATED_RESPONSE) { + if (error_flags & TCP_ERROR_UNRELATED_RESPONSE) { nebula_errors.push_back("Received unrelated response"); } From 5bba66d3d6cffed13bbf515bb759f23dd049f6a8 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 23 Apr 2024 15:35:45 +0900 Subject: [PATCH 041/122] refactor(hesai): re-introduce parameter update mechanism --- .../include/nebula_common/nebula_common.hpp | 6 +- .../decoders/angle_corrector.hpp | 8 +- .../angle_corrector_calibration_based.hpp | 8 +- .../angle_corrector_correction_based.hpp | 4 +- .../decoders/hesai_decoder.hpp | 18 +- .../nebula_decoders_hesai/hesai_driver.hpp | 8 +- .../nebula_decoders_hesai/hesai_driver.cpp | 14 +- .../hesai_hw_interface.hpp | 18 +- .../hesai_hw_interface.cpp | 16 +- nebula_ros/CMakeLists.txt | 1 + .../common/parameter_descriptors.hpp | 41 ++ .../nebula_ros/hesai/decoder_wrapper.hpp | 41 +- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 39 +- .../nebula_ros/hesai/hw_interface_wrapper.hpp | 9 +- .../nebula_ros/hesai/hw_monitor_wrapper.hpp | 13 +- .../src/common/parameter_descriptors.cpp | 29 ++ nebula_ros/src/hesai/decoder_wrapper.cpp | 118 +++-- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 428 ++++++------------ nebula_ros/src/hesai/hw_interface_wrapper.cpp | 46 +- nebula_ros/src/hesai/hw_monitor_wrapper.cpp | 17 +- 20 files changed, 430 insertions(+), 452 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp create mode 100644 nebula_ros/src/common/parameter_descriptors.cpp diff --git a/nebula_common/include/nebula_common/nebula_common.hpp b/nebula_common/include/nebula_common/nebula_common.hpp index 9d04a267a..cf1eb0841 100644 --- a/nebula_common/include/nebula_common/nebula_common.hpp +++ b/nebula_common/include/nebula_common/nebula_common.hpp @@ -346,7 +346,7 @@ enum class PtpProfile { IEEE_1588v2 = 0, IEEE_802_1AS, IEEE_802_1AS_AUTO, - PROFILE_UNKNOWN + UNKNOWN_PROFILE }; enum class PtpTransportType { @@ -624,7 +624,7 @@ inline PtpProfile PtpProfileFromString(const std::string & ptp_profile) if (tmp_str == "802.1as") return PtpProfile::IEEE_802_1AS; if (tmp_str == "automotive") return PtpProfile::IEEE_802_1AS_AUTO; - return PtpProfile::PROFILE_UNKNOWN; + return PtpProfile::UNKNOWN_PROFILE; } /// @brief Convert PtpProfile enum to string (Overloading the << operator) @@ -643,7 +643,7 @@ inline std::ostream & operator<<(std::ostream & os, nebula::drivers::PtpProfile case PtpProfile::IEEE_802_1AS_AUTO: os << "IEEE_802.1AS Automotive"; break; - case PtpProfile::PROFILE_UNKNOWN: + case PtpProfile::UNKNOWN_PROFILE: os << "UNKNOWN"; break; } diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp index 42fd0a008..121913c34 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp @@ -26,13 +26,13 @@ struct CorrectedAngleData class AngleCorrector { protected: - const std::shared_ptr sensor_calibration_; - const std::shared_ptr sensor_correction_; + const std::shared_ptr sensor_calibration_; + const std::shared_ptr sensor_correction_; public: AngleCorrector( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) + const std::shared_ptr & sensor_calibration, + const std::shared_ptr & sensor_correction) : sensor_calibration_(sensor_calibration), sensor_correction_(sensor_correction) { } diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp index 3e0c999b0..bee570afc 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp @@ -27,8 +27,8 @@ class AngleCorrectorCalibrationBased : public AngleCorrector public: AngleCorrectorCalibrationBased( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) + const std::shared_ptr & sensor_calibration, + const std::shared_ptr & sensor_correction) : AngleCorrector(sensor_calibration, sensor_correction) { if (sensor_calibration == nullptr) { @@ -37,8 +37,8 @@ class AngleCorrectorCalibrationBased : public AngleCorrector } for (size_t channel_id = 0; channel_id < ChannelN; ++channel_id) { - float elevation_angle_deg = sensor_calibration->elev_angle_map[channel_id]; - float azimuth_offset_deg = sensor_calibration->azimuth_offset_map[channel_id]; + float elevation_angle_deg = sensor_calibration->elev_angle_map.at(channel_id); + float azimuth_offset_deg = sensor_calibration->azimuth_offset_map.at(channel_id); elevation_angle_rad_[channel_id] = deg2rad(elevation_angle_deg); azimuth_offset_rad_[channel_id] = deg2rad(azimuth_offset_deg); diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp index be60078de..d23dfc1f2 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp @@ -43,8 +43,8 @@ class AngleCorrectorCorrectionBased : public AngleCorrector public: AngleCorrectorCorrectionBased( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) + const std::shared_ptr & sensor_calibration, + const std::shared_ptr & sensor_correction) : AngleCorrector(sensor_calibration, sensor_correction), logger_(rclcpp::get_logger("AngleCorrectorCorrectionBased")) { diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index daf9406cc..e8a9afc34 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -18,7 +18,7 @@ class HesaiDecoder : public HesaiScanDecoder { protected: /// @brief Configuration for this decoder - const std::shared_ptr sensor_configuration_; + const std::shared_ptr sensor_configuration_; /// @brief The sensor definition, used for return mode and time offset handling SensorT sensor_{}; @@ -34,13 +34,13 @@ class HesaiDecoder : public HesaiScanDecoder /// @brief The last decoded packet typename SensorT::packet_t packet_; /// @brief The last azimuth processed - int last_phase_; + int last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet /// @brief The timestamp of the last completed scan in nanoseconds - uint64_t output_scan_timestamp_ns_; + uint64_t output_scan_timestamp_ns_ = 0; /// @brief The timestamp of the scan currently in progress - uint64_t decode_scan_timestamp_ns_; + uint64_t decode_scan_timestamp_ns_ = 0; /// @brief Whether a full scan has been processed - bool has_scanned_; + bool has_scanned_ = false; rclcpp::Logger logger_; @@ -209,9 +209,9 @@ class HesaiDecoder : public HesaiScanDecoder /// @param correction_configuration Correction for this decoder (can be nullptr if /// calibration_configuration is set) explicit HesaiDecoder( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration, + const std::shared_ptr & correction_configuration) : sensor_configuration_(sensor_configuration), angle_corrector_(calibration_configuration, correction_configuration), logger_(rclcpp::get_logger("HesaiDecoder")) @@ -224,8 +224,6 @@ class HesaiDecoder : public HesaiScanDecoder decode_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); output_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); - - last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet } int unpack(const std::vector & packet) override diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index 5ee9892d4..87798dbd1 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -22,7 +22,7 @@ namespace nebula namespace drivers { /// @brief Hesai driver -class HesaiDriver : NebulaDriverBase +class HesaiDriver { private: /// @brief Current driver status @@ -37,8 +37,8 @@ class HesaiDriver : NebulaDriverBase /// @param calibration_configuration CalibrationConfiguration for this driver (either HesaiCalibrationConfiguration /// for sensors other than AT128 or HesaiCorrection for AT128) explicit HesaiDriver( - const std::shared_ptr& sensor_configuration, - const std::shared_ptr& calibration_configuration = nullptr); + const std::shared_ptr& sensor_configuration, + const std::shared_ptr& calibration_configuration = nullptr); /// @brief Get current status of this driver /// @return Current status @@ -47,7 +47,7 @@ class HesaiDriver : NebulaDriverBase /// @brief Setting CalibrationConfiguration (not used) /// @param calibration_configuration /// @return Resulting status - Status SetCalibrationConfiguration(const CalibrationConfigurationBase& calibration_configuration) override; + Status SetCalibrationConfiguration(const HesaiCalibrationConfigurationBase& calibration_configuration); /// @brief Convert PandarScan message to point cloud /// @param pandar_scan Message diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index 27624a469..beafd8e71 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -17,22 +17,22 @@ namespace nebula { namespace drivers { -HesaiDriver::HesaiDriver(const std::shared_ptr& sensor_configuration, - const std::shared_ptr& calibration_configuration) +HesaiDriver::HesaiDriver(const std::shared_ptr& sensor_configuration, + const std::shared_ptr& calibration_configuration) { // initialize proper parser from cloud config's model and echo mode driver_status_ = nebula::Status::OK; - std::shared_ptr calibration = nullptr; - std::shared_ptr correction = nullptr; + std::shared_ptr calibration = nullptr; + std::shared_ptr correction = nullptr; if (sensor_configuration->sensor_model == SensorModel::HESAI_PANDARAT128) { - correction = std::static_pointer_cast(calibration_configuration); + correction = std::static_pointer_cast(calibration_configuration); } else { - calibration = std::static_pointer_cast(calibration_configuration); + calibration = std::static_pointer_cast(calibration_configuration); } switch (sensor_configuration->sensor_model) @@ -104,7 +104,7 @@ std::tuple HesaiDriver::ParseCloudPacket( } Status HesaiDriver::SetCalibrationConfiguration( - const CalibrationConfigurationBase & calibration_configuration) + const HesaiCalibrationConfigurationBase & calibration_configuration) { throw std::runtime_error( "SetCalibrationConfiguration. Not yet implemented (" + diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index b0a443495..d3472afbe 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -103,7 +103,7 @@ const int HESAI_LIDAR_GPS_CLOCK_SOURCE = 0; const int HESAI_LIDAR_PTP_CLOCK_SOURCE = 1; /// @brief Hardware interface of hesai driver -class HesaiHwInterface : public NebulaHwInterfaceBase +class HesaiHwInterface { private: struct ptc_error_t @@ -120,10 +120,12 @@ class HesaiHwInterface : public NebulaHwInterfaceBase std::shared_ptr m_owned_ctx; std::unique_ptr<::drivers::udp_driver::UdpDriver> cloud_udp_driver_; std::shared_ptr<::drivers::tcp_driver::TcpDriver> tcp_driver_; - std::shared_ptr sensor_configuration_; + std::shared_ptr sensor_configuration_; std::function & buffer)> cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ + std::mutex mtx_inflight_tcp_request_; + int prev_phase_{}; bool is_solid_state = false; @@ -195,14 +197,14 @@ class HesaiHwInterface : public NebulaHwInterfaceBase void ReceiveSensorPacketCallback(std::vector & buffer); /// @brief Starting the interface that handles UDP streams /// @return Resulting status - Status SensorInterfaceStart() final; + Status SensorInterfaceStart(); /// @brief Function for stopping the interface that handles UDP streams /// @return Resulting status - Status SensorInterfaceStop() final; + Status SensorInterfaceStop(); /// @brief Printing sensor configuration /// @param sensor_configuration SensorConfiguration for this interface /// @return Resulting status - Status GetSensorConfiguration(SensorConfigurationBase & sensor_configuration) final; + Status GetSensorConfiguration(const SensorConfigurationBase & sensor_configuration); /// @brief Printing calibration configuration /// @param calibration_configuration CalibrationConfiguration for the checking /// @return Resulting status @@ -211,7 +213,7 @@ class HesaiHwInterface : public NebulaHwInterfaceBase /// @param sensor_configuration SensorConfiguration for this interface /// @return Resulting status Status SetSensorConfiguration( - std::shared_ptr sensor_configuration) final; + std::shared_ptr sensor_configuration); /// @brief Registering callback for PandarScan /// @param scan_callback Callback function /// @return Resulting status @@ -382,13 +384,13 @@ class HesaiHwInterface : public NebulaHwInterfaceBase /// @param hesai_config Current HesaiConfig /// @return Resulting status HesaiStatus CheckAndSetConfig( - std::shared_ptr sensor_configuration, HesaiConfig hesai_config); + std::shared_ptr sensor_configuration, HesaiConfig hesai_config); /// @brief Checking the current settings and changing the difference point /// @param sensor_configuration Current SensorConfiguration /// @param hesai_lidar_range_all Current HesaiLidarRangeAll /// @return Resulting status HesaiStatus CheckAndSetConfig( - std::shared_ptr sensor_configuration, + std::shared_ptr sensor_configuration, HesaiLidarRangeAll hesai_lidar_range_all); /// @brief Checking the current settings and changing the difference point /// @return Resulting status diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 39279aed8..b6d7b68e2 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -28,6 +28,8 @@ HesaiHwInterface::~HesaiHwInterface() HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( const uint8_t command_id, const std::vector & payload) { + std::lock_guard lock(mtx_inflight_tcp_request_); + uint32_t len = payload.size(); std::vector send_buf; @@ -121,10 +123,10 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( } Status HesaiHwInterface::SetSensorConfiguration( - std::shared_ptr sensor_configuration) + std::shared_ptr sensor_configuration) { sensor_configuration_ = - std::static_pointer_cast(sensor_configuration); + std::static_pointer_cast(sensor_configuration); return Status::OK; } @@ -176,7 +178,7 @@ Status HesaiHwInterface::SensorInterfaceStop() return Status::ERROR_1; } -Status HesaiHwInterface::GetSensorConfiguration(SensorConfigurationBase & sensor_configuration) +Status HesaiHwInterface::GetSensorConfiguration(const SensorConfigurationBase & sensor_configuration) { std::stringstream ss; ss << sensor_configuration; @@ -809,7 +811,7 @@ HesaiStatus HesaiHwInterface::GetLidarMonitorAsyncHttp( } HesaiStatus HesaiHwInterface::CheckAndSetConfig( - std::shared_ptr sensor_configuration, HesaiConfig hesai_config) + std::shared_ptr sensor_configuration, HesaiConfig hesai_config) { using namespace std::chrono_literals; #ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE @@ -968,7 +970,7 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( } HesaiStatus HesaiHwInterface::CheckAndSetConfig( - std::shared_ptr sensor_configuration, + std::shared_ptr sensor_configuration, HesaiLidarRangeAll hesai_lidar_range_all) { #ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE @@ -1032,7 +1034,7 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig() ss << result; PrintInfo(ss.str()); CheckAndSetConfig( - std::static_pointer_cast(sensor_configuration_), result); + std::static_pointer_cast(sensor_configuration_), result); }); t.join(); @@ -1042,7 +1044,7 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig() ss << result; PrintInfo(ss.str()); CheckAndSetConfig( - std::static_pointer_cast(sensor_configuration_), result); + std::static_pointer_cast(sensor_configuration_), result); }); t2.join(); #ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index b11339765..324d38074 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -40,6 +40,7 @@ ament_auto_add_library(hesai_ros_wrapper SHARED src/hesai/decoder_wrapper.cpp src/hesai/hw_interface_wrapper.cpp src/hesai/hw_monitor_wrapper.cpp + src/common/parameter_descriptors.cpp ) rclcpp_components_register_node(hesai_ros_wrapper diff --git a/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp new file mode 100644 index 000000000..b54d8ad63 --- /dev/null +++ b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp @@ -0,0 +1,41 @@ +#pragma once + +#include +#include +#include + +namespace nebula +{ +namespace ros +{ + +rcl_interfaces::msg::ParameterDescriptor param_read_write(); + +rcl_interfaces::msg::ParameterDescriptor param_read_only(); + +rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range(double start, double stop, + double step); + +rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int start, int stop, int step); + +/// @brief Get a parameter's value from a list of parameters, if that parameter is in the list. +/// @tparam T The parameter's expected value type +/// @param p A vector of parameters +/// @param name Target parameter name +/// @param value (out) Parameter value. Set if parameter is found, left untouched otherwise. +/// @return Whether the target name existed +template +bool get_param(const std::vector& p, const std::string& name, T& value) +{ + auto it = std::find_if(p.cbegin(), p.cend(), + [&name](const rclcpp::Parameter & parameter) { return parameter.get_name() == name; }); + if (it != p.cend()) + { + value = it->template get_value(); + return true; + } + return false; +} + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp index 262c16839..3b2af26d4 100644 --- a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp @@ -2,17 +2,19 @@ #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" +#include "nebula_ros/common/parameter_descriptors.hpp" -#include #include +#include #include #include "nebula_msgs/msg/nebula_packet.hpp" #include "pandar_msgs/msg/pandar_packet.hpp" #include "pandar_msgs/msg/pandar_scan.hpp" -#include #include +#include +#include namespace nebula { @@ -20,22 +22,38 @@ namespace ros { class HesaiDecoderWrapper { + using get_calibration_result_t = + nebula::util::expected, nebula::Status>; + public: HesaiDecoderWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, - std::shared_ptr& config); - - nebula::util::expected, nebula::Status> - GetCalibrationData(); + std::shared_ptr& config); void ProcessCloudPacket(std::unique_ptr packet_msg); - void PublishCloud(std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr& publisher); + void OnConfigChange(const std::shared_ptr& new_config); + + void + OnCalibrationChange(const std::shared_ptr& new_calibration); + + rcl_interfaces::msg::SetParametersResult OnParameterChange(const std::vector& p); nebula::Status Status(); private: + /// @brief Load calibration data from the best available source: + /// 1. If sensor connected, download and save from sensor + /// 2. If downloaded file available, load that file + /// 3. Load the file given by `calibration_file_path` + /// @param calibration_file_path The file to use if no better option is available + /// @param ignore_others If true, skip straight so step 3 above, ignoring better calibration options + /// @return The calibration data if successful, or an error code if not + get_calibration_result_t GetCalibrationData(const std::string& calibration_file_path, bool ignore_others = false); + + void PublishCloud(std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr& publisher); + /// @brief Convert seconds to chrono::nanoseconds /// @param seconds /// @return chrono::nanoseconds @@ -48,12 +66,13 @@ class HesaiDecoderWrapper rclcpp::Logger logger_; const std::shared_ptr hw_interface_; - std::shared_ptr sensor_cfg_; + std::shared_ptr sensor_cfg_; std::string calibration_file_path_{}; - std::shared_ptr calibration_cfg_ptr_{}; + std::shared_ptr calibration_cfg_ptr_{}; - std::shared_ptr driver_ptr_; + std::shared_ptr driver_ptr_{}; + std::mutex mtx_driver_ptr_; rclcpp::Publisher::SharedPtr packets_pub_{}; pandar_msgs::msg::PandarScan::UniquePtr current_scan_msg_{}; diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index e037bce40..42d8bdc36 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -1,6 +1,7 @@ #pragma once #include "boost_tcp_driver/tcp_driver.hpp" + #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" @@ -9,6 +10,7 @@ #include "nebula_ros/hesai/hw_interface_wrapper.hpp" #include "nebula_ros/hesai/hw_monitor_wrapper.hpp" #include "nebula_ros/hesai/mt_queue.hpp" +#include "nebula_ros/common/parameter_descriptors.hpp" #include #include @@ -31,31 +33,12 @@ namespace nebula namespace ros { -/// @brief Get parameter from rclcpp::Parameter -/// @tparam T -/// @param p Parameter from rclcpp parameter callback -/// @param name Target parameter name -/// @param value Corresponding value -/// @return Whether the target name existed -template -bool get_param(const std::vector& p, const std::string& name, T& value) -{ - auto it = std::find_if(p.cbegin(), p.cend(), - [&name](const rclcpp::Parameter& parameter) { return parameter.get_name() == name; }); - if (it != p.cend()) - { - value = it->template get_value(); - return true; - } - return false; -} - /// @brief Ros wrapper of hesai driver class HesaiRosWrapper final : public rclcpp::Node { public: explicit HesaiRosWrapper(const rclcpp::NodeOptions& options); - ~HesaiRosWrapper() noexcept; + ~HesaiRosWrapper() noexcept {}; /// @brief Get current status of this driver /// @return Current status @@ -72,23 +55,16 @@ class HesaiRosWrapper final : public rclcpp::Node Status DeclareAndGetSensorConfigParams(); - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @return Resulting status - Status DeclareAndGetWrapperParams(); - /// @brief rclcpp parameter callback /// @param parameters Received parameters /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector& parameters); + rcl_interfaces::msg::SetParametersResult OnParameterChange(const std::vector& p); - /// @brief Updating rclcpp parameter - /// @return SetParametersResult - std::vector updateParameters(); + Status ValidateAndSetConfig(std::shared_ptr& new_config); Status wrapper_status_; - std::shared_ptr sensor_cfg_ptr_{}; + std::shared_ptr sensor_cfg_ptr_{}; /// @brief Stores received packets that have not been processed yet by the decoder thread mt_queue> packet_queue_; @@ -104,7 +80,8 @@ class HesaiRosWrapper final : public rclcpp::Node std::optional decoder_wrapper_; std::mutex mtx_config_; - OnSetParametersCallbackHandle::SharedPtr set_param_res_{}; + + OnSetParametersCallbackHandle::SharedPtr parameter_event_cb_; }; } // namespace ros diff --git a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp index 30f069c99..cbf78d130 100644 --- a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp @@ -1,8 +1,10 @@ #pragma once +#include "nebula_ros/common/parameter_descriptors.hpp" + #include -#include +#include #include #include @@ -15,9 +17,9 @@ class HesaiHwInterfaceWrapper { public: HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, - std::shared_ptr& config); + std::shared_ptr& config); - nebula::Status InitializeHwInterface(); + void OnConfigChange(const std::shared_ptr & new_config); nebula::Status Status(); @@ -27,6 +29,7 @@ class HesaiHwInterfaceWrapper std::shared_ptr hw_interface_; rclcpp::Logger logger_; nebula::Status status_; + bool setup_sensor_; }; } // namespace ros } // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp index 5ddfc9e79..5209f64a2 100644 --- a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp @@ -1,7 +1,10 @@ #pragma once +#include "nebula_ros/common/parameter_descriptors.hpp" + #include #include + #include #include #include @@ -22,10 +25,13 @@ class HesaiHwMonitorWrapper public: HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, - std::shared_ptr& config); + std::shared_ptr& config); - nebula::Status InitializeHwMonitor(); + void OnConfigChange(const std::shared_ptr & /* new_config */) {} + + nebula::Status Status(); +private: void InitializeHesaiDiagnostics(); std::string GetPtreeValue(boost::property_tree::ptree* pt, const std::string& key); @@ -50,9 +56,6 @@ class HesaiHwMonitorWrapper void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); - nebula::Status Status(); - -private: rclcpp::Logger logger_; diagnostic_updater::Updater diagnostics_updater_; nebula::Status status_; diff --git a/nebula_ros/src/common/parameter_descriptors.cpp b/nebula_ros/src/common/parameter_descriptors.cpp new file mode 100644 index 000000000..ffd0fff37 --- /dev/null +++ b/nebula_ros/src/common/parameter_descriptors.cpp @@ -0,0 +1,29 @@ +#include "nebula_ros/common/parameter_descriptors.hpp" + +namespace nebula +{ +namespace ros +{ + +rcl_interfaces::msg::ParameterDescriptor param_read_write() +{ + return rcl_interfaces::msg::ParameterDescriptor{}; +}; + +rcl_interfaces::msg::ParameterDescriptor param_read_only() +{ + return rcl_interfaces::msg::ParameterDescriptor{}.set__read_only(true); +} + +rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range(double start, double stop, double step) +{ + return { rcl_interfaces::msg::FloatingPointRange().set__from_value(start).set__to_value(stop).set__step(step) }; +} + +rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int start, int stop, int step) +{ + return { rcl_interfaces::msg::IntegerRange().set__from_value(start).set__to_value(stop).set__step(step) }; +} + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp index 1ae6d2837..1b7c10582 100644 --- a/nebula_ros/src/hesai/decoder_wrapper.cpp +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -7,7 +7,7 @@ namespace ros HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, - std::shared_ptr& config) + std::shared_ptr& config) : status_(nebula::Status::NOT_INITIALIZED) , logger_(parent_node->get_logger().get_child("HesaiDecoder")) , hw_interface_(hw_interface) @@ -20,26 +20,14 @@ HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, if (config->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - parent_node->declare_parameter("correction_file", "", descriptor); - calibration_file_path_ = parent_node->get_parameter("correction_file").as_string(); + calibration_file_path_ = parent_node->declare_parameter("correction_file", "", param_read_write()); } else { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - parent_node->declare_parameter("calibration_file", "", descriptor); - calibration_file_path_ = parent_node->get_parameter("calibration_file").as_string(); + calibration_file_path_ = parent_node->declare_parameter("calibration_file", "", param_read_write()); } - auto calibration_result = GetCalibrationData(); + auto calibration_result = GetCalibrationData(calibration_file_path_, false); if (!calibration_result.has_value()) { @@ -78,8 +66,64 @@ HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); } -nebula::util::expected, nebula::Status> -HesaiDecoderWrapper::GetCalibrationData() +void HesaiDecoderWrapper::OnConfigChange( + const std::shared_ptr& new_config) +{ + std::lock_guard lock(mtx_driver_ptr_); + auto new_driver = std::make_shared(new_config, calibration_cfg_ptr_); + driver_ptr_ = new_driver; + sensor_cfg_ = new_config; +} + +void HesaiDecoderWrapper::OnCalibrationChange( + const std::shared_ptr& new_calibration) +{ + std::lock_guard lock(mtx_driver_ptr_); + auto new_driver = std::make_shared(sensor_cfg_, new_calibration); + driver_ptr_ = new_driver; + calibration_cfg_ptr_ = new_calibration; + calibration_file_path_ = calibration_cfg_ptr_->calibration_file; +} + +rcl_interfaces::msg::SetParametersResult HesaiDecoderWrapper::OnParameterChange(const std::vector& p) +{ + using namespace rcl_interfaces::msg; + + std::string calibration_path = ""; + + // Only one of the two parameters is defined, so not checking for sensor model explicitly here is fine + bool got_any = get_param(p, "calibration_file", calibration_path) | get_param(p, "correction_file", calibration_path); + if (!got_any) + { + return rcl_interfaces::build().successful(true).reason(""); + } + + if (!std::filesystem::exists(calibration_path)) + { + auto result = SetParametersResult(); + result.successful = false; + result.reason = "The given calibration path does not exist, ignoring: '" + calibration_path + "'"; + return result; + } + + auto get_calibration_result = GetCalibrationData(calibration_path, true); + if (!get_calibration_result.has_value()) + { + auto result = SetParametersResult(); + result.successful = false; + result.reason = (std::stringstream() << "Could not change calibration file to '" << calibration_path + << "': " << get_calibration_result.error()) + .str(); + return result; + } + + OnCalibrationChange(get_calibration_result.value()); + RCLCPP_INFO_STREAM(logger_, "Changed calibration to '" << calibration_cfg_ptr_->calibration_file << "'"); + return rcl_interfaces::build().successful(true).reason(""); +} + +HesaiDecoderWrapper::get_calibration_result_t +HesaiDecoderWrapper::GetCalibrationData(const std::string& calibration_file_path, bool ignore_others) { std::shared_ptr calib; @@ -96,16 +140,15 @@ HesaiDecoderWrapper::GetCalibrationData() std::string calibration_file_path_from_sensor; { - int ext_pos = calibration_file_path_.find_last_of('.'); - calibration_file_path_from_sensor = calibration_file_path_.substr(0, ext_pos); + int ext_pos = calibration_file_path.find_last_of('.'); + calibration_file_path_from_sensor = calibration_file_path.substr(0, ext_pos); // TODO: if multiple different sensors of the same type are used, this will mix up their calibration data calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += - calibration_file_path_.substr(ext_pos, calibration_file_path_.size() - ext_pos); + calibration_file_path_from_sensor += calibration_file_path.substr(ext_pos, calibration_file_path.size() - ext_pos); } // If a sensor is connected, try to download and save its calibration data - if (hw_connected) + if (!ignore_others && hw_connected) { try { @@ -128,7 +171,7 @@ HesaiDecoderWrapper::GetCalibrationData() } // If saved calibration data from a sensor exists (either just downloaded above, or previously), try to load it - if (std::filesystem::exists(calibration_file_path_from_sensor)) + if (!ignore_others && std::filesystem::exists(calibration_file_path_from_sensor)) { auto status = calib->LoadFromFile(calibration_file_path_from_sensor); if (status == Status::OK) @@ -139,31 +182,34 @@ HesaiDecoderWrapper::GetCalibrationData() RCLCPP_ERROR_STREAM(logger_, "Could not load downloaded calibration data: " << status); } - else + else if (!ignore_others) { RCLCPP_ERROR(logger_, "No downloaded calibration data found."); } - RCLCPP_WARN(logger_, "Falling back to generic calibration file."); + if (!ignore_others) + { + RCLCPP_WARN(logger_, "Falling back to generic calibration file."); + } // If downloaded data did not exist or could not be loaded, fall back to a generic file. // If that file does not exist either, return an error code - if (!std::filesystem::exists(calibration_file_path_)) + if (!std::filesystem::exists(calibration_file_path)) { RCLCPP_ERROR(logger_, "No calibration data found."); return nebula::Status(Status::INVALID_CALIBRATION_FILE); } // Try to load the existing fallback calibration file. Return an error if this fails - auto status = calib->LoadFromFile(calibration_file_path_); + auto status = calib->LoadFromFile(calibration_file_path); if (status != Status::OK) { - RCLCPP_ERROR(logger_, "Could not load fallback calibration file."); + RCLCPP_ERROR_STREAM(logger_, "Could not load calibration file at '" << calibration_file_path << "'"); return status; } // Return the fallback calibration file - calib->calibration_file = calibration_file_path_; + calib->calibration_file = calibration_file_path; return calib; } @@ -185,9 +231,13 @@ void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptrpackets.emplace_back(std::move(pandar_packet_msg)); } - std::tuple pointcloud_ts = - driver_ptr_->ParseCloudPacket(packet_msg->data); - nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + std::tuple pointcloud_ts{}; + nebula::drivers::NebulaPointCloudPtr pointcloud = nullptr; + { + std::lock_guard lock(mtx_driver_ptr_); + pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); + pointcloud = std::get<0>(pointcloud_ts); + } if (pointcloud == nullptr) { @@ -244,6 +294,8 @@ void HesaiDecoderWrapper::PublishCloud(std::unique_ptr("launch_hw", param_read_only()); if (launch_hw_) { @@ -27,10 +35,6 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions& options) decoder_wrapper_.emplace(this, hw_interface_wrapper_ ? hw_interface_wrapper_->HwInterface() : nullptr, sensor_cfg_ptr_); - RCLCPP_INFO_STREAM(get_logger(), "SensorConfig:" << *sensor_cfg_ptr_); - set_param_res_ = - add_on_set_parameters_callback(std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); - RCLCPP_DEBUG(get_logger(), "Starting stream"); decoder_thread_ = std::thread([this]() { @@ -42,263 +46,164 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions& options) if (launch_hw_) { - StreamStart(); hw_interface_wrapper_->HwInterface()->RegisterScanCallback( std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + StreamStart(); } else { packets_sub_ = create_subscription( "pandar_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); - RCLCPP_INFO_STREAM(get_logger(), "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); + RCLCPP_INFO_STREAM(get_logger(), + "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); } + + // Register parameter callback after all params have been declared. Otherwise it would be called once for each + // declaration + parameter_event_cb_ = + add_on_set_parameters_callback(std::bind(&HesaiRosWrapper::OnParameterChange, this, std::placeholders::_1)); } nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() { - nebula::drivers::HesaiSensorConfiguration sensor_configuration; + nebula::drivers::HesaiSensorConfiguration config; + + auto _sensor_model = declare_parameter("sensor_model", "", param_read_only()); + config.sensor_model = drivers::SensorModelFromString(_sensor_model); + + auto _return_mode = declare_parameter("return_mode", "", param_read_write()); + config.return_mode = drivers::ReturnModeFromStringHesai(_return_mode, config.sensor_model); + + config.host_ip = declare_parameter("host_ip", "255.255.255.255", param_read_only()); + config.sensor_ip = declare_parameter("sensor_ip", "192.168.1.201", param_read_only()); + config.data_port = declare_parameter("data_port", 2368, param_read_only()); + config.gnss_port = declare_parameter("gnss_port", 2369, param_read_only()); + config.frame_id = declare_parameter("frame_id", "pandar", param_read_write()); { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = get_parameter("gnss_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = { range }; - declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("min_range", 0.3, descriptor); - sensor_configuration.min_range = get_parameter("min_range").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("max_range", 300., descriptor); - sensor_configuration.max_range = get_parameter("max_range").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = get_parameter("packet_mtu_size").as_int(); + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.])"; + descriptor.floating_point_range = float_range(0, 360, 0.01); + config.scan_phase = declare_parameter("scan_phase", 0., descriptor); } + + config.min_range = declare_parameter("min_range", 0.3, param_read_write()); + config.max_range = declare_parameter("max_range", 300., param_read_write()); + config.packet_mtu_size = declare_parameter("packet_mtu_size", 1500, param_read_only()); + { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - RCLCPP_DEBUG_STREAM(get_logger(), sensor_configuration.sensor_model); - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + uint16_t default_value; + RCLCPP_DEBUG_STREAM(get_logger(), config.sensor_model); + if (config.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { - descriptor.additional_constraints = "200, 300, 400, 500"; - // range.set__from_value(200).set__to_value(500).set__step(100); - // descriptor.integer_range = {range}; //todo - declare_parameter("rotation_speed", 200, descriptor); + descriptor.additional_constraints = "200, 400"; + descriptor.integer_range = int_range(200, 400, 200); + default_value = 200; } else { descriptor.additional_constraints = "300, 600, 1200"; - // range.set__from_value(300).set__to_value(1200).set__step(300); - // descriptor.integer_range = {range}; //todo - declare_parameter("rotation_speed", 600, descriptor); + descriptor.integer_range = int_range(300, 1200, 300); + default_value = 600; } - sensor_configuration.rotation_speed = get_parameter("rotation_speed").as_int(); + config.rotation_speed = declare_parameter("rotation_speed", default_value, descriptor); } { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = { range }; - declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = get_parameter("cloud_min_angle").as_int(); + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.integer_range = int_range(0, 360, 1); + config.cloud_min_angle = declare_parameter("cloud_min_angle", 0, descriptor); } { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = { range }; - declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = get_parameter("cloud_max_angle").as_int(); + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.integer_range = int_range(0, 360, 1); + config.cloud_max_angle = declare_parameter("cloud_max_angle", 360, descriptor); } { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = { range }; - declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = get_parameter("dual_return_distance_threshold").as_double(); + descriptor.floating_point_range = float_range(0.01, 0.5, 0.01); + config.dual_return_distance_threshold = + declare_parameter("dual_return_distance_threshold", 0.1, descriptor); } + + auto _ptp_profile = declare_parameter("ptp_profile", "", param_read_only()); + config.ptp_profile = drivers::PtpProfileFromString(_ptp_profile); + + auto _ptp_transport = declare_parameter("ptp_transport_type", "", param_read_only()); + config.ptp_transport_type = drivers::PtpTransportTypeFromString(_ptp_transport); + + if (config.ptp_transport_type != drivers::PtpTransportType::L2 && + config.ptp_profile != drivers::PtpProfile::IEEE_1588v2 && + config.ptp_profile != drivers::PtpProfile::UNKNOWN_PROFILE) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("ptp_profile", ""); - sensor_configuration.ptp_profile = nebula::drivers::PtpProfileFromString(get_parameter("ptp_profile").as_string()); + RCLCPP_WARN_STREAM(get_logger(), "PTP transport was set to '" << _ptp_transport << "' but PTP profile '" + << _ptp_profile + << "' only supports 'L2'. Setting it to 'L2'."); + config.ptp_transport_type = drivers::PtpTransportType::L2; + set_parameter(rclcpp::Parameter("ptp_transport_type", "L2")); } + + auto _ptp_switch = declare_parameter("ptp_switch_type", "", param_read_only()); + config.ptp_switch_type = drivers::PtpSwitchTypeFromString(_ptp_switch); + { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("ptp_transport_type", ""); - sensor_configuration.ptp_transport_type = - nebula::drivers::PtpTransportTypeFromString(get_parameter("ptp_transport_type").as_string()); - if (static_cast(sensor_configuration.ptp_profile) > 0) - { - sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; - } + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_only(); + descriptor.integer_range = int_range(0, 127, 1); + config.ptp_domain = declare_parameter("ptp_domain", 0, descriptor); } + + auto new_cfg_ptr = std::make_shared(config); + return ValidateAndSetConfig(new_cfg_ptr); +} + +Status HesaiRosWrapper::ValidateAndSetConfig(std::shared_ptr& new_config) +{ + if (new_config->sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("ptp_switch_type", ""); - sensor_configuration.ptp_switch_type = - nebula::drivers::PtpSwitchTypeFromString(get_parameter("ptp_switch_type").as_string()); + return Status::INVALID_SENSOR_MODEL; } + if (new_config->return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(127).set__step(1); - descriptor.integer_range = { range }; - declare_parameter("ptp_domain", 0, descriptor); - sensor_configuration.ptp_domain = get_parameter("ptp_domain").as_int(); + return Status::INVALID_ECHO_MODE; } - - if (sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) + if (new_config->frame_id.empty()) + { + return Status::SENSOR_CONFIG_ERROR; + } + if (new_config->ptp_profile == nebula::drivers::PtpProfile::UNKNOWN_PROFILE) { RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) + if (new_config->ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " "using the '1588v2' PTP Profile"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) + if (new_config->ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) + + if (hw_interface_wrapper_) { - return Status::INVALID_SENSOR_MODEL; + hw_interface_wrapper_->OnConfigChange(new_config); } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) + if (hw_monitor_wrapper_) { - return Status::INVALID_ECHO_MODE; + hw_monitor_wrapper_->OnConfigChange(new_config); } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) + if (decoder_wrapper_) { - return Status::SENSOR_CONFIG_ERROR; + decoder_wrapper_->OnConfigChange(new_config); } - auto new_cfg_ptr_ = std::make_shared(sensor_configuration); - sensor_cfg_ptr_.swap(new_cfg_ptr_); + sensor_cfg_ptr_ = new_config; return Status::OK; } @@ -326,25 +231,6 @@ Status HesaiRosWrapper::GetStatus() return wrapper_status_; } -Status HesaiRosWrapper::DeclareAndGetWrapperParams() -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("launch_hw", "", descriptor); - launch_hw_ = get_parameter("launch_hw").as_bool(); - } - - return Status::OK; -} - -HesaiRosWrapper::~HesaiRosWrapper() -{ -} - Status HesaiRosWrapper::StreamStart() { if (!hw_interface_wrapper_) @@ -360,74 +246,60 @@ Status HesaiRosWrapper::StreamStart() return hw_interface_wrapper_->HwInterface()->SensorInterfaceStart(); } -rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback(const std::vector& p) +rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::OnParameterChange(const std::vector& p) { + using namespace rcl_interfaces::msg; + + if (p.empty()) + { + return rcl_interfaces::build().successful(true).reason(""); + } + std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback"); - RCLCPP_DEBUG_STREAM(get_logger(), p); - RCLCPP_DEBUG_STREAM(get_logger(), *sensor_cfg_ptr_); + + RCLCPP_INFO(get_logger(), "OnParameterChange"); drivers::HesaiSensorConfiguration new_cfg(*sensor_cfg_ptr_); - std::string sensor_model_str; - std::string return_mode_str; - if (get_param(p, "sensor_model", sensor_model_str) | get_param(p, "return_mode", return_mode_str) | - get_param(p, "host_ip", new_cfg.host_ip) | get_param(p, "sensor_ip", new_cfg.sensor_ip) | - get_param(p, "frame_id", new_cfg.frame_id) | get_param(p, "data_port", new_cfg.data_port) | - get_param(p, "gnss_port", new_cfg.gnss_port) | get_param(p, "scan_phase", new_cfg.scan_phase) | - get_param(p, "packet_mtu_size", new_cfg.packet_mtu_size) | - get_param(p, "rotation_speed", new_cfg.rotation_speed) | - get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | - get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle) | - get_param(p, "dual_return_distance_threshold", new_cfg.dual_return_distance_threshold)) + std::string _return_mode = ""; + bool got_any = get_param(p, "return_mode", _return_mode) | get_param(p, "frame_id", new_cfg.frame_id) | + get_param(p, "scan_phase", new_cfg.scan_phase) | get_param(p, "min_range", new_cfg.min_range) | + get_param(p, "max_range", new_cfg.max_range) | get_param(p, "rotation_speed", new_cfg.rotation_speed) | + get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | + get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle) | + get_param(p, "dual_return_distance_threshold", new_cfg.dual_return_distance_threshold); + + // Currently, HW interface and monitor wrappers have only read-only parameters, so their update logic is not + // implemented + if (decoder_wrapper_) + { + auto result = decoder_wrapper_->OnParameterChange(p); + if (!result.successful) { + return result; + } + } + + if (!got_any) { - if (0 < sensor_model_str.length()) - new_cfg.sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); - if (0 < return_mode_str.length()) - new_cfg.return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); - - auto new_cfg_ptr = std::make_shared(new_cfg); - sensor_cfg_ptr_.swap(new_cfg_ptr); - RCLCPP_INFO_STREAM(get_logger(), "Update sensor_configuration"); - RCLCPP_DEBUG_STREAM(get_logger(), "hw_interface_.SetSensorConfiguration"); - hw_interface_wrapper_->HwInterface()->SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - hw_interface_wrapper_->HwInterface()->CheckAndSetConfig(); + return rcl_interfaces::build().successful(true).reason(""); } - auto result = std::make_shared(); - result->successful = true; - result->reason = "success"; + if (_return_mode.length() > 0) + new_cfg.return_mode = nebula::drivers::ReturnModeFromString(_return_mode); - RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback success"); + auto new_cfg_ptr = std::make_shared(new_cfg); + auto status = ValidateAndSetConfig(new_cfg_ptr); - return *result; -} + if (status != Status::OK) + { + RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); + auto result = SetParametersResult(); + result.successful = false; + result.reason = (std::stringstream() << "Invalid configuration: " << status).str(); + return result; + } -std::vector HesaiRosWrapper::updateParameters() -{ - std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(get_logger(), "updateParameters start"); - std::ostringstream os_sensor_model; - os_sensor_model << sensor_cfg_ptr_->sensor_model; - std::ostringstream os_return_mode; - os_return_mode << sensor_cfg_ptr_->return_mode; - RCLCPP_INFO_STREAM(get_logger(), "set_parameters"); - auto results = set_parameters( - { rclcpp::Parameter("sensor_model", os_sensor_model.str()), - rclcpp::Parameter("return_mode", os_return_mode.str()), rclcpp::Parameter("host_ip", sensor_cfg_ptr_->host_ip), - rclcpp::Parameter("sensor_ip", sensor_cfg_ptr_->sensor_ip), - rclcpp::Parameter("frame_id", sensor_cfg_ptr_->frame_id), - rclcpp::Parameter("data_port", sensor_cfg_ptr_->data_port), - rclcpp::Parameter("gnss_port", sensor_cfg_ptr_->gnss_port), - rclcpp::Parameter("scan_phase", sensor_cfg_ptr_->scan_phase), - rclcpp::Parameter("packet_mtu_size", sensor_cfg_ptr_->packet_mtu_size), - rclcpp::Parameter("rotation_speed", sensor_cfg_ptr_->rotation_speed), - rclcpp::Parameter("cloud_min_angle", sensor_cfg_ptr_->cloud_min_angle), - rclcpp::Parameter("cloud_max_angle", sensor_cfg_ptr_->cloud_max_angle), - rclcpp::Parameter("dual_return_distance_threshold", sensor_cfg_ptr_->dual_return_distance_threshold) }); - RCLCPP_DEBUG_STREAM(get_logger(), "updateParameters end"); - return results; + return rcl_interfaces::build().successful(true).reason(""); } void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector& packet) diff --git a/nebula_ros/src/hesai/hw_interface_wrapper.cpp b/nebula_ros/src/hesai/hw_interface_wrapper.cpp index e38f6b181..c10319c1e 100644 --- a/nebula_ros/src/hesai/hw_interface_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_interface_wrapper.cpp @@ -5,36 +5,20 @@ namespace nebula namespace ros { -HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, - std::shared_ptr& config) +HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper( + rclcpp::Node* const parent_node, std::shared_ptr& config) : hw_interface_(new nebula::drivers::HesaiHwInterface()) , logger_(parent_node->get_logger().get_child("HwInterface")) , status_(Status::NOT_INITIALIZED) { - bool setup_sensor, retry_connect; + setup_sensor_ = parent_node->declare_parameter("setup_sensor", true, param_read_only()); + bool retry_connect = parent_node->declare_parameter("retry_hw", true, param_read_only()); - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - parent_node->declare_parameter("setup_sensor", true, descriptor); - setup_sensor = parent_node->get_parameter("setup_sensor").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - parent_node->declare_parameter("retry_hw", true, descriptor); - retry_connect = parent_node->get_parameter("retry_hw").as_bool(); - } - - hw_interface_->SetSensorConfiguration(std::static_pointer_cast(config)); + status_ = hw_interface_->SetSensorConfiguration(std::static_pointer_cast(config)); - status_ = Status::OK; + if (status_ != Status::OK) { + throw std::runtime_error((std::stringstream{} << "Could not initialize HW interface: " << status_).str()); + } hw_interface_->SetLogger(std::make_shared(parent_node->get_logger())); hw_interface_->SetTargetModel(config->sensor_model); @@ -51,7 +35,7 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node retry_count++; std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 - RCLCPP_WARN_STREAM(logger_, "Retry: " << retry_count); + RCLCPP_WARN_STREAM(logger_, status_ << ". Retry #" << retry_count); } if (status_ == Status::OK) @@ -66,10 +50,9 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node { RCLCPP_ERROR_STREAM(logger_, "Failed to get model from sensor..."); } - if (setup_sensor) + if (setup_sensor_) { hw_interface_->CheckAndSetConfig(); - // updateParameters(); TODO } } else @@ -80,6 +63,15 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node status_ = Status::OK; } +void HesaiHwInterfaceWrapper::OnConfigChange( + const std::shared_ptr& new_config) +{ + hw_interface_->SetSensorConfiguration(std::static_pointer_cast(new_config)); + if (setup_sensor_) { + hw_interface_->CheckAndSetConfig(); + } +} + Status HesaiHwInterfaceWrapper::Status() { return status_; diff --git a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp index 579e32a4e..0a56bec57 100644 --- a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp @@ -6,22 +6,14 @@ namespace ros { HesaiHwMonitorWrapper::HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, - std::shared_ptr& config) + std::shared_ptr& config) : logger_(parent_node->get_logger().get_child("HwMonitor")) , diagnostics_updater_(parent_node) , status_(Status::OK) , hw_interface_(hw_interface) , parent_node_(parent_node) { - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - parent_node->declare_parameter("diag_span", 1000, descriptor); - diag_span_ = parent_node->get_parameter("diag_span").as_int(); - } + diag_span_ = parent_node->declare_parameter("diag_span", 1000, param_read_only()); switch (config->sensor_model) { @@ -66,11 +58,6 @@ HesaiHwMonitorWrapper::HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, RCLCPP_INFO_STREAM(logger_, "Model:" << info_model_); RCLCPP_INFO_STREAM(logger_, "Serial:" << info_serial_); InitializeHesaiDiagnostics(); - - if (Status::OK != status_) - { - throw std::runtime_error((std::stringstream() << "Error getting calibration data: " << status_).str()); - } } void HesaiHwMonitorWrapper::InitializeHesaiDiagnostics() From 37bc57555bcc764fd9f3b3b6cb31c4247603f2cd Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 23 Apr 2024 16:58:52 +0900 Subject: [PATCH 042/122] feat(hesai_ros): add watchdog timer for pointcloud output --- .../nebula_ros/common/watchdog_timer.hpp | 52 +++++++++++++++++++ .../nebula_ros/hesai/decoder_wrapper.hpp | 3 ++ nebula_ros/src/hesai/decoder_wrapper.cpp | 10 ++++ 3 files changed, 65 insertions(+) create mode 100644 nebula_ros/include/nebula_ros/common/watchdog_timer.hpp diff --git a/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp b/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp new file mode 100644 index 000000000..ae556e33e --- /dev/null +++ b/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp @@ -0,0 +1,52 @@ +#pragma once + +#include +#include +#include +#include +#include + +namespace nebula +{ +namespace ros +{ + +class WatchdogTimer +{ + using watchdog_cb_t = std::function; + +public: + WatchdogTimer(rclcpp::Node& node, const std::chrono::microseconds& expected_update_interval, const watchdog_cb_t& callback) + : node_(node) + , callback_(callback) + , expected_update_interval_ns_( + std::chrono::duration_cast(expected_update_interval).count()) + { + timer_ = node_.create_wall_timer(expected_update_interval, std::bind(&WatchdogTimer::onTimer, this)); + } + + void update() + { + last_update_ns_ = node_.get_clock()->now().nanoseconds(); + } + +private: + void onTimer() + { + uint64_t now_ns = node_.get_clock()->now().nanoseconds(); + + bool is_late = (now_ns - last_update_ns_) > expected_update_interval_ns_; + + callback_(!is_late); + } + + rclcpp::Node& node_; + rclcpp::TimerBase::SharedPtr timer_; + std::atomic last_update_ns_; + const watchdog_cb_t callback_; + + const uint64_t expected_update_interval_ns_; +}; + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp index 3b2af26d4..da5e60ff0 100644 --- a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp @@ -3,6 +3,7 @@ #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" #include "nebula_ros/common/parameter_descriptors.hpp" +#include "nebula_ros/common/watchdog_timer.hpp" #include #include @@ -80,6 +81,8 @@ class HesaiDecoderWrapper rclcpp::Publisher::SharedPtr nebula_points_pub_{}; rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; + + std::shared_ptr cloud_watchdog_; }; } // namespace ros } // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp index 1b7c10582..0ddfd599e 100644 --- a/nebula_ros/src/hesai/decoder_wrapper.cpp +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -5,6 +5,8 @@ namespace nebula namespace ros { +using namespace std::chrono_literals; + HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, std::shared_ptr& config) @@ -64,6 +66,12 @@ HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, aw_points_ex_pub_ = parent_node->create_publisher("aw_points_ex", pointcloud_qos); RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); + + cloud_watchdog_ = std::make_shared(*parent_node, 100'000us, [this, parent_node](bool ok) { + if (ok) + return; + RCLCPP_WARN_THROTTLE(logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline"); + }); } void HesaiDecoderWrapper::OnConfigChange( @@ -246,6 +254,8 @@ void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptrupdate(); + // Publish scan message only if it has been written to if (current_scan_msg_ && !current_scan_msg_->packets.empty()) { From eb80e3a889292c48036e2ad9c305f3bd81d74193 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 25 Apr 2024 18:29:33 +0900 Subject: [PATCH 043/122] fix(hesai): change to possibly more accurate high_resolution_clock --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 1bce59ffe..6e08c0e3b 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -309,7 +309,7 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector& packet) return; } - const auto now = std::chrono::system_clock::now(); + const auto now = std::chrono::high_resolution_clock::now(); const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); auto msg_ptr = std::make_unique(); From 0f0456a07c3fb1ad31011bdfa36bddae67277bf7 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 25 Apr 2024 18:34:02 +0900 Subject: [PATCH 044/122] fix(hesai): fix crash on QT128 --- .../hesai_hw_interface.cpp | 47 ++++++++++++------- 1 file changed, 31 insertions(+), 16 deletions(-) diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index b6d7b68e2..3ce70dd1f 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -262,8 +262,10 @@ HesaiPtpDiagStatus HesaiHwInterface::GetPtpDiagStatus() auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_STATUS}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiPtpDiagStatus)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiPtpDiagStatus)) { + throw std::runtime_error("HesaiPtpDiagStatus has unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpDiagStatus)) { + PrintError("HesaiPtpDiagStatus from Sensor has unknown format. Will parse anyway."); } HesaiPtpDiagStatus hesai_ptp_diag_status; @@ -281,9 +283,12 @@ HesaiPtpDiagPort HesaiHwInterface::GetPtpDiagPort() auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_PORT_DATA_SET}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiPtpDiagPort)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiPtpDiagPort)) { + throw std::runtime_error("HesaiPtpDiagPort has unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpDiagPort)) { + PrintError("HesaiPtpDiagPort from Sensor has unknown format. Will parse anyway."); } + HesaiPtpDiagPort hesai_ptp_diag_port; memcpy(&hesai_ptp_diag_port, response.data(), sizeof(HesaiPtpDiagPort)); @@ -299,8 +304,10 @@ HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_TIME_STATUS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiPtpDiagTime)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiPtpDiagTime)) { + throw std::runtime_error("HesaiPtpDiagTime has unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpDiagTime)) { + PrintError("HesaiPtpDiagTime from Sensor has unknown format. Will parse anyway."); } HesaiPtpDiagTime hesai_ptp_diag_time; @@ -318,8 +325,10 @@ HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiPtpDiagGrandmaster)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiPtpDiagGrandmaster)) { + throw std::runtime_error("HesaiPtpDiagGrandmaster has unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpDiagGrandmaster)) { + PrintError("HesaiPtpDiagGrandmaster from Sensor has unknown format. Will parse anyway."); } HesaiPtpDiagGrandmaster hesai_ptp_diag_grandmaster; @@ -338,7 +347,7 @@ HesaiInventory HesaiHwInterface::GetInventory() auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() < sizeof(HesaiInventory)) { - throw std::runtime_error("Unexpected payload size"); + throw std::runtime_error("HesaiInventory has unexpected payload size"); } else if (response.size() > sizeof(HesaiInventory)) { PrintError("HesaiInventory from Sensor has unknown format. Will parse anyway."); } @@ -354,8 +363,10 @@ HesaiConfig HesaiHwInterface::GetConfig() auto response_or_err = SendReceive(PTC_COMMAND_GET_CONFIG_INFO); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiConfig)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiConfig)) { + throw std::runtime_error("HesaiConfig has unexpected payload size"); + } else if (response.size() > sizeof(HesaiConfig)) { + PrintError("HesaiConfig from Sensor has unknown format. Will parse anyway."); } HesaiConfig hesai_config; @@ -370,8 +381,10 @@ HesaiLidarStatus HesaiHwInterface::GetLidarStatus() auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_STATUS); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiLidarStatus)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiLidarStatus)) { + throw std::runtime_error("HesaiLidarStatus has unexpected payload size"); + } else if (response.size() > sizeof(HesaiLidarStatus)) { + PrintError("HesaiLidarStatus from Sensor has unknown format. Will parse anyway."); } HesaiLidarStatus hesai_status; @@ -590,7 +603,7 @@ HesaiPtpConfig HesaiHwInterface::GetPtpConfig() auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() < sizeof(HesaiPtpConfig)) { - throw std::runtime_error("Unexpected payload size"); + throw std::runtime_error("HesaiPtpConfig has unexpected payload size"); } else if (response.size() > sizeof(HesaiPtpConfig)) { PrintError("HesaiPtpConfig from Sensor has unknown format. Will parse anyway."); } @@ -630,8 +643,10 @@ HesaiLidarMonitor HesaiHwInterface::GetLidarMonitor() auto response_or_err = SendReceive(PTC_COMMAND_LIDAR_MONITOR); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiLidarMonitor)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiLidarMonitor)) { + throw std::runtime_error("HesaiLidarMonitor has unexpected payload size"); + } else if (response.size() > sizeof(HesaiLidarMonitor)) { + PrintError("HesaiLidarMonitor from Sensor has unknown format. Will parse anyway."); } HesaiLidarMonitor hesai_lidar_monitor; From 897bfb43286b36e8a7242bcdd1379fb765d32164 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 30 Apr 2024 11:14:00 +0900 Subject: [PATCH 045/122] refactor(hesai_hw_interface): refactor repeated error handling code --- .../hesai_hw_interface.hpp | 6 + .../hesai_hw_interface.cpp | 116 +++++------------- 2 files changed, 35 insertions(+), 87 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index d3472afbe..8dc270b8e 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -168,6 +168,12 @@ class HesaiHwInterface /// @return A string description of all errors in this code std::string PrettyPrintPTCError(ptc_error_t error_code); + /// @brief Checks if the data size matches that of the struct to be parsed, and parses the struct. + /// If data is too small, a std::runtime_error is thrown. If data is too large, a warning is printed + /// and the struct is parsed with the first sizeof(T) bytes. + template + T CheckSizeAndParse(const std::vector & data); + /// @brief Send a PTC request with an optional payload, and return the full response payload. /// Blocking. /// @param command_id PTC command number. diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 3ce70dd1f..efd7dcf80 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -261,117 +261,66 @@ HesaiPtpDiagStatus HesaiHwInterface::GetPtpDiagStatus() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_STATUS}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiPtpDiagStatus)) { - throw std::runtime_error("HesaiPtpDiagStatus has unexpected payload size"); - } else if (response.size() > sizeof(HesaiPtpDiagStatus)) { - PrintError("HesaiPtpDiagStatus from Sensor has unknown format. Will parse anyway."); - } - - HesaiPtpDiagStatus hesai_ptp_diag_status; - memcpy(&hesai_ptp_diag_status, response.data(), sizeof(HesaiPtpDiagStatus)); + auto diag_status = CheckSizeAndParse(response); std::stringstream ss; - ss << "HesaiHwInterface::GetPtpDiagStatus: " << hesai_ptp_diag_status; + ss << "HesaiHwInterface::GetPtpDiagStatus: " << diag_status; PrintInfo(ss.str()); - return hesai_ptp_diag_status; + return diag_status; } HesaiPtpDiagPort HesaiHwInterface::GetPtpDiagPort() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_PORT_DATA_SET}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiPtpDiagPort)) { - throw std::runtime_error("HesaiPtpDiagPort has unexpected payload size"); - } else if (response.size() > sizeof(HesaiPtpDiagPort)) { - PrintError("HesaiPtpDiagPort from Sensor has unknown format. Will parse anyway."); - } - - HesaiPtpDiagPort hesai_ptp_diag_port; - memcpy(&hesai_ptp_diag_port, response.data(), sizeof(HesaiPtpDiagPort)); + auto diag_port = CheckSizeAndParse(response); std::stringstream ss; - ss << "HesaiHwInterface::GetPtpDiagPort: " << hesai_ptp_diag_port; + ss << "HesaiHwInterface::GetPtpDiagPort: " << diag_port; PrintInfo(ss.str()); - return hesai_ptp_diag_port; + return diag_port; } HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_TIME_STATUS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiPtpDiagTime)) { - throw std::runtime_error("HesaiPtpDiagTime has unexpected payload size"); - } else if (response.size() > sizeof(HesaiPtpDiagTime)) { - PrintError("HesaiPtpDiagTime from Sensor has unknown format. Will parse anyway."); - } - - HesaiPtpDiagTime hesai_ptp_diag_time; - memcpy(&hesai_ptp_diag_time, response.data(), sizeof(HesaiPtpDiagTime)); + auto diag_time = CheckSizeAndParse(response); std::stringstream ss; - ss << "HesaiHwInterface::GetPtpDiagTime: " << hesai_ptp_diag_time; + ss << "HesaiHwInterface::GetPtpDiagTime: " << diag_time; PrintInfo(ss.str()); - return hesai_ptp_diag_time; + return diag_time; } HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiPtpDiagGrandmaster)) { - throw std::runtime_error("HesaiPtpDiagGrandmaster has unexpected payload size"); - } else if (response.size() > sizeof(HesaiPtpDiagGrandmaster)) { - PrintError("HesaiPtpDiagGrandmaster from Sensor has unknown format. Will parse anyway."); - } - - HesaiPtpDiagGrandmaster hesai_ptp_diag_grandmaster; - memcpy(&hesai_ptp_diag_grandmaster, response.data(), sizeof(HesaiPtpDiagGrandmaster)); + auto diag_grandmaster = CheckSizeAndParse(response); std::stringstream ss; - ss << "HesaiHwInterface::GetPtpDiagGrandmaster: " << hesai_ptp_diag_grandmaster; + ss << "HesaiHwInterface::GetPtpDiagGrandmaster: " << diag_grandmaster; PrintInfo(ss.str()); - return hesai_ptp_diag_grandmaster; + return diag_grandmaster; } HesaiInventory HesaiHwInterface::GetInventory() { auto response_or_err = SendReceive(PTC_COMMAND_GET_INVENTORY_INFO); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiInventory)) { - throw std::runtime_error("HesaiInventory has unexpected payload size"); - } else if (response.size() > sizeof(HesaiInventory)) { - PrintError("HesaiInventory from Sensor has unknown format. Will parse anyway."); - } - - HesaiInventory hesai_inventory; - memcpy(&hesai_inventory, response.data(), sizeof(HesaiInventory)); - - return hesai_inventory; + return CheckSizeAndParse(response); } HesaiConfig HesaiHwInterface::GetConfig() { auto response_or_err = SendReceive(PTC_COMMAND_GET_CONFIG_INFO); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiConfig)) { - throw std::runtime_error("HesaiConfig has unexpected payload size"); - } else if (response.size() > sizeof(HesaiConfig)) { - PrintError("HesaiConfig from Sensor has unknown format. Will parse anyway."); - } - - HesaiConfig hesai_config; - memcpy(&hesai_config, response.data(), sizeof(HesaiConfig)); - + auto hesai_config = CheckSizeAndParse(response); std::cout << "Config: " << hesai_config << std::endl; return hesai_config; } @@ -380,17 +329,7 @@ HesaiLidarStatus HesaiHwInterface::GetLidarStatus() { auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_STATUS); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiLidarStatus)) { - throw std::runtime_error("HesaiLidarStatus has unexpected payload size"); - } else if (response.size() > sizeof(HesaiLidarStatus)) { - PrintError("HesaiLidarStatus from Sensor has unknown format. Will parse anyway."); - } - - HesaiLidarStatus hesai_status; - memcpy(&hesai_status, response.data(), sizeof(HesaiLidarStatus)); - - return hesai_status; + return CheckSizeAndParse(response); } Status HesaiHwInterface::SetSpinRate(uint16_t rpm) @@ -642,17 +581,7 @@ HesaiLidarMonitor HesaiHwInterface::GetLidarMonitor() { auto response_or_err = SendReceive(PTC_COMMAND_LIDAR_MONITOR); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiLidarMonitor)) { - throw std::runtime_error("HesaiLidarMonitor has unexpected payload size"); - } else if (response.size() > sizeof(HesaiLidarMonitor)) { - PrintError("HesaiLidarMonitor from Sensor has unknown format. Will parse anyway."); - } - - HesaiLidarMonitor hesai_lidar_monitor; - memcpy(&hesai_lidar_monitor, response.data(), sizeof(HesaiLidarMonitor)); - - return hesai_lidar_monitor; + return CheckSizeAndParse(response); } void HesaiHwInterface::IOContextRun() @@ -1324,5 +1253,18 @@ std::string HesaiHwInterface::PrettyPrintPTCError(ptc_error_t error_code) { return ss.str(); } +template +T HesaiHwInterface::CheckSizeAndParse(const std::vector & data) { + if (data.size() < sizeof(T)) { + throw std::runtime_error("Attempted to parse too-small payload"); + } else if (data.size() > sizeof(T)) { + PrintError("Sensor returned longer payload than expected. Will parse anyway."); + } + + T parsed; + memcpy(&parsed, data.data(), sizeof(T)); + return parsed; +} + } // namespace drivers } // namespace nebula From 8a11d98674588736c5a6d4f60c4a1f85682b77ed Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 30 Apr 2024 13:20:08 +0900 Subject: [PATCH 046/122] fix(hesai_launch_all_hw.xml): set valid RPM when AT128 is selected --- nebula_ros/launch/hesai_launch_all_hw.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index 1bd285766..b0f804441 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -33,6 +33,8 @@ + + Date: Tue, 30 Apr 2024 13:20:49 +0900 Subject: [PATCH 047/122] refactor(hesai_decoder): remove redundant arguments for correction/calibration --- .../decoders/angle_corrector.hpp | 12 +--- .../angle_corrector_calibration_based.hpp | 6 +- .../angle_corrector_correction_based.hpp | 27 +++++---- .../decoders/hesai_decoder.hpp | 10 +--- .../nebula_decoders_hesai/hesai_driver.hpp | 22 ++++++-- .../nebula_decoders_hesai/hesai_driver.cpp | 56 +++++++++---------- 6 files changed, 63 insertions(+), 70 deletions(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp index 121913c34..914d2da49 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp @@ -23,19 +23,11 @@ struct CorrectedAngleData /// @brief Handles angle correction for given azimuth/channel combinations, as well as trigonometry /// lookup tables +template class AngleCorrector { -protected: - const std::shared_ptr sensor_calibration_; - const std::shared_ptr sensor_correction_; - public: - AngleCorrector( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) - : sensor_calibration_(sensor_calibration), sensor_correction_(sensor_correction) - { - } + using correction_data_t = CorrectionDataT; /// @brief Get the corrected azimuth and elevation for a given block and channel, along with their /// sin/cos values. diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp index bee570afc..d2c078e2d 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp @@ -11,7 +11,7 @@ namespace drivers { template -class AngleCorrectorCalibrationBased : public AngleCorrector +class AngleCorrectorCalibrationBased : public AngleCorrector { private: static constexpr size_t MAX_AZIMUTH_LEN = 360 * AngleUnit; @@ -27,9 +27,7 @@ class AngleCorrectorCalibrationBased : public AngleCorrector public: AngleCorrectorCalibrationBased( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) - : AngleCorrector(sensor_calibration, sensor_correction) + const std::shared_ptr & sensor_calibration) { if (sensor_calibration == nullptr) { throw std::runtime_error( diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp index d23dfc1f2..52cbaf315 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp @@ -13,10 +13,11 @@ namespace drivers { template -class AngleCorrectorCorrectionBased : public AngleCorrector +class AngleCorrectorCorrectionBased : public AngleCorrector { private: static constexpr size_t MAX_AZIMUTH_LENGTH = 360 * AngleUnit; + const std::shared_ptr correction_; rclcpp::Logger logger_; std::array cos_{}; @@ -31,26 +32,25 @@ class AngleCorrectorCorrectionBased : public AngleCorrector // * none of the startFrames are defined as > 360 deg (< 0 not possible since they are unsigned) // * the fields are arranged in ascending order (e.g. field 1: 20-140deg, field 2: 140-260deg etc.) // These assumptions hold for AT128E2X. - int field = sensor_correction_->frameNumber - 1; - for (size_t i = 0; i < sensor_correction_->frameNumber; ++i) { - if (azimuth < sensor_correction_->startFrame[i]) return field; + int field = correction_->frameNumber - 1; + for (size_t i = 0; i < correction_->frameNumber; ++i) { + if (azimuth < correction_->startFrame[i]) return field; field = i; } - // This is never reached if sensor_correction_ is correct + // This is never reached if correction_ is correct return field; } public: AngleCorrectorCorrectionBased( - const std::shared_ptr & sensor_calibration, const std::shared_ptr & sensor_correction) - : AngleCorrector(sensor_calibration, sensor_correction), + : correction_(sensor_correction), logger_(rclcpp::get_logger("AngleCorrectorCorrectionBased")) { if (sensor_correction == nullptr) { throw std::runtime_error( - "Cannot instantiate AngleCorrectorCalibrationBased without calibration data"); + "Cannot instantiate AngleCorrectorCorrectionBased without correction data"); } logger_.set_level(rclcpp::Logger::Level::Debug); @@ -64,17 +64,16 @@ class AngleCorrectorCorrectionBased : public AngleCorrector CorrectedAngleData getCorrectedAngleData(uint32_t block_azimuth, uint32_t channel_id) override { - const auto & correction = AngleCorrector::sensor_correction_; int field = findField(block_azimuth); auto elevation = - correction->elevation[channel_id] + - correction->getElevationAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100); + correction_->elevation[channel_id] + + correction_->getElevationAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100); elevation = (MAX_AZIMUTH_LENGTH + elevation) % MAX_AZIMUTH_LENGTH; - auto azimuth = (block_azimuth + MAX_AZIMUTH_LENGTH - correction->startFrame[field]) * 2 - - correction->azimuth[channel_id] + - correction->getAzimuthAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100); + auto azimuth = (block_azimuth + MAX_AZIMUTH_LENGTH - correction_->startFrame[field]) * 2 - + correction_->azimuth[channel_id] + + correction_->getAzimuthAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100); azimuth = (MAX_AZIMUTH_LENGTH + azimuth) % MAX_AZIMUTH_LENGTH; float azimuth_rad = 2.f * azimuth * M_PI / MAX_AZIMUTH_LENGTH; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index e8a9afc34..ea5dbe727 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -204,16 +204,12 @@ class HesaiDecoder : public HesaiScanDecoder public: /// @brief Constructor /// @param sensor_configuration SensorConfiguration for this decoder - /// @param calibration_configuration Calibration for this decoder (can be nullptr if - /// correction_configuration is set) - /// @param correction_configuration Correction for this decoder (can be nullptr if - /// calibration_configuration is set) + /// @param correction_data Calibration data for this decoder explicit HesaiDecoder( const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) + const std::shared_ptr & correction_data) : sensor_configuration_(sensor_configuration), - angle_corrector_(calibration_configuration, correction_configuration), + angle_corrector_(correction_data), logger_(rclcpp::get_logger("HesaiDecoder")) { logger_.set_level(rclcpp::Logger::Level::Debug); diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index 87798dbd1..099e022c5 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -16,6 +16,7 @@ #include #include #include +#include namespace nebula { @@ -30,15 +31,22 @@ class HesaiDriver /// @brief Decoder according to the model std::shared_ptr scan_decoder_; + template + std::shared_ptr InitializeDecoder( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & + calibration_configuration); + public: HesaiDriver() = delete; /// @brief Constructor /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver (either HesaiCalibrationConfiguration - /// for sensors other than AT128 or HesaiCorrection for AT128) + /// @param calibration_configuration CalibrationConfiguration for this driver (either + /// HesaiCalibrationConfiguration for sensors other than AT128 or HesaiCorrection for AT128) explicit HesaiDriver( - const std::shared_ptr& sensor_configuration, - const std::shared_ptr& calibration_configuration = nullptr); + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & + calibration_configuration); /// @brief Get current status of this driver /// @return Current status @@ -47,12 +55,14 @@ class HesaiDriver /// @brief Setting CalibrationConfiguration (not used) /// @param calibration_configuration /// @return Resulting status - Status SetCalibrationConfiguration(const HesaiCalibrationConfigurationBase& calibration_configuration); + Status SetCalibrationConfiguration( + const HesaiCalibrationConfigurationBase & calibration_configuration); /// @brief Convert PandarScan message to point cloud /// @param pandar_scan Message /// @return tuple of Point cloud and timestamp - std::tuple ParseCloudPacket(const std::vector& packet); + std::tuple ParseCloudPacket( + const std::vector & packet); }; } // namespace drivers diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index beafd8e71..c8aea2b40 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -17,64 +17,62 @@ namespace nebula { namespace drivers { -HesaiDriver::HesaiDriver(const std::shared_ptr& sensor_configuration, - const std::shared_ptr& calibration_configuration) +HesaiDriver::HesaiDriver( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_data) { // initialize proper parser from cloud config's model and echo mode driver_status_ = nebula::Status::OK; - std::shared_ptr calibration = nullptr; - std::shared_ptr correction = nullptr; - - if (sensor_configuration->sensor_model == SensorModel::HESAI_PANDARAT128) - { - correction = std::static_pointer_cast(calibration_configuration); - } - else - { - calibration = std::static_pointer_cast(calibration_configuration); - } - - switch (sensor_configuration->sensor_model) - { - case SensorModel::UNKNOWN: - driver_status_ = nebula::Status::INVALID_SENSOR_MODEL; - break; + switch (sensor_configuration->sensor_model) { case SensorModel::HESAI_PANDAR64: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDAR40P: case SensorModel::HESAI_PANDAR40M: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARQT64: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARQT128: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARXT32: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARXT32M: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARAT128: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDAR128_E3X: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDAR128_E4X: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; + case SensorModel::UNKNOWN: + driver_status_ = nebula::Status::INVALID_SENSOR_MODEL; + throw std::runtime_error("Invalid sensor model."); default: driver_status_ = nebula::Status::NOT_INITIALIZED; throw std::runtime_error("Driver not Implemented for selected sensor."); - break; } } +template +std::shared_ptr HesaiDriver::InitializeDecoder( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & + calibration_configuration) +{ + using CalibT = typename SensorT::angle_corrector_t::correction_data_t; + return std::make_shared>( + sensor_configuration, std::dynamic_pointer_cast(calibration_configuration)); +} + std::tuple HesaiDriver::ParseCloudPacket( const std::vector & packet) { From 74388c97b77663cf0cf8ae3d4d5fb2ef48a73182 Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Sat, 11 May 2024 20:18:09 +0900 Subject: [PATCH 048/122] refactor(nebula_ros): move mt_queue to common --- nebula_ros/include/nebula_ros/{hesai => common}/mt_queue.hpp | 0 nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) rename nebula_ros/include/nebula_ros/{hesai => common}/mt_queue.hpp (100%) diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/common/mt_queue.hpp similarity index 100% rename from nebula_ros/include/nebula_ros/hesai/mt_queue.hpp rename to nebula_ros/include/nebula_ros/common/mt_queue.hpp diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 42d8bdc36..ed76343c7 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -9,7 +9,7 @@ #include "nebula_ros/hesai/decoder_wrapper.hpp" #include "nebula_ros/hesai/hw_interface_wrapper.hpp" #include "nebula_ros/hesai/hw_monitor_wrapper.hpp" -#include "nebula_ros/hesai/mt_queue.hpp" +#include "nebula_ros/common/mt_queue.hpp" #include "nebula_ros/common/parameter_descriptors.hpp" #include From 8aeca9b613779327ccfd6641dcc82f0b675a47c3 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 16 May 2024 18:18:27 +0900 Subject: [PATCH 049/122] refactor(velodyne)!: unify wrapper nodes. Currently WIP but compiling --- .../decoders/velodyne_scan_decoder.hpp | 31 +- .../decoders/vlp16_decoder.hpp | 9 +- .../decoders/vlp32_decoder.hpp | 9 +- .../decoders/vls128_decoder.hpp | 9 +- .../velodyne_driver.hpp | 8 +- .../decoders/vlp16_decoder.cpp | 19 +- .../decoders/vlp32_decoder.cpp | 17 +- .../decoders/vls128_decoder.cpp | 19 +- .../velodyne_driver.cpp | 30 +- .../velodyne_hw_interface.hpp | 53 +- .../velodyne_hw_interface.cpp | 72 +- nebula_ros/CMakeLists.txt | 33 +- .../nebula_ros/velodyne/decoder_wrapper.hpp | 91 ++ .../velodyne/hw_interface_wrapper.hpp | 35 + ...ros_wrapper.hpp => hw_monitor_wrapper.hpp} | 333 +++--- .../velodyne/velodyne_decoder_ros_wrapper.hpp | 83 -- .../velodyne_hw_interface_ros_wrapper.hpp | 202 ---- .../velodyne/velodyne_ros_wrapper.hpp | 90 ++ nebula_ros/src/velodyne/decoder_wrapper.cpp | 242 ++++ .../src/velodyne/hw_interface_wrapper.cpp | 55 + ...ros_wrapper.cpp => hw_monitor_wrapper.cpp} | 1043 +++++------------ .../velodyne/velodyne_decoder_ros_wrapper.cpp | 281 ----- .../velodyne_hw_interface_ros_wrapper.cpp | 326 ------ .../src/velodyne/velodyne_ros_wrapper.cpp | 265 +++++ 24 files changed, 1336 insertions(+), 2019 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/velodyne/decoder_wrapper.hpp create mode 100644 nebula_ros/include/nebula_ros/velodyne/hw_interface_wrapper.hpp rename nebula_ros/include/nebula_ros/velodyne/{velodyne_hw_monitor_ros_wrapper.hpp => hw_monitor_wrapper.hpp} (69%) delete mode 100644 nebula_ros/include/nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp delete mode 100644 nebula_ros/include/nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp create mode 100644 nebula_ros/include/nebula_ros/velodyne/velodyne_ros_wrapper.hpp create mode 100644 nebula_ros/src/velodyne/decoder_wrapper.cpp create mode 100644 nebula_ros/src/velodyne/hw_interface_wrapper.cpp rename nebula_ros/src/velodyne/{velodyne_hw_monitor_ros_wrapper.cpp => hw_monitor_wrapper.cpp} (55%) delete mode 100644 nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp delete mode 100644 nebula_ros/src/velodyne/velodyne_hw_interface_ros_wrapper.cpp create mode 100644 nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp index 7c319e0fe..8c35f105f 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp @@ -20,6 +20,7 @@ #include #include +#include namespace nebula { @@ -138,17 +139,14 @@ class VelodyneScanDecoder /// @brief Point cloud overflowing from one cycle drivers::NebulaPointCloudPtr overflow_pc_; - uint16_t scan_phase_{}; - uint16_t last_phase_{}; - bool has_scanned_ = true; double dual_return_distance_threshold_{}; // Velodyne does this internally, this will not be // implemented here double scan_timestamp_{}; /// @brief SensorConfiguration for this decoder - std::shared_ptr sensor_configuration_; + std::shared_ptr sensor_configuration_; /// @brief Calibration for this decoder - std::shared_ptr calibration_configuration_; + std::shared_ptr calibration_configuration_; public: VelodyneScanDecoder(VelodyneScanDecoder && c) = delete; @@ -161,7 +159,7 @@ class VelodyneScanDecoder /// @brief Virtual function for parsing and shaping VelodynePacket /// @param pandar_packet - virtual void unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_packet) = 0; + virtual void unpack(const std::vector & packet, int32_t packet_seconds) = 0; /// @brief Virtual function for parsing VelodynePacket based on packet structure /// @param pandar_packet /// @return Resulting flag @@ -169,7 +167,26 @@ class VelodyneScanDecoder /// @brief Virtual function for getting the flag indicating whether one cycle is ready /// @return Readied - virtual bool hasScanned() = 0; + virtual bool hasScanned() { + if (scan_pc_->size() < 2) { + return false; + } + + float scan_phase = angles::from_degrees(sensor_configuration_->scan_phase); + float first_azimuth = scan_pc_->points.front().azimuth - scan_phase; + float last_azimuth = scan_pc_->points.back().azimuth - scan_phase; + + if (first_azimuth < 0) { + first_azimuth += 2 * M_PI; + } + + if (last_azimuth < 0) { + last_azimuth += 2 * M_PI; + } + + return first_azimuth > last_azimuth; + } + /// @brief Calculation of points in each packet /// @return # of points virtual int pointsPerPacket() = 0; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp index 730f7045f..3829a2d70 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp @@ -25,14 +25,11 @@ class Vlp16Decoder : public VelodyneScanDecoder /// @param sensor_configuration SensorConfiguration for this decoder /// @param calibration_configuration Calibration for this decoder explicit Vlp16Decoder( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration); + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration); /// @brief Parsing and shaping VelodynePacket /// @param velodyne_packet - void unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_packet) override; - /// @brief Get the flag indicating whether one cycle is ready - /// @return Readied - bool hasScanned() override; + void unpack(const std::vector & packet, int32_t packet_seconds) override; /// @brief Calculation of points in each packet /// @return # of points int pointsPerPacket() override; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp index 0ffa1e3ce..04160ab19 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp @@ -24,14 +24,11 @@ class Vlp32Decoder : public VelodyneScanDecoder /// @param sensor_configuration SensorConfiguration for this decoder /// @param calibration_configuration Calibration for this decoder explicit Vlp32Decoder( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration); + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration); /// @brief Parsing and shaping VelodynePacket /// @param velodyne_packet - void unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_packet) override; - /// @brief Get the flag indicating whether one cycle is ready - /// @return Readied - bool hasScanned() override; + void unpack(const std::vector & packet, int32_t packet_seconds) override; /// @brief Calculation of points in each packet /// @return # of points int pointsPerPacket() override; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp index e440096e9..0626e2e47 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp @@ -21,14 +21,11 @@ class Vls128Decoder : public VelodyneScanDecoder /// @param sensor_configuration SensorConfiguration for this decoder /// @param calibration_configuration Calibration for this decoder explicit Vls128Decoder( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration); + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration); /// @brief Parsing and shaping VelodynePacket /// @param velodyne_packet - void unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_packet) override; - /// @brief Get the flag indicating whether one cycle is ready - /// @return Readied - bool hasScanned() override; + void unpack(const std::vector & packet, int32_t packet_seconds) override; /// @brief Calculation of points in each packet /// @return # of points int pointsPerPacket() override; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp index d0257b82d..c5caf00b8 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp @@ -36,8 +36,8 @@ class VelodyneDriver : NebulaDriverBase /// @param sensor_configuration SensorConfiguration for this driver /// @param calibration_configuration CalibrationConfiguration for this driver VelodyneDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration); + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration); /// @brief Setting CalibrationConfiguration (not used) /// @param calibration_configuration @@ -52,8 +52,8 @@ class VelodyneDriver : NebulaDriverBase /// @brief Convert VelodyneScan message to point cloud /// @param velodyne_scan Message /// @return tuple of Point cloud and timestamp - std::tuple ConvertScanToPointcloud( - const std::shared_ptr & velodyne_scan); + std::tuple ParseCloudPacket( + const std::vector & packet, int32_t packet_seconds); }; } // namespace drivers diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp index 338163d60..02bed010e 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp @@ -12,8 +12,8 @@ namespace drivers namespace vlp16 { Vlp16Decoder::Vlp16Decoder( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration) + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration) { sensor_configuration_ = sensor_configuration; calibration_configuration_ = calibration_configuration; @@ -56,11 +56,6 @@ Vlp16Decoder::Vlp16Decoder( phase_ = (uint16_t)round(sensor_configuration_->scan_phase * 100); } -bool Vlp16Decoder::hasScanned() -{ - return has_scanned_; -} - std::tuple Vlp16Decoder::get_pointcloud() { double phase = angles::from_degrees(sensor_configuration_->scan_phase); @@ -138,12 +133,12 @@ void Vlp16Decoder::reset_overflow(double time_stamp) overflow_pc_->points.reserve(max_pts_); } -void Vlp16Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_packet) +void Vlp16Decoder::unpack(const std::vector & packet, int32_t packet_seconds) { - const raw_packet_t * raw = (const raw_packet_t *)&velodyne_packet.data[0]; + const raw_packet_t * raw = (const raw_packet_t *)packet.data(); float last_azimuth_diff = 0; uint16_t azimuth_next; - const uint8_t return_mode = velodyne_packet.data[RETURN_MODE_INDEX]; + const uint8_t return_mode = packet[RETURN_MODE_INDEX]; const bool dual_return = (return_mode == RETURN_MODE_DUAL); for (uint block = 0; block < BLOCKS_PER_PACKET; block++) { @@ -203,7 +198,7 @@ void Vlp16Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa block % 2 ? raw->blocks[block - 1].data[k + 1] : raw->blocks[block + 1].data[k + 1]; } // Apply timestamp if this is the first new packet in the scan. - auto block_timestamp = rclcpp::Time(velodyne_packet.stamp).seconds(); + auto block_timestamp = packet_seconds; if (scan_timestamp_ < 0) { scan_timestamp_ = block_timestamp; } @@ -216,7 +211,7 @@ void Vlp16Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa continue; } { - VelodyneLaserCorrection & corrections = + const VelodyneLaserCorrection & corrections = calibration_configuration_->velodyne_calibration.laser_corrections[dsr]; float distance = current_return.uint * calibration_configuration_->velodyne_calibration.distance_resolution_m; diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp index ec3e06745..4c06faf87 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp @@ -12,8 +12,8 @@ namespace drivers namespace vlp32 { Vlp32Decoder::Vlp32Decoder( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration) + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration) { sensor_configuration_ = sensor_configuration; calibration_configuration_ = calibration_configuration; @@ -56,11 +56,6 @@ Vlp32Decoder::Vlp32Decoder( } } -bool Vlp32Decoder::hasScanned() -{ - return has_scanned_; -} - std::tuple Vlp32Decoder::get_pointcloud() { double phase = angles::from_degrees(sensor_configuration_->scan_phase); @@ -137,10 +132,10 @@ void Vlp32Decoder::reset_overflow(double time_stamp) overflow_pc_->points.reserve(max_pts_); } -void Vlp32Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_packet) +void Vlp32Decoder::unpack(const std::vector & packet, int32_t packet_seconds) { - const raw_packet_t * raw = (const raw_packet_t *)&velodyne_packet.data[0]; - uint8_t return_mode = velodyne_packet.data[RETURN_MODE_INDEX]; + const raw_packet_t * raw = (const raw_packet_t *)packet.data(); + uint8_t return_mode = packet[RETURN_MODE_INDEX]; const bool dual_return = (return_mode == RETURN_MODE_DUAL); for (int i = 0; i < BLOCKS_PER_PACKET; i++) { @@ -170,7 +165,7 @@ void Vlp32Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa i % 2 ? raw->blocks[i - 1].data[k + 1] : raw->blocks[i + 1].data[k + 1]; } // Apply timestamp if this is the first new packet in the scan. - auto block_timestamp = rclcpp::Time(velodyne_packet.stamp).seconds(); + auto block_timestamp = packet_seconds; if (scan_timestamp_ < 0) { scan_timestamp_ = block_timestamp; } diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp index c42f9b0b5..8992b537e 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp @@ -12,8 +12,8 @@ namespace drivers namespace vls128 { Vls128Decoder::Vls128Decoder( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration) + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration) { sensor_configuration_ = sensor_configuration; calibration_configuration_ = calibration_configuration; @@ -56,11 +56,6 @@ Vls128Decoder::Vls128Decoder( } } -bool Vls128Decoder::hasScanned() -{ - return has_scanned_; -} - std::tuple Vls128Decoder::get_pointcloud() { double phase = angles::from_degrees(sensor_configuration_->scan_phase); @@ -139,12 +134,12 @@ void Vls128Decoder::reset_overflow(double time_stamp) overflow_pc_->points.reserve(max_pts_); } -void Vls128Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_packet) +void Vls128Decoder::unpack(const std::vector & packet, int32_t packet_seconds) { - const raw_packet_t * raw = (const raw_packet_t *)&velodyne_packet.data[0]; + const raw_packet_t * raw = (const raw_packet_t *)packet.data(); float last_azimuth_diff = 0; uint16_t azimuth_next; - const uint8_t return_mode = velodyne_packet.data[RETURN_MODE_INDEX]; + const uint8_t return_mode = packet[RETURN_MODE_INDEX]; const bool dual_return = (return_mode == RETURN_MODE_DUAL); for (uint block = 0; block < static_cast(BLOCKS_PER_PACKET - (4 * dual_return)); block++) { @@ -223,7 +218,7 @@ void Vls128Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_p block % 2 ? raw->blocks[block - 1].data[k + 1] : raw->blocks[block + 1].data[k + 1]; } // Apply timestamp if this is the first new packet in the scan. - auto block_timestamp = rclcpp::Time(velodyne_packet.stamp).seconds(); + auto block_timestamp = packet_seconds; if (scan_timestamp_ < 0) { scan_timestamp_ = block_timestamp; } @@ -240,7 +235,7 @@ void Vls128Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_p j + bank_origin; // offset the laser in this block by which block it's in const uint firing_order = laser_number / 8; // VLS-128 fires 8 lasers at a time - VelodyneLaserCorrection & corrections = + const VelodyneLaserCorrection & corrections = calibration_configuration_->velodyne_calibration.laser_corrections[laser_number]; float distance = current_return.uint * VLP128_DISTANCE_RESOLUTION; diff --git a/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp b/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp index b0f664c8c..07569b8d9 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp @@ -9,8 +9,8 @@ namespace nebula namespace drivers { VelodyneDriver::VelodyneDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration) + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration) { // initialize proper parser from cloud config's model and echo mode driver_status_ = nebula::Status::OK; @@ -46,20 +46,24 @@ Status VelodyneDriver::SetCalibrationConfiguration( calibration_configuration.calibration_file + ")"); } -std::tuple VelodyneDriver::ConvertScanToPointcloud( - const std::shared_ptr & velodyne_scan) +std::tuple VelodyneDriver::ParseCloudPacket( + const std::vector & packet, int32_t packet_seconds) { std::tuple pointcloud; - if (driver_status_ == nebula::Status::OK) { - scan_decoder_->reset_pointcloud( - velodyne_scan->packets.size(), rclcpp::Time(velodyne_scan->packets.front().stamp).seconds()); - for (auto & packet : velodyne_scan->packets) { - scan_decoder_->unpack(packet); - } - pointcloud = scan_decoder_->get_pointcloud(); - } else { - std::cout << "not ok driver_status_ = " << driver_status_ << std::endl; + + if (driver_status_ != nebula::Status::OK) + { + auto logger = rclcpp::get_logger("VelodyneDriver"); + RCLCPP_ERROR(logger, "Driver not OK."); + return pointcloud; } + + scan_decoder_->unpack(packet, packet_seconds); + if (scan_decoder_->hasScanned()) + { + pointcloud = scan_decoder_->get_pointcloud(); + } + return pointcloud; } Status VelodyneDriver::GetStatus() diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp index fcb907a15..4c7971b2d 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp @@ -11,16 +11,15 @@ #if (BOOST_VERSION / 100 == 1074) // Boost 1.74 #define BOOST_ALLOW_DEPRECATED_HEADERS #endif -#include "boost_tcp_driver/http_client_driver.hpp" -#include "boost_udp_driver/udp_driver.hpp" -#include "nebula_common/velodyne/velodyne_common.hpp" -#include "nebula_common/velodyne/velodyne_status.hpp" + #include "nebula_hw_interfaces/nebula_hw_interfaces_common/nebula_hw_interface_base.hpp" -#include +#include +#include +#include +#include -#include -#include +#include #include #include @@ -32,26 +31,14 @@ namespace nebula namespace drivers { /// @brief Hardware interface of velodyne driver -class VelodyneHwInterface : NebulaHwInterfaceBase +class VelodyneHwInterface { private: std::unique_ptr<::drivers::common::IoContext> cloud_io_context_; std::unique_ptr<::drivers::udp_driver::UdpDriver> cloud_udp_driver_; - std::shared_ptr sensor_configuration_; - std::shared_ptr calibration_configuration_; - std::unique_ptr scan_cloud_ptr_; - std::function - is_valid_packet_; /*Lambda Function Array to verify proper packet size*/ - std::function buffer)> - scan_reception_callback_; /**This function pointer is called when the scan is complete*/ - - uint16_t packet_first_azm_ = 0; - uint16_t packet_first_azm_phased_ = 0; - uint16_t packet_last_azm_ = 0; - uint16_t packet_last_azm_phased_ = 0; - uint16_t prev_packet_first_azm_phased_ = 0; - uint16_t phase_ = 0; - uint processed_packets_ = 0; + std::shared_ptr sensor_configuration_; + std::function&)> + cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ std::shared_ptr boost_ctx_; std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> http_client_driver_; @@ -86,7 +73,7 @@ class VelodyneHwInterface : NebulaHwInterfaceBase /// @param tree Current settings (property_tree) /// @return Resulting status VelodyneStatus CheckAndSetConfig( - std::shared_ptr sensor_configuration, + std::shared_ptr sensor_configuration, boost::property_tree::ptree tree); std::shared_ptr parent_node_logger; @@ -106,38 +93,38 @@ class VelodyneHwInterface : NebulaHwInterfaceBase /// @brief Callback function to receive the Cloud Packet data from the UDP Driver /// @param buffer Buffer containing the data received from the UDP socket - void ReceiveSensorPacketCallback(const std::vector & buffer) final; + void ReceiveSensorPacketCallback(std::vector & buffer); /// @brief Starting the interface that handles UDP streams /// @return Resulting status - Status SensorInterfaceStart() final; + Status SensorInterfaceStart(); /// @brief Function for stopping the interface that handles UDP streams /// @return Resulting status - Status SensorInterfaceStop() final; + Status SensorInterfaceStop(); /// @brief Printing sensor configuration /// @param sensor_configuration SensorConfiguration for this interface /// @return Resulting status - Status GetSensorConfiguration(SensorConfigurationBase & sensor_configuration) final; + Status GetSensorConfiguration(SensorConfigurationBase & sensor_configuration); /// @brief Printing calibration configuration /// @param calibration_configuration CalibrationConfiguration for the checking /// @return Resulting status Status GetCalibrationConfiguration( - CalibrationConfigurationBase & calibration_configuration) final; + CalibrationConfigurationBase & calibration_configuration); /// @brief Initializing sensor configuration /// @param sensor_configuration SensorConfiguration for this interface /// @return Resulting status Status InitializeSensorConfiguration( - std::shared_ptr sensor_configuration); + std::shared_ptr sensor_configuration); /// @brief Setting sensor configuration with InitializeSensorConfiguration & /// CheckAndSetConfigBySnapshotAsync /// @param sensor_configuration SensorConfiguration for this interface /// @return Resulting status Status SetSensorConfiguration( - std::shared_ptr sensor_configuration) final; + std::shared_ptr sensor_configuration); /// @brief Registering callback for PandarScan /// @param scan_callback Callback function /// @return Resulting status Status RegisterScanCallback( - std::function)> scan_callback); + std::function& packet)> scan_callback); /// @brief Parsing JSON string to property_tree /// @param str JSON string @@ -244,7 +231,7 @@ class VelodyneHwInterface : NebulaHwInterfaceBase /// @brief Checking the current settings and changing the difference point /// @return Resulting status VelodyneStatus CheckAndSetConfigBySnapshotAsync( - std::shared_ptr sensor_configuration); + std::shared_ptr sensor_configuration); /// @brief Setting Motor RPM (async) /// @param rpm the RPM of the motor /// @return Resulting status diff --git a/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp index 8a8bfefbe..f31bb413b 100644 --- a/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp @@ -7,18 +7,15 @@ namespace drivers VelodyneHwInterface::VelodyneHwInterface() : cloud_io_context_{new ::drivers::common::IoContext(1)}, cloud_udp_driver_{new ::drivers::udp_driver::UdpDriver(*cloud_io_context_)}, - scan_cloud_ptr_{std::make_unique()}, boost_ctx_{new boost::asio::io_context()}, http_client_driver_{new ::drivers::tcp_driver::HttpClientDriver(boost_ctx_)} { } Status VelodyneHwInterface::InitializeSensorConfiguration( - std::shared_ptr sensor_configuration) + std::shared_ptr sensor_configuration) { - sensor_configuration_ = - std::static_pointer_cast(sensor_configuration); - phase_ = (uint16_t)round(sensor_configuration_->scan_phase * 100); + sensor_configuration_ = sensor_configuration; GetDiagAsync(); GetStatusAsync(); @@ -27,10 +24,9 @@ Status VelodyneHwInterface::InitializeSensorConfiguration( } Status VelodyneHwInterface::SetSensorConfiguration( - std::shared_ptr sensor_configuration) + std::shared_ptr sensor_configuration) { - auto velodyne_sensor_configuration = - std::static_pointer_cast(sensor_configuration); + auto velodyne_sensor_configuration = sensor_configuration; VelodyneStatus status = CheckAndSetConfigBySnapshotAsync(velodyne_sensor_configuration); Status rt = status; return rt; @@ -55,49 +51,19 @@ Status VelodyneHwInterface::SensorInterfaceStart() } Status VelodyneHwInterface::RegisterScanCallback( - std::function)> scan_callback) + std::function& packet)> scan_callback) { - scan_reception_callback_ = std::move(scan_callback); + cloud_packet_callback_ = std::move(scan_callback); return Status::OK; } -void VelodyneHwInterface::ReceiveSensorPacketCallback(const std::vector & buffer) -{ - // Process current packet - const uint32_t buffer_size = buffer.size(); - velodyne_msgs::msg::VelodynePacket velodyne_packet; - std::copy_n(std::make_move_iterator(buffer.begin()), buffer_size, velodyne_packet.data.begin()); - auto now = std::chrono::system_clock::now(); - auto now_secs = std::chrono::duration_cast(now.time_since_epoch()).count(); - auto now_nanosecs = - std::chrono::duration_cast(now.time_since_epoch()).count(); - velodyne_packet.stamp.sec = static_cast(now_secs); - velodyne_packet.stamp.nanosec = static_cast(now_nanosecs % 1'000'000'000); - scan_cloud_ptr_->packets.emplace_back(velodyne_packet); - processed_packets_++; - - // Check if scan is complete - packet_first_azm_ = scan_cloud_ptr_->packets.back().data[2]; // lower word of azimuth block 0 - packet_first_azm_ |= scan_cloud_ptr_->packets.back().data[3] - << 8; // higher word of azimuth block 0 - - packet_last_azm_ = scan_cloud_ptr_->packets.back().data[1102]; - packet_last_azm_ |= scan_cloud_ptr_->packets.back().data[1103] << 8; - - packet_first_azm_phased_ = (36000 + packet_first_azm_ - phase_) % 36000; - packet_last_azm_phased_ = (36000 + packet_last_azm_ - phase_) % 36000; - - if (processed_packets_ > 1) { - if ( - packet_last_azm_phased_ < packet_first_azm_phased_ || - packet_first_azm_phased_ < prev_packet_first_azm_phased_) { - // Callback - scan_reception_callback_(std::move(scan_cloud_ptr_)); - scan_cloud_ptr_ = std::make_unique(); - processed_packets_ = 0; - } +void VelodyneHwInterface::ReceiveSensorPacketCallback(std::vector & buffer) +{ + if (!cloud_packet_callback_) { + return; } - prev_packet_first_azm_phased_ = packet_first_azm_phased_; + + cloud_packet_callback_(buffer); } Status VelodyneHwInterface::SensorInterfaceStop() { @@ -112,13 +78,6 @@ Status VelodyneHwInterface::GetSensorConfiguration(SensorConfigurationBase & sen return Status::ERROR_1; } -Status VelodyneHwInterface::GetCalibrationConfiguration( - CalibrationConfigurationBase & calibration_configuration) -{ - PrintDebug(calibration_configuration.calibration_file); - return Status::ERROR_1; -} - VelodyneStatus VelodyneHwInterface::InitHttpClient() { try { @@ -188,7 +147,7 @@ boost::property_tree::ptree VelodyneHwInterface::ParseJson(const std::string & s } VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( - std::shared_ptr sensor_configuration, + std::shared_ptr sensor_configuration, boost::property_tree::ptree tree) { std::string target_key = "config.returns"; @@ -523,15 +482,14 @@ VelodyneStatus VelodyneHwInterface::GetSnapshotAsync() } VelodyneStatus VelodyneHwInterface::CheckAndSetConfigBySnapshotAsync( - std::shared_ptr sensor_configuration) + std::shared_ptr sensor_configuration) { sensor_configuration_ = sensor_configuration; return GetSnapshotAsync([this](const std::string & str) { auto tree = ParseJson(str); std::cout << "ParseJson OK\n"; - CheckAndSetConfig( - std::static_pointer_cast(sensor_configuration_), tree); + CheckAndSetConfig(sensor_configuration_, tree); }); } diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index 324d38074..d756a3d51 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -49,32 +49,17 @@ rclcpp_components_register_node(hesai_ros_wrapper ) ## Velodyne -# Hw Interface -ament_auto_add_library(velodyne_hw_ros_wrapper SHARED - src/velodyne/velodyne_hw_interface_ros_wrapper.cpp - ) -rclcpp_components_register_node(velodyne_hw_ros_wrapper - PLUGIN "VelodyneHwInterfaceRosWrapper" - EXECUTABLE velodyne_hw_ros_wrapper_node - ) - - -# Monitor -ament_auto_add_library(velodyne_hw_monitor_ros_wrapper SHARED - src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp - ) -rclcpp_components_register_node(velodyne_hw_monitor_ros_wrapper - PLUGIN "VelodyneHwMonitorRosWrapper" - EXECUTABLE velodyne_hw_monitor_ros_wrapper_node +ament_auto_add_library(velodyne_ros_wrapper SHARED + src/velodyne/velodyne_ros_wrapper.cpp + src/velodyne/decoder_wrapper.cpp + src/velodyne/hw_interface_wrapper.cpp + src/velodyne/hw_monitor_wrapper.cpp + src/common/parameter_descriptors.cpp ) -# DriverDecoder -ament_auto_add_library(velodyne_driver_ros_wrapper SHARED - src/velodyne/velodyne_decoder_ros_wrapper.cpp - ) -rclcpp_components_register_node(velodyne_driver_ros_wrapper - PLUGIN "VelodyneDriverRosWrapper" - EXECUTABLE velodyne_driver_ros_wrapper_node +rclcpp_components_register_node(velodyne_ros_wrapper + PLUGIN "VelodyneRosWrapper" + EXECUTABLE velodyne_ros_wrapper_node ) ## Robosense diff --git a/nebula_ros/include/nebula_ros/velodyne/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/decoder_wrapper.hpp new file mode 100644 index 000000000..283b68368 --- /dev/null +++ b/nebula_ros/include/nebula_ros/velodyne/decoder_wrapper.hpp @@ -0,0 +1,91 @@ +#pragma once + +#include "nebula_ros/common/parameter_descriptors.hpp" +#include "nebula_ros/common/watchdog_timer.hpp" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +namespace nebula +{ +namespace ros +{ +class VelodyneDecoderWrapper +{ + using get_calibration_result_t = nebula::util::expected< + std::shared_ptr, nebula::Status>; + +public: + VelodyneDecoderWrapper( + rclcpp::Node * const parent_node, + const std::shared_ptr & hw_interface, + std::shared_ptr & config); + + void ProcessCloudPacket(std::unique_ptr packet_msg); + + void OnConfigChange( + const std::shared_ptr & new_config); + + void OnCalibrationChange( + const std::shared_ptr & + new_calibration); + + rcl_interfaces::msg::SetParametersResult OnParameterChange( + const std::vector & p); + + nebula::Status Status(); + +private: + /// @brief Load calibration data from file + /// @param calibration_file_path The file to read from + /// @return The calibration data if successful, or an error code if not + get_calibration_result_t GetCalibrationData(const std::string & calibration_file_path); + + void PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher); + + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast( + std::chrono::duration(seconds)); + } + + nebula::Status status_; + rclcpp::Logger logger_; + + const std::shared_ptr hw_interface_; + std::shared_ptr sensor_cfg_; + + std::string calibration_file_path_{}; + std::shared_ptr calibration_cfg_ptr_{}; + + std::shared_ptr driver_ptr_{}; + std::mutex mtx_driver_ptr_; + + rclcpp::Publisher::SharedPtr packets_pub_{}; + velodyne_msgs::msg::VelodyneScan::UniquePtr current_scan_msg_{}; + + rclcpp::Publisher::SharedPtr nebula_points_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; + + std::shared_ptr cloud_watchdog_; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/velodyne/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/hw_interface_wrapper.hpp new file mode 100644 index 000000000..5c857fa12 --- /dev/null +++ b/nebula_ros/include/nebula_ros/velodyne/hw_interface_wrapper.hpp @@ -0,0 +1,35 @@ +#pragma once + +#include "nebula_ros/common/parameter_descriptors.hpp" + +#include + +#include +#include + +#include + +namespace nebula +{ +namespace ros +{ +class VelodyneHwInterfaceWrapper +{ +public: + VelodyneHwInterfaceWrapper(rclcpp::Node* const parent_node, + std::shared_ptr& config); + + void OnConfigChange(const std::shared_ptr & new_config); + + nebula::Status Status(); + + std::shared_ptr HwInterface() const; + +private: + std::shared_ptr hw_interface_; + rclcpp::Logger logger_; + nebula::Status status_; + bool setup_sensor_; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_monitor_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp similarity index 69% rename from nebula_ros/include/nebula_ros/velodyne/velodyne_hw_monitor_ros_wrapper.hpp rename to nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp index 3f589bbbf..a003aad43 100644 --- a/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_monitor_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp @@ -1,92 +1,63 @@ -#ifndef NEBULA_VelodyneHwMonitorRosWrapper_H -#define NEBULA_VelodyneHwMonitorRosWrapper_H +#pragma once -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/velodyne/velodyne_common.hpp" -#include "nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp" -#include "nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp" +#include "nebula_ros/common/parameter_descriptors.hpp" -#include #include +#include +#include #include -#include -#include +#include +#include +#include +#include + +#include +#include namespace nebula { namespace ros { -/// @brief Get parameter from rclcpp::Parameter -/// @tparam T -/// @param p Parameter from rclcpp parameter callback -/// @param name Target parameter name -/// @param value Corresponding value -/// @return Whether the target name existed -template -bool get_param(const std::vector & p, const std::string & name, T & value) +class VelodyneHwMonitorWrapper { - auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { - return parameter.get_name() == name; - }); - if (it != p.cend()) { - value = it->template get_value(); - return true; +public: + VelodyneHwMonitorWrapper( + rclcpp::Node * const parent_node, + const std::shared_ptr & hw_interface, + std::shared_ptr & config); + + void OnConfigChange( + const std::shared_ptr & /* new_config */) + { } - return false; -} -/// @brief Hardware monitor ros wrapper of velodyne driver -class VelodyneHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapperBase -{ - drivers::VelodyneHwInterface hw_interface_; - Status interface_status_; + nebula::Status Status(); - drivers::VelodyneSensorConfiguration sensor_configuration_; - drivers::VelodyneCalibrationConfiguration calibration_configuration_; +private: + void InitializeVelodyneDiagnostics(); - /// @brief Initializing hardware monitor ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - Status InitializeHwMonitor( - const drivers::SensorConfigurationBase & sensor_configuration) override; + /// @brief Callback of the timer for getting the current lidar status + void OnVelodyneStatusTimer(); + + /// @brief Callback of the timer for getting the current lidar snapshot + void OnVelodyneSnapshotTimer(); + + /// @brief Callback of the timer for getting the current lidar status & updating the diagnostics + void OnVelodyneDiagnosticsTimer(); -public: - explicit VelodyneHwMonitorRosWrapper(const rclcpp::NodeOptions & options); - - /// @brief Not used - /// @return Current status - Status MonitorStart() override; - /// @brief Not used - /// @return Status::OK - Status MonitorStop() override; - /// @brief Not used - /// @return Status::OK - Status Shutdown() override; - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @return Resulting status - Status GetParameters(drivers::VelodyneSensorConfiguration & sensor_configuration); - -private: // ROS Diagnostics - diagnostic_updater::Updater diagnostics_updater_; - /// @brief Initializing diagnostics - void InitializeVelodyneDiagnostics(); /// @brief Get value from property_tree /// @param pt property_tree /// @param key Pey string /// @return Value std::string GetPtreeValue( std::shared_ptr pt, const std::string & key); + /// @brief Making fixed precision string /// @param val Target value /// @param pre Precision /// @return Created string std::string GetFixedPrecisionString(double val, int pre = 2); - rclcpp::TimerBase::SharedPtr diagnostics_diag_timer_; - std::shared_ptr current_diag_tree; - /// @brief Callback of the timer for getting the current lidar status & updating the diagnostics - void OnVelodyneDiagnosticsTimer(); /// @brief Getting top:hv from the current property_tree /// @return tuple @@ -242,8 +213,6 @@ class VelodyneHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWr void VelodyneCheckAdctpStat(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); rclcpp::TimerBase::SharedPtr diagnostics_status_timer_; std::shared_ptr current_status_tree; - /// @brief Callback of the timer for getting the current lidar status - void OnVelodyneStatusTimer(); /// @brief Check gps:pps_state from the current property_tree for diagnostic_updater /// @param diagnostics DiagnosticStatusWrapper void VelodyneCheckGpsPpsState(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); @@ -286,150 +255,110 @@ class VelodyneHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWr /// @param diagnostics DiagnosticStatusWrapper void VelodyneCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Callback of the timer for getting the current lidar snapshot - void OnVelodyneSnapshotTimer(); + rclcpp::Logger logger_; + diagnostic_updater::Updater diagnostics_updater_; + nebula::Status status_; + + const std::shared_ptr hw_interface_; + rclcpp::Node * const parent_node_; + + std::shared_ptr sensor_configuration_; + + uint16_t diag_span_; + bool show_advanced_diagnostics_; + + rclcpp::TimerBase::SharedPtr diagnostics_snapshot_timer_; rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; + rclcpp::TimerBase::SharedPtr diagnostics_diag_timer_; + std::shared_ptr current_snapshot; std::shared_ptr current_snapshot_tree; + std::shared_ptr current_diag_tree; std::shared_ptr current_snapshot_time; - // rclcpp::Time current_snapshot_time; - // std::shared_ptr current_diag_status; uint8_t current_diag_status; - uint16_t diag_span_; - std::mutex mtx_diag; - std::mutex mtx_status; - std::mutex mtx_config_; - - /// @brief Test callback function for getting json with curl - /// @param err Error - /// @param body Received body - void curl_callback(std::string err, std::string body); - - const char * key_volt_temp_top_hv; - const char * key_volt_temp_top_ad_temp; - const char * key_volt_temp_top_lm20_temp; - const char * key_volt_temp_top_pwr_5v; - const char * key_volt_temp_top_pwr_2_5v; - const char * key_volt_temp_top_pwr_3_3v; - const char * key_volt_temp_top_pwr_5v_raw; - const char * key_volt_temp_top_pwr_raw; - const char * key_volt_temp_top_pwr_vccint; - const char * key_volt_temp_bot_i_out; - const char * key_volt_temp_bot_pwr_1_2v; - const char * key_volt_temp_bot_lm20_temp; - const char * key_volt_temp_bot_pwr_5v; - const char * key_volt_temp_bot_pwr_2_5v; - const char * key_volt_temp_bot_pwr_3_3v; - const char * key_volt_temp_bot_pwr_v_in; - const char * key_volt_temp_bot_pwr_1_25v; - const char * key_vhv; - const char * key_adc_nf; - const char * key_adc_stats; - const char * key_ixe; - const char * key_adctp_stat; - const char * key_status_gps_pps_state; - const char * key_status_gps_pps_position; - const char * key_status_motor_state; - const char * key_status_motor_rpm; - const char * key_status_motor_lock; - const char * key_status_motor_phase; - const char * key_status_laser_state; - - /* - const char* name_volt_temp_top_hv; - const char* name_volt_temp_top_ad_temp; - const char* name_volt_temp_top_lm20_temp; - const char* name_volt_temp_top_pwr_5v; - const char* name_volt_temp_top_pwr_2_5v; - const char* name_volt_temp_top_pwr_3_3v; - const char* name_volt_temp_top_pwr_raw; - const char* name_volt_temp_top_pwr_vccint; - const char* name_volt_temp_bot_i_out; - const char* name_volt_temp_bot_pwr_1_2v; - const char* name_volt_temp_bot_lm20_temp; - const char* name_volt_temp_bot_pwr_5v; - const char* name_volt_temp_bot_pwr_2_5v; - const char* name_volt_temp_bot_pwr_3_3v; - const char* name_volt_temp_bot_pwr_v_in; - const char* name_volt_temp_bot_pwr_1_25v; - const char* name_vhv; - const char* name_adc_nf; - const char* name_adc_stats; - const char* name_ixe; - const char* name_adctp_stat; - const char* name_status_gps_pps_state; - const char* name_status_gps_pps_position; - const char* name_status_motor_state; - const char* name_status_motor_rpm; - const char* name_status_motor_lock; - const char* name_status_motor_phase; - const char* name_status_laser_state; - */ - - std::string name_volt_temp_top_hv; - std::string name_volt_temp_top_ad_temp; - std::string name_volt_temp_top_lm20_temp; - std::string name_volt_temp_top_pwr_5v; - std::string name_volt_temp_top_pwr_2_5v; - std::string name_volt_temp_top_pwr_3_3v; - std::string name_volt_temp_top_pwr_5v_raw; - std::string name_volt_temp_top_pwr_raw; - std::string name_volt_temp_top_pwr_vccint; - std::string name_volt_temp_bot_i_out; - std::string name_volt_temp_bot_pwr_1_2v; - std::string name_volt_temp_bot_lm20_temp; - std::string name_volt_temp_bot_pwr_5v; - std::string name_volt_temp_bot_pwr_2_5v; - std::string name_volt_temp_bot_pwr_3_3v; - std::string name_volt_temp_bot_pwr_v_in; - std::string name_volt_temp_bot_pwr_1_25v; - std::string name_vhv; - std::string name_adc_nf; - std::string name_adc_stats; - std::string name_ixe; - std::string name_adctp_stat; - std::string name_status_gps_pps_state; - std::string name_status_gps_pps_position; - std::string name_status_motor_state; - std::string name_status_motor_rpm; - std::string name_status_motor_lock; - std::string name_status_motor_phase; - std::string name_status_laser_state; - - const char * not_supported_message; - const char * error_message; - std::string message_sep; - - const char * key_info_model; - const char * key_info_serial; - - std::string temperature_cold_message; - std::string temperature_hot_message; - std::string voltage_low_message; - std::string voltage_high_message; - std::string ampere_low_message; - std::string ampere_high_message; - - std::string info_model; - std::string info_serial; - - bool use_advanced_diagnostics; - - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - /// @brief rclcpp parameter callback - /// @param parameters Received parameters - /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); - - // rclcpp::callback_group::CallbackGroup::SharedPtr cbg_; - rclcpp::CallbackGroup::SharedPtr cbg_r_; - rclcpp::CallbackGroup::SharedPtr cbg_m_; -}; + std::timed_mutex tm_status_; + std::timed_mutex tm_diag_; -} // namespace ros -} // namespace nebula + std::string info_model_; + std::string info_serial_; + + static constexpr auto key_volt_temp_top_hv = "volt_temp.top.hv"; + static constexpr auto key_volt_temp_top_ad_temp = "volt_temp.top.ad_temp"; // only32 + static constexpr auto key_volt_temp_top_lm20_temp = "volt_temp.top.lm20_temp"; + static constexpr auto key_volt_temp_top_pwr_5v = "volt_temp.top.pwr_5v"; + static constexpr auto key_volt_temp_top_pwr_2_5v = "volt_temp.top.pwr_2_5v"; + static constexpr auto key_volt_temp_top_pwr_3_3v = "volt_temp.top.pwr_3_3v"; + static constexpr auto key_volt_temp_top_pwr_5v_raw = "volt_temp.top.pwr_5v_raw"; // only16 + static constexpr auto key_volt_temp_top_pwr_raw = "volt_temp.top.pwr_raw"; // only32 + static constexpr auto key_volt_temp_top_pwr_vccint = "volt_temp.top.pwr_vccint"; + static constexpr auto key_volt_temp_bot_i_out = "volt_temp.bot.i_out"; + static constexpr auto key_volt_temp_bot_pwr_1_2v = "volt_temp.bot.pwr_1_2v"; + static constexpr auto key_volt_temp_bot_lm20_temp = "volt_temp.bot.lm20_temp"; + static constexpr auto key_volt_temp_bot_pwr_5v = "volt_temp.bot.pwr_5v"; + static constexpr auto key_volt_temp_bot_pwr_2_5v = "volt_temp.bot.pwr_2_5v"; + static constexpr auto key_volt_temp_bot_pwr_3_3v = "volt_temp.bot.pwr_3_3v"; + static constexpr auto key_volt_temp_bot_pwr_v_in = "volt_temp.bot.pwr_v_in"; + static constexpr auto key_volt_temp_bot_pwr_1_25v = "volt_temp.bot.pwr_1_25v"; + static constexpr auto key_vhv = "vhv"; + static constexpr auto key_adc_nf = "adc_nf"; + static constexpr auto key_adc_stats = "adc_stats"; + static constexpr auto key_ixe = "ixe"; + static constexpr auto key_adctp_stat = "adctp_stat"; + static constexpr auto key_status_gps_pps_state = "gps.pps_state"; + static constexpr auto key_status_gps_pps_position = "gps.position"; + static constexpr auto key_status_motor_state = "motor.state"; + static constexpr auto key_status_motor_rpm = "motor.rpm"; + static constexpr auto key_status_motor_lock = "motor.lock"; + static constexpr auto key_status_motor_phase = "motor.phase"; + static constexpr auto key_status_laser_state = "laser.state"; + + static constexpr auto name_volt_temp_top_hv = "Top HV"; + static constexpr auto name_volt_temp_top_ad_temp = "Top A/D TD"; + static constexpr auto name_volt_temp_top_lm20_temp = "Top Temp"; + static constexpr auto name_volt_temp_top_pwr_5v = "Top 5v"; + static constexpr auto name_volt_temp_top_pwr_2_5v = "Top 2.5v"; + static constexpr auto name_volt_temp_top_pwr_3_3v = "Top 3.3v"; + static constexpr auto name_volt_temp_top_pwr_5v_raw = "Top 5v(RAW)"; + static constexpr auto name_volt_temp_top_pwr_raw = "Top RAW"; + static constexpr auto name_volt_temp_top_pwr_vccint = "Top VCCINT"; + static constexpr auto name_volt_temp_bot_i_out = "Bot I out"; + static constexpr auto name_volt_temp_bot_pwr_1_2v = "Bot 1.2v"; + static constexpr auto name_volt_temp_bot_lm20_temp = "Bot Temp"; + static constexpr auto name_volt_temp_bot_pwr_5v = "Bot 5v"; + static constexpr auto name_volt_temp_bot_pwr_2_5v = "Bot 2.5v"; + static constexpr auto name_volt_temp_bot_pwr_3_3v = "Bot 3.3v"; + static constexpr auto name_volt_temp_bot_pwr_v_in = "Bot V in"; + static constexpr auto name_volt_temp_bot_pwr_1_25v = "Bot 1.25v"; // N/A? + static constexpr auto name_vhv = "VHV"; + static constexpr auto name_adc_nf = "adc_nf"; + static constexpr auto name_adc_stats = "adc_stats"; + static constexpr auto name_ixe = "ixe"; + static constexpr auto name_adctp_stat = "adctp_stat"; + static constexpr auto name_status_gps_pps_state = "GPS PPS"; + static constexpr auto name_status_gps_pps_position = "GPS Position"; + static constexpr auto name_status_motor_state = "Motor State"; + static constexpr auto name_status_motor_rpm = "Motor RPM"; + static constexpr auto name_status_motor_lock = "Motor Lock"; + static constexpr auto name_status_motor_phase = "Motor Phase"; + static constexpr auto name_status_laser_state = "Laser State"; + + const std::string message_sep{": "}; + static constexpr auto not_supported_message = "Not supported"; + static constexpr auto error_message = "Error"; -#endif // NEBULA_VelodyneHwMonitorRosWrapper_H + static constexpr auto key_info_model = "info.model"; + static constexpr auto key_info_serial = "info.serial"; + + static constexpr auto temperature_cold_message = "temperature cold"; + static constexpr auto temperature_hot_message = "temperature hot"; + + static constexpr auto voltage_low_message = "voltage low"; + static constexpr auto voltage_high_message = "voltage high"; + + static constexpr auto ampere_low_message = "ampere low"; + static constexpr auto ampere_high_message = "ampere high"; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp deleted file mode 100644 index 5bc79b6c8..000000000 --- a/nebula_ros/include/nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp +++ /dev/null @@ -1,83 +0,0 @@ -#ifndef NEBULA_VelodyneDriverRosWrapper_H -#define NEBULA_VelodyneDriverRosWrapper_H - -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" -#include "nebula_common/velodyne/velodyne_common.hpp" -#include "nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp" -#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" - -#include -#include -#include -#include - -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Ros wrapper of velodyne driver -class VelodyneDriverRosWrapper final : public rclcpp::Node, NebulaDriverRosWrapperBase -{ - std::shared_ptr driver_ptr_; - Status wrapper_status_; - rclcpp::Subscription::SharedPtr velodyne_scan_sub_; - rclcpp::Publisher::SharedPtr nebula_points_pub_; - rclcpp::Publisher::SharedPtr aw_points_ex_pub_; - rclcpp::Publisher::SharedPtr aw_points_base_pub_; - - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; - - /// @brief Initializing ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @param calibration_configuration Output of CalibrationConfiguration - /// @return Resulting status - Status GetParameters( - drivers::VelodyneSensorConfiguration & sensor_configuration, - drivers::VelodyneCalibrationConfiguration & calibration_configuration); - - /// @brief Convert seconds to chrono::nanoseconds - /// @param seconds - /// @return chrono::nanoseconds - static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) - { - return std::chrono::duration_cast( - std::chrono::duration(seconds)); - } - - /*** - * Publishes a sensor_msgs::msg::PointCloud2 to the specified publisher - * @param pointcloud unique pointer containing the point cloud to publish - * @param publisher - */ - void PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher); - -public: - explicit VelodyneDriverRosWrapper(const rclcpp::NodeOptions & options); - - /// @brief Callback for VelodyneScan subscriber - /// @param scan_msg Received VelodyneScan - void ReceiveScanMsgCallback(const velodyne_msgs::msg::VelodyneScan::SharedPtr scan_msg); - /// @brief Get current status of this driver - /// @return Current status - Status GetStatus(); -}; - -} // namespace ros -} // namespace nebula - -#endif // NEBULA_VelodyneDriverRosWrapper_H diff --git a/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp deleted file mode 100644 index 5a0e094c3..000000000 --- a/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp +++ /dev/null @@ -1,202 +0,0 @@ -#ifndef NEBULA_VelodyneHwInterfaceRosWrapper_H -#define NEBULA_VelodyneHwInterfaceRosWrapper_H - -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/velodyne/velodyne_common.hpp" -#include "nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp" -#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" - -#include -#include -#include - -#include -#include - -#include - -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Get parameter from rclcpp::Parameter -/// @tparam T -/// @param p Parameter from rclcpp parameter callback -/// @param name Target parameter name -/// @param value Corresponding value -/// @return Whether the target name existed -template -bool get_param(const std::vector & p, const std::string & name, T & value) -{ - auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { - return parameter.get_name() == name; - }); - if (it != p.cend()) { - value = it->template get_value(); - return true; - } - return false; -} - -/// @brief Hardware interface ros wrapper of velodyne driver -class VelodyneHwInterfaceRosWrapper final : public rclcpp::Node, NebulaHwInterfaceWrapperBase -{ - drivers::VelodyneHwInterface hw_interface_; - Status interface_status_; - - drivers::VelodyneSensorConfiguration sensor_configuration_; - drivers::VelodyneCalibrationConfiguration calibration_configuration_; - - /// @brief Received Velodyne message publisher - rclcpp::Publisher::SharedPtr velodyne_scan_pub_; - - /// @brief Initializing hardware interface ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - Status InitializeHwInterface( - const drivers::SensorConfigurationBase & sensor_configuration) override; - /// @brief Callback for receiving VelodyneScan - /// @param scan_buffer Received VelodyneScan - void ReceiveScanDataCallback(std::unique_ptr scan_buffer); - -public: - explicit VelodyneHwInterfaceRosWrapper(const rclcpp::NodeOptions & options); - /// @brief Start point cloud streaming (Call SensorInterfaceStart of HwInterface) - /// @return Resulting status - Status StreamStart() override; - /// @brief Stop point cloud streaming (not used) - /// @return Resulting status - Status StreamStop() override; - /// @brief Shutdown (not used) - /// @return Resulting status - Status Shutdown() override; - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @return Resulting status - Status GetParameters(drivers::VelodyneSensorConfiguration & sensor_configuration); - -private: // ROS Diagnostics - /* -diagnostic_updater::Updater diagnostics_updater_; -void InitializeVelodyneDiagnostics(); -*/ - - /// @brief Get value from property_tree - /// @param pt property_tree - /// @param key Pey string - /// @return Value - std::string GetPtreeValue( - std::shared_ptr pt, const std::string & key); - /* - rclcpp::TimerBase::SharedPtr diagnostics_diag_timer_; -*/ - std::shared_ptr current_diag_tree; - /* - void OnVelodyneDiagnosticsTimer(); - void VelodyneCheckTopHv(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckTopAdTemp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckTopLm20Temp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckTopPwr5v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckTopPwr25v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckTopPwr33v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckTopPwrRaw(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckTopPwrVccint(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckBotIOut(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckBotPwr12v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckBotLm20Temp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckBotPwr5v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckBotPwr25v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckBotPwr33v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckBotPwrVIn(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckBotPwr125v(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckVhv(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckAdcNf(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckAdcStats(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckIxe(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckAdctpStat(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - rclcpp::TimerBase::SharedPtr diagnostics_status_timer_; -*/ - std::shared_ptr current_status_tree; - /* - void OnVelodyneStatusTimer(); - void VelodyneCheckGpsPpsState(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckGpsPosition(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckMotorState(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckMotorRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckMotorLock(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckMotorPhase(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void VelodyneCheckLaserState(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - - void VelodyneCheckSnapshot(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - - void OnVelodyneSnapshotTimer(); - rclcpp::TimerBase::SharedPtr diagnostics_snapshot_timer_; - rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; -*/ - std::shared_ptr current_snapshot; - std::shared_ptr current_snapshot_tree; - std::shared_ptr current_snapshot_time; - // rclcpp::Time current_snapshot_time; - // std::shared_ptr current_diag_status; - uint8_t current_diag_status; - - uint16_t diag_span_; - std::mutex mtx_diag; - std::mutex mtx_status; - std::mutex mtx_config_; - - void curl_callback(std::string err, std::string body); - /* - const char* key_volt_temp_top_hv; - const char* key_volt_temp_top_ad_temp; - const char* key_volt_temp_top_lm20_temp; - const char* key_volt_temp_top_pwr_5v; - const char* key_volt_temp_top_pwr_2_5v; - const char* key_volt_temp_top_pwr_3_3v; - const char* key_volt_temp_top_pwr_raw; - const char* key_volt_temp_top_pwr_vccint; - const char* key_volt_temp_bot_i_out; - const char* key_volt_temp_bot_pwr_1_2v; - const char* key_volt_temp_bot_lm20_temp; - const char* key_volt_temp_bot_pwr_5v; - const char* key_volt_temp_bot_pwr_2_5v; - const char* key_volt_temp_bot_pwr_3_3v; - const char* key_volt_temp_bot_pwr_v_in; - const char* key_volt_temp_bot_pwr_1_25v; - const char* key_vhv; - const char* key_adc_nf; - const char* key_adc_stats; - const char* key_ixe; - const char* key_adctp_stat; - const char* key_status_gps_pps_state; - const char* key_status_gps_pps_position; - const char* key_status_motor_state; - const char* key_status_motor_rpm; - const char* key_status_motor_lock; - const char* key_status_motor_phase; - const char* key_status_laser_state; -*/ - const char * not_supported_message; - - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - /// @brief rclcpp parameter callback - /// @param parameters Received parameters - /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); - /// @brief Updating rclcpp parameter - /// @return SetParametersResult - std::vector updateParameters(); - - // rclcpp::callback_group::CallbackGroup::SharedPtr cbg_; - rclcpp::CallbackGroup::SharedPtr cbg_r_; - rclcpp::CallbackGroup::SharedPtr cbg_m_; -}; - -} // namespace ros -} // namespace nebula - -#endif // NEBULA_VelodyneHwInterfaceRosWrapper_H diff --git a/nebula_ros/include/nebula_ros/velodyne/velodyne_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/velodyne_ros_wrapper.hpp new file mode 100644 index 000000000..a7110bd4a --- /dev/null +++ b/nebula_ros/include/nebula_ros/velodyne/velodyne_ros_wrapper.hpp @@ -0,0 +1,90 @@ +#pragma once + +#include "nebula_ros/common/mt_queue.hpp" +#include "nebula_ros/common/parameter_descriptors.hpp" +#include "nebula_ros/velodyne/decoder_wrapper.hpp" +#include "nebula_ros/velodyne/hw_interface_wrapper.hpp" +#include "nebula_ros/velodyne/hw_monitor_wrapper.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace nebula +{ +namespace ros +{ + +/// @brief Ros wrapper of velodyne driver +class VelodyneRosWrapper final : public rclcpp::Node +{ +public: + explicit VelodyneRosWrapper(const rclcpp::NodeOptions & options); + ~VelodyneRosWrapper() noexcept {}; + + /// @brief Get current status of this driver + /// @return Current status + Status GetStatus(); + + /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) + /// @return Resulting status + Status StreamStart(); + +private: + void ReceiveCloudPacketCallback(std::vector & packet); + + void ReceiveScanMessageCallback(std::unique_ptr scan_msg); + + Status DeclareAndGetSensorConfigParams(); + + /// @brief rclcpp parameter callback + /// @param parameters Received parameters + /// @return SetParametersResult + rcl_interfaces::msg::SetParametersResult OnParameterChange( + const std::vector & p); + + Status ValidateAndSetConfig( + std::shared_ptr & new_config); + + Status wrapper_status_; + + std::shared_ptr sensor_cfg_ptr_{}; + + /// @brief Stores received packets that have not been processed yet by the decoder thread + mt_queue> packet_queue_; + /// @brief Thread to isolate decoding from receiving + std::thread decoder_thread_; + + rclcpp::Subscription::SharedPtr packets_sub_{}; + + bool launch_hw_; + + std::optional hw_interface_wrapper_; + std::optional hw_monitor_wrapper_; + std::optional decoder_wrapper_; + + std::mutex mtx_config_; + + OnSetParametersCallbackHandle::SharedPtr parameter_event_cb_; +}; + +} // namespace ros +} // namespace nebula diff --git a/nebula_ros/src/velodyne/decoder_wrapper.cpp b/nebula_ros/src/velodyne/decoder_wrapper.cpp new file mode 100644 index 000000000..cfbf21869 --- /dev/null +++ b/nebula_ros/src/velodyne/decoder_wrapper.cpp @@ -0,0 +1,242 @@ +#include "nebula_ros/velodyne/decoder_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ + +using namespace std::chrono_literals; + +VelodyneDecoderWrapper::VelodyneDecoderWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config) + : status_(nebula::Status::NOT_INITIALIZED) + , logger_(parent_node->get_logger().get_child("VelodyneDecoder")) + , hw_interface_(hw_interface) + , sensor_cfg_(config) +{ + if (!config) + { + throw std::runtime_error("VelodyneDecoderWrapper cannot be instantiated without a valid config!"); + } + + calibration_file_path_ = parent_node->declare_parameter("calibration_file", "", param_read_write()); + auto calibration_result = GetCalibrationData(calibration_file_path_); + + if (!calibration_result.has_value()) + { + throw std::runtime_error( + (std::stringstream() << "No valid calibration found: " << calibration_result.error()).str()); + } + + calibration_cfg_ptr_ = calibration_result.value(); + RCLCPP_INFO_STREAM(logger_, "Using calibration data from " << calibration_cfg_ptr_->calibration_file); + + RCLCPP_INFO(logger_, "Starting Decoder"); + + driver_ptr_ = std::make_shared(config, calibration_cfg_ptr_); + status_ = driver_ptr_->GetStatus(); + + if (Status::OK != status_) + { + throw std::runtime_error((std::stringstream() << "Error instantiating decoder: " << status_).str()); + } + + // Publish packets only if HW interface is connected + if (hw_interface_) + { + current_scan_msg_ = std::make_unique(); + packets_pub_ = + parent_node->create_publisher("velodyne_packets", rclcpp::SensorDataQoS()); + } + + auto qos_profile = rmw_qos_profile_sensor_data; + auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + + nebula_points_pub_ = parent_node->create_publisher("velodyne_points", pointcloud_qos); + aw_points_base_pub_ = parent_node->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = parent_node->create_publisher("aw_points_ex", pointcloud_qos); + + RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); + + cloud_watchdog_ = std::make_shared(*parent_node, 100'000us, [this, parent_node](bool ok) { + if (ok) + return; + RCLCPP_WARN_THROTTLE(logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline"); + }); +} + +void VelodyneDecoderWrapper::OnConfigChange( + const std::shared_ptr& new_config) +{ + std::lock_guard lock(mtx_driver_ptr_); + auto new_driver = std::make_shared(new_config, calibration_cfg_ptr_); + driver_ptr_ = new_driver; + sensor_cfg_ = new_config; +} + +void VelodyneDecoderWrapper::OnCalibrationChange( + const std::shared_ptr& new_calibration) +{ + std::lock_guard lock(mtx_driver_ptr_); + auto new_driver = std::make_shared(sensor_cfg_, new_calibration); + driver_ptr_ = new_driver; + calibration_cfg_ptr_ = new_calibration; + calibration_file_path_ = calibration_cfg_ptr_->calibration_file; +} + +rcl_interfaces::msg::SetParametersResult VelodyneDecoderWrapper::OnParameterChange(const std::vector& p) +{ + using namespace rcl_interfaces::msg; + + std::string calibration_path = ""; + + bool got_any = get_param(p, "calibration_file", calibration_path); + if (!got_any) + { + return rcl_interfaces::build().successful(true).reason(""); + } + + if (!std::filesystem::exists(calibration_path)) + { + auto result = SetParametersResult(); + result.successful = false; + result.reason = "The given calibration path does not exist, ignoring: '" + calibration_path + "'"; + return result; + } + + auto get_calibration_result = GetCalibrationData(calibration_path); + if (!get_calibration_result.has_value()) + { + auto result = SetParametersResult(); + result.successful = false; + result.reason = (std::stringstream() << "Could not change calibration file to '" << calibration_path + << "': " << get_calibration_result.error()) + .str(); + return result; + } + + OnCalibrationChange(get_calibration_result.value()); + RCLCPP_INFO_STREAM(logger_, "Changed calibration to '" << calibration_cfg_ptr_->calibration_file << "'"); + return rcl_interfaces::build().successful(true).reason(""); +} + +VelodyneDecoderWrapper::get_calibration_result_t +VelodyneDecoderWrapper::GetCalibrationData(const std::string& calibration_file_path) +{ + auto calib = std::make_shared(); + + // If downloaded data did not exist or could not be loaded, fall back to a generic file. + // If that file does not exist either, return an error code + if (!std::filesystem::exists(calibration_file_path)) + { + RCLCPP_ERROR(logger_, "No calibration data found."); + return nebula::Status(Status::INVALID_CALIBRATION_FILE); + } + + // Try to load the existing fallback calibration file. Return an error if this fails + auto status = calib->LoadFromFile(calibration_file_path); + if (status != Status::OK) + { + RCLCPP_ERROR_STREAM(logger_, "Could not load calibration file at '" << calibration_file_path << "'"); + return status; + } + + // Return the fallback calibration file + calib->calibration_file = calibration_file_path; + return calib; +} + +void VelodyneDecoderWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) +{ + // Accumulate packets for recording only if someone is subscribed to the topic (for performance) + if (hw_interface_ && + (packets_pub_->get_subscription_count() > 0 || packets_pub_->get_intra_process_subscription_count() > 0)) + { + if (current_scan_msg_->packets.size() == 0) + { + current_scan_msg_->header.stamp = packet_msg->stamp; + } + + velodyne_msgs::msg::VelodynePacket velodyne_packet_msg{}; + velodyne_packet_msg.stamp = packet_msg->stamp; + std::copy(packet_msg->data.begin(), packet_msg->data.end(), velodyne_packet_msg.data.begin()); + current_scan_msg_->packets.emplace_back(std::move(velodyne_packet_msg)); + } + + std::tuple pointcloud_ts{}; + nebula::drivers::NebulaPointCloudPtr pointcloud = nullptr; + { + std::lock_guard lock(mtx_driver_ptr_); + pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data, packet_msg->stamp.sec); + pointcloud = std::get<0>(pointcloud_ts); + } + + if (pointcloud == nullptr) + { + // todo + // RCLCPP_WARN_STREAM(logger_, "Empty cloud parsed."); + return; + }; + + cloud_watchdog_->update(); + + // Publish scan message only if it has been written to + if (current_scan_msg_ && !current_scan_msg_->packets.empty()) + { + packets_pub_->publish(std::move(current_scan_msg_)); + current_scan_msg_ = std::make_unique(); + } + + if (nebula_points_pub_->get_subscription_count() > 0 || + nebula_points_pub_->get_intra_process_subscription_count() > 0) + { + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); + } + if (aw_points_base_pub_->get_subscription_count() > 0 || + aw_points_base_pub_->get_intra_process_subscription_count() > 0) + { + const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); + } + if (aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) + { + const auto autoware_ex_cloud = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); + } +} + +void VelodyneDecoderWrapper::PublishCloud(std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr& publisher) +{ + if (pointcloud->header.stamp.sec < 0) + { + RCLCPP_WARN_STREAM(logger_, "Timestamp error, verify clock source."); + } + pointcloud->header.frame_id = sensor_cfg_->frame_id; + publisher->publish(std::move(pointcloud)); +} + +nebula::Status VelodyneDecoderWrapper::Status() +{ + std::lock_guard lock(mtx_driver_ptr_); + + if (!driver_ptr_) + { + return nebula::Status::NOT_INITIALIZED; + } + + return driver_ptr_->GetStatus(); +} +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp new file mode 100644 index 000000000..57e1cd927 --- /dev/null +++ b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp @@ -0,0 +1,55 @@ +#include "nebula_ros/velodyne/hw_interface_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ + +VelodyneHwInterfaceWrapper::VelodyneHwInterfaceWrapper( + rclcpp::Node* const parent_node, std::shared_ptr& config) + : hw_interface_(new nebula::drivers::VelodyneHwInterface()) + , logger_(parent_node->get_logger().get_child("HwInterfaceWrapper")) + , status_(Status::NOT_INITIALIZED) +{ + setup_sensor_ = parent_node->declare_parameter("setup_sensor", true, param_read_only()); + + hw_interface_->SetLogger(std::make_shared(parent_node->get_logger().get_child("HwInterface"))); + status_ = hw_interface_->InitializeSensorConfiguration(config); + + if (status_ != Status::OK) { + throw std::runtime_error((std::stringstream{} << "Could not initialize HW interface: " << status_).str()); + } + + if (setup_sensor_) { + RCLCPP_INFO_STREAM(logger_, "Setting sensor configuration"); + status_ = hw_interface_->SetSensorConfiguration(config); + } + + if (status_ != Status::OK) { + throw std::runtime_error((std::stringstream{} << "Could not set sensor configuration: " << status_).str()); + } + + status_ = Status::OK; +} + +void VelodyneHwInterfaceWrapper::OnConfigChange( + const std::shared_ptr& new_config) +{ + hw_interface_->InitializeSensorConfiguration(new_config); + if (setup_sensor_) { + hw_interface_->SetSensorConfiguration(new_config); + } +} + +Status VelodyneHwInterfaceWrapper::Status() +{ + return status_; +} + +std::shared_ptr VelodyneHwInterfaceWrapper::HwInterface() const +{ + return hw_interface_; +} + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp similarity index 55% rename from nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp rename to nebula_ros/src/velodyne/hw_monitor_wrapper.cpp index 172e61c83..17d02c42c 100644 --- a/nebula_ros/src/velodyne/velodyne_hw_monitor_ros_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp @@ -1,126 +1,27 @@ -#include "nebula_ros/velodyne/velodyne_hw_monitor_ros_wrapper.hpp" - -#include -#include - -#include -#include - -#include +#include "nebula_ros/velodyne/hw_monitor_wrapper.hpp" namespace nebula { namespace ros { -VelodyneHwMonitorRosWrapper::VelodyneHwMonitorRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("velodyne_hw_monitor_ros_wrapper", options), - hw_interface_(), - diagnostics_updater_(this) -{ - cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); - cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - - if (mtx_config_.try_lock()) { - interface_status_ = GetParameters(sensor_configuration_); - mtx_config_.unlock(); - } - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - // Initialize sensor_configuration - RCLCPP_INFO_STREAM(this->get_logger(), "Initialize sensor_configuration"); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - RCLCPP_INFO_STREAM(this->get_logger(), "hw_interface_.InitializeSensorConfiguration"); - hw_interface_.InitializeSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&VelodyneHwMonitorRosWrapper::paramCallback, this, std::placeholders::_1)); - - key_volt_temp_top_hv = "volt_temp.top.hv"; - key_volt_temp_top_ad_temp = "volt_temp.top.ad_temp"; // only32 - key_volt_temp_top_lm20_temp = "volt_temp.top.lm20_temp"; - key_volt_temp_top_pwr_5v = "volt_temp.top.pwr_5v"; - key_volt_temp_top_pwr_2_5v = "volt_temp.top.pwr_2_5v"; - key_volt_temp_top_pwr_3_3v = "volt_temp.top.pwr_3_3v"; - key_volt_temp_top_pwr_5v_raw = "volt_temp.top.pwr_5v_raw"; // only16 - key_volt_temp_top_pwr_raw = "volt_temp.top.pwr_raw"; // only32 - key_volt_temp_top_pwr_vccint = "volt_temp.top.pwr_vccint"; - key_volt_temp_bot_i_out = "volt_temp.bot.i_out"; - key_volt_temp_bot_pwr_1_2v = "volt_temp.bot.pwr_1_2v"; - key_volt_temp_bot_lm20_temp = "volt_temp.bot.lm20_temp"; - key_volt_temp_bot_pwr_5v = "volt_temp.bot.pwr_5v"; - key_volt_temp_bot_pwr_2_5v = "volt_temp.bot.pwr_2_5v"; - key_volt_temp_bot_pwr_3_3v = "volt_temp.bot.pwr_3_3v"; - key_volt_temp_bot_pwr_v_in = "volt_temp.bot.pwr_v_in"; - key_volt_temp_bot_pwr_1_25v = "volt_temp.bot.pwr_1_25v"; - key_vhv = "vhv"; - key_adc_nf = "adc_nf"; - key_adc_stats = "adc_stats"; - key_ixe = "ixe"; - key_adctp_stat = "adctp_stat"; - key_status_gps_pps_state = "gps.pps_state"; - key_status_gps_pps_position = "gps.position"; - key_status_motor_state = "motor.state"; - key_status_motor_rpm = "motor.rpm"; - key_status_motor_lock = "motor.lock"; - key_status_motor_phase = "motor.phase"; - key_status_laser_state = "laser.state"; - - name_volt_temp_top_hv = "Top HV"; - name_volt_temp_top_ad_temp = "Top A/D TD"; - name_volt_temp_top_lm20_temp = "Top Temp"; - name_volt_temp_top_pwr_5v = "Top 5v"; - name_volt_temp_top_pwr_2_5v = "Top 2.5v"; - name_volt_temp_top_pwr_3_3v = "Top 3.3v"; - name_volt_temp_top_pwr_5v_raw = "Top 5v(RAW)"; - name_volt_temp_top_pwr_raw = "Top RAW"; - name_volt_temp_top_pwr_vccint = "Top VCCINT"; - name_volt_temp_bot_i_out = "Bot I out"; - name_volt_temp_bot_pwr_1_2v = "Bot 1.2v"; - name_volt_temp_bot_lm20_temp = "Bot Temp"; - name_volt_temp_bot_pwr_5v = "Bot 5v"; - name_volt_temp_bot_pwr_2_5v = "Bot 2.5v"; - name_volt_temp_bot_pwr_3_3v = "Bot 3.3v"; - name_volt_temp_bot_pwr_v_in = "Bot V in"; - name_volt_temp_bot_pwr_1_25v = "Bot 1.25v"; // N/A? - name_vhv = "VHV"; - name_adc_nf = "adc_nf"; - name_adc_stats = "adc_stats"; - name_ixe = "ixe"; - name_adctp_stat = "adctp_stat"; - name_status_gps_pps_state = "GPS PPS"; - name_status_gps_pps_position = "GPS Position"; - name_status_motor_state = "Motor State"; - name_status_motor_rpm = "Motor RPM"; - name_status_motor_lock = "Motor Lock"; - name_status_motor_phase = "Motor Phase"; - name_status_laser_state = "Laser State"; - - message_sep = ": "; - - not_supported_message = "Not supported"; - error_message = "Error"; - - key_info_model = "info.model"; - key_info_serial = "info.serial"; - - temperature_cold_message = "temperature cold"; - temperature_hot_message = "temperature hot"; - voltage_low_message = "voltage low"; - voltage_high_message = "voltage high"; - ampere_low_message = "ampere low"; - ampere_high_message = "ampere high"; +VelodyneHwMonitorWrapper::VelodyneHwMonitorWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config) + : logger_(parent_node->get_logger().get_child("HwMonitor")) + , diagnostics_updater_(parent_node) + , status_(Status::OK) + , hw_interface_(hw_interface) + , parent_node_(parent_node) + , sensor_configuration_(config) +{ + diag_span_ = parent_node->declare_parameter("diag_span", 1000, param_read_only()); + show_advanced_diagnostics_ = parent_node->declare_parameter("advanced_diagnostics", false, param_read_only()); std::cout << "Get model name and serial." << std::endl; - hw_interface_.GetSnapshotAsync([this](const std::string & str) { - current_snapshot_time.reset(new rclcpp::Time(this->get_clock()->now())); + hw_interface_->GetSnapshotAsync([this](const std::string & str) { + current_snapshot_time.reset(new rclcpp::Time(parent_node_->now())); current_snapshot_tree = - std::make_shared(hw_interface_.ParseJson(str)); + std::make_shared(hw_interface_->ParseJson(str)); current_diag_tree = std::make_shared(current_snapshot_tree->get_child("diag")); current_status_tree = @@ -128,14 +29,12 @@ VelodyneHwMonitorRosWrapper::VelodyneHwMonitorRosWrapper(const rclcpp::NodeOptio current_snapshot.reset(new std::string(str)); try { - info_model = GetPtreeValue(current_snapshot_tree, key_info_model); - info_serial = GetPtreeValue(current_snapshot_tree, key_info_serial); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); + info_model_ = GetPtreeValue(current_snapshot_tree, key_info_model); + info_serial_ = GetPtreeValue(current_snapshot_tree, key_info_serial); + RCLCPP_INFO_STREAM(logger_, "Model:" << info_model_); + RCLCPP_INFO_STREAM(logger_, "Serial:" << info_serial_); } catch (boost::bad_lexical_cast & ex) { - RCLCPP_ERROR_STREAM( - this->get_logger(), this->get_name() << " Error:" - << "Can't get model and serial"); + RCLCPP_ERROR(logger_, " Error: Can't get model and serial"); return; } @@ -143,484 +42,179 @@ VelodyneHwMonitorRosWrapper::VelodyneHwMonitorRosWrapper(const rclcpp::NodeOptio }); } -Status VelodyneHwMonitorRosWrapper::MonitorStart() { return interface_status_; } - -Status VelodyneHwMonitorRosWrapper::MonitorStop() { return Status::OK; } -Status VelodyneHwMonitorRosWrapper::Shutdown() { return Status::OK; } - -Status VelodyneHwMonitorRosWrapper::InitializeHwMonitor( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) +void VelodyneHwMonitorWrapper::InitializeVelodyneDiagnostics() { - std::stringstream ss; - ss << sensor_configuration; - RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); - return Status::OK; -} - -Status VelodyneHwMonitorRosWrapper::GetParameters( - drivers::VelodyneSensorConfiguration & sensor_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = - nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "velodyne", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "range from 300 to 1200, in increments of 60"; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(300).set__to_value(1200).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 600, descriptor); - sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { // || - return Status::SENSOR_CONFIG_ERROR; - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "It may be safe if it is 5000 milliseconds or more..."; - this->declare_parameter("diag_span", 3000, descriptor); - diag_span_ = this->get_parameter("diag_span").as_int(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; // because it affects initialization - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Showing advanced diagnostics"; - this->declare_parameter("advanced_diagnostics", false, descriptor); - use_advanced_diagnostics = this->get_parameter("advanced_diagnostics").as_bool(); - } - - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); - - return Status::OK; -} - -void VelodyneHwMonitorRosWrapper::InitializeVelodyneDiagnostics() -{ - RCLCPP_INFO_STREAM(get_logger(), "InitializeVelodyneDiagnostics"); + RCLCPP_INFO_STREAM(logger_, "InitializeVelodyneDiagnostics"); using std::chrono_literals::operator""s; std::ostringstream os; - auto hardware_id = info_model + ": " + info_serial; + auto hardware_id = info_model_ + ": " + info_serial_; diagnostics_updater_.setHardwareID(hardware_id); - RCLCPP_INFO_STREAM(get_logger(), "hardware_id" << hardware_id); + RCLCPP_INFO_STREAM(logger_, "hardware_id" << hardware_id); - if (use_advanced_diagnostics) { + if (show_advanced_diagnostics_) { diagnostics_updater_.add( - "velodyne_snapshot-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckSnapshot); + "velodyne_snapshot-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckSnapshot); diagnostics_updater_.add( - "velodyne_volt_temp_top_hv-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckTopHv); - if (sensor_configuration_.sensor_model != nebula::drivers::SensorModel::VELODYNE_VLP16) { + "velodyne_volt_temp_top_hv-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckTopHv); + if (sensor_configuration_->sensor_model != nebula::drivers::SensorModel::VELODYNE_VLP16) { diagnostics_updater_.add( - "velodyne_volt_temp_top_ad_temp-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckTopAdTemp); + "velodyne_volt_temp_top_ad_temp-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckTopAdTemp); } diagnostics_updater_.add( - "velodyne_volt_temp_top_lm20_temp-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckTopLm20Temp); + "velodyne_volt_temp_top_lm20_temp-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckTopLm20Temp); diagnostics_updater_.add( - "velodyne_volt_temp_top_pwr_5v-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwr5v); + "velodyne_volt_temp_top_pwr_5v-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckTopPwr5v); diagnostics_updater_.add( - "velodyne_volt_temp_top_pwr_2_5v-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwr25v); + "velodyne_volt_temp_top_pwr_2_5v-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckTopPwr25v); diagnostics_updater_.add( - "velodyne_volt_temp_top_pwr_3_3v-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwr33v); + "velodyne_volt_temp_top_pwr_3_3v-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckTopPwr33v); diagnostics_updater_.add( - "velodyne_volt_temp_top_pwr_raw-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwrRaw); + "velodyne_volt_temp_top_pwr_raw-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckTopPwrRaw); diagnostics_updater_.add( - "velodyne_volt_temp_top_pwr_vccint-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwrVccint); + "velodyne_volt_temp_top_pwr_vccint-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckTopPwrVccint); diagnostics_updater_.add( - "velodyne_volt_temp_bot_i_out-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckBotIOut); + "velodyne_volt_temp_bot_i_out-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckBotIOut); diagnostics_updater_.add( - "velodyne_volt_temp_bot_pwr_1_2v-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr12v); + "velodyne_volt_temp_bot_pwr_1_2v-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckBotPwr12v); diagnostics_updater_.add( - "velodyne_volt_temp_bot_lm20_temp-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckBotLm20Temp); + "velodyne_volt_temp_bot_lm20_temp-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckBotLm20Temp); diagnostics_updater_.add( - "velodyne_volt_temp_bot_pwr_5v-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr5v); + "velodyne_volt_temp_bot_pwr_5v-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckBotPwr5v); diagnostics_updater_.add( - "velodyne_volt_temp_bot_pwr_2_5v-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr25v); + "velodyne_volt_temp_bot_pwr_2_5v-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckBotPwr25v); diagnostics_updater_.add( - "velodyne_volt_temp_bot_pwr_3_3v-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr33v); + "velodyne_volt_temp_bot_pwr_3_3v-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckBotPwr33v); diagnostics_updater_.add( - "velodyne_volt_temp_bot_pwr_v_in-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwrVIn); + "velodyne_volt_temp_bot_pwr_v_in-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckBotPwrVIn); diagnostics_updater_.add( - "velodyne_volt_temp_bot_pwr_1_25v-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr125v); + "velodyne_volt_temp_bot_pwr_1_25v-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckBotPwr125v); diagnostics_updater_.add( - "velodyne_vhv-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckVhv); + "velodyne_vhv-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckVhv); diagnostics_updater_.add( - "velodyne_adc_nf-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckAdcNf); + "velodyne_adc_nf-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckAdcNf); diagnostics_updater_.add( - "velodyne_adc_stats-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckAdcStats); + "velodyne_adc_stats-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckAdcStats); diagnostics_updater_.add( - "velodyne_ixe-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckIxe); + "velodyne_ixe-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckIxe); diagnostics_updater_.add( - "velodyne_adctp_stat-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckAdctpStat); + "velodyne_adctp_stat-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckAdctpStat); diagnostics_updater_.add( - "velodyne_status_gps_pps_state-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckGpsPpsState); + "velodyne_status_gps_pps_state-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckGpsPpsState); diagnostics_updater_.add( - "velodyne_status_gps_pps_position-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckGpsPosition); + "velodyne_status_gps_pps_position-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckGpsPosition); diagnostics_updater_.add( - "velodyne_status_motor_state-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckMotorState); + "velodyne_status_motor_state-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckMotorState); diagnostics_updater_.add( - "velodyne_status_motor_rpm-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckMotorRpm); + "velodyne_status_motor_rpm-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckMotorRpm); diagnostics_updater_.add( - "velodyne_status_motor_lock-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckMotorLock); + "velodyne_status_motor_lock-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckMotorLock); diagnostics_updater_.add( - "velodyne_status_motor_phase-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckMotorPhase); + "velodyne_status_motor_phase-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckMotorPhase); diagnostics_updater_.add( - "velodyne_status_laser_state-" + sensor_configuration_.frame_id, this, - &VelodyneHwMonitorRosWrapper::VelodyneCheckLaserState); + "velodyne_status_laser_state-" + sensor_configuration_->frame_id, this, + &VelodyneHwMonitorWrapper::VelodyneCheckLaserState); } diagnostics_updater_.add( - "velodyne_status", this, &VelodyneHwMonitorRosWrapper::VelodyneCheckStatus); - diagnostics_updater_.add("velodyne_pps", this, &VelodyneHwMonitorRosWrapper::VelodyneCheckPps); + "velodyne_status", this, &VelodyneHwMonitorWrapper::VelodyneCheckStatus); + diagnostics_updater_.add("velodyne_pps", this, &VelodyneHwMonitorWrapper::VelodyneCheckPps); diagnostics_updater_.add( - "velodyne_temperature", this, &VelodyneHwMonitorRosWrapper::VelodyneCheckTemperature); - diagnostics_updater_.add("velodyne_rpm", this, &VelodyneHwMonitorRosWrapper::VelodyneCheckRpm); + "velodyne_temperature", this, &VelodyneHwMonitorWrapper::VelodyneCheckTemperature); + diagnostics_updater_.add("velodyne_rpm", this, &VelodyneHwMonitorWrapper::VelodyneCheckRpm); diagnostics_updater_.add( - "velodyne_voltage", this, &VelodyneHwMonitorRosWrapper::VelodyneCheckVoltage); + "velodyne_voltage", this, &VelodyneHwMonitorWrapper::VelodyneCheckVoltage); current_snapshot.reset(new std::string("")); - current_snapshot_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_snapshot_time.reset(new rclcpp::Time(parent_node_->now())); current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; auto on_timer_snapshot = [this] { OnVelodyneSnapshotTimer(); }; - diagnostics_snapshot_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(on_timer_snapshot), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(diagnostics_snapshot_timer_, cbg_m_); + diagnostics_snapshot_timer_ = parent_node_->create_wall_timer(std::chrono::milliseconds(diag_span_), std::move(on_timer_snapshot)); auto on_timer_update = [this] { - auto now = this->get_clock()->now(); + auto now = parent_node_->now(); auto dif = (now - *current_snapshot_time).seconds(); if (diag_span_ * 2.0 < dif * 1000) { current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); + RCLCPP_DEBUG_STREAM(logger_, "STALE"); } else { current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); + RCLCPP_DEBUG_STREAM(logger_, "OK"); } diagnostics_updater_.force_update(); }; - diagnostics_update_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(1000), std::move(on_timer_update), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(diagnostics_update_timer_, cbg_r_); -} - -std::string VelodyneHwMonitorRosWrapper::GetPtreeValue( - std::shared_ptr pt, const std::string & key) -{ - boost::optional value = pt->get_optional(key); - if (value) { - return value.get(); - } else { - return not_supported_message; - } -} -std::string VelodyneHwMonitorRosWrapper::GetFixedPrecisionString(double val, int pre) -{ - std::stringstream ss; - ss << std::fixed << std::setprecision(pre) << val; - return ss.str(); + diagnostics_update_timer_ = parent_node_->create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); } -// https://memo.appri.me/programming/cpp-curl-http-client -using namespace std; -typedef void (*CurlCallback)(string err, string body); - -class Curl -{ -private: - /** response body */ - string body; - - // see: https://curl.se/docs/faq.html#Using_C_non_static_functions_f - static size_t invoke_write_data(char * buffer, size_t size, size_t nmemb, void * f) - { - // Call non-static member function. - return static_cast(f)->write_data(buffer, size, nmemb, f); - } - - /** a callback function for libcurl request */ - size_t write_data(char * buffer, size_t size, size_t nmemb, void *) - { - int dataLength = size * nmemb; - this->body.append(buffer, dataLength); - return dataLength; - } - -public: - /** user-agent */ - string useragent = "libcurl-agent/1.0"; - /** timeout */ - int timeout = 30L; // timeout 30 seconds - - /** - * Constructor - */ - Curl() - { - // - } - - /** - * HTTP GET - */ - void get(const string url, const CurlCallback cb) - { - CURL * curl; - CURLcode ret; - - this->body = ""; // init result body. - string err = ""; - - curl_global_init(CURL_GLOBAL_ALL); - curl = curl_easy_init(); - - if (curl == NULL) { - err = "curl_easy_init() failed on " + url; - return cb(err, ""); - } - - curl_easy_setopt(curl, CURLOPT_URL, url.c_str()); - curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, this->invoke_write_data); - curl_easy_setopt(curl, CURLOPT_WRITEDATA, this); - curl_easy_setopt(curl, CURLOPT_USERAGENT, this->useragent.c_str()); // UA - curl_easy_setopt(curl, CURLOPT_TIMEOUT, this->timeout); // timeout - // curl_easy_setopt(curl, CURLOPT_VERBOSE, 1L); // verbose - ret = curl_easy_perform(curl); - curl_easy_cleanup(curl); - curl_global_cleanup(); - - if (ret != CURLE_OK) { - err = "curl_easy_perform() failed on " + url + " (ret:" + to_string(ret) + ")"; - return cb(err, ""); - } - return cb(err, this->body); - } - - /** - * HTTP POST - */ - void post(const string url, const string data, const CurlCallback cb) - { - CURL * curl; - CURLcode ret; - - this->body = ""; // init result body. - string err = ""; - - curl_global_init(CURL_GLOBAL_ALL); - curl = curl_easy_init(); - - if (curl == NULL) { - err = "curl_easy_init() failed on " + url; - return cb(err, ""); - } - - curl_easy_setopt(curl, CURLOPT_URL, url.c_str()); - curl_easy_setopt(curl, CURLOPT_POST, 1); - curl_easy_setopt(curl, CURLOPT_POSTFIELDS, data.c_str()); - curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, this->invoke_write_data); - curl_easy_setopt(curl, CURLOPT_WRITEDATA, this); - curl_easy_setopt(curl, CURLOPT_USERAGENT, this->useragent.c_str()); // UA - curl_easy_setopt(curl, CURLOPT_TIMEOUT, this->timeout); // timeout - // curl_easy_setopt(curl, CURLOPT_VERBOSE, 1L); // verbose - ret = curl_easy_perform(curl); - curl_easy_cleanup(curl); - curl_global_cleanup(); - - if (ret != CURLE_OK) { - err = "curl_easy_perform() failed on " + url + " (ret:" + to_string(ret) + ")"; - return cb(err, ""); - } - return cb(err, this->body); - } -}; - -void VelodyneHwMonitorRosWrapper::curl_callback(std::string err, std::string body) +void VelodyneHwMonitorWrapper::OnVelodyneSnapshotTimer() { - if (err != "") { - RCLCPP_ERROR_STREAM(get_logger(), "curl_callback:" << err); - } else { - RCLCPP_INFO_STREAM(get_logger(), body); + hw_interface_->GetSnapshotAsync([this](const std::string & str) { + current_snapshot_time.reset(new rclcpp::Time(parent_node_->now())); + current_snapshot_tree = + std::make_shared(hw_interface_->ParseJson(str)); current_diag_tree = - std::make_shared(hw_interface_.ParseJson(body)); - RCLCPP_DEBUG_STREAM(get_logger(), "diagnostics_updater_.force_update()"); - diagnostics_updater_.force_update(); - } + std::make_shared(current_snapshot_tree->get_child("diag")); + current_status_tree = + std::make_shared(current_snapshot_tree->get_child("status")); + current_snapshot.reset(new std::string(str)); + }); } -void VelodyneHwMonitorRosWrapper::OnVelodyneDiagnosticsTimer() +void VelodyneHwMonitorWrapper::OnVelodyneDiagnosticsTimer() { std::cout << "OnVelodyneDiagnosticsTimer" << std::endl; - if (mtx_diag.try_lock() || true) { + if (tm_diag_.try_lock_for(std::chrono::milliseconds(500))) { std::cout << "mtx_diag lock" << std::endl; - hw_interface_.GetDiagAsync([this](const std::string & str) { + hw_interface_->GetDiagAsync([this](const std::string & str) { current_diag_tree = - std::make_shared(hw_interface_.ParseJson(str)); + std::make_shared(hw_interface_->ParseJson(str)); diagnostics_updater_.force_update(); - mtx_diag.unlock(); + tm_diag_.unlock(); std::cout << "mtx_diag unlock" << std::endl; }); + + if (!tm_diag_.try_lock_for(std::chrono::milliseconds(500))) { + RCLCPP_ERROR(logger_, "GetDiagAsync callback timed out"); + return; + } + + tm_diag_.unlock(); } else { - std::cout << "mtx_diag is locked..." << std::endl; + RCLCPP_ERROR(logger_, "Wait for GetDiagAsync mutex timed out"); } } -std::tuple VelodyneHwMonitorRosWrapper::VelodyneGetTopHv() +std::tuple VelodyneHwMonitorWrapper::VelodyneGetTopHv() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -647,7 +241,7 @@ std::tuple VelodyneHwMonitorRosWrapper: } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetTopAdTemp() +VelodyneHwMonitorWrapper::VelodyneGetTopAdTemp() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -667,7 +261,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetTopAdTemp() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetTopLm20Temp() +VelodyneHwMonitorWrapper::VelodyneGetTopLm20Temp() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -696,7 +290,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetTopLm20Temp() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetTopPwr5v() +VelodyneHwMonitorWrapper::VelodyneGetTopPwr5v() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -723,7 +317,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetTopPwr5v() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetTopPwr25v() +VelodyneHwMonitorWrapper::VelodyneGetTopPwr25v() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -750,7 +344,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetTopPwr25v() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetTopPwr33v() +VelodyneHwMonitorWrapper::VelodyneGetTopPwr33v() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -777,7 +371,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetTopPwr33v() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetTopPwr5vRaw() +VelodyneHwMonitorWrapper::VelodyneGetTopPwr5vRaw() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -805,7 +399,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetTopPwr5vRaw() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetTopPwrRaw() +VelodyneHwMonitorWrapper::VelodyneGetTopPwrRaw() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -832,7 +426,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetTopPwrRaw() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetTopPwrVccint() +VelodyneHwMonitorWrapper::VelodyneGetTopPwrVccint() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -861,7 +455,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetTopPwrVccint() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetBotIOut() +VelodyneHwMonitorWrapper::VelodyneGetBotIOut() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -888,7 +482,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetBotIOut() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr12v() +VelodyneHwMonitorWrapper::VelodyneGetBotPwr12v() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -915,7 +509,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr12v() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetBotLm20Temp() +VelodyneHwMonitorWrapper::VelodyneGetBotLm20Temp() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -944,7 +538,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetBotLm20Temp() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr5v() +VelodyneHwMonitorWrapper::VelodyneGetBotPwr5v() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -971,7 +565,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr5v() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr25v() +VelodyneHwMonitorWrapper::VelodyneGetBotPwr25v() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -998,7 +592,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr25v() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr33v() +VelodyneHwMonitorWrapper::VelodyneGetBotPwr33v() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1025,7 +619,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr33v() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetBotPwrVIn() +VelodyneHwMonitorWrapper::VelodyneGetBotPwrVIn() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1052,7 +646,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetBotPwrVIn() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr125v() +VelodyneHwMonitorWrapper::VelodyneGetBotPwr125v() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1079,7 +673,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetBotPwr125v() return std::make_tuple(not_ex, level, mes, error_mes); } -std::tuple VelodyneHwMonitorRosWrapper::VelodyneGetVhv() +std::tuple VelodyneHwMonitorWrapper::VelodyneGetVhv() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1097,7 +691,7 @@ std::tuple VelodyneHwMonitorRosWrapper: return std::make_tuple(not_ex, level, mes, error_mes); } -std::tuple VelodyneHwMonitorRosWrapper::VelodyneGetAdcNf() +std::tuple VelodyneHwMonitorWrapper::VelodyneGetAdcNf() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1125,7 +719,7 @@ std::tuple VelodyneHwMonitorRosWrapper: } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetAdcStats() +VelodyneHwMonitorWrapper::VelodyneGetAdcStats() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1155,7 +749,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetAdcStats() return std::make_tuple(not_ex, level, mes, error_mes); } -std::tuple VelodyneHwMonitorRosWrapper::VelodyneGetIxe() +std::tuple VelodyneHwMonitorWrapper::VelodyneGetIxe() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1172,7 +766,7 @@ std::tuple VelodyneHwMonitorRosWrapper: } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetAdctpStat() +VelodyneHwMonitorWrapper::VelodyneGetAdctpStat() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1200,7 +794,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetAdctpStat() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetGpsPpsState() +VelodyneHwMonitorWrapper::VelodyneGetGpsPpsState() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1224,7 +818,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetGpsPpsState() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetGpsPosition() +VelodyneHwMonitorWrapper::VelodyneGetGpsPosition() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1241,7 +835,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetGpsPosition() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetMotorState() +VelodyneHwMonitorWrapper::VelodyneGetMotorState() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1258,7 +852,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetMotorState() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetMotorRpm() +VelodyneHwMonitorWrapper::VelodyneGetMotorRpm() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1275,7 +869,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetMotorRpm() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetMotorLock() +VelodyneHwMonitorWrapper::VelodyneGetMotorLock() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1292,7 +886,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetMotorLock() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetMotorPhase() +VelodyneHwMonitorWrapper::VelodyneGetMotorPhase() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1309,7 +903,7 @@ VelodyneHwMonitorRosWrapper::VelodyneGetMotorPhase() } std::tuple -VelodyneHwMonitorRosWrapper::VelodyneGetLaserState() +VelodyneHwMonitorWrapper::VelodyneGetLaserState() { bool not_ex = true; uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; @@ -1325,383 +919,373 @@ VelodyneHwMonitorRosWrapper::VelodyneGetLaserState() return std::make_tuple(not_ex, level, mes, error_mes); } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTopHv( +void VelodyneHwMonitorWrapper::VelodyneCheckTopHv( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetTopHv(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTopAdTemp( +void VelodyneHwMonitorWrapper::VelodyneCheckTopAdTemp( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetTopAdTemp(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTopLm20Temp( +void VelodyneHwMonitorWrapper::VelodyneCheckTopLm20Temp( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetTopLm20Temp(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwr5v( +void VelodyneHwMonitorWrapper::VelodyneCheckTopPwr5v( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetTopPwr5v(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwr25v( +void VelodyneHwMonitorWrapper::VelodyneCheckTopPwr25v( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetTopPwr25v(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwr33v( +void VelodyneHwMonitorWrapper::VelodyneCheckTopPwr33v( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetTopPwr33v(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwrRaw( +void VelodyneHwMonitorWrapper::VelodyneCheckTopPwrRaw( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetTopPwrRaw(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTopPwrVccint( +void VelodyneHwMonitorWrapper::VelodyneCheckTopPwrVccint( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetTopPwrVccint(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckBotIOut( +void VelodyneHwMonitorWrapper::VelodyneCheckBotIOut( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetBotIOut(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr12v( +void VelodyneHwMonitorWrapper::VelodyneCheckBotPwr12v( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetBotPwr12v(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckBotLm20Temp( +void VelodyneHwMonitorWrapper::VelodyneCheckBotLm20Temp( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetBotLm20Temp(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr5v( +void VelodyneHwMonitorWrapper::VelodyneCheckBotPwr5v( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetBotPwr5v(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr25v( +void VelodyneHwMonitorWrapper::VelodyneCheckBotPwr25v( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetBotPwr25v(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr33v( +void VelodyneHwMonitorWrapper::VelodyneCheckBotPwr33v( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetBotPwr33v(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwrVIn( +void VelodyneHwMonitorWrapper::VelodyneCheckBotPwrVIn( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetBotPwrVIn(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckBotPwr125v( +void VelodyneHwMonitorWrapper::VelodyneCheckBotPwr125v( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetBotPwr125v(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckVhv( +void VelodyneHwMonitorWrapper::VelodyneCheckVhv( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetVhv(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckAdcNf( +void VelodyneHwMonitorWrapper::VelodyneCheckAdcNf( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetAdcNf(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckAdcStats( +void VelodyneHwMonitorWrapper::VelodyneCheckAdcStats( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetAdcStats(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckIxe( +void VelodyneHwMonitorWrapper::VelodyneCheckIxe( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetIxe(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckAdctpStat( +void VelodyneHwMonitorWrapper::VelodyneCheckAdctpStat( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { auto tpl = VelodyneGetAdctpStat(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::OnVelodyneStatusTimer() +void VelodyneHwMonitorWrapper::OnVelodyneStatusTimer() { - if (mtx_status.try_lock()) { - hw_interface_.GetStatusAsync([this](const std::string & str) { - current_status_tree = - std::make_shared(hw_interface_.ParseJson(str)); - diagnostics_updater_.force_update(); - mtx_status.unlock(); - }); + tm_status_.lock(); + hw_interface_->GetStatusAsync([this](const std::string & str) { + current_status_tree = + std::make_shared(hw_interface_->ParseJson(str)); + diagnostics_updater_.force_update(); + tm_status_.unlock(); + }); + + if (!tm_status_.try_lock_for(std::chrono::seconds(1))) { + RCLCPP_ERROR(logger_, "Sensor status request timed out!"); } + + tm_status_.unlock(); } -void VelodyneHwMonitorRosWrapper::VelodyneCheckGpsPpsState( +void VelodyneHwMonitorWrapper::VelodyneCheckGpsPpsState( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { auto tpl = VelodyneGetGpsPpsState(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckGpsPosition( +void VelodyneHwMonitorWrapper::VelodyneCheckGpsPosition( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { auto tpl = VelodyneGetGpsPosition(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckMotorState( +void VelodyneHwMonitorWrapper::VelodyneCheckMotorState( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { auto tpl = VelodyneGetMotorState(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckMotorRpm( +void VelodyneHwMonitorWrapper::VelodyneCheckMotorRpm( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { auto tpl = VelodyneGetMotorRpm(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckMotorLock( +void VelodyneHwMonitorWrapper::VelodyneCheckMotorLock( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { auto tpl = VelodyneGetMotorLock(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckMotorPhase( +void VelodyneHwMonitorWrapper::VelodyneCheckMotorPhase( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { auto tpl = VelodyneGetMotorPhase(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckLaserState( +void VelodyneHwMonitorWrapper::VelodyneCheckLaserState( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { auto tpl = VelodyneGetLaserState(); - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(std::get<1>(tpl), std::get<2>(tpl)); } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckSnapshot( +void VelodyneHwMonitorWrapper::VelodyneCheckSnapshot( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { uint8_t level = current_diag_status; - diagnostics.add("sensor", sensor_configuration_.frame_id); + diagnostics.add("sensor", sensor_configuration_->frame_id); diagnostics.summary(level, *current_snapshot); - // } } -void VelodyneHwMonitorRosWrapper::OnVelodyneSnapshotTimer() -{ - hw_interface_.GetSnapshotAsync([this](const std::string & str) { - current_snapshot_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_snapshot_tree = - std::make_shared(hw_interface_.ParseJson(str)); - current_diag_tree = - std::make_shared(current_snapshot_tree->get_child("diag")); - current_status_tree = - std::make_shared(current_snapshot_tree->get_child("status")); - current_snapshot.reset(new std::string(str)); - }); -} - -void VelodyneHwMonitorRosWrapper::VelodyneCheckStatus( +void VelodyneHwMonitorWrapper::VelodyneCheckStatus( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; @@ -1727,12 +1311,12 @@ void VelodyneHwMonitorRosWrapper::VelodyneCheckStatus( } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckPps( +void VelodyneHwMonitorWrapper::VelodyneCheckPps( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_status_tree && - !VelodyneHwMonitorRosWrapper::current_status_tree->empty()) { + VelodyneHwMonitorWrapper::current_status_tree && + !VelodyneHwMonitorWrapper::current_status_tree->empty()) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; @@ -1758,12 +1342,12 @@ void VelodyneHwMonitorRosWrapper::VelodyneCheckPps( } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckTemperature( +void VelodyneHwMonitorWrapper::VelodyneCheckTemperature( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; @@ -1789,12 +1373,12 @@ void VelodyneHwMonitorRosWrapper::VelodyneCheckTemperature( } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckRpm( +void VelodyneHwMonitorWrapper::VelodyneCheckRpm( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; @@ -1820,12 +1404,12 @@ void VelodyneHwMonitorRosWrapper::VelodyneCheckRpm( } } -void VelodyneHwMonitorRosWrapper::VelodyneCheckVoltage( +void VelodyneHwMonitorWrapper::VelodyneCheckVoltage( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { if ( - VelodyneHwMonitorRosWrapper::current_diag_tree && - !VelodyneHwMonitorRosWrapper::current_diag_tree->empty()) { + VelodyneHwMonitorWrapper::current_diag_tree && + !VelodyneHwMonitorWrapper::current_diag_tree->empty()) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; @@ -1865,7 +1449,7 @@ void VelodyneHwMonitorRosWrapper::VelodyneCheckVoltage( } diagnostics.add(name_volt_temp_top_pwr_3_3v, std::get<2>(tpl)); - if (sensor_configuration_.sensor_model == nebula::drivers::SensorModel::VELODYNE_VLP16) { + if (sensor_configuration_->sensor_model == nebula::drivers::SensorModel::VELODYNE_VLP16) { tpl = VelodyneGetTopPwr5vRaw(); if (std::get<0>(tpl)) { level = std::max(level, std::get<1>(tpl)); @@ -1961,36 +1545,27 @@ void VelodyneHwMonitorRosWrapper::VelodyneCheckVoltage( } } -rcl_interfaces::msg::SetParametersResult VelodyneHwMonitorRosWrapper::paramCallback( - const std::vector & p) +std::string VelodyneHwMonitorWrapper::GetPtreeValue( + std::shared_ptr pt, const std::string & key) { - std::scoped_lock lock(mtx_config_); - RCLCPP_INFO_STREAM(get_logger(), p); - RCLCPP_INFO_STREAM(get_logger(), sensor_configuration_); - - drivers::VelodyneSensorConfiguration new_param{sensor_configuration_}; - - std::cout << new_param << std::endl; - std::string sensor_model_str; - std::string return_mode_str; - uint16_t new_diag_span = 0; - if (get_param(p, "diag_span", new_diag_span)) { - sensor_configuration_ = new_param; - // Update sensor_configuration - RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - RCLCPP_INFO_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); + boost::optional value = pt->get_optional(key); + if (value) { + return value.get(); + } else { + return not_supported_message; } +} - auto result = std::make_shared(); - result->successful = true; - result->reason = "success"; - - std::cout << "add_on_set_parameters_callback success" << std::endl; +std::string VelodyneHwMonitorWrapper::GetFixedPrecisionString(double val, int pre) +{ + std::stringstream ss; + ss << std::fixed << std::setprecision(pre) << val; + return ss.str(); +} - return *result; +Status VelodyneHwMonitorWrapper::Status() +{ + return Status::NOT_IMPLEMENTED; // TODO } -RCLCPP_COMPONENTS_REGISTER_NODE(VelodyneHwMonitorRosWrapper) } // namespace ros -} // namespace nebula +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp deleted file mode 100644 index df484a27a..000000000 --- a/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp +++ /dev/null @@ -1,281 +0,0 @@ -#include "nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp" - -namespace nebula -{ -namespace ros -{ -VelodyneDriverRosWrapper::VelodyneDriverRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("velodyne_driver_ros_wrapper", options) -{ - drivers::VelodyneCalibrationConfiguration calibration_configuration; - drivers::VelodyneSensorConfiguration sensor_configuration; - - wrapper_status_ = GetParameters(sensor_configuration, calibration_configuration); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return; - } - RCLCPP_DEBUG_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - - calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); - - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); - - RCLCPP_DEBUG_STREAM(this->get_logger(), this->get_name() << ". Driver "); - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); - - RCLCPP_DEBUG_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); - - velodyne_scan_sub_ = create_subscription( - "velodyne_packets", rclcpp::SensorDataQoS(), - std::bind(&VelodyneDriverRosWrapper::ReceiveScanMsgCallback, this, std::placeholders::_1)); - nebula_points_pub_ = this->create_publisher( - "velodyne_points", rclcpp::SensorDataQoS()); - aw_points_base_pub_ = - this->create_publisher("aw_points", rclcpp::SensorDataQoS()); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", rclcpp::SensorDataQoS()); -} - -void VelodyneDriverRosWrapper::ReceiveScanMsgCallback( - const velodyne_msgs::msg::VelodyneScan::SharedPtr scan_msg) -{ - auto t_start = std::chrono::high_resolution_clock::now(); - - std::tuple pointcloud_ts = - driver_ptr_->ConvertScanToPointcloud(scan_msg); - nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - double cloud_stamp = std::get<1>(pointcloud_ts); - if (pointcloud == nullptr) { - RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); - return; - }; - if ( - nebula_points_pub_->get_subscription_count() > 0 || - nebula_points_pub_->get_intra_process_subscription_count() > 0) { - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); - } - if ( - aw_points_base_pub_->get_subscription_count() > 0 || - aw_points_base_pub_->get_intra_process_subscription_count() > 0) { - const auto autoware_cloud_xyzi = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); - } - if ( - aw_points_ex_pub_->get_subscription_count() > 0 || - aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - const auto autoware_ex_cloud = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, cloud_stamp); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); - } - - auto runtime = std::chrono::high_resolution_clock::now() - t_start; - RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); -} - -void VelodyneDriverRosWrapper::PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher) -{ - if (pointcloud->header.stamp.sec < 0) { - RCLCPP_WARN_STREAM(this->get_logger(), "Timestamp error, verify clock source."); - } - pointcloud->header.frame_id = sensor_cfg_ptr_->frame_id; - publisher->publish(std::move(pointcloud)); -} - -Status VelodyneDriverRosWrapper::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status VelodyneDriverRosWrapper::GetStatus() { return wrapper_status_; } - -Status VelodyneDriverRosWrapper::GetParameters( - drivers::VelodyneSensorConfiguration & sensor_configuration, - drivers::VelodyneCalibrationConfiguration & calibration_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = - nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "velodyne", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("calibration_file", "", descriptor); - calibration_configuration.calibration_file = - this->get_parameter("calibration_file").as_string(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("min_range", 0.3, descriptor); - sensor_configuration.min_range = this->get_parameter("min_range").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("max_range", 300., descriptor); - sensor_configuration.max_range = this->get_parameter("max_range").as_double(); - } - double view_direction; - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("view_direction", 0., descriptor); - view_direction = this->get_parameter("view_direction").as_double(); - } - double view_width = 2.0 * M_PI; - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("view_width", 2.0 * M_PI, descriptor); - view_width = this->get_parameter("view_width").as_double(); - } - - if (sensor_configuration.sensor_model != nebula::drivers::SensorModel::VELODYNE_HDL64) { - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - } else { - double min_angle = fmod(fmod(view_direction + view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI); - double max_angle = fmod(fmod(view_direction - view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI); - sensor_configuration.cloud_min_angle = 100 * (2 * M_PI - min_angle) * 180 / M_PI + 0.5; - sensor_configuration.cloud_max_angle = 100 * (2 * M_PI - max_angle) * 180 / M_PI + 0.5; - if (sensor_configuration.cloud_min_angle == sensor_configuration.cloud_max_angle) { - // avoid returning empty cloud if min_angle = max_angle - sensor_configuration.cloud_min_angle = 0; - sensor_configuration.cloud_max_angle = 36000; - } - } - - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { - return Status::SENSOR_CONFIG_ERROR; - } - - if (calibration_configuration.calibration_file.empty()) { - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = - calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), - "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); - return cal_status; - } - } - - RCLCPP_INFO_STREAM( - this->get_logger(), "Sensor model: " << sensor_configuration.sensor_model - << ", Return mode: " << sensor_configuration.return_mode - << ", Scan Phase: " << sensor_configuration.scan_phase); - return Status::OK; -} - -RCLCPP_COMPONENTS_REGISTER_NODE(VelodyneDriverRosWrapper) -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/src/velodyne/velodyne_hw_interface_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_hw_interface_ros_wrapper.cpp deleted file mode 100644 index cbbc19e05..000000000 --- a/nebula_ros/src/velodyne/velodyne_hw_interface_ros_wrapper.cpp +++ /dev/null @@ -1,326 +0,0 @@ -#include "nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp" - -namespace nebula -{ -namespace ros -{ -VelodyneHwInterfaceRosWrapper::VelodyneHwInterfaceRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("velodyne_hw_interface_ros_wrapper", options), hw_interface_() -{ - not_supported_message = "Not supported"; - - if (mtx_config_.try_lock()) { - interface_status_ = GetParameters(sensor_configuration_); - mtx_config_.unlock(); - } - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - // Initialize sensor_configuration - RCLCPP_INFO_STREAM(this->get_logger(), "Initialize sensor_configuration"); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - RCLCPP_INFO_STREAM(this->get_logger(), "hw_interface_.InitializeSensorConfiguration"); - hw_interface_.InitializeSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - - if (this->setup_sensor) { - RCLCPP_INFO_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - updateParameters(); - } - - // register scan callback and publisher - hw_interface_.RegisterScanCallback(std::bind( - &VelodyneHwInterfaceRosWrapper::ReceiveScanDataCallback, this, std::placeholders::_1)); - velodyne_scan_pub_ = this->create_publisher( - "velodyne_packets", - rclcpp::SensorDataQoS(rclcpp::KeepLast(10)).best_effort().durability_volatile()); - - if (this->setup_sensor) { - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&VelodyneHwInterfaceRosWrapper::paramCallback, this, std::placeholders::_1)); - } - - auto status = StreamStart(); - if (status == nebula::Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "UDP Driver Started"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), status); - } -} - -Status VelodyneHwInterfaceRosWrapper::StreamStart() -{ - if (Status::OK == interface_status_) { - interface_status_ = hw_interface_.SensorInterfaceStart(); - } - return interface_status_; -} - -Status VelodyneHwInterfaceRosWrapper::StreamStop() { return Status::OK; } -Status VelodyneHwInterfaceRosWrapper::Shutdown() { return Status::OK; } - -Status VelodyneHwInterfaceRosWrapper::InitializeHwInterface( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) -{ - std::stringstream ss; - ss << sensor_configuration; - RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); - return Status::OK; -} - -Status VelodyneHwInterfaceRosWrapper::GetParameters( - drivers::VelodyneSensorConfiguration & sensor_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = - nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "velodyne", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "range from 300 to 1200, in increments of 60"; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(300).set__to_value(1200).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 600, descriptor); - sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("setup_sensor", true, descriptor); - this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); - } - - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { // || - return Status::SENSOR_CONFIG_ERROR; - } - - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); - return Status::OK; -} - -void VelodyneHwInterfaceRosWrapper::ReceiveScanDataCallback( - std::unique_ptr scan_buffer) -{ - // Publish - scan_buffer->header.frame_id = sensor_configuration_.frame_id; - scan_buffer->header.stamp = scan_buffer->packets.front().stamp; - velodyne_scan_pub_->publish(*scan_buffer); -} - -std::string VelodyneHwInterfaceRosWrapper::GetPtreeValue( - std::shared_ptr pt, const std::string & key) -{ - boost::optional value = pt->get_optional(key); - if (value) { - return value.get(); - } else { - return not_supported_message; - } -} - -rcl_interfaces::msg::SetParametersResult VelodyneHwInterfaceRosWrapper::paramCallback( - const std::vector & p) -{ - std::scoped_lock lock(mtx_config_); - std::cout << "add_on_set_parameters_callback" << std::endl; - std::cout << p << std::endl; - std::cout << sensor_configuration_ << std::endl; - - drivers::VelodyneSensorConfiguration new_param{sensor_configuration_}; - std::cout << new_param << std::endl; - std::string sensor_model_str; - std::string return_mode_str; - if ( - get_param(p, "sensor_model", sensor_model_str) || - get_param(p, "return_mode", return_mode_str) || get_param(p, "host_ip", new_param.host_ip) || - get_param(p, "sensor_ip", new_param.sensor_ip) || - get_param(p, "frame_id", new_param.frame_id) || - get_param(p, "data_port", new_param.data_port) || - get_param(p, "gnss_port", new_param.gnss_port) || - get_param(p, "scan_phase", new_param.scan_phase) || - get_param(p, "packet_mtu_size", new_param.packet_mtu_size) || - get_param(p, "rotation_speed", new_param.rotation_speed) || - get_param(p, "cloud_min_angle", new_param.cloud_min_angle) || - get_param(p, "cloud_max_angle", new_param.cloud_max_angle)) { // || - - if (0 < sensor_model_str.length()) - new_param.sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); - if (0 < return_mode_str.length()) - new_param.return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); - - sensor_configuration_ = new_param; - // Update sensor_configuration - RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - RCLCPP_INFO_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - } - - auto result = std::make_shared(); - result->successful = true; - result->reason = "success"; - - std::cout << "add_on_set_parameters_callback success" << std::endl; - - return *result; -} - -std::vector -VelodyneHwInterfaceRosWrapper::updateParameters() -{ - std::scoped_lock lock(mtx_config_); - std::cout << "!!!!!!!!!!!updateParameters!!!!!!!!!!!!" << std::endl; - std::ostringstream os_sensor_model; - os_sensor_model << sensor_configuration_.sensor_model; - std::ostringstream os_return_mode; - os_return_mode << sensor_configuration_.return_mode; - std::cout << "set_parameters start" << std::endl; - auto results = set_parameters({ - rclcpp::Parameter("sensor_model", os_sensor_model.str()), - rclcpp::Parameter("return_mode", os_return_mode.str()), - rclcpp::Parameter("host_ip", sensor_configuration_.host_ip), - rclcpp::Parameter("sensor_ip", sensor_configuration_.sensor_ip), - rclcpp::Parameter("frame_id", sensor_configuration_.frame_id), - rclcpp::Parameter("data_port", sensor_configuration_.data_port), - rclcpp::Parameter("gnss_port", sensor_configuration_.gnss_port), - rclcpp::Parameter("scan_phase", sensor_configuration_.scan_phase), - rclcpp::Parameter("packet_mtu_size", sensor_configuration_.packet_mtu_size), - rclcpp::Parameter("rotation_speed", sensor_configuration_.rotation_speed), - rclcpp::Parameter("cloud_min_angle", sensor_configuration_.cloud_min_angle), - rclcpp::Parameter("cloud_max_angle", sensor_configuration_.cloud_max_angle) //, - }); - std::cout << "set_parameters fin" << std::endl; - return results; -} -RCLCPP_COMPONENTS_REGISTER_NODE(VelodyneHwInterfaceRosWrapper) -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp new file mode 100644 index 000000000..88df4a529 --- /dev/null +++ b/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp @@ -0,0 +1,265 @@ +#include "nebula_ros/velodyne/velodyne_ros_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ +VelodyneRosWrapper::VelodyneRosWrapper(const rclcpp::NodeOptions& options) + : rclcpp::Node("velodyne_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)) + , wrapper_status_(Status::NOT_INITIALIZED) + , sensor_cfg_ptr_(nullptr) + , packet_queue_(3000) + , hw_interface_wrapper_() + , hw_monitor_wrapper_() + , decoder_wrapper_() +{ + setvbuf(stdout, NULL, _IONBF, BUFSIZ); + + wrapper_status_ = DeclareAndGetSensorConfigParams(); + + if (wrapper_status_ != Status::OK) + { + throw std::runtime_error((std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str()); + } + + RCLCPP_INFO_STREAM(get_logger(), "SensorConfig:" << *sensor_cfg_ptr_); + + launch_hw_ = declare_parameter("launch_hw", param_read_only()); + + if (launch_hw_) + { + hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_); + hw_monitor_wrapper_.emplace(this, hw_interface_wrapper_->HwInterface(), sensor_cfg_ptr_); + } + + decoder_wrapper_.emplace(this, hw_interface_wrapper_ ? hw_interface_wrapper_->HwInterface() : nullptr, + sensor_cfg_ptr_); + + RCLCPP_DEBUG(get_logger(), "Starting stream"); + + decoder_thread_ = std::thread([this]() { + while (true) + { + decoder_wrapper_->ProcessCloudPacket(std::move(packet_queue_.pop())); + } + }); + + if (launch_hw_) + { + hw_interface_wrapper_->HwInterface()->RegisterScanCallback( + std::bind(&VelodyneRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + StreamStart(); + } + else + { + packets_sub_ = create_subscription( + "velodyne_packets", rclcpp::SensorDataQoS(), + std::bind(&VelodyneRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); + RCLCPP_INFO_STREAM(get_logger(), + "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); + } + + // Register parameter callback after all params have been declared. Otherwise it would be called once for each + // declaration + parameter_event_cb_ = + add_on_set_parameters_callback(std::bind(&VelodyneRosWrapper::OnParameterChange, this, std::placeholders::_1)); +} + +nebula::Status VelodyneRosWrapper::DeclareAndGetSensorConfigParams() +{ + nebula::drivers::VelodyneSensorConfiguration config; + + auto _sensor_model = declare_parameter("sensor_model", "", param_read_only()); + config.sensor_model = drivers::SensorModelFromString(_sensor_model); + + auto _return_mode = declare_parameter("return_mode", "", param_read_write()); + config.return_mode = drivers::ReturnModeFromString(_return_mode); + + config.host_ip = declare_parameter("host_ip", "255.255.255.255", param_read_only()); + config.sensor_ip = declare_parameter("sensor_ip", "192.168.1.201", param_read_only()); + config.data_port = declare_parameter("data_port", 2368, param_read_only()); + config.gnss_port = declare_parameter("gnss_port", 2369, param_read_only()); + config.frame_id = declare_parameter("frame_id", "pandar", param_read_write()); + + { + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.])"; + descriptor.floating_point_range = float_range(0, 360, 0.01); + config.scan_phase = declare_parameter("scan_phase", 0., descriptor); + } + + config.min_range = declare_parameter("min_range", 0.3, param_read_write()); + config.max_range = declare_parameter("max_range", 300., param_read_write()); + config.packet_mtu_size = declare_parameter("packet_mtu_size", 1500, param_read_only()); + + { + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.additional_constraints = "from 300 to 1200, in increments of 60"; + descriptor.integer_range = int_range(300, 1200, 60); + config.rotation_speed = declare_parameter("rotation_speed", 600, descriptor); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.integer_range = int_range(0, 360, 1); + config.cloud_min_angle = declare_parameter("cloud_min_angle", 0, descriptor); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.integer_range = int_range(0, 360, 1); + config.cloud_max_angle = declare_parameter("cloud_max_angle", 360, descriptor); + } + + auto new_cfg_ptr = std::make_shared(config); + return ValidateAndSetConfig(new_cfg_ptr); +} + +Status VelodyneRosWrapper::ValidateAndSetConfig(std::shared_ptr& new_config) +{ + if (new_config->sensor_model == nebula::drivers::SensorModel::UNKNOWN) + { + return Status::INVALID_SENSOR_MODEL; + } + if (new_config->return_mode == nebula::drivers::ReturnMode::UNKNOWN) + { + return Status::INVALID_ECHO_MODE; + } + if (new_config->frame_id.empty()) + { + return Status::SENSOR_CONFIG_ERROR; + } + + if (hw_interface_wrapper_) + { + hw_interface_wrapper_->OnConfigChange(new_config); + } + if (hw_monitor_wrapper_) + { + hw_monitor_wrapper_->OnConfigChange(new_config); + } + if (decoder_wrapper_) + { + decoder_wrapper_->OnConfigChange(new_config); + } + + sensor_cfg_ptr_ = new_config; + return Status::OK; +} + +void VelodyneRosWrapper::ReceiveScanMessageCallback(std::unique_ptr scan_msg) +{ + if (hw_interface_wrapper_) + { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 1000, + "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); + return; + } + + for (auto& pkt : scan_msg->packets) + { + auto nebula_pkt_ptr = std::make_unique(); + nebula_pkt_ptr->stamp = pkt.stamp; + std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); + + packet_queue_.push(std::move(nebula_pkt_ptr)); + } +} + +Status VelodyneRosWrapper::GetStatus() +{ + return wrapper_status_; +} + +Status VelodyneRosWrapper::StreamStart() +{ + if (!hw_interface_wrapper_) + { + return Status::UDP_CONNECTION_ERROR; + } + + if (hw_interface_wrapper_->Status() != Status::OK) + { + return hw_interface_wrapper_->Status(); + } + + return hw_interface_wrapper_->HwInterface()->SensorInterfaceStart(); +} + +rcl_interfaces::msg::SetParametersResult VelodyneRosWrapper::OnParameterChange(const std::vector& p) +{ + using namespace rcl_interfaces::msg; + + if (p.empty()) + { + return rcl_interfaces::build().successful(true).reason(""); + } + + std::scoped_lock lock(mtx_config_); + + RCLCPP_INFO(get_logger(), "OnParameterChange"); + + drivers::VelodyneSensorConfiguration new_cfg(*sensor_cfg_ptr_); + + std::string _return_mode = ""; + bool got_any = get_param(p, "return_mode", _return_mode) | get_param(p, "frame_id", new_cfg.frame_id) | + get_param(p, "scan_phase", new_cfg.scan_phase) | get_param(p, "min_range", new_cfg.min_range) | + get_param(p, "max_range", new_cfg.max_range) | get_param(p, "rotation_speed", new_cfg.rotation_speed) | + get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | + get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle); + + // Currently, HW interface and monitor wrappers have only read-only parameters, so their update logic is not + // implemented + if (decoder_wrapper_) + { + auto result = decoder_wrapper_->OnParameterChange(p); + if (!result.successful) { + return result; + } + } + + if (!got_any) + { + return rcl_interfaces::build().successful(true).reason(""); + } + + if (_return_mode.length() > 0) + new_cfg.return_mode = nebula::drivers::ReturnModeFromString(_return_mode); + + auto new_cfg_ptr = std::make_shared(new_cfg); + auto status = ValidateAndSetConfig(new_cfg_ptr); + + if (status != Status::OK) + { + RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); + auto result = SetParametersResult(); + result.successful = false; + result.reason = (std::stringstream() << "Invalid configuration: " << status).str(); + return result; + } + + return rcl_interfaces::build().successful(true).reason(""); +} + +void VelodyneRosWrapper::ReceiveCloudPacketCallback(std::vector& packet) +{ + if (!decoder_wrapper_ || decoder_wrapper_->Status() != Status::OK) + { + return; + } + + const auto now = std::chrono::high_resolution_clock::now(); + const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); + + auto msg_ptr = std::make_unique(); + msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); + msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); + msg_ptr->data.swap(packet); + + if (!packet_queue_.try_push(std::move(msg_ptr))) + { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); + } +} + +RCLCPP_COMPONENTS_REGISTER_NODE(VelodyneRosWrapper) +} // namespace ros +} // namespace nebula From 8d1f47039be857a92e4f712471bc80feddd6b5b3 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 17 May 2024 16:32:17 +0900 Subject: [PATCH 050/122] fix(velodyne_decoders): after the last commit, point clouds weren't reset correctly. fixed in this commit --- .../decoders/velodyne_scan_decoder.hpp | 58 +++++++++++++------ .../decoders/vlp16_decoder.hpp | 3 +- .../decoders/vlp32_decoder.hpp | 3 +- .../decoders/vls128_decoder.hpp | 3 +- .../decoders/vlp16_decoder.cpp | 6 +- .../decoders/vlp32_decoder.cpp | 6 +- .../decoders/vls128_decoder.cpp | 6 +- .../velodyne_driver.cpp | 2 +- 8 files changed, 52 insertions(+), 35 deletions(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp index 8c35f105f..1d8cb9255 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp @@ -133,7 +133,44 @@ enum RETURN_TYPE { /// @brief Base class for Velodyne LiDAR decoder class VelodyneScanDecoder { +private: + size_t processed_packets_; + uint32_t prev_packet_first_azm_phased_; + bool has_scanned_; + protected: + /// @brief Checks if the current packet completes the ongoing scan. + /// TODO: this has been moved from velodyne_hw_interface.cpp and is a temporary solution until + /// the Velodyne decoder uses the same structure as Hesai/Robosense + /// @param packet The packet buffer to extract azimuths from + /// @param packet_seconds The seconds-since-epoch part of the packet's timestamp + /// @param phase The sensor's scan phase used for scan cutting + void checkAndHandleScanComplete(const std::vector & packet, int32_t packet_seconds, const uint32_t phase) { + if (has_scanned_) { + processed_packets_ = 0; + reset_pointcloud(packet_seconds); + } + + has_scanned_ = false; + processed_packets_++; + + // Check if scan is complete + uint32_t packet_first_azm = packet[2]; // lower word of azimuth block 0 + packet_first_azm |= packet[3] << 8; // higher word of azimuth block 0 + + uint32_t packet_last_azm = packet[1102]; + packet_last_azm |= packet[1103] << 8; + + uint32_t packet_first_azm_phased = (36000 + packet_first_azm - phase) % 36000; + uint32_t packet_last_azm_phased = (36000 + packet_last_azm - phase) % 36000; + + has_scanned_ = + processed_packets_ > 1 && (packet_last_azm_phased < packet_first_azm_phased || + packet_first_azm_phased < prev_packet_first_azm_phased_); + + prev_packet_first_azm_phased_ = packet_first_azm_phased; + } + /// @brief Decoded point cloud drivers::NebulaPointCloudPtr scan_pc_; /// @brief Point cloud overflowing from one cycle @@ -168,23 +205,7 @@ class VelodyneScanDecoder /// @brief Virtual function for getting the flag indicating whether one cycle is ready /// @return Readied virtual bool hasScanned() { - if (scan_pc_->size() < 2) { - return false; - } - - float scan_phase = angles::from_degrees(sensor_configuration_->scan_phase); - float first_azimuth = scan_pc_->points.front().azimuth - scan_phase; - float last_azimuth = scan_pc_->points.back().azimuth - scan_phase; - - if (first_azimuth < 0) { - first_azimuth += 2 * M_PI; - } - - if (last_azimuth < 0) { - last_azimuth += 2 * M_PI; - } - - return first_azimuth > last_azimuth; + return has_scanned_; } /// @brief Calculation of points in each packet @@ -195,8 +216,7 @@ class VelodyneScanDecoder /// @return tuple of Point cloud and timestamp virtual std::tuple get_pointcloud() = 0; /// @brief Resetting point cloud buffer - /// @param n_pts # of points - virtual void reset_pointcloud(size_t n_pts, double time_stamp) = 0; + virtual void reset_pointcloud(double time_stamp) = 0; /// @brief Resetting overflowed point cloud buffer virtual void reset_overflow(double time_stamp) = 0; }; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp index 3829a2d70..be920a3e1 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp @@ -37,8 +37,7 @@ class Vlp16Decoder : public VelodyneScanDecoder /// @return tuple of Point cloud and timestamp std::tuple get_pointcloud() override; /// @brief Resetting point cloud buffer - /// @param n_pts # of points - void reset_pointcloud(size_t n_pts, double time_stamp) override; + void reset_pointcloud(double time_stamp) override; /// @brief Resetting overflowed point cloud buffer void reset_overflow(double time_stamp) override; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp index 04160ab19..4d5cb938b 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp @@ -36,8 +36,7 @@ class Vlp32Decoder : public VelodyneScanDecoder /// @return tuple of Point cloud and timestamp std::tuple get_pointcloud() override; /// @brief Resetting point cloud buffer - /// @param n_pts # of points - void reset_pointcloud(size_t n_pts, double time_stamp) override; + void reset_pointcloud(double time_stamp) override; /// @brief Resetting overflowed point cloud buffer void reset_overflow(double time_stamp) override; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp index 0626e2e47..af84a33f4 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp @@ -33,8 +33,7 @@ class Vls128Decoder : public VelodyneScanDecoder /// @return tuple of Point cloud and timestamp std::tuple get_pointcloud() override; /// @brief Resetting point cloud buffer - /// @param n_pts # of points - void reset_pointcloud(size_t n_pts, double time_stamp) override; + void reset_pointcloud(double time_stamp) override; /// @brief Resetting overflowed point cloud buffer void reset_overflow(double time_stamp) override; diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp index 02bed010e..298431f7b 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp16_decoder.cpp @@ -82,11 +82,9 @@ int Vlp16Decoder::pointsPerPacket() return BLOCKS_PER_PACKET * VLP16_FIRINGS_PER_BLOCK * VLP16_SCANS_PER_FIRING; } -void Vlp16Decoder::reset_pointcloud(size_t n_pts, double time_stamp) +void Vlp16Decoder::reset_pointcloud(double time_stamp) { scan_pc_->points.clear(); - max_pts_ = n_pts * pointsPerPacket(); - scan_pc_->points.reserve(max_pts_); reset_overflow(time_stamp); // transfer existing overflow points to the cleared pointcloud } @@ -135,6 +133,8 @@ void Vlp16Decoder::reset_overflow(double time_stamp) void Vlp16Decoder::unpack(const std::vector & packet, int32_t packet_seconds) { + checkAndHandleScanComplete(packet, packet_seconds, phase_); + const raw_packet_t * raw = (const raw_packet_t *)packet.data(); float last_azimuth_diff = 0; uint16_t azimuth_next; diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp index 4c06faf87..3b82bf522 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vlp32_decoder.cpp @@ -80,12 +80,10 @@ int Vlp32Decoder::pointsPerPacket() return BLOCKS_PER_PACKET * SCANS_PER_BLOCK; } -void Vlp32Decoder::reset_pointcloud(size_t n_pts, double time_stamp) +void Vlp32Decoder::reset_pointcloud(double time_stamp) { // scan_pc_.reset(new NebulaPointCloud); scan_pc_->points.clear(); - max_pts_ = n_pts * pointsPerPacket(); - scan_pc_->points.reserve(max_pts_); reset_overflow(time_stamp); // transfer existing overflow points to the cleared pointcloud } @@ -134,6 +132,8 @@ void Vlp32Decoder::reset_overflow(double time_stamp) void Vlp32Decoder::unpack(const std::vector & packet, int32_t packet_seconds) { + checkAndHandleScanComplete(packet, packet_seconds, phase_); + const raw_packet_t * raw = (const raw_packet_t *)packet.data(); uint8_t return_mode = packet[RETURN_MODE_INDEX]; const bool dual_return = (return_mode == RETURN_MODE_DUAL); diff --git a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp index 8992b537e..a3bff8fdc 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/decoders/vls128_decoder.cpp @@ -82,12 +82,10 @@ int Vls128Decoder::pointsPerPacket() return BLOCKS_PER_PACKET * SCANS_PER_BLOCK; } -void Vls128Decoder::reset_pointcloud(size_t n_pts, double time_stamp) +void Vls128Decoder::reset_pointcloud(double time_stamp) { // scan_pc_.reset(new NebulaPointCloud); scan_pc_->points.clear(); - max_pts_ = n_pts * pointsPerPacket(); - scan_pc_->points.reserve(max_pts_); reset_overflow(time_stamp); // transfer existing overflow points to the cleared pointcloud } @@ -136,6 +134,8 @@ void Vls128Decoder::reset_overflow(double time_stamp) void Vls128Decoder::unpack(const std::vector & packet, int32_t packet_seconds) { + checkAndHandleScanComplete(packet, packet_seconds, phase_); + const raw_packet_t * raw = (const raw_packet_t *)packet.data(); float last_azimuth_diff = 0; uint16_t azimuth_next; diff --git a/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp b/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp index 07569b8d9..310e75697 100644 --- a/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_velodyne/velodyne_driver.cpp @@ -62,7 +62,7 @@ std::tuple VelodyneDriver::ParseCloudPacke if (scan_decoder_->hasScanned()) { pointcloud = scan_decoder_->get_pointcloud(); - } + } return pointcloud; } From b2343d529afb7ec6735687326bb3e55a3ff10316 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 17 May 2024 16:33:12 +0900 Subject: [PATCH 051/122] fix(velodyne_tests): make tests compile with the new decoder API --- .../velodyne_ros_decoder_test_vlp16.cpp | 60 +++++++++--------- .../velodyne_ros_decoder_test_vlp16.hpp | 11 ++-- .../velodyne_ros_decoder_test_vlp32.cpp | 62 +++++++++---------- .../velodyne_ros_decoder_test_vlp32.hpp | 11 ++-- .../velodyne_ros_decoder_test_vls128.cpp | 61 +++++++++--------- .../velodyne_ros_decoder_test_vls128.hpp | 11 ++-- 6 files changed, 107 insertions(+), 109 deletions(-) diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp index fa3604485..c513cbc2b 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.cpp @@ -34,26 +34,22 @@ VelodyneRosDecoderTest::VelodyneRosDecoderTest( RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); + std::make_shared(calibration_configuration); - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + wrapper_status_ = InitializeDriver(sensor_cfg_ptr_, calibration_cfg_ptr_); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); } Status VelodyneRosDecoderTest::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); + driver_ptr_ = std::make_shared(sensor_configuration, calibration_configuration); return driver_ptr_->GetStatus(); } @@ -336,27 +332,31 @@ void VelodyneRosDecoderTest::ReadBag() << bag_message->time_stamp << std::endl; auto extracted_msg_ptr = std::make_shared(extracted_msg); - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud(extracted_msg_ptr); - pointcloud = std::get<0>(pointcloud_ts); - - // There are very rare cases where has_scanned_ does not become true, but it is not known - // whether it is because of decoder or deserialize_message. - if (!pointcloud) continue; - - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - - auto target_pcd_path = (pcd_dir / fn); - std::cout << target_pcd_path << std::endl; - if (target_pcd_path.exists()) { - std::cout << "exists: " << target_pcd_path << std::endl; - auto rt = pcd_reader.read(target_pcd_path.string(), *ref_pointcloud); - std::cout << rt << " loaded: " << target_pcd_path << std::endl; - checkPCDs(pointcloud, ref_pointcloud); - check_cnt++; - // ref_pointcloud.reset(new nebula::drivers::NebulaPointCloud); - ref_pointcloud.reset(new pcl::PointCloud); + for (auto & pkt : extracted_msg.packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket( + std::vector(pkt.data.begin(), pkt.data.end()), + pkt.stamp.sec); + auto pointcloud = std::get<0>(pointcloud_ts); + + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + + auto target_pcd_path = (pcd_dir / fn); + std::cout << target_pcd_path << std::endl; + if (target_pcd_path.exists()) { + std::cout << "exists: " << target_pcd_path << std::endl; + auto rt = pcd_reader.read(target_pcd_path.string(), *ref_pointcloud); + std::cout << rt << " loaded: " << target_pcd_path << std::endl; + checkPCDs(pointcloud, ref_pointcloud); + check_cnt++; + // ref_pointcloud.reset(new nebula::drivers::NebulaPointCloud); + ref_pointcloud.reset(new pcl::PointCloud); + } + pointcloud.reset(new nebula::drivers::NebulaPointCloud); } - pointcloud.reset(new nebula::drivers::NebulaPointCloud); } } EXPECT_GT(check_cnt, 0); diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp index 2b889358e..4a938e388 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp @@ -21,22 +21,21 @@ namespace nebula namespace ros { /// @brief Testing decoder of VLP16 (Keeps VelodyneDriverRosWrapper structure as much as possible) -class VelodyneRosDecoderTest final : public rclcpp::Node, - NebulaDriverRosWrapperBase //, testing::Test +class VelodyneRosDecoderTest final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; /// @brief Initializing ros wrapper /// @param sensor_configuration SensorConfiguration for this driver /// @param calibration_configuration CalibrationConfiguration for this driver /// @return Resulting status Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration); /// @brief Get configurations (Magic numbers for VLP16 is described, each function can be /// integrated if the ros parameter can be passed to Google Test) diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp index c7623ca50..3fa61c95a 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp @@ -34,26 +34,22 @@ VelodyneRosDecoderTest::VelodyneRosDecoderTest( RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); + std::make_shared(calibration_configuration); - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + wrapper_status_ = InitializeDriver(sensor_cfg_ptr_, calibration_cfg_ptr_); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); } Status VelodyneRosDecoderTest::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); + driver_ptr_ = std::make_shared(sensor_configuration, calibration_configuration); return driver_ptr_->GetStatus(); } @@ -340,28 +336,32 @@ void VelodyneRosDecoderTest::ReadBag() << bag_message->time_stamp << std::endl; auto extracted_msg_ptr = std::make_shared(extracted_msg); - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud(extracted_msg_ptr); - pointcloud = std::get<0>(pointcloud_ts); - - // There are very rare cases where has_scanned_ does not become true, but it is not known - // whether it is because of decoder or deserialize_message. - if (!pointcloud) continue; - - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - - auto target_pcd_path = (pcd_dir / fn); - std::cout << target_pcd_path << std::endl; - - if (target_pcd_path.exists()) { - std::cout << "exists: " << target_pcd_path << std::endl; - auto rt = pcd_reader.read(target_pcd_path.string(), *ref_pointcloud); - std::cout << rt << " loaded: " << target_pcd_path << std::endl; - checkPCDs(pointcloud, ref_pointcloud); - check_cnt++; - // ref_pointcloud.reset(new nebula::drivers::NebulaPointCloud); - ref_pointcloud.reset(new pcl::PointCloud); + for (auto & pkt : extracted_msg.packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket( + std::vector(pkt.data.begin(), pkt.data.end()), + pkt.stamp.sec); + auto pointcloud = std::get<0>(pointcloud_ts); + + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + + auto target_pcd_path = (pcd_dir / fn); + std::cout << target_pcd_path << std::endl; + + if (target_pcd_path.exists()) { + std::cout << "exists: " << target_pcd_path << std::endl; + auto rt = pcd_reader.read(target_pcd_path.string(), *ref_pointcloud); + std::cout << rt << " loaded: " << target_pcd_path << std::endl; + checkPCDs(pointcloud, ref_pointcloud); + check_cnt++; + // ref_pointcloud.reset(new nebula::drivers::NebulaPointCloud); + ref_pointcloud.reset(new pcl::PointCloud); + } + pointcloud.reset(new nebula::drivers::NebulaPointCloud); } - pointcloud.reset(new nebula::drivers::NebulaPointCloud); } } EXPECT_GT(check_cnt, 0); diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp index 2b889358e..4a938e388 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp @@ -21,22 +21,21 @@ namespace nebula namespace ros { /// @brief Testing decoder of VLP16 (Keeps VelodyneDriverRosWrapper structure as much as possible) -class VelodyneRosDecoderTest final : public rclcpp::Node, - NebulaDriverRosWrapperBase //, testing::Test +class VelodyneRosDecoderTest final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; /// @brief Initializing ros wrapper /// @param sensor_configuration SensorConfiguration for this driver /// @param calibration_configuration CalibrationConfiguration for this driver /// @return Resulting status Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration); /// @brief Get configurations (Magic numbers for VLP16 is described, each function can be /// integrated if the ros parameter can be passed to Google Test) diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp index b00a9433d..00397570a 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp @@ -34,26 +34,23 @@ VelodyneRosDecoderTest::VelodyneRosDecoderTest( RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); + std::make_shared(calibration_configuration); + + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + wrapper_status_ = InitializeDriver(sensor_cfg_ptr_, calibration_cfg_ptr_); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); } Status VelodyneRosDecoderTest::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); + driver_ptr_ = std::make_shared(sensor_configuration, calibration_configuration); return driver_ptr_->GetStatus(); } @@ -337,27 +334,31 @@ void VelodyneRosDecoderTest::ReadBag() << bag_message->time_stamp << std::endl; auto extracted_msg_ptr = std::make_shared(extracted_msg); - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud(extracted_msg_ptr); - pointcloud = std::get<0>(pointcloud_ts); - - // There are very rare cases where has_scanned_ does not become true, but it is not known - // whether it is because of decoder or deserialize_message. - if (!pointcloud) continue; - - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - - auto target_pcd_path = (pcd_dir / fn); - std::cout << target_pcd_path << std::endl; - if (target_pcd_path.exists()) { - std::cout << "exists: " << target_pcd_path << std::endl; - auto rt = pcd_reader.read(target_pcd_path.string(), *ref_pointcloud); - std::cout << rt << " loaded: " << target_pcd_path << std::endl; - checkPCDs(pointcloud, ref_pointcloud); - check_cnt++; - // ref_pointcloud.reset(new nebula::drivers::NebulaPointCloud); - ref_pointcloud.reset(new pcl::PointCloud); + for (auto & pkt : extracted_msg.packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket( + std::vector(pkt.data.begin(), pkt.data.end()), + pkt.stamp.sec); + auto pointcloud = std::get<0>(pointcloud_ts); + + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + + auto target_pcd_path = (pcd_dir / fn); + std::cout << target_pcd_path << std::endl; + if (target_pcd_path.exists()) { + std::cout << "exists: " << target_pcd_path << std::endl; + auto rt = pcd_reader.read(target_pcd_path.string(), *ref_pointcloud); + std::cout << rt << " loaded: " << target_pcd_path << std::endl; + checkPCDs(pointcloud, ref_pointcloud); + check_cnt++; + // ref_pointcloud.reset(new nebula::drivers::NebulaPointCloud); + ref_pointcloud.reset(new pcl::PointCloud); + } + pointcloud.reset(new nebula::drivers::NebulaPointCloud); } - pointcloud.reset(new nebula::drivers::NebulaPointCloud); } } EXPECT_GT(check_cnt, 0); diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp index a2432838f..ad29dd961 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp @@ -20,18 +20,17 @@ namespace nebula { namespace ros { -class VelodyneRosDecoderTest final : public rclcpp::Node, - NebulaDriverRosWrapperBase //, testing::Test +class VelodyneRosDecoderTest final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration); Status GetParameters( drivers::VelodyneSensorConfiguration & sensor_configuration, From c004ac158b93adc2ef1099c0dcb3963a39655e47 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 17 May 2024 16:33:36 +0900 Subject: [PATCH 052/122] fix(velodyne_examples): make examples compile with new decoder API --- .../velodyne_ros_offline_extract_bag_pcd.hpp | 10 +-- .../velodyne_ros_offline_extract_bag_pcd.cpp | 83 ++++++++++--------- 2 files changed, 49 insertions(+), 44 deletions(-) diff --git a/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp index c1910d294..33966d955 100644 --- a/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp +++ b/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp @@ -48,21 +48,21 @@ namespace nebula namespace ros { /// @brief Offline velodyne driver usage example (Output PCD data) -class VelodyneRosOfflineExtractBag final : public rclcpp::Node, NebulaDriverRosWrapperBase +class VelodyneRosOfflineExtractBag final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; /// @brief Initializing ros wrapper /// @param sensor_configuration SensorConfiguration for this driver /// @param calibration_configuration CalibrationConfiguration for this driver /// @return Resulting status Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration); /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration diff --git a/nebula_examples/src/velodyne/velodyne_ros_offline_extract_bag_pcd.cpp b/nebula_examples/src/velodyne/velodyne_ros_offline_extract_bag_pcd.cpp index 913898b7c..ce3a69966 100644 --- a/nebula_examples/src/velodyne/velodyne_ros_offline_extract_bag_pcd.cpp +++ b/nebula_examples/src/velodyne/velodyne_ros_offline_extract_bag_pcd.cpp @@ -33,26 +33,22 @@ VelodyneRosOfflineExtractBag::VelodyneRosOfflineExtractBag( RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); + std::make_shared(calibration_configuration); - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + wrapper_status_ = InitializeDriver(sensor_cfg_ptr_ ,calibration_cfg_ptr_); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); } Status VelodyneRosOfflineExtractBag::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); + driver_ptr_ = std::make_shared(sensor_configuration, calibration_configuration); return driver_ptr_->GetStatus(); } @@ -338,37 +334,46 @@ Status VelodyneRosOfflineExtractBag::ReadBag() // nebula::drivers::NebulaPointCloudPtr pointcloud = // driver_ptr_->ConvertScanToPointcloud( // std::make_shared(extracted_msg)); - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud( - std::make_shared(extracted_msg)); - auto pointcloud = std::get<0>(pointcloud_ts); - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - if (needs_open) { - const rosbag2_storage::StorageOptions storage_options_w( - {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); - const rosbag2_cpp::ConverterOptions converter_options_w( - {rmw_get_serialization_format(), rmw_get_serialization_format()}); - writer_ = std::make_unique(); - writer_->open(storage_options_w, converter_options_w); - writer_->create_topic( - {bag_message->topic_name, "velodyne_msgs/msg/VelodyneScan", - rmw_get_serialization_format(), ""}); - needs_open = false; - } - writer_->write(bag_message); - cnt++; - if (skip_num < cnt) { - out_cnt++; - if (only_xyz) { - pcl::PointCloud cloud_xyz; - pcl::copyPointCloud(*pointcloud, cloud_xyz); - writer.writeBinary((o_dir / fn).string(), cloud_xyz); - } else { - writer.writeBinary((o_dir / fn).string(), *pointcloud); + for (auto & pkt : extracted_msg.packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket( + std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.data.size())), + pkt.stamp.sec); + auto pointcloud = std::get<0>(pointcloud_ts); + + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + + if (needs_open) { + const rosbag2_storage::StorageOptions storage_options_w( + {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); + const rosbag2_cpp::ConverterOptions converter_options_w( + {rmw_get_serialization_format(), rmw_get_serialization_format()}); + writer_ = std::make_unique(); + writer_->open(storage_options_w, converter_options_w); + writer_->create_topic( + {bag_message->topic_name, "velodyne_msgs/msg/VelodyneScan", + rmw_get_serialization_format(), ""}); + needs_open = false; + } + writer_->write(bag_message); + cnt++; + if (skip_num < cnt) { + out_cnt++; + if (only_xyz) { + pcl::PointCloud cloud_xyz; + pcl::copyPointCloud(*pointcloud, cloud_xyz); + writer.writeBinary((o_dir / fn).string(), cloud_xyz); + } else { + writer.writeBinary((o_dir / fn).string(), *pointcloud); + } + } + if (out_num <= out_cnt) { + break; } - } - if (out_num <= out_cnt) { - break; } } } From d34ef8dc86fd46939ef97e5aa52bead5c425c791 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 17 May 2024 16:34:35 +0900 Subject: [PATCH 053/122] feat(velodyne_hw_interface): synchronous, null- and thread-safe HTTP requests --- .../velodyne_hw_interface.hpp | 94 +--- .../velodyne_hw_interface.cpp | 522 +++--------------- 2 files changed, 79 insertions(+), 537 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp index 4c7971b2d..858e29488 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp @@ -43,6 +43,8 @@ class VelodyneHwInterface std::shared_ptr boost_ctx_; std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> http_client_driver_; + std::mutex mtx_inflight_request_; + std::string TARGET_STATUS{"/cgi/status.json"}; std::string TARGET_DIAG{"/cgi/diag.json"}; std::string TARGET_SNAPSHOT{"/cgi/snapshot.hdl"}; @@ -54,6 +56,9 @@ class VelodyneHwInterface std::string TARGET_RESET{"/cgi/reset"}; void StringCallback(const std::string & str); + std::string HttpGetRequest(const std::string & endpoint); + std::string HttpPostRequest(const std::string & endpoint, const std::string & body); + /// @brief Get a one-off HTTP client to communicate with the hardware /// @param ctx IO Context /// @param hcd Got http client driver @@ -204,95 +209,6 @@ class VelodyneHwInterface /// @return Resulting status VelodyneStatus SetNetDhcp(bool use_dhcp); - /// @brief Initializing HTTP client (async) - /// @return Resulting status - VelodyneStatus InitHttpClientAsync(); - /// @brief Getting the current operational state and parameters of the sensor (async) - /// @param str_callback Callback function for received JSON string - /// @return Resulting status - VelodyneStatus GetStatusAsync(std::function str_callback); - /// @brief Getting the current operational state and parameters of the sensor (async) - /// @return Resulting status - VelodyneStatus GetStatusAsync(); - /// @brief Getting diagnostic information from the sensor (async) - /// @param str_callback Callback function for received JSON string - /// @return Resulting status - VelodyneStatus GetDiagAsync(std::function str_callback); - /// @brief Getting diagnostic information from the sensor (async) - /// @return Resulting status - VelodyneStatus GetDiagAsync(); - /// @brief Getting current sensor configuration and status data (async) - /// @param str_callback Callback function for received JSON string - /// @return Resulting status - VelodyneStatus GetSnapshotAsync(std::function str_callback); - /// @brief Getting current sensor configuration and status data (async) - /// @return Resulting status - VelodyneStatus GetSnapshotAsync(); - /// @brief Checking the current settings and changing the difference point - /// @return Resulting status - VelodyneStatus CheckAndSetConfigBySnapshotAsync( - std::shared_ptr sensor_configuration); - /// @brief Setting Motor RPM (async) - /// @param rpm the RPM of the motor - /// @return Resulting status - VelodyneStatus SetRpmAsync(uint16_t rpm); - /// @brief Setting Field of View Start (async) - /// @param fov_start FOV start - /// @return Resulting status - VelodyneStatus SetFovStartAsync(uint16_t fov_start); - /// @brief Setting Field of View End (async) - /// @param fov_end FOV end - /// @return Resulting status - VelodyneStatus SetFovEndAsync(uint16_t fov_end); - /// @brief Setting Return Type (async) - /// @param return_mode ReturnMode - /// @return Resulting status - VelodyneStatus SetReturnTypeAsync(ReturnMode return_mode); - /// @brief Save Configuration to the LiDAR memory (async) - /// @return Resulting status - VelodyneStatus SaveConfigAsync(); - /// @brief Resets the sensor (async) - /// @return Resulting status - VelodyneStatus ResetSystemAsync(); - /// @brief Turn laser state on (async) - /// @return Resulting status - VelodyneStatus LaserOnAsync(); - /// @brief Turn laser state off (async) - /// @return Resulting status - VelodyneStatus LaserOffAsync(); - /// @brief Turn laser state on/off (async) - /// @param on is ON - /// @return Resulting status - VelodyneStatus LaserOnOffAsync(bool on); - /// @brief Setting host (destination) IP address (async) - /// @param addr destination IP address - /// @return Resulting status - VelodyneStatus SetHostAddrAsync(std::string addr); - /// @brief Setting host (destination) data port (async) - /// @param dport destination data port - /// @return Resulting status - VelodyneStatus SetHostDportAsync(uint16_t dport); - /// @brief Setting host (destination) telemetry port (async) - /// @param tport destination telemetry port - /// @return Resulting status - VelodyneStatus SetHostTportAsync(uint16_t tport); - /// @brief Setting network (sensor) IP address (async) - /// @param addr sensor IP address - /// @return Resulting status - VelodyneStatus SetNetAddrAsync(std::string addr); - /// @brief Setting the network mask of the sensor (async) - /// @param mask Network mask - /// @return Resulting status - VelodyneStatus SetNetMaskAsync(std::string mask); - /// @brief Setting the gateway address of the sensor (async) - /// @param gateway Gateway address - /// @return Resulting status - VelodyneStatus SetNetGatewayAsync(std::string gateway); - /// @brief This determines if the sensor is to rely on a DHCP server for its IP address (async) - /// @param use_dhcp DHCP on - /// @return Resulting status - VelodyneStatus SetNetDhcpAsync(bool use_dhcp); - /// @brief Setting rclcpp::Logger /// @param node Logger void SetLogger(std::shared_ptr node); diff --git a/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp index f31bb413b..fdc1051ba 100644 --- a/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_velodyne_hw_interfaces/velodyne_hw_interface.cpp @@ -12,24 +12,45 @@ VelodyneHwInterface::VelodyneHwInterface() { } +std::string VelodyneHwInterface::HttpGetRequest(const std::string & endpoint) +{ + std::lock_guard lock(mtx_inflight_request_); + if (!http_client_driver_->client()->isOpen()) { + http_client_driver_->client()->open(); + } + + std::string response = http_client_driver_->get(endpoint); + http_client_driver_->client()->close(); + return response; +} + +std::string VelodyneHwInterface::HttpPostRequest(const std::string & endpoint, const std::string & body) +{ + std::lock_guard lock(mtx_inflight_request_); + if (!http_client_driver_->client()->isOpen()) { + http_client_driver_->client()->open(); + } + + std::string response = http_client_driver_->post(endpoint, body); + http_client_driver_->client()->close(); + return response; +} + Status VelodyneHwInterface::InitializeSensorConfiguration( std::shared_ptr sensor_configuration) { sensor_configuration_ = sensor_configuration; - - GetDiagAsync(); - GetStatusAsync(); - Status status = Status::OK; - return status; + return Status::OK; } Status VelodyneHwInterface::SetSensorConfiguration( std::shared_ptr sensor_configuration) { - auto velodyne_sensor_configuration = sensor_configuration; - VelodyneStatus status = CheckAndSetConfigBySnapshotAsync(velodyne_sensor_configuration); - Status rt = status; - return rt; + auto snapshot = GetSnapshot(); + auto tree = ParseJson(snapshot); + VelodyneStatus status = CheckAndSetConfig(sensor_configuration, tree); + + return status; } Status VelodyneHwInterface::SensorInterfaceStart() @@ -92,42 +113,6 @@ VelodyneStatus VelodyneHwInterface::InitHttpClient() return Status::OK; } -VelodyneStatus VelodyneHwInterface::InitHttpClientAsync() -{ - try { - http_client_driver_->init_client(sensor_configuration_->sensor_ip, 80); - } catch (const std::exception & ex) { - VelodyneStatus status = Status::HTTP_CONNECTION_ERROR; - return status; - } - return Status::OK; -} - -VelodyneStatus VelodyneHwInterface::GetHttpClientDriverOnce( - std::shared_ptr ctx, - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & hcd) -{ - hcd = std::unique_ptr<::drivers::tcp_driver::HttpClientDriver>( - new ::drivers::tcp_driver::HttpClientDriver(ctx)); - try { - hcd->init_client(sensor_configuration_->sensor_ip, 80); - } catch (const std::exception & ex) { - Status status = Status::HTTP_CONNECTION_ERROR; - std::cerr << status << sensor_configuration_->sensor_ip << "," << 80 << std::endl; - return Status::HTTP_CONNECTION_ERROR; - } - return Status::OK; -} - -VelodyneStatus VelodyneHwInterface::GetHttpClientDriverOnce( - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> & hcd) -{ - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd_tmp; - auto st = GetHttpClientDriverOnce(std::make_shared(), hcd_tmp); - hcd = std::move(hcd_tmp); - return st; -} - void VelodyneHwInterface::StringCallback(const std::string & str) { std::cout << "VelodyneHwInterface::StringCallback: " << str << std::endl; @@ -150,12 +135,17 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( std::shared_ptr sensor_configuration, boost::property_tree::ptree tree) { + VelodyneStatus status; + const auto & OK = VelodyneStatus::OK; + std::string target_key = "config.returns"; auto current_return_mode_str = tree.get(target_key); auto current_return_mode = nebula::drivers::ReturnModeFromStringVelodyne(tree.get(target_key)); if (sensor_configuration->return_mode != current_return_mode) { - SetReturnTypeAsync(sensor_configuration->return_mode); + status = SetReturnType(sensor_configuration->return_mode); + if (status != OK) return status; + std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_return_mode_str << std::endl; std::cout << "current_return_mode: " << current_return_mode << std::endl; @@ -166,7 +156,9 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( target_key = "config.rpm"; auto current_rotation_speed = tree.get(target_key); if (sensor_configuration->rotation_speed != current_rotation_speed) { - SetRpmAsync(sensor_configuration->rotation_speed); + status = SetRpm(sensor_configuration->rotation_speed); + if (status != OK) return status; + std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_rotation_speed << std::endl; std::cout << "sensor_configuration->rotation_speed: " << sensor_configuration->rotation_speed @@ -181,7 +173,9 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( setting_cloud_min_angle = 359; } if (setting_cloud_min_angle != current_cloud_min_angle) { - SetFovStartAsync(setting_cloud_min_angle); + status = SetFovStart(setting_cloud_min_angle); + if (status != OK) return status; + std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_cloud_min_angle << std::endl; std::cout << "sensor_configuration->cloud_min_angle: " << setting_cloud_min_angle << std::endl; @@ -195,7 +189,9 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( setting_cloud_max_angle = 359; } if (setting_cloud_max_angle != current_cloud_max_angle) { - SetFovEndAsync(setting_cloud_max_angle); + status = SetFovEnd(setting_cloud_max_angle); + if (status != OK) return status; + std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_cloud_max_angle << std::endl; std::cout << "sensor_configuration->cloud_max_angle: " << setting_cloud_max_angle << std::endl; @@ -204,7 +200,9 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( target_key = "config.host.addr"; auto current_host_addr = tree.get(target_key); if (sensor_configuration->host_ip != current_host_addr) { - SetHostAddrAsync(sensor_configuration->host_ip); + status = SetHostAddr(sensor_configuration->host_ip); + if (status != OK) return status; + std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_host_addr << std::endl; std::cout << "sensor_configuration->host_ip: " << sensor_configuration->host_ip << std::endl; @@ -213,7 +211,9 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( target_key = "config.host.dport"; auto current_host_dport = tree.get(target_key); if (sensor_configuration->data_port != current_host_dport) { - SetHostDportAsync(sensor_configuration->data_port); + status = SetHostDport(sensor_configuration->data_port); + if (status != OK) return status; + std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_host_dport << std::endl; std::cout << "sensor_configuration->data_port: " << sensor_configuration->data_port @@ -223,46 +223,35 @@ VelodyneStatus VelodyneHwInterface::CheckAndSetConfig( target_key = "config.host.tport"; auto current_host_tport = tree.get(target_key); if (sensor_configuration->gnss_port != current_host_tport) { - SetHostTportAsync(sensor_configuration->gnss_port); + status = SetHostTport(sensor_configuration->gnss_port); + if (status != OK) return status; + std::cout << "VelodyneHwInterface::parse_json(" << target_key << "): " << current_host_tport << std::endl; std::cout << "sensor_configuration->gnss_port: " << sensor_configuration->gnss_port << std::endl; } - return Status::WAITING_FOR_SENSOR_RESPONSE; + return OK; } // sync std::string VelodyneHwInterface::GetStatus() { - auto rt = http_client_driver_->get(TARGET_STATUS); - http_client_driver_->client()->close(); - // str_cb(rt); - // return Status::OK; - return rt; + return HttpGetRequest(TARGET_STATUS); } std::string VelodyneHwInterface::GetDiag() { - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - std::cout << "GetHttpClientDriverOnce" << std::endl; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return ""; - } - auto rt = hcd->get(TARGET_DIAG); + auto rt = HttpGetRequest(TARGET_DIAG); std::cout << "read_response: " << rt << std::endl; return rt; } std::string VelodyneHwInterface::GetSnapshot() { - auto rt = http_client_driver_->get(TARGET_SNAPSHOT); - http_client_driver_->client()->close(); - return rt; + return HttpGetRequest(TARGET_SNAPSHOT); } VelodyneStatus VelodyneHwInterface::SetRpm(uint16_t rpm) @@ -270,8 +259,7 @@ VelodyneStatus VelodyneHwInterface::SetRpm(uint16_t rpm) if (rpm < 300 || 1200 < rpm || rpm % 60 != 0) { return VelodyneStatus::INVALID_RPM_ERROR; } - auto rt = http_client_driver_->post(TARGET_SETTING, (boost::format("rpm=%d") % rpm).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_SETTING, (boost::format("rpm=%d") % rpm).str()); StringCallback(rt); return Status::OK; } @@ -281,8 +269,7 @@ VelodyneStatus VelodyneHwInterface::SetFovStart(uint16_t fov_start) if (359 < fov_start) { return VelodyneStatus::INVALID_FOV_ERROR; } - auto rt = http_client_driver_->post(TARGET_FOV, (boost::format("start=%d") % fov_start).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_FOV, (boost::format("start=%d") % fov_start).str()); StringCallback(rt); return Status::OK; } @@ -292,8 +279,7 @@ VelodyneStatus VelodyneHwInterface::SetFovEnd(uint16_t fov_end) if (359 < fov_end) { return VelodyneStatus::INVALID_FOV_ERROR; } - auto rt = http_client_driver_->post(TARGET_FOV, (boost::format("end=%d") % fov_end).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_FOV, (boost::format("end=%d") % fov_end).str()); StringCallback(rt); return Status::OK; } @@ -314,8 +300,7 @@ VelodyneStatus VelodyneHwInterface::SetReturnType(nebula::drivers::ReturnMode re default: return VelodyneStatus::INVALID_RETURN_MODE_ERROR; } - auto rt = http_client_driver_->post(TARGET_SETTING, body_str); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_SETTING, body_str); StringCallback(rt); return Status::OK; } @@ -323,8 +308,7 @@ VelodyneStatus VelodyneHwInterface::SetReturnType(nebula::drivers::ReturnMode re VelodyneStatus VelodyneHwInterface::SaveConfig() { std::string body_str = "submit"; - auto rt = http_client_driver_->post(TARGET_SAVE, body_str); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_SAVE, body_str); StringCallback(rt); return Status::OK; } @@ -332,8 +316,7 @@ VelodyneStatus VelodyneHwInterface::SaveConfig() VelodyneStatus VelodyneHwInterface::ResetSystem() { std::string body_str = "reset_system"; - auto rt = http_client_driver_->post(TARGET_RESET, body_str); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_RESET, body_str); StringCallback(rt); return Status::OK; } @@ -341,8 +324,7 @@ VelodyneStatus VelodyneHwInterface::ResetSystem() VelodyneStatus VelodyneHwInterface::LaserOn() { std::string body_str = "laser=on"; - auto rt = http_client_driver_->post(TARGET_SETTING, body_str); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_SETTING, body_str); StringCallback(rt); return Status::OK; } @@ -350,8 +332,7 @@ VelodyneStatus VelodyneHwInterface::LaserOn() VelodyneStatus VelodyneHwInterface::LaserOff() { std::string body_str = "laser=off"; - auto rt = http_client_driver_->post(TARGET_SETTING, body_str); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_SETTING, body_str); StringCallback(rt); return Status::OK; } @@ -359,416 +340,61 @@ VelodyneStatus VelodyneHwInterface::LaserOff() VelodyneStatus VelodyneHwInterface::LaserOnOff(bool on) { std::string body_str = (boost::format("laser=%s") % (on ? "on" : "off")).str(); - auto rt = http_client_driver_->post(TARGET_SETTING, body_str); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_SETTING, body_str); StringCallback(rt); return Status::OK; } VelodyneStatus VelodyneHwInterface::SetHostAddr(std::string addr) { - auto rt = http_client_driver_->post(TARGET_HOST, (boost::format("addr=%s") % addr).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_HOST, (boost::format("addr=%s") % addr).str()); StringCallback(rt); return Status::OK; } VelodyneStatus VelodyneHwInterface::SetHostDport(uint16_t dport) { - auto rt = http_client_driver_->post(TARGET_HOST, (boost::format("dport=%d") % dport).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_HOST, (boost::format("dport=%d") % dport).str()); StringCallback(rt); return Status::OK; } VelodyneStatus VelodyneHwInterface::SetHostTport(uint16_t tport) { - auto rt = http_client_driver_->post(TARGET_HOST, (boost::format("tport=%d") % tport).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_HOST, (boost::format("tport=%d") % tport).str()); StringCallback(rt); return Status::OK; } VelodyneStatus VelodyneHwInterface::SetNetAddr(std::string addr) { - auto rt = http_client_driver_->post(TARGET_NET, (boost::format("addr=%s") % addr).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_NET, (boost::format("addr=%s") % addr).str()); StringCallback(rt); return Status::OK; } VelodyneStatus VelodyneHwInterface::SetNetMask(std::string mask) { - auto rt = http_client_driver_->post(TARGET_NET, (boost::format("mask=%s") % mask).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_NET, (boost::format("mask=%s") % mask).str()); StringCallback(rt); return Status::OK; } VelodyneStatus VelodyneHwInterface::SetNetGateway(std::string gateway) { - auto rt = http_client_driver_->post(TARGET_NET, (boost::format("gateway=%s") % gateway).str()); - http_client_driver_->client()->close(); + auto rt = HttpPostRequest(TARGET_NET, (boost::format("gateway=%s") % gateway).str()); StringCallback(rt); return Status::OK; } VelodyneStatus VelodyneHwInterface::SetNetDhcp(bool use_dhcp) { - auto rt = http_client_driver_->post( + auto rt = HttpPostRequest( TARGET_NET, (boost::format("dhcp=%s") % (use_dhcp ? "on" : "off")).str()); - http_client_driver_->client()->close(); StringCallback(rt); return Status::OK; } -VelodyneStatus VelodyneHwInterface::GetStatusAsync( - std::function str_callback) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncGet(str_callback, TARGET_STATUS); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::GetStatusAsync() -{ - return GetStatusAsync([this](const std::string & str) { StringCallback(str); }); -} - -VelodyneStatus VelodyneHwInterface::GetDiagAsync( - std::function str_callback) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncGet(str_callback, TARGET_DIAG); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::GetDiagAsync() -{ - return GetDiagAsync([this](const std::string & str) { StringCallback(str); }); -} - -VelodyneStatus VelodyneHwInterface::GetSnapshotAsync( - std::function str_callback) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - hcd->asyncGet(str_callback, TARGET_SNAPSHOT); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::GetSnapshotAsync() -{ - return GetSnapshotAsync([this](const std::string & str) { ParseJson(str); }); -} - -VelodyneStatus VelodyneHwInterface::CheckAndSetConfigBySnapshotAsync( - std::shared_ptr sensor_configuration) -{ - sensor_configuration_ = sensor_configuration; - - return GetSnapshotAsync([this](const std::string & str) { - auto tree = ParseJson(str); - std::cout << "ParseJson OK\n"; - CheckAndSetConfig(sensor_configuration_, tree); - }); -} - -VelodyneStatus VelodyneHwInterface::SetRpmAsync(uint16_t rpm) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - if (rpm < 300 || 1200 < rpm || rpm % 60 != 0) { - return VelodyneStatus::INVALID_RPM_ERROR; - } - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_SETTING, - (boost::format("rpm=%d") % rpm).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetFovStartAsync(uint16_t fov_start) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - if (359 < fov_start) { - return VelodyneStatus::INVALID_FOV_ERROR; - } - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_FOV, - (boost::format("start=%d") % fov_start).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetFovEndAsync(uint16_t fov_end) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - if (359 < fov_end) { - return VelodyneStatus::INVALID_FOV_ERROR; - } - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_FOV, - (boost::format("end=%d") % fov_end).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetReturnTypeAsync(nebula::drivers::ReturnMode return_mode) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - std::string body_str = ""; - switch (return_mode) { - case nebula::drivers::ReturnMode::SINGLE_STRONGEST: - body_str = "returns=Strongest"; - break; - case nebula::drivers::ReturnMode::SINGLE_LAST: - body_str = "returns=Last"; - break; - case nebula::drivers::ReturnMode::DUAL_ONLY: - body_str = "returns=Dual"; - break; - default: - return VelodyneStatus::INVALID_RETURN_MODE_ERROR; - } - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_SETTING, body_str); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SaveConfigAsync() -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - std::string body_str = "submit"; - hcd->asyncPost([this](const std::string & str) { StringCallback(str); }, TARGET_SAVE, body_str); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::ResetSystemAsync() -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - std::string body_str = "reset_system"; - hcd->asyncPost([this](const std::string & str) { StringCallback(str); }, TARGET_RESET, body_str); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::LaserOnAsync() -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - std::string body_str = "laser=on"; - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_SETTING, body_str); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::LaserOffAsync() -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - std::string body_str = "laser=off"; - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_SETTING, body_str); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::LaserOnOffAsync(bool on) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - std::string body_str = (boost::format("laser=%s") % (on ? "on" : "off")).str(); - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_SETTING, body_str); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetHostAddrAsync(std::string addr) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_HOST, - (boost::format("addr=%s") % addr).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetHostDportAsync(uint16_t dport) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_HOST, - (boost::format("dport=%d") % dport).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetHostTportAsync(uint16_t tport) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_HOST, - (boost::format("tport=%d") % tport).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetNetAddrAsync(std::string addr) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_NET, - (boost::format("addr=%s") % addr).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetNetMaskAsync(std::string mask) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_NET, - (boost::format("mask=%s") % mask).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetNetGatewayAsync(std::string gateway) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_NET, - (boost::format("gateway=%s") % gateway).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - -VelodyneStatus VelodyneHwInterface::SetNetDhcpAsync(bool use_dhcp) -{ - auto ctx = std::make_shared(); - std::unique_ptr<::drivers::tcp_driver::HttpClientDriver> hcd; - auto st = GetHttpClientDriverOnce(ctx, hcd); - if (st != Status::OK) { - return st; - } - - hcd->asyncPost( - [this](const std::string & str) { StringCallback(str); }, TARGET_NET, - (boost::format("dhcp=%s") % (use_dhcp ? "on" : "off")).str()); - ctx->run(); - return Status::WAITING_FOR_SENSOR_RESPONSE; -} - void VelodyneHwInterface::SetLogger(std::shared_ptr logger) { parent_node_logger = logger; From 5a91d32ccdb2c9d1b19a19fedca31735b919b522 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 17 May 2024 16:34:56 +0900 Subject: [PATCH 054/122] fix(velodyne_launch_all_hw.xml): refactor to single-node --- nebula_ros/launch/velodyne_launch_all_hw.xml | 33 +++----------------- 1 file changed, 4 insertions(+), 29 deletions(-) diff --git a/nebula_ros/launch/velodyne_launch_all_hw.xml b/nebula_ros/launch/velodyne_launch_all_hw.xml index c39437039..717aa5afd 100644 --- a/nebula_ros/launch/velodyne_launch_all_hw.xml +++ b/nebula_ros/launch/velodyne_launch_all_hw.xml @@ -1,5 +1,6 @@ + @@ -19,41 +20,15 @@ - + + - - - - - - - - - - - - - - - - - - - - - - - - - From 62d7f92e9e2b6c31f273fd75dac5104ef26cd40c Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 17 May 2024 16:38:21 +0900 Subject: [PATCH 055/122] fix(velodyne): make hw interface wrapper work with new hw interface API --- nebula_ros/src/velodyne/hw_interface_wrapper.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp index 57e1cd927..8ce73a2a8 100644 --- a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp @@ -20,6 +20,12 @@ VelodyneHwInterfaceWrapper::VelodyneHwInterfaceWrapper( throw std::runtime_error((std::stringstream{} << "Could not initialize HW interface: " << status_).str()); } + status_ = hw_interface_->InitHttpClient(); + + if (status_ != Status::OK) { + throw std::runtime_error((std::stringstream{} << "Could not initialize HTTP client: " << status_).str()); + } + if (setup_sensor_) { RCLCPP_INFO_STREAM(logger_, "Setting sensor configuration"); status_ = hw_interface_->SetSensorConfiguration(config); @@ -36,6 +42,7 @@ void VelodyneHwInterfaceWrapper::OnConfigChange( const std::shared_ptr& new_config) { hw_interface_->InitializeSensorConfiguration(new_config); + hw_interface_->InitHttpClient(); if (setup_sensor_) { hw_interface_->SetSensorConfiguration(new_config); } From f18215d684b829fac16ed9ed7aa76e7bf5de4c7c Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 17 May 2024 17:07:50 +0900 Subject: [PATCH 056/122] fix(velodyne): implement correct locking behavior in hw monitor wrapper --- .../velodyne/hw_monitor_wrapper.hpp | 8 +- .../src/velodyne/hw_monitor_wrapper.cpp | 158 +++++++++--------- 2 files changed, 82 insertions(+), 84 deletions(-) diff --git a/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp index a003aad43..e695f3114 100644 --- a/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/hw_monitor_wrapper.hpp @@ -48,10 +48,11 @@ class VelodyneHwMonitorWrapper /// @brief Get value from property_tree /// @param pt property_tree + /// @param mtx_pt the mutex associated with `pt` /// @param key Pey string /// @return Value std::string GetPtreeValue( - std::shared_ptr pt, const std::string & key); + std::shared_ptr pt, std::mutex & mtx_pt, const std::string & key); /// @brief Making fixed precision string /// @param val Target value @@ -278,8 +279,9 @@ class VelodyneHwMonitorWrapper std::shared_ptr current_snapshot_time; uint8_t current_diag_status; - std::timed_mutex tm_status_; - std::timed_mutex tm_diag_; + std::mutex mtx_snapshot_; + std::mutex mtx_status_; + std::mutex mtx_diag_; std::string info_model_; std::string info_serial_; diff --git a/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp index 17d02c42c..836f81e6b 100644 --- a/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp @@ -18,28 +18,27 @@ VelodyneHwMonitorWrapper::VelodyneHwMonitorWrapper(rclcpp::Node* const parent_no show_advanced_diagnostics_ = parent_node->declare_parameter("advanced_diagnostics", false, param_read_only()); std::cout << "Get model name and serial." << std::endl; - hw_interface_->GetSnapshotAsync([this](const std::string & str) { - current_snapshot_time.reset(new rclcpp::Time(parent_node_->now())); - current_snapshot_tree = - std::make_shared(hw_interface_->ParseJson(str)); - current_diag_tree = - std::make_shared(current_snapshot_tree->get_child("diag")); - current_status_tree = - std::make_shared(current_snapshot_tree->get_child("status")); - current_snapshot.reset(new std::string(str)); + auto str = hw_interface_->GetSnapshot(); + current_snapshot_time.reset(new rclcpp::Time(parent_node_->now())); + current_snapshot_tree = + std::make_shared(hw_interface_->ParseJson(str)); + current_diag_tree = + std::make_shared(current_snapshot_tree->get_child("diag")); + current_status_tree = + std::make_shared(current_snapshot_tree->get_child("status")); + current_snapshot.reset(new std::string(str)); - try { - info_model_ = GetPtreeValue(current_snapshot_tree, key_info_model); - info_serial_ = GetPtreeValue(current_snapshot_tree, key_info_serial); - RCLCPP_INFO_STREAM(logger_, "Model:" << info_model_); - RCLCPP_INFO_STREAM(logger_, "Serial:" << info_serial_); - } catch (boost::bad_lexical_cast & ex) { - RCLCPP_ERROR(logger_, " Error: Can't get model and serial"); - return; - } + try { + info_model_ = GetPtreeValue(current_snapshot_tree, mtx_snapshot_, key_info_model); + info_serial_ = GetPtreeValue(current_snapshot_tree, mtx_snapshot_, key_info_serial); + RCLCPP_INFO_STREAM(logger_, "Model:" << info_model_); + RCLCPP_INFO_STREAM(logger_, "Serial:" << info_serial_); + } catch (boost::bad_lexical_cast & ex) { + RCLCPP_ERROR(logger_, " Error: Can't get model and serial"); + return; + } - InitializeVelodyneDiagnostics(); - }); + InitializeVelodyneDiagnostics(); } void VelodyneHwMonitorWrapper::InitializeVelodyneDiagnostics() @@ -154,8 +153,12 @@ void VelodyneHwMonitorWrapper::InitializeVelodyneDiagnostics() diagnostics_updater_.add( "velodyne_voltage", this, &VelodyneHwMonitorWrapper::VelodyneCheckVoltage); - current_snapshot.reset(new std::string("")); - current_snapshot_time.reset(new rclcpp::Time(parent_node_->now())); + { + std::lock_guard lock(mtx_snapshot_); + current_snapshot.reset(new std::string("")); + current_snapshot_time.reset(new rclcpp::Time(parent_node_->now())); + } + current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; auto on_timer_snapshot = [this] { OnVelodyneSnapshotTimer(); }; @@ -163,7 +166,11 @@ void VelodyneHwMonitorWrapper::InitializeVelodyneDiagnostics() auto on_timer_update = [this] { auto now = parent_node_->now(); - auto dif = (now - *current_snapshot_time).seconds(); + double dif; + { + std::lock_guard lock(mtx_snapshot_); + dif = (now - *current_snapshot_time).seconds(); + } if (diag_span_ * 2.0 < dif * 1000) { current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; RCLCPP_DEBUG_STREAM(logger_, "STALE"); @@ -178,40 +185,34 @@ void VelodyneHwMonitorWrapper::InitializeVelodyneDiagnostics() void VelodyneHwMonitorWrapper::OnVelodyneSnapshotTimer() { - hw_interface_->GetSnapshotAsync([this](const std::string & str) { + + auto str = hw_interface_->GetSnapshot(); + auto ptree = hw_interface_->ParseJson(str); + + { + std::lock_guard lock(mtx_snapshot_); + current_snapshot_time.reset(new rclcpp::Time(parent_node_->now())); current_snapshot_tree = - std::make_shared(hw_interface_->ParseJson(str)); + std::make_shared(ptree); current_diag_tree = std::make_shared(current_snapshot_tree->get_child("diag")); current_status_tree = std::make_shared(current_snapshot_tree->get_child("status")); current_snapshot.reset(new std::string(str)); - }); + } } void VelodyneHwMonitorWrapper::OnVelodyneDiagnosticsTimer() { std::cout << "OnVelodyneDiagnosticsTimer" << std::endl; - if (tm_diag_.try_lock_for(std::chrono::milliseconds(500))) { - std::cout << "mtx_diag lock" << std::endl; - hw_interface_->GetDiagAsync([this](const std::string & str) { - current_diag_tree = - std::make_shared(hw_interface_->ParseJson(str)); - diagnostics_updater_.force_update(); - tm_diag_.unlock(); - std::cout << "mtx_diag unlock" << std::endl; - }); - - if (!tm_diag_.try_lock_for(std::chrono::milliseconds(500))) { - RCLCPP_ERROR(logger_, "GetDiagAsync callback timed out"); - return; - } - - tm_diag_.unlock(); - } else { - RCLCPP_ERROR(logger_, "Wait for GetDiagAsync mutex timed out"); + auto str = hw_interface_->GetDiag(); + { + std::lock_guard lock(mtx_diag_); + current_diag_tree = + std::make_shared(hw_interface_->ParseJson(str)); } + diagnostics_updater_.force_update(); } std::tuple VelodyneHwMonitorWrapper::VelodyneGetTopHv() @@ -222,7 +223,7 @@ std::tuple VelodyneHwMonitorWrapper::Ve std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_hv)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_hv)); val = 101.0 * (val * 5.0 / 4096.0 - 5.0); if (val < -150.0) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -249,7 +250,7 @@ VelodyneHwMonitorWrapper::VelodyneGetTopAdTemp() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_ad_temp)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_ad_temp)); val = val * 5.0 / 4096.0; mes = GetFixedPrecisionString(val) + " V"; } catch (boost::bad_lexical_cast & ex) { @@ -270,7 +271,7 @@ VelodyneHwMonitorWrapper::VelodyneGetTopLm20Temp() try { double val = 0.0; val = - boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_lm20_temp)); + boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_lm20_temp)); val = -1481.96 + std::sqrt(2.1962e6 + ((1.8639 - val * 5.0 / 4096.0) / 3.88e-6)); if (val < -25.0) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -298,7 +299,7 @@ VelodyneHwMonitorWrapper::VelodyneGetTopPwr5v() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_pwr_5v)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_pwr_5v)); val = 2.0 * val * 5.0 / 4096.0; if (val < 4.8) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -325,7 +326,7 @@ VelodyneHwMonitorWrapper::VelodyneGetTopPwr25v() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_pwr_2_5v)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_pwr_2_5v)); val = val * 5.0 / 4096.0; if (val < 2.3) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -352,7 +353,7 @@ VelodyneHwMonitorWrapper::VelodyneGetTopPwr33v() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_pwr_3_3v)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_pwr_3_3v)); val = val * 5.0 / 4096.0; if (val < 3.1) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -380,7 +381,7 @@ VelodyneHwMonitorWrapper::VelodyneGetTopPwr5vRaw() try { double val = 0.0; val = - boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_pwr_5v_raw)); + boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_pwr_5v_raw)); val = 2.0 * val * 5.0 / 4096.0; if (val < 2.3) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -407,7 +408,7 @@ VelodyneHwMonitorWrapper::VelodyneGetTopPwrRaw() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_pwr_raw)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_pwr_raw)); val = val * 5.0 / 4096.0; if (val < 1.6) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -435,7 +436,7 @@ VelodyneHwMonitorWrapper::VelodyneGetTopPwrVccint() try { double val = 0.0; val = - boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_top_pwr_vccint)); + boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_top_pwr_vccint)); val = val * 5.0 / 4096.0; if (val < 1.0) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -463,7 +464,7 @@ VelodyneHwMonitorWrapper::VelodyneGetBotIOut() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_bot_i_out)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_bot_i_out)); val = 10.0 * (val * 5.0 / 4096.0 - 2.5); if (val < 0.3) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -490,7 +491,7 @@ VelodyneHwMonitorWrapper::VelodyneGetBotPwr12v() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_bot_pwr_1_2v)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_bot_pwr_1_2v)); val = val * 5.0 / 4096.0; if (val < 1.0) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -518,7 +519,7 @@ VelodyneHwMonitorWrapper::VelodyneGetBotLm20Temp() try { double val = 0.0; val = - boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_bot_lm20_temp)); + boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_bot_lm20_temp)); val = -1481.96 + std::sqrt(2.1962e6 + ((1.8639 - val * 5.0 / 4096.0) / 3.88e-6)); if (val < -25.0) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -546,7 +547,7 @@ VelodyneHwMonitorWrapper::VelodyneGetBotPwr5v() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_bot_pwr_5v)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_bot_pwr_5v)); val = 2.0 * val * 5.0 / 4096.0; if (val < 4.8) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -573,7 +574,7 @@ VelodyneHwMonitorWrapper::VelodyneGetBotPwr25v() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_bot_pwr_2_5v)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_bot_pwr_2_5v)); val = val * 5.0 / 4096.0; if (val < 2.3) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -600,7 +601,7 @@ VelodyneHwMonitorWrapper::VelodyneGetBotPwr33v() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_bot_pwr_3_3v)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_bot_pwr_3_3v)); val = val * 5.0 / 4096.0; if (val < 3.1) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -627,7 +628,7 @@ VelodyneHwMonitorWrapper::VelodyneGetBotPwrVIn() std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_bot_pwr_v_in)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_bot_pwr_v_in)); val = 11.0 * val * 5.0 / 4096.0; if (val < 8.0) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -655,7 +656,7 @@ VelodyneHwMonitorWrapper::VelodyneGetBotPwr125v() try { double val = 0.0; val = - boost::lexical_cast(GetPtreeValue(current_diag_tree, key_volt_temp_bot_pwr_1_25v)); + boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_volt_temp_bot_pwr_1_25v)); val = val * 5.0 / 4096.0; if (val < 1.0) { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; @@ -681,7 +682,7 @@ std::tuple VelodyneHwMonitorWrapper::Ve std::string error_mes; try { double val = 0.0; - val = boost::lexical_cast(GetPtreeValue(current_diag_tree, key_vhv)); + val = boost::lexical_cast(GetPtreeValue(current_diag_tree, mtx_diag_, key_vhv)); mes = boost::lexical_cast(val); } catch (boost::bad_lexical_cast & ex) { not_ex = false; @@ -756,7 +757,7 @@ std::tuple VelodyneHwMonitorWrapper::Ve std::string mes; std::string error_mes; try { - mes = GetPtreeValue(current_diag_tree, key_ixe); + mes = GetPtreeValue(current_diag_tree, mtx_diag_, key_ixe); } catch (boost::bad_lexical_cast & ex) { not_ex = false; level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; @@ -801,7 +802,7 @@ VelodyneHwMonitorWrapper::VelodyneGetGpsPpsState() std::string mes; std::string error_mes; try { - mes = GetPtreeValue(current_status_tree, key_status_gps_pps_state); + mes = GetPtreeValue(current_status_tree, mtx_status_, key_status_gps_pps_state); if (mes == "Absent") { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; error_mes = mes; @@ -825,7 +826,7 @@ VelodyneHwMonitorWrapper::VelodyneGetGpsPosition() std::string mes; std::string error_mes; try { - mes = GetPtreeValue(current_status_tree, key_status_gps_pps_position); + mes = GetPtreeValue(current_status_tree, mtx_status_, key_status_gps_pps_position); } catch (boost::bad_lexical_cast & ex) { not_ex = false; level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; @@ -842,7 +843,7 @@ VelodyneHwMonitorWrapper::VelodyneGetMotorState() std::string mes; std::string error_mes; try { - mes = GetPtreeValue(current_status_tree, key_status_motor_state); + mes = GetPtreeValue(current_status_tree, mtx_status_, key_status_motor_state); } catch (boost::bad_lexical_cast & ex) { not_ex = false; level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; @@ -859,7 +860,7 @@ VelodyneHwMonitorWrapper::VelodyneGetMotorRpm() std::string mes; std::string error_mes; try { - mes = GetPtreeValue(current_status_tree, key_status_motor_rpm); + mes = GetPtreeValue(current_status_tree, mtx_status_, key_status_motor_rpm); } catch (boost::bad_lexical_cast & ex) { not_ex = false; level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; @@ -876,7 +877,7 @@ VelodyneHwMonitorWrapper::VelodyneGetMotorLock() std::string mes; std::string error_mes; try { - mes = GetPtreeValue(current_status_tree, key_status_motor_lock); + mes = GetPtreeValue(current_status_tree, mtx_status_, key_status_motor_lock); } catch (boost::bad_lexical_cast & ex) { not_ex = false; level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; @@ -893,7 +894,7 @@ VelodyneHwMonitorWrapper::VelodyneGetMotorPhase() std::string mes; std::string error_mes; try { - mes = GetPtreeValue(current_status_tree, key_status_motor_phase); + mes = GetPtreeValue(current_status_tree, mtx_status_, key_status_motor_phase); } catch (boost::bad_lexical_cast & ex) { not_ex = false; level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; @@ -910,7 +911,7 @@ VelodyneHwMonitorWrapper::VelodyneGetLaserState() std::string mes; std::string error_mes; try { - mes = GetPtreeValue(current_status_tree, key_status_laser_state); + mes = GetPtreeValue(current_status_tree, mtx_status_, key_status_laser_state); } catch (boost::bad_lexical_cast & ex) { not_ex = false; level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; @@ -1173,19 +1174,13 @@ void VelodyneHwMonitorWrapper::VelodyneCheckAdctpStat( void VelodyneHwMonitorWrapper::OnVelodyneStatusTimer() { - tm_status_.lock(); - hw_interface_->GetStatusAsync([this](const std::string & str) { + auto str = hw_interface_->GetStatus(); + { + std::lock_guard lock(mtx_status_); current_status_tree = std::make_shared(hw_interface_->ParseJson(str)); - diagnostics_updater_.force_update(); - tm_status_.unlock(); - }); - - if (!tm_status_.try_lock_for(std::chrono::seconds(1))) { - RCLCPP_ERROR(logger_, "Sensor status request timed out!"); } - - tm_status_.unlock(); + diagnostics_updater_.force_update(); } void VelodyneHwMonitorWrapper::VelodyneCheckGpsPpsState( @@ -1546,8 +1541,9 @@ void VelodyneHwMonitorWrapper::VelodyneCheckVoltage( } std::string VelodyneHwMonitorWrapper::GetPtreeValue( - std::shared_ptr pt, const std::string & key) + std::shared_ptr pt, std::mutex & mtx_pt, const std::string & key) { + std::lock_guard lock(mtx_pt); boost::optional value = pt->get_optional(key); if (value) { return value.get(); From 0ae9198d2a06a5722380e3d918e22416991394f3 Mon Sep 17 00:00:00 2001 From: Max Schmeller <6088931+mojomex@users.noreply.github.com> Date: Mon, 20 May 2024 20:34:20 +0900 Subject: [PATCH 057/122] fix(nebula_tests): re-cut scans in existing reference data correctly (360deg). has been ~372deg before (#150) --- .../velodyne/vls128/1585897255376374245.pcd | Bin 0 -> 2513322 bytes .../1614315746471294674_0.db3 | Bin 3072000 -> 2695168 bytes .../vls128/1614315746471294674/metadata.yaml | 14 +++++++------- .../velodyne/vls128/1614315746748918706.pcd | Bin 2606550 -> 0 bytes .../velodyne_ros_decoder_test_vls128.cpp | 3 +-- 5 files changed, 8 insertions(+), 9 deletions(-) create mode 100644 nebula_tests/data/velodyne/vls128/1585897255376374245.pcd delete mode 100644 nebula_tests/data/velodyne/vls128/1614315746748918706.pcd diff --git a/nebula_tests/data/velodyne/vls128/1585897255376374245.pcd b/nebula_tests/data/velodyne/vls128/1585897255376374245.pcd new file mode 100644 index 0000000000000000000000000000000000000000..5da07e0631b3b1ad264c733a1b908735d43693f2 GIT binary patch literal 2513322 zcmXtfc{Eku|GpxbQld0S%Da>XnkV<{^Frn!LqtfU2xTa9Wr&igGDajr2n`y9yI;pF zQ)wO~Lqs&tJo?^Gzx7+^kGs~rXWezyKCk_}p4am{TUlx8CM|8HL+VS{C@oRiwBOm? zTS?1x|G`~K+S|RiEA4T1-L14|zo*-FZwaf7<`(*yt__x;w8PnbyQiN-=qzzqk#Pv={$3pJ^@Ys9^Z2(- z0*j|4vg&JH==8@i%-9EJ(3-N7j(VhG<o;S6=Q=vw}GT- z6zOk1f`^hEVA!dKWWLH`yq4QS^ZFWmFt-5%avs7J1##}$MiDHNPGqf?xX_f|66VJ< zH!v3prdV?tPcN(l@yuIHVCG`p^1FB7zpII4$(c2*_S$XWry52680g{1K2y*ecZ=lN zk20li17I||8*e^3j-|#OP;E7lbIM?d_TnUVzn>e_%R!?Vw2Sg?mG6{|gNGY=llHI)Dk9$ZfYyB&CNE z+045xG$2C+jYGnKR}o94t3zp{Q8keK+l>3oT5?9+3_h<=AWawI@tSK8bkE5knPoS4 z*J@hfhR14F@t{4MVEYnI%jj|?%NA0hDX$@Mk}T)>X&&ph7mwi=qcymRw0r_bTI5y&!lkkwGfe&B+Ny2Vkg}ILM%Zl7vhDdGEhvcbQ#B26A($a3lN)CoIdEGwP9(fhS z@)TIneg_dzo4I9|$FsaVdzd&BgQb(>Q29XuyXBrUExUG@ckPcWI2mqdVlsE& zp=V7ndrdM4PIn~r8G7LJIe^scuEey}SK+F?0&8|q1YKKgL8iV2>o*sn>#c{Nxj>xj zGI_y2xi5h&Ug}Jr9_wKWti9mo&roW$<^W2jR71t^ZKiX`&1;BLpFM1ftw+Dv@mTZs75sLa#0{!uF{0jytZS1CeV6M` z^wzk+)V!ng?Nv1lSW*Y^yDJ#OZ^mTYEJJWEkSCJT&Dbv=1ldFBM09O4O^q>zX^uC@ zXTMz};!g;CK0An6mu8@Wbtg=^IEiZ?bC7me0}N9|*J&YNR`*3^Og{tBjcXaQR#;RFkgEhan1TcLqP5WJJg zAQSRsNkq;@AiImn^Fz0Bp3@u9wX@{LSFa^M0u;bM%oLAW^y0_A32f%5Hw~mMUK&qPtJQ$Y}(be6>ZxJU~7?7;2?CF!>g z;iIvy;qNIkZdcG5QheVU4EDz2^6^!ubt!=jF+NDg?z_leC07eS&wi#Rvqwnq8FOHW z3iG`z8HILLK(WCwvf<+u-mhzF#P1^Dh|E!caUBwMP^ zk@r!0;Ogu}l1^viz1>@3$;S$^_sL6s$i)4ym!JAXew%{S;3)srR46%R-UG* zI2_?0#sklLQOw8(R_)EjW8cK_jG)f9zxAV;>tmSNAI(74`~+PXnTih=g~8GdER$)y zheq#igSf0X618GHdvMeNHdG%Y*VY`t1@rCUaCZgyf)|+5B3rO|)`$*y4XEY#0=&{? zIlCibI3YKIU1sD@*BmHe#E165bhEQ`SK=w$F|!sdtYVqIdFs5bwT;kMe3HB$T*E4- zYy;=n;Y1}~566v|!jaUgq;Fu9S=HhXu{r&CLhm?A{pbKGiK*O9mJnXHphtWOpp*7$ zBRLQPO<4u>knk9EnpFdt=VF-nrHSNIl_AVPDN-R-fZwJEK~Gx}ajaFO>Sm45*}Rw? ze^Q(+>NyC~@~`pT5)(Y${~E%?W^kof&Ju%`1onQkKb<*A1dY5R;iuvaT3>X6j{R5z z4Xb0B!*=y#T)P?U{xXT2pPGOTLWjZ1E}3kec9VBep#{FEsj;~!TiHunI>3T8;WWpo z(ki81uw6QXJ5e>C70XIs|I_uS1?H-G3Ml^}Bv?|ND{HC!zH65Fz_QU+y z^GM^NxhU#g3z}U+{ygf#QHMuhv9peAZ5?lUyox(suNiC!~QhJ)`_mD zZGg|_!f29shU}kg0!A;UFbbY8(e`*b*qjI^y~pQbnDZT&ojFXb2cD9v_V$83%O`P) zN%%MNBY4i)#+}l9Le74%h90w1SV=BojZp&o;-()pG*hY=9Mb~6(?sz{%73iF(ftsp zx|A6&8;3`G8^FINl6bxN%-jv$#_p2|XD0L>#olq(;G@(u)>qyhQ|5mJ^BM;(R9Boe zSZxpG&*PEzAQt7{C9q?w{i*%i!@Q&&ZgA!NVrKj34y<)(f;WCq#7x?etmx2#-#-qJ zg7``dU2_!*?Bv;b&LSu$z7^z`HsP0qBJ|t*1m^Zl;>0I+@JDhISP?-T$_(@{1}g4Q zS(i$`%-n}f+AUDIF@gD5(aE$FX|R%(W0`w);kYHx2co>#)7VCSkxC|oJT&CBA`pKo8oLWvpN(!b+a6HH`N=LXV>_msXqTnCdL zkHO!cIA-3B2DtF~6ti4n5qnA66+TZ;CO@)l(e1}ZFqO|Ir%G<)vw3e|uZtBIldzV| zDOG^)1Ll}_wHLj+64~2Z1F69^MY_zq72H0HVn=u*`QvB;u5weEwFZ|l7Rw>vaxkgS ziK4#)o8h6^7qY@@JnK*?=;=;;5}W0N&GA2=I@F0XJd{aLdJDAfIE7JAg}%oV*c&ta zsk6>S{-{q4TnrJyV#i@JU~UdiN2W1ZCzCPaM+Mj(48NcfMv#(Bfg)odKNa}<>YJ&rpYNCRRen4|%K)kQ(Hw5bOx z1Q_lfzxW@9CoijmsJ`PQOgNo98rFkI84r@yosE8NcA$E;g4Dn(e&=3yAa3Vzq@Q43 zK?3{Q!k;$ESTK`E&EWag6ZBT@4YU;r0fp&2W}E6Tb^bL$({x@9Y1NQpPfKot!;Qy? zpFt{?U$li)m1QKHdBB@FMjY60A^&*z4|iXfv9K8Zvn9~FE`hz1eT)ty3GhzJ927dv z)6ExBaiMesT$L4LEbaEu(j!fReGyC^Y!hb9zPdoUbvVI&;rPwSA#+PVjbO}FNA5Y>!HL+pZOq@LY6Hyf-|XO2sjkrZKGR| zo7zUY`*+jzaRE^8_YtRwTHxHw9yoetHmCb4g-jBxNu*#+{)gKi&5ppE6Vo7lZ>q)kU8Lap$LQdAkW2^ja$jEy@+VVu0)UFnoBc{qewzgyEn{>g?ZPr|> z?P6NiHv(FEs@$f>>TJ!Q1eSSxjJ|r4Ov4}4LDj}-ILA|yi0i7b-y`!h^2VlN*>-oh zXD&~U|DJ=1nYAE4+C?S~Wf8|+IzXQaJ_S6SK9tlPEjY&Izs_e$D-zfhX~+KIcK3yP zIQ4oOwp5=cHn}DczWN?--oy@+R1AlCI;v!*XFt8Rs2-{-dx)jSW1^O254MuG{_${l z{uRD_-^Uq_wiA*0TR<)%38#5p#G4lrSnm_Z==CzCig8BIVX>MDis-AcBIDdZ=-zuC zcP0jNOBz7t?qQOZ@R`{kw~f7%d*mN(Q|oK+L|>M*-fNGtN^fCD>o)FD&p37{+#alq zQvdPrTcHW8mGd!rNb4|ffY}eLq=$JuHM?+KbS?1i`jge?Y>23WK3M+PP2#F6F{$_( z#GR65JG{qX$-}K+^xu8V*DuCi&!_OcLY_OO|BByww-anq8gSjZMeNHl?r=)?CN28q zf(z%@!pAHf#_-7#CU8W9E$IHh`yUU#eajC*>to1Qy}7vlOD&89Dzh1N1w^vh0T%y! zh-aU~;|beWpc1dZRW)5;G>tB^zg^O(qU>q1{mnj5y>y+1;!*_jIxxPk%UDb|AwAR( z)UC#lSLd7Y{MVbXd|eyqiiiz9wu$_;dnh{JNS2% z5UD3QjOewka9`so>Q~*tq|8Woytok`r5Dmz+fJBK{SY_Cin3dpU0`%lE0rFM!_=+S zU?%^9r*md0uVUR}XcqP*-3^-T)Fs>D=nHRB`dS|&PVIz}V>gKIdr9)eJ`fakf5&8U z0!`z(p?&2%Zj+ZL3A>TV&K-)OOHOO!{K62}V&D5uOYv{G10qJQHiz(rOr!ABGC`fE?I8mp7oKOLy;B@|U3da!hnsO==Pl-`qASdE3ge~M zZO3ITwJ=3!H!*0pA&iYa1drH~LnD>ABcud=s7+-1L`CuZpRKSV;wg>^D#nNI&tPwq zB4@d+lYhdd0}|TrWAFBb?Cl&+IQ;n`{gAL9PhGD8wX^NKN}DH4Ezw{QA@~{T(^V@lUpMN8@ zQr-}?aRS+-6pI%uT0!5glk}%ckn*qZ*{n3?pRRJf_ymlEj_1TC^J$7rFZ|R{;l5gk zvUh&F!g}h6H&JdpS*Y10bRXxa&YuEe%drfb8#-rI*qCN(4+;FH0QP8PZi>THv>*U>4jg##&g~!`h%iBJ=(b z4i^stDe~mnBhpCvgDr4k`vtUDsK(5J2w1sJFn=f})9DU%@bMfEuhe`Z&Z-vB;oYX; zKQ9HPWhi*68k6V)*LYWU-T{*-4~RtJMivw8peyAP@pL0tcKkCu=sw6vwk~2FvkyV0 z^lfZ?9gJVbb;6gIFEKLPnA9_xFu%Hte&)T#`lGJk;{8Yi+g0$zpL)1oWkn9`%pfU= z`tbg?xnO3>LGeR&(4&5dL=<)KJW5zW26Hg z=r-ahjaYd8wwmV(d*}ddzkdpEeyfH%>DM&u6xDboS0BQ8 zZwKP%0Ic!f?T{_wOw8jA(0ztKglPW3WZC2R>*pZwN|$r9QVd8-jT*Q{s-wC|FIvSN zfui=`RP@PjDs-|2#OIZ0h#gHN8{3Uwf!1SYPG14)oG69Oo2a12Inlg`$M9nEJoeQU z8CLuHL73C}9o6(rP;OEmywh09-8z>_25)SJWw}=97FL0Y17YwgSQuqih0*RGP2fLx zTSLXKmFTKiz>KHu%#D!*^jUoyM#ds3EEZvSi2>k~SV>l#5M>*kbHOKc0XKU8FMr3p zv6}biY~&o$dF+P8`(f_71K2$1g|lzf!@08?QQuaJlol>v4e9g^<4n(?y48MAHvh@Y zO`eNlUNvwgrIA>?yg+D#4yaWp|KsNq*NSU8e~RQ@x92kC-3W~NwT2sdoXaj9aD#%+ z?s%(X4F<+Ez_tB4sNs8t*ch0?qmLRInfwl1y6hN8nn;rThCXW1-U7xZ4~awMOY+%q z8@%hfM4nqFqlx)Dm|}K-%gT93x*u(UU2C)P#*{qt43C9-Dsh;*Y6ib(c@H!;Ibx2_ zYBnZgFMJtqsgd*UB&LKnL-fFA61wyUBlf|8eKxS0+2wl_t6NII(N=;Tn6wRN&wK-I z<6O879TC<_(;lQxU&Poyu{dM)GgvMA9B*DNWfWLf*kom`(c8NnwPx4ChD9bsVyX?v zIHnKxADWVKnJPSe>pJL5OR~dVqF5~0Q-7IP81beDa5;$#PE zK3Kr+`+5L$UEWjO5jT7xQU@ME*EROudCC|(SkLP3spdKU3B&PPez0FKCwdRe!PW(J zFxP(?Tkx=ebiQza_m{eGXlw$m@92aYV^vOKOg3{}OVEES-%^!EHFV<%`hI^ZZw#Fg#Ge6ctXdoIHbcGlAB*j~UFOSor;McJ8?>>zx+J-T?F#Mx?%@Lp06cO=y? z;~g8}&B0QQd0vazqWP|{{LfeBf4YjiVLMRu9zt}FlHMyi@Vq;jj4m$2s1OCHo8*Ry zXM1szl`kA~^TYn4vFJ9T1^l`V@crgHMB3RD?o07B&Z%5M;t~%20)1)FM4v{yY=s!> zN95{|7<=W40~p#~A}ja#qNItqW})~=ZeiC|a*o)5@9}K(52;2yI1YZ#kE3g7GF`N> z6$Ymo;j_R$#AB-k)a0-lKlM^D?hJyXgC1#nR>HGi&<+8(T7vjxwrAy&AnOCtrr{p6sB#6N7Hf?) zk_+&qLLK<6G$rr5&yilf z-omruT4=H66&Nh<#Ll2|qIvDn zY8&V;-}6snF}r39=XCRk>BI-TRXt*`;%Ll23=jQv2%Lng{^{gl`j0_`^kCY5&4kgk zfIm6?bX@D) zIm}9PJD9Mw7ng)KV$}R-=&XE+`L8b1kdjW&FnEvjfhhZD)D7IEgmL1#)2KYD1_r`I z_!cYGcuuPx!r8StM7f`3*G}3AT?g!m_hCca>{1UK9>}t?vIoi22LVtjE6n-Jp1}VW zcY$x0I%l;5h}@tWoQ_$Kw$Z)Fq#S`cd?{S><~KF=tO2ct5Wa?6B59s%47*~G>5;yK zg{HS*wDdYTv2ib*TPE;uS1GXh6DP8VXZgV03?WW4&J;V8M<9I_!~ORpi%gfaf(O5M zp!f3%WV^ya|AZX=ToO*Rj@CeHTL}L`e;p}4Yym^jwaod&iMUa@97KX|lI3EeOl-10 z+^xP%cwfh{mF791IYYq7wg2#ycDx5=%?(_{ttITeKkiWP5rkolUO4iz9=5KxL+cA# z#I0>U>pZKY{MDIM3|n>pj@orH84HwA;&2TFoyUK8zWk03G;BRXvfw=Kej%zkd1n;o zJSm&`;P?qHFC|>V%8Ts8VRwLCL1=noE&dL=0|~F~v0!mL$+%<+^FV@cKK~W+=Z8Ud z*H@`bi?!oe)#(KD)w=hHB|Xe{#;7+n@Ox+tdD8KLkrr}b?;hR4 z2;V(|AKOcy#&X<0JP)|o2Q3N*xQDVL?1XN6_+?m(!ya)s?_?*q&wh_W6Oh>w=nlVX z6!{y(cVVV+Em#|^CDXNRi1mm*tRB%O5&NsqDZd0xEgi@Hk`hH{Y6m4vy?By$8JTU* z;lqhVTx?JmzhAxsw897RwdO*0uBQhq7!g4yFL#u6u7xPqP`=pgr_ABw8m#)vE4*&? za6C5P4dTz-37Ie(g#_69-ddI&HM~UJytl#P^nR4_Pe3+x7>pZvoX5s1%wc;s_q+O148FQ_+}Hn5r?-2Kvlep34myv z@6iq1qjoY)W*Yf){yp39TAc(KyusBAV+5L~ESJ5jn(o{+2pRorIgKykY?rqi$h8Gv z;n75#XWj_wS{+agYnY(=7I^&kIKR_IjrE%A29m)qnXwUDabt#*W~Z_^D^rn00>u17fo$09k4bGd;N^4~hv(K{ za{CGRnU;j>x1FWDre^pO>wylpe-Up33wY*ooc|v$1-o}39BEP}!r3LfxACpuXIDwI ziw)S(COf!fo^M?=imD< zOn0uTh33=q$+x-|B3&f#J!ftrzA>pdY;+SQi3zhmAF44wy2aqs&eJ$Grx$JG!(egk z6O>&nhgXg~g_Zna3^QsaAEGRvZj%st+)G0}(UV}<_>^y_<4Lbq)TF?EyQ8Bty7seiL3S1^rM|5(afHuoWj9#~37+E}(LeJ9LaZ$`pC8RGNo8tB^~ z#fB$&5Uc+Jph#bon^bcgebu|5m081W_5sqKp$3PhYvbH?y=a^i4)Gh6QB!>!ZuhB$ zNnfW^{;DK$RnHg{Tl1LQHJ4E3p@2W%Eg;&j_EO=Ck3iUd8fzdV!$wE>L+JN$+<}wk zIOcmVc+B0v(Y#b*5@!XI;`d|FRz4~mI|g6B&%xm*0`EDy86sn5(@*p7l6%)JKyGR= z<7k?Qt4hnEC#sNC?h|F2|M)}MpKIjM98os?T`tImE$6JCj`H)?e+EUq4)<4lIjgkJ z8zgOxV~3g_3duFYk2oKcyrfH(NU5-)Oh|=xQ!38gasVVHR*UkA_QMwwp_K*G6-#$-nGfIAo{9>Wp4wRkn55tdgT#6_d=q^-ad7QD^; zhvCBGkHJvgbLO;HA5A~e2vv*9$n00oh?JNkJgLqgAw|jP^K!E0j)~{E3AcpVylNYe zSa}um2lH_I%qSQ>kcK*`Q~6=boI$1S27j7P6t)W9Y2es7q&E0H6Ml0C8@+22Q<4;d zW^&h|ZJ!W(P-`2;MfQW}WnXUo+Hq{rhy(QOyMa5^Pa#v&0rxAuqhA7_DOm3Ta#Je! zh5381Y*{U+s>~%)vjv*@AAJZfSoaUNmzFF`MG zC6_d_m#^LZ3YPu;fr$mG?4qLw!L?rwcL#c6v~Dfb-J4ETe?4JlMQgC-lBxf2d%OD~ z2oBpp%*H68k9RdZ+9Amf?93wv{kOr(Kku13^tKl&yC=+S02-s(}HS)mLk1d?dIv zdehNkQ8$d2T+4lsZzGc{qhZ$9Md)_lpge}HhcMfjG_Lk*3KUHC`xLMaHGWGQzkiVp$n(x#SpjLGPE)f)m$*` zG6fGTyGN)>cs(3jKbiC`zDF7sm_tY98j`Ja z8tc4ng0%2&k}#ykJU%T3b3Z2F?)3ux5gH0b2VY{nm@I}oe*q5%ggBk3HWK;G0-n1{ zq4>OW*fr}U{5r2nmwI^8IqlV8ttv?>@HhEX>jKkr4T!I5I9|360+GlfA}3SE{AslV zPnVH@_&lXP1+x9da6pmDdax~QsR)~mm z8=sq@l=5p>KSf|e`<*2+Sym8pBLG!>`S`0)(C@rF>7yA9q+^36lr|?a5`~GVaI_p2 zKg}fl8lp_$Jpq?)y+pbN{=P=&#ZE?iGJPAm$}W8j7HnwtIb z+(gwJ=F#T;u-qyN4Q8yv%VA0E$4WiAyWfFnkk|y}s-t}2*jMP05(-m=%bDF@dgzDM zO%S#BGAWLEPOg+V!0V`Fa^rRqj#)cVvu49NZhx>4D?P^+X6N0)Dy@7x|KdIf>wd#6 zw|4L!pGaiS9Mq*pUk@{pvz=k&t2EWth{DW84dAj~nk;Jl#GG}oV-43Z%+P}%tPfR3$OOE`*UgP%;Fr%a#zpX!oPdhr`YVlZ(DdjUoHXaZ)R*sG|?7=xR z>!7bnifo%{OG5Jv!0-K1(k@wzDGvi-t$Gn@3$LKh_Sr+;)KAC^U&jC3UO*YHTI%QM`~=6mFFeht*D@}Orf zej|fE-Z1TY5wm<#ELKfx0S~dO#HL7`s2q69jwC9PfT=zBw>K6Ve$L|9Z?#lU>N~uB zx`_++mthlo9U%8w2=-Y=quaP7)?&IIUEg<_S5kz2KoMD8wZi2bdqx{9+uHec8VW79Ng7GrYp=K-VVE>d$#8^R?Eg7+g zYhuadtE~^tSty~YR-D9HY6!fsNLvUOD#e7(8uZVJhIj=*E;T=$=6EKs7ln1`#7=+V z1k$~fs7&q%O-`$Yzk8*K{*qSm^z|kPGhIpk@=jsu=|B(>E+Tu5ed4)Pib3o6v;R2o z_d^1VZ4qea0*o~~_#6h-i*k({?~#x5!{K_MBh77grdB&@z(8$~G2Huy>{i|jxNUOn!Y$X^L3Sd`_2!7jpEgjhvyJ7HL1O23j|*|MA{(_e9n~WefEX^qXlj8(^;6McTwm zA!-kdAvfp{vnBfy{@7avw+|%}Ce)eoZwQ`$G>3e5xRElk~q~G?k)(!j<-qddr5XK$Y0&S#paIkdn$!AUF99Q;`R;fH%Cv16nIvl?mpNN zo5=pO+CpF2$THK9s<4Lhr1;Y7(=ceED=c%4W(>9~VO&-X*q5f0X|FGkqXoLquM$cU z+s>o>PD#y#ziC|Wy?n;_v^x|ep2h>QYjHm>iFMp$Ll+)*U^e@2g01dLsfu_fP8$h^ zob*)YlWZ4l`7usYSnnx`pEQa6{ZycXNt_|m4<)0!hm2;`y(}(1ZY(=1-4@gsisNtO zBfI_)%n=dhzM1dlA3T!4#@@A}eE7&LaM%x2M~`kBjm7bkdqGiEoG2caB%8YJ*;mt6 zFlWM#;EKFJc>Ohp9F9;xZS`LQY>eg@iAij{j|0%8N(}rJhpUeE!J^Cw+$!xFW^k1| zberhXqQ;$Qb-fm3YlfJ$xi;iRj{%HSE0e1A)o7|62s$@%h|+`#8s26PMUQ{r2kR?n zzu+Z^d$Zi8bFcZ_#36VgDZ^z*tYod_6WQi`YwBkZPr;xLR`uu5Su>t7dFM8;ikBUE zs=>!_K;Ij@1i6d;XhodAPf#bVIYipZhFDfPKws}qoU$$fhb!K|q)Z{DT!>< zt}V1sXB(AosE5lc7isBvQ__=T3{JX-m`l#BST$M(2RThIEkvAL;In4~Y z#^SsgEua#eL)tHjla00gY(w8PGIehkzLtsuH8Pjmxv`GAjPC>U#d_SIFQRN1u?IRF zfd!kRaPPT9cE8IOS`vPm#~;1}Z@=cz{%MQZMP=^bG!nyX9I->^{{*>8pHQ;PxEyD_ z71mUJl*q~KwIE676~O#+B-*I-;ai6QxPB!aXS#`?@~T93_270|edY`^GO!80wHVMF zURTjNCIa#o#xboQ3}}x`9o$}a%*g96*0u4Dq_gVx#tW&7ujZ+}bdP< zXBm^3i;~zq(!1#ex(x5UaD}LK`>6Na1-R|JKtH_I%p_-}5%JlE@bk}1;JV=~1+GV$C$ zEjnyRD7cjlV$tYi?3mvLCbp9}?#5%1B-rnh_Bc~jvrhVAT^MXHiKJ@Yd#ImSElAC+ zVt%jxOH{`@!DIEM)^BPJ*sSj;Kp+y&DSiMFY{g0B8}LoR z%gA$jo_3hz)&u4uMqK~Qv*e<)HQb*WiLY6TBuUVNcJHMluM_xpBWmI6io3M@M?INf zBGAE>ZDI`mCZOo$3OJ(`LpsIBGkID5ux;cV$$K!4bzCt3nt|b*+_&Xa*iT6F&EY-V zQ0N9$Q}+OfO*o6gHV1J_Ujn<;(ur2yp3KyJR$*5xRpR^gV0x|1*NIH82Sb8vuG}a{H6mJ>Ltm=zg z<%O~A%eS`BvAqT(g$e}T`a`hQ6618TcJXJOO<+qq_E5P)ADO%T?ogQOPvgsCarW*$ z_$}1KoH39hljm<^f0G6O{KUEWf#A0`gX|1az`(elPdoL%j@uPd_g@H3P<&5Aw z3wxJ7vV6)+dZfWdPFT= ze%dg2=x*Vzt6X6UJQLYBi}%vyQ@7EjbDAJr_7R<>XhCM*Hipkv4Vd44t+>3s9L{A& zlUe%m_+dp5498}Wea2B_?}lLbGhqrhX4P~w5oC!)cbIct($7fPlLXeE=R_9;S(PX;c=k(|H)!a3Fc(k6Vq<6{FjtewmEQ5h`9?o`BWE(%qThw%Ar@AzpT}iu z*U}p}2&w@VoScIMoBiDZoIl54&!K3Hl1pUsQ=O>A_|v>`N4h~L@g2Q59@xtN++f*7 zXQtCgei0-l{@snGbWI{^DoDm!oN_rK7q?#Y(yFz72vUoAc-yD+hQ01 z%|f|ok}rbEOB30d*F68>`G&P-(Ei+yzAn9r>9xTiG~Sj8)Yhb%PSr#0s#r4ivoPyE z&Jn)KogfDS{IL3su%>@9u>OHWF1Q=Q&ZrY3D|ny2of4wtshpxOs8(%DM&k zxTyx52G27~Yto3`7DKRYm?X$?#p}ToCkiRjVnR&CB6pom| ziC#JK>&+>go*f9a5h-MF_b1*^u^322WnvBXVt1neyQD{OXxC(9q`P2M`c&>`(PI*H zJ(1;m`q8_wuV}1sG&DAsP(_17bgUrf=5Z#GnI}9-=AUtb*z7q1Z!Qd{8wt*Z1t*ia zUALLd`vtn9r!Z$f(u_h6a^a=J49`jy7YFD4Y z15$6`UGrvcRkIFJ>QaLb&in9Kb1%y5NMtv?_5H`mr7iElXru_*#RzoOLK7(Pn#KII zEJRK53W#At$v(e*bn4t@NV@xlY}g^eaxs3OR9{HZa-Nj z@znyhtjmh;5`GSc<=kLy`bwtvw-WN4Bs6EOsU)N8dWqLwJs=hy#M3ep!|g>hPkE$q zKKnA6*4+KjyW>3S99f4)Bm{GcjW3<^#E$vfy9u7Y38My~o%l^M6c!iiGD=^&={G8- zdAE-e`O(R&X0QVUe>+Cj_$1-!$s(G+rloNXTi=n!Ra@cM(?*mwD!`VLk0C2zBDb+) z5C4^5hTZMp^N*9i4{-+}OrqzG#NwWvE%4Ddjd?ZeC-bdv8!I_SfqBFo#Q=pM_`WNd zh?gl~%-0{_d+Q9h$A2Ol>FNN_+gkqNxpP|wJW-s&O?=2_(ktBH5t~F;+3&RBT39#2zV+<;|buj-aYOwj6Ch|m|9m5WlLm+*B5fQsJ z8^zfg2s0ZZ+TD31zrX=T5`;Nwl7Ph^q`AW0jaz=WoKcKOVEd2w&<9oa^n^W(DT#oyP=PP`|!Q@v78kbMNm4fraBkz6w=_jLkW-zex7_FRs4GUg} z!|~(BjM;mAy56uE3R7apoXO+a-);Ng>91&V+$ax;-s0IkY6bso zab!WA0ehBigVQ&|iA)Qi?|2c-7m{h5^W^ocPUu0fR_nowNx?Ym{{{x%&fv1{TawvY zN$dj$e|q!vGCaA<6^3>v(m8D^IKH?Vf@BjIxz1GLl4=N_6{SgeRW2?(cN6-1Ul8q? zYiY!3AJ`z@ixK_0xZ3P9up!EvLv|ra6U=Tz$B*jo8;i5Y1i}T&^Yjf4&^1SD;Kj8B z#{6e9@!ew%PueFF(>15DP`(T_rgjn=ofXWE3Nf$<%|V4Py;%G*1nkcKK&umzkuY6g zCO3;)H1wD-cM{mWwqewh*FpchKLNhht<-q`0je2R2hKH{nZ}7i>`%qr;I1G`9z6@e ze!+hKT_DPJDYgjmTBqURW=Ssl;7xk|x4Y2-J6=x56uo;SX^sUvwCUlUe35`-RwA@S93=Oe#h6n9T|IMQ90?yU%AR!_ zgucKS&b56dEkYs9#JGdpdl>;XygLYMf-m6#?Eo~|n#dk{5k{Y^lVzq_EMzAe2k}>Y zIfr4{uHb+FFK^mqC2SL{ISw5rO53u@m+|^=R~wP2+4or0Mx438y*oNg989;ug?Vjw*P{S0zk4jmbWPz{8z=tbwnTQN_Az=Q zc!V)maEI3E*J!Tx|8aC4el`7J9B+^&A|W9m$tat2&-Xl+2q~pR(jZw4qm1y=9;mb@ zNrpZ61j%lisIXQCPNFZ&@{Zq05; z8$Ou*Q05+hZ%;K*Ik^L+6~%>xx(PI!QDQTTtl`a}=a^v`it6hcfn-gftJiXj$YDP? zSKZ?zKkmd_%My@A3uacJ6*<|s4qQ4UNaC0RG_c8ni0jWtikS=^)wTg?rD4=F{Vt}S zZ-V}Xo9L>;ogxo~ZkT#u8hx(4kk!qLWEYwFaPMRyI0g42xaz8eEt_i@i+DXYZro$N zf7y>&vyZ|%i^)VxYzoTx6+mf1GubuzI`L#|V9LZ{w52c-LqGIE6T6>=F3Dm>^Sbf5 z$cM{px8`0e@$Z$IO1P?HJyA|Ff)bAg!FKCP+~ny8QV(a7$ze5|@xo$AN^2uNSL(=_ z8V|7Voj_-Hj>DlvU*MzfE^67>L{#LW*tiHEuHp5j>>+0g;mxDbSn>2H5%}%{_45OQ z7Mas{U}6b~PI!=BMv8>a?PiCC4I>WzZ74r62wqld(H*{doU%n1boyD-lOttVkE_%K7Z4J3y?!p*ubnC8k_`1?*BV^Wr}zx-U_MXwmsp0W)cb&KKai&La3dl&Iw zd99Y+MMllb#g(T0Fnf4BZ9BD=ys%M)7V#LY8qtBaF~>oD#Qnk9Tbl2HTu?4V?Z|5K ztl9+9v~O}NSEOUY9&hlwT_LE>SjlZ|EQG52E@by(307z9J}6J|BIjOu;Yf!*7;+`T$<2JSJwNmT_6)qlLCc8FYhX8hc^YQFy-d3$D3nfDdlGg;~WK)cbKVY5x$# zwyT}xs!#$Q5BPvqRXz72=R0SYUjQr5C@=v`If=P$3xDTHk;BRfsJ1B^zMd^7=}rrn zC(<&ox9mF3i0r^C=3bEc>n}bQ8-=f)wLoy_G-~HjLyj9nv!iANbEiC;xb#ClAWK_0 z+YSe=p}Go&gh(>#8B%Q0az}V|SeEp)`QhTR72q(enb^%7OW>O|R7{qodoP!xR$eHu z>LciKl}yfFxedaPPp7GqWLU?3C)k~6gEnKrv23+BSmiczGcw=lo#Hd1FX$hEX4Vq6 zTh|HP<>g3%r5RqhTn?*GHxZ%U3I6XNf=%jU>2TH;3)H@WeU1zLxXhI7i`0f&#s3ZF z`c^#kg?-15qe<`(oc*#0dcSDlJ>wV>W@-#w30{KQx|`F3_Ql&YS`J}1Q6eSV;O^CYUd_;FwQ zpFo424hDo(l8TKRp+enP@Xt$m_f7;(m#oSCx?xPEWFObxPO0idLyCHLb811{W zi2JP216y+T(Zjp6*_h9V;6i^I&M-NKS0A>*tiBgGeV7f|qoK))g`N{FZ%V*xMUJ33 zD^g%usD?FDO5tPiKC;dGDjBh84cMe_B|F=aP_<;F@ZRiTy7p)>``@X9pwe>(gQ}L} zGw0Xvj+CQA)kQuf!uRye?{i^Cn$dEjFYFyi5e#kb;1(p6z~p)RNOAlt@`car-7s<@ zPL1K%HDZh~=x!FBqb$Wf=-LWDzP>`XKNUxOJq;wW6nzuMh_nmpq0p`hQ#Q_Lt>hg+ z@pBocB^!($sReNO$q#|*@lVVYV#5kvOALA`dmlZ3IhRYwpMyJ4rKS&V4o#rl86(*v zpRA$u{c9ZN8;WxlGz09IN)P-(W|_Y;w2dm~JT>i6)SM3y6J;G57oMz?i2`!?56Z`>_kJU8hGY^@ndV%Mo*o_ry!)OBv?+@(SZgKK>Q3qCV z!SJ?Tht6p#;0F3T;b)mWwSFhfRz~pe$S0Bp_59@3IxsP>M2o7I%-_wmpi!@j`&KPu z59~e&?hj%F;wHA(!|%a&O79}i7wjaDPp*MdaVrvUor{LMe!A^J{kai`x@$_Har%FPqaShvQj4F!m|Zqx;S>Y*T&*nx-R3)w zNkZO(7$P(F>L-%q@2?e03I8xw|GC;PxI0({@#CSfG%#Fx*9-#Df~4-Ay!SiLZa$I-N{D3f!~Y=d0e*>vS;8FuzaXV8&#!ho6K zICiKPoJsEIG>>=cxfSwx?Cqlj|1u;i6`i2ezK_YAYlf!Z^Fi!a8To3spR^?Gg<g~VOH*uf3K84|^yvl;N8H-71|F*Inz z=oPEoLVmpnf8Ey*rI$|Ji1-RH7JEsCf0tt?9P$Few&@gxT4CjMG2zZ*o;33NEwZI< zGkiV3dmROc_R9m{=oNo#yzkE?9(fG2Zs}u~LIo*Uu#xXY#_6fOjYQvkgxQwsh_{vu z^Y>CIWWKH7SOQPDnY?FL zZQ~EY_CrW1;MPLIzFh1ApLTU}XTFEv#NaY;aa0m4zuL0Ix^UF$p(IN3N)RhqXoYQKTmej_fqdg zy<@wfs%IXRHDAd3>o~)1Ehp?byAO+)GSEG_5`TEtGbhIh*h?X&m;dX)?56!5?^odg97K_q1`yh6gAj-<=HVW&Y`T%DHgx7_ofNOIfj{6MoaZ)G}6@)jVho5h*Dcx;_ZM-D-f2ta>bY zQNx^``Uc*1nBnMZUAFg#BTQO#OK4AnO&#KYocjCOs#TMy9}-JmG%aO~)8_ zzK?u|>RD8*Y0PDRweiBK^$gn;q|a-gg{0wOCZ=#0e!`m zgA?hu8}r!i*yE70@DIBG^1)1lRv58<7JaE{Lei%T zfsbaP;*mDoz(0f5dpbDH-J1C1LIG%u9w|^dpFpPa9qrLgHOz$lDVW-q1;uelaH}q- z9WEj4^u0n&xCC~navEiYkQA~(w0h28 zvOeAsW*%x{5=Q%D+Rqm7vTh*F4jQCL-v&-+j-=mbR^Z(wp>X?^GMyil!HMG9V7h2N zwe^)@k1lWqi9mNOSRIbC_CYXr&UiF_)vvcwR16=^n~GBYTg1L|b%C`rTA68vn{Y~0 zKGa`8{(Iy?)Pnhc?-dPtBKj=unDQH5cY4zDNDI<%L>rFH3mlx!yXE|#s{bs`do=`C ztSJSrk(TJVG>%+V-T)c<-sHBPx`nqI{2{1SjO-tw#r15dgt+OCiL0|b>ul=<{!&uAZY%3w)&s_h3AEK<8JBwLD};|aN&lNOpFO*X z|2)pmkXd~iCz`#5V56^ClCqtwov6v)QOg|E^E5L@IJw|guI~{wG<7I~?1g&7d+}xR z`_>v56Rl6)&A)^r4vrKWF*)>LKpL~>)JWlqaZz+M6tnkr4}r^U4)s0taNN2EC@Am3 zx!K92Jj)au*0gaL+=4f&d|-pTyl9d{2bUaJ3AK$YiELj3IU=Y{?flN_2D&-%@9BSM(w-H2MMrBI;PCc$Nc9)6fBrbb5jSxhSrdXu zUkYJE_6Cu>>}O_dku4j&?1kWgi6_ofcnFb(8Dz>=do))23w2wsP$q8_doRQWf|hn- z*zhoH8r}*?{_|+?okz@}aR(qKMgsrkx3v@tA?%5COP&_sotP{* z`uaZUbdW*+uQs4LLy-o>rt>_vHdyHIL=%2=ixT?Y!(Y#(^p(*<_Dre^c#S@R8~7ez znGWyu$!$fkKyUyKJ zbziP)v=!C;1{O8wlUomSapv@&uy1-YedWHITwkjSvzK4NcBTVw z2z|il#xwLdFNaU`_*s2g7aEJI$?XhNSQq`3dp7DGh7R?CBWuG%Wf%0hXr2j^mo zmX~D5w(o@FZ#I*NtWzlb-Us_$T%j>zFO%n=tYBqp7uww@#s#DnE>53I=XZYP6fK(J z4BuyQe;~^?d6|Qf)KBj3mpI&bw-BP+T15^2JrtPhm&5ey^T`OcHEf9cb{HjQPPD$Q zz?QZ?X#RPHc7316mcKaxlZHysE1WM5Jm`d!CS97hW)oR9UkCz6Gn{_D4d3&eoWi%V zSS~vgyB9r$dp^HK6_@$!k;!@}2)fHmA9)R1t~~_RvA4<6pSqlKojdqW9ZE;`uSK!I zx6s4t((<}w;(c)wgxl=HOoeRx732xMpU2`P*BSUh=fWCJ`OA0gWF^cG(F?GHwg zt&GlGEpBLE1r*OklBFTf{_OOI%%Zt;ZLT$%cYT4)37&Md)D@Eba0>+3q~Y%C6hEb% z28WbbT)Ol$_sjAzJdrGT;3&@#|Ux8$5K$Y|BgdO+!&=YD%f+sk@AeCC|S2 zT!<462(W!kI|NGoL96%INN}|&`26bQuH0?G&pBQo`RJi&!|oQ&{l7|JlIM^UT@9pS z#dgU5!*@q&VsWorKV1HGl?JJ_lHrH8fu~6~>h8ITwe#PAROmdq9~?y~>lTqfW|kK&+VBuI&bmR`mhHsEwX#BH z`2%V=Z!)`Vw=H-d`-H1*g`t&a7j(}M(AiMTZ1i@8u1Wmd(Yps%`#px|Q6o9yp|<3C zpCPyg-eBm6LUbCH4OtC0Naj&lJh0IgZu2{FJ+XTzlhg+7zYo!a(jP<#=ikG*dWK4k z<^58@A^0ouL(^;fv9td%Y^vay1n!N@iqi~hwaq`*K=+wp0m@~N-W^DAP4r}i-V~;w+wDCT;dgwe{`PLW~-3u3`UarEu zwcgNtqmEfT|2da-pbV7%WD`T_Ch}#RC)}5xMcvMf$BxTi!AZ=E=8tY6+6T_S_7ica zQoA~5gZ5q+u)ZoPVgpg;IM2Ttr$IcGhmt1z#9AJzXa2EaZwMp#uC6{Ex~PKdsu+M$ zM}L~LWegjtZVTDxGH~*-U|e&&0X`h>#ST#oV_vx*T1VdyoquVKnR9sdsrYnaA=pU_ zg=@jMT9?@O=AwefA9(#Mm5$6XB%^*#fO^yGgL}+vHoW$lyg`o=IUGN;2E?p?;EUVO ziKp5|u&Nn~cMjb{VsHljILL8R|J%UD@_j>5i!xDjlVFDy?18VljY(m@C)P9$5yHcC z8aewGY2!Onr_6dVr@a`5ck&&REc?zWd%F??U{`j(|1vD?~(Py$I zBvGvcM)S=Dh*Ov5AoTZ4s3kj39ly(ry=2rnDew5POcYF>ld%c z@3u`aYMMJb#wOxVn=%->U@xa0B*BK6xxiKbTg=+{037|g4YbY`kyDv7NRN*#{MS2{ zjts8ELzd^jPh%2|y?LK|5Zei~Ur5JE$+Krux50pfCwff|#I`-fkW=Wu-Cekdoqg8@ z%F1prvPU;zuhmnqPRStS*Lsk!YaU=Zb1og-a26Lu4H4Q3L+Ocpdop>mHtZY-8=Rl} zV*+{hU98ytFQ7g4GCfqF%XI~a3wON>q6U`*Y@MDb#NVpH(iJ`^ zajyY76U3>BktK2ctI1lo)rl%ZJa2^GOK$xj&HdX;_D?T@m>VNV?5|`JwsS2=BxsZ3 zj7u1AD<=F@e2b=yKF^r&dA9Y^<+vnG!0%yOAwy>f-D90XeB$`LXtE3%o@_yNxJiZJtthun4+aMvybJUl4B84j4aFpQLY#!$@+=-M@); z!{5M!OG{{@wxj5Zk4J$GBBhl#DSWzEEs2j}5GUD+Tx=Mq^q za~Ez>9VRqv&!kHdC$QH~+QPXn-*HHJ7|uM=1>xB%=osT-#!uxjbjt4IG|$-(OTKCL zs5*i%Fe=2xli9GKGKpkAlEtbowou28qxy08&{Vb)zAX8Vw%_g%`R@A)*M=KXy~(<4 zdDH>0i$9B%N-k)!E1K14*XI_tT@kEa$FTiN>T>^eY7%C;!|LrBjA(&6PT}7{hEBUl zoIFyA!U{W>bz~eZI~$F|*Y!f?J3spI)P3d=x`1xr87!BakLNZ=v-MB)xy`#LGCdj_ z;9N_OsJp!iADH^VjM6+NOS6V6g>u+1Hl0+DZzYZ=JRs`BoWcELj?^>Qo%|ga38Qn0 z7Duz`SM)jKFpe?X;s~;N(wv>&Xr({CjyN7i}a)va9)i zjgBn0OMDwPU*$Pek;6%Bygk_)v=$;bZKAqB#AlHQ;MI#8RGl>>R*I@Hir-!Q+d0nH z@_~<$_1F<1hd%E`%%B z?YYWb4+XCxn_=_0sYG3T8(Zsb50?6?$kJ4OJh*!RNi!F)LA@tnM3^l7)Wm1< zmp4Our5>Gs(wMwg7sB4(c7yZnnGH|i_5nxkE?y$CrR!npqDaQW=^A=%&4om#WRjOG z;AVQBgn@cl8YNhdPRrUL(S%S@R1%pNVF6M-?x^}H8>>cDL+OM=oIw2zL0>btJ~oay zAH~nHV@2?D zq;PCkIQ7%mLE2NaVddf&yd&3vxG4b6ZM}+z7Z2lqgZMo8o=sfurCm&Q;RXmeID^|V z<~Hh|aAUBva7mb2YTth?DPUZxcnAwa~qO+MwQ!Ga4_n|M-j^ zOUq##Rb8RQ{}~>)7odV>7f6xeRP)UZa&fK~Bt6@}Ej`lA&Eh%9d;? z&*-IOjYb?QrpgFs8gtac_9yZGxD7hpe&LO;H&JSL9qbxlcwUW@=t58nWG<1VlJ<*P z>(fOLDM;kb6n|!7)3>nOe0&8-&hBV+m(LpcN0Y5J4mhw!T6jAmmj*7G$ju6N)0@gg`08De{cN&Xa zFoVz7d5ZMI!x;=b(k!L2uUt z8ehXRXCDs}&Q6Y@66(cFTBGulAe4lAkWSY1t9B0x8yEExI z-r&yr4C@!mq3euh$l!NO^;hai*V{<;ujNGV0LU-t+ z`JsMTxb!aleq%mc=6ej}-VUdtSw6Vwb_Z-LF{Br-m=VhN%6B)o;)K(@=dd`6tI0`o%fwLtFY{PRRl%m|t_EgA2~Yxq8k|J~0FAqJn8bLZCbJ;YFDDpzcVE6#R6 z;D8~8&BB9ua!}GVnw_R^&)q#C&pl#Ff!SWjJ?nW&*7$FPeOI?J>zc#x z*pyu8Sb2`D`?QeB;G|*hFN$;8J5Z*|6C}=$p{t)M;^&qxaMgSZH8brbs__d#_wzFK07lt9fzHNUa02W&GfW(hZFGF$CkQqgeNL2QHJ@#dzqOz{~heoSfHfT$Oni zhG_;d86$PL>D`rJKj}Qt$&_bV15cQFU@;9!v&7*NeemeYIoep5N?a=~A+#(XJzhRS zwe>H-J71cv7QNtZ-i>01-*Xt$YOniduwsfOH<{;=rj6id;~S5d;WDxed;BpNPO>VWsVMxYsVcm{Wy7#FV8@Eta5s`vvT}p9i3M zUmX79sU}oMvZ32{awUr{3nW)Ftof7`qJML8m#I6fns}V~$H)G;pa52{h#YO+Z#JMaV1s8`0@q_>^0~1 z?|zC7JkR-Fl0V~mww9aISPpkXg27UQgeAQa>OX3hZz&T_99i97BL*Uq_e z*%?+CQG&IQcq#q(WWzM~bJOqs;ij1Sz^-?3oWuB4oSUE+wtq}z9-fzE zQ@`-}@Tl3O&e9jR$4Ll%d$OsNUn*&TVGZ9eNl>-oQVe}|4UX(qp%b5rxKGPlLG0uh z8Zk_s&0fy;k_rxRH??1Lv%E@x>+j}zwQ>bVTpz>IRX3U0Yge;}10A4u_H;7MbTtM$ z4uE@52F*XZfYovHfOAijY5j}&>()XItWwqv{=mWr+d#47q+D<2m?Fl?MsMV)= z&de+Q_uSiY=gA>6BM|PI&CIX4hIQ&Wur=71_v!VxE=eC~nmK{a9kB^luy5h@3^Tg1 zGnuH(*$f-2gK=g|4(@e`VoS0PaU-wEaew%{P|NxcTt#>}Nt8E(WmR*T@5{qcunys8 zzdt$kWeL;rLmDRO72?^wZ}Ek>C%DjYw8u&jZLar1K-vy^TdJGft+Rm7&qDC?!Hejq z#d82gx(#aeu=FxGG;@F(T`a-MA9scNM26Yydj`LLEdzb=U^4ld5^+9j2TOLUQ?u48 zzLOXNZn69h=0dydJtuwSlp>BJk|=)97Rt#a{e%cu=e5N7O?9*1kLCDb9s3tvGG?NeXmD%W zDxupgl+3sx&#sH`gk>?hbgbD{G@aiE!J8uJKz}N!UAqpn=j{@8I28R`RtZ-9Mhwxzzi#S0wo3^WbqP9w)56^$Z1WZ zM-l|wg_B~!(T}2OfxRC4;h`(cf7^`f&>dUF8(>EFXsTPWg-j~cV&|@w=e`|H#9@0K z!8kdbqd{tzHnjk*evDxp4K9(~QR|>mc{mB4m5i!A;=%)}IdouEBJ(oc4Zc5V8Pw`5 z4c>FUqeSoVyG!+pk*w2GH_muK4Zkb+K>f$dTu)9Lm(Fu4rdq@@3zj}3`pu>=J7_e? zGYG-DI}*ZkI=OVVQa3sCz#6oCC8><)77i(HfFqaJ)1G7dMGB7H(B?Ohsvcn2ajg;T zn>bf4-tr!INsG@$nqK8@YhPmKG}^F>g69hUbz#aMor0vV^NC1t61MIcCKUghN6&*Q zyHCXqIz9{;)atLdBH78EZhVI~g!^)_2(-rh4xz^XXxMK-$g6D-@})kTWGSuLRL)v5VZFs;o+?Pc&|H> zU2J@qOWAT+Fn@qy-A_A<=63qyuubl8S!czdR$q(X4j!6Q>G0ebKI1n;XzZ9kFYL`@ z_NncM(m#pVvVT6Fn#|wPxOAA4U98Fkt}ua0o{t_OSB?35yx^?$I%eAQr<`AJAsqHT zO~$@|O|0H~LhP93bXB_wP6SC|>X3N4WyCj9X8#i0YlqX7PhxX^c|@_5!XtzF9DDNs zEborus#Ak-{J26`dMlQ3n>>VPGPkf!>n|`g(o@!B z*g5ewV6?je)h&ZjbsW#4-!O(=IP;qM-WmYqdusS)YVm;g#|9}IfMyQ{q+dfQiAZzqSN<~PGH zIc3^gSWlcz@*Rg5H|~J&567)N17CmM;v7zI;LIKtfZ2}N!MQrOV-GyOHg(V|zHUEE z=>8**CRL`900kT9c_2xTiI?G$(bu4GI^U-d7jZiL&Uew8vGmkOIrjFlDE3bI;X$ol zV_gc9J^Q%-e&-6#b~S_N^fac@U>kc(X*UFKS0@Hn4DfW@P@zQyrLs2#Y`ozixP5a3 zE&AqxOMTyhccwW__cJF_uK}WFdJg6^Zt{K1xSYd-T8(3hzi0*u&?)jc(Sp;*^e8}1@e8=gMG^|Q5!P>ta z7`D}~2Ydo*QuBX&l-sp2mHAr%A)bn_E0wN-yYP4djGO#y`JTvaiJsLFb%dgS)(! zW+hp|vkaU;*G4}-$0MYPb>AI&v>!24s7wDz(&86u$#n>?-#YW0dkzTj^05QiP+ z8JGOK(osd9L9O2V*#vw;<2aA8ckpP74-C8-&AbE+?z1v~hl`#he>V+f^>w^poi3rB zr>yYpfj;ON6+_j?4bmO46=FN9@Z7CD)JhBhB@`iN5x^~<62)%J@#b{q$1tCWIpm3* z=WKRHqvzHlcy-5$*;1*%Y&`T6J{`%V(;5l)^O~42;$l4Y6Y=*33*2CLbr;sZJB|jm zEnx3Ik&aHZCgbF^Shs~^xPSK_L(84uKczd|KaSIw)A_JCXbV$aoJ3L+)`9qFNkSr$ z(ebi`u&WKJJadt`xco5OT=5PyRuYsP-wIdnO{CrdDMac-6#GZkXK=e;9;asEA5 zaT8tCcThAtxf@PzoJPfNGHgnJ1RIy_#dUe!<8-r&;F9quv{LxOsMXrB>H2+ou`Ql> zZnpMc<>2E zDcaMK5lh&N$|LZ7%uSr;?S@JB-oW@`ibedKulgUu29vX*e>*!d19#Y>E5}$e>iBAD z32bTeAVJ+sAv7J)(N@k@14(#)N8YpMZCq2jJ?e zSQ^T`C)IYZ;LEu&)GsJ5C%En{oH_Uy>lTb+7mjg;R%5!fVnIItyJ&{LSFqN=dZJ^mihR!`)hPOJe zg7O4)n(-`$yBFRL8egW;`d|fi%^dzdI`5P@i5w|}jyI=q z#mhEK+Q{eXmsq0vLrqN2D}pJ1)$x(_1(N#C2$UKw3UoJIN4cZ9fG@Wb-*^G{?9M9T z#wALR9$);#{#Wh=;ftowcN@%b_>T@y|7A;Md9L!L+nXV1b3D(!%SCMWg)hGk-i>^~Z~SoRrtu4Bgk-(D0Xnug=GsgFR?-P%iD&mKjNS8oTcx|wwKrfQUVbq>5XEuhc14DR&(&oH#Ykm=h?Y^YI*p|b|}7D zSqERw^IeZ`{QIo6DeTyp&LteagHG=QAlWEWFm3%TZhm|L1gY;L8GnYb3yyoiQl}O4 z;M8q+(V`Dd#KqI(m3&rUk`?T__6mFS@-gpX4J`IorAcfJ2TyB3)r^0>-qexHU1ne$ zbf0sb6^#am@&PAFFpk-B%)pBZSUK|$`FA_)zW7f#`0yc}mO{9>@-jl7wCnV(#v1lX zKF=IT{(;W1o_O_76EuaX(}D&oa(=^1cDKSLE_(I_oLu1y8@dkL#>!4)phG!!}>#7SS?K+cA8bYJk9 z2^uC~Jq$03{$-@^364VNiYtPmcWU?_e{b<`iX)j+caw|}?f{Xt7WK1^MU{K=lQfH9d8%)NL?A|>0w!cu=mMymlYe=jah*6_*Nk14x*sMhKjGYqt@++KKYRa@ z81%F|^bEmzLJzYukwcY91ANvL=_E@-a*>rAnStj$0^#M=K5l5|dM=f}_2Y0LL16SzoV9+l2P7|ulf-xYotJL| zFg=vgu@kP6rNK6E%UzyM#4^muyb9lTX;9TWIb5V0&&Cwaq^4c+?9Kb;kh01cU-13R zqKBtpVEVsNT?mqynf81Q?ov>Uz7QMbjUOsIMWP;YNLck`eD@3 zp_0E_x*0SKl5qRBT+G$+gWR`X{9Te?oCD8QkTzq`Vd@Jqi}zX|q{s^lZiS>rDq`QbPw*mbKMfnzP8R9#d0_4m{)|Y%?)3ri z_CG(=?Q`O4)CxgPMGsS4{*e5!dm+5LS?}K*-o)>Wv^g^(eqE6aAHD-jXUw5ScdD^< zVInBFuAyd4#axhMCk*|yhnBItFJWf`D%(?VyyI!K+EoRP$>sPaQdf}qpau*c8{rNK zeO7m(3(PI-(938y$B-!n(3@*Qnx^e1XY-H1sxNx{fzbf;IoJzw-SPB|kbmDcE zi9g%Or`_^w$xAP|8@!qdTDIXBjXv;czd+9~<5@JD`FlN8^_b+7j~hqT!mku{`XR4| zTWI$h?2f;}@yF^(h1Mp}w|c_g0gOTOZAD;ofC&E0;d{4NK=(Z>qV;ksn+1bcLup%rKPFXnf$Rcpx;|znk+?pCJ?1i<`^ST7;xo50 zj;-AKjwx7fnGdOfdV6aa6w!fs`B>;hIqD0xroACb)D8mod}eYs z#-fFxlyK{dC-nKquf)8{26W_HsAxE`*pdW}<(zc3bV44a*sF*u(`&p!++<3H#vh@Ol(V~auKtr-#Zq>^vv zcfg3qIdpbLEP6M|2p=B4O?xxSn6EnyLg~c}3|+Gjf2TEoXYLzxezS{ctu=))*Gstf zYR^z%uQx2dHlP>j_>9wOu7H!vw-L3pHsTN*2=3)3)M~>toao#K%A*r$joLdh*|Zjl zU#So3`6s(3$l6tppHC~Wtu^~0?rA&Mv4p=zAXf_WhY1B)c~WHIt`BTt<4K0UDuL|A z7*I0XP4z6FaaIxhZawe<9rJ56`jI_l%@!ZQn6x^$+;1kx(b&w|-Ps2Q zGX2ca+v~7YTvBLIRZLg+EMpr>JYnmyX|(%sAZ9;T5T+Id)2%1jffIkHz*u29BS)lR6n!?Bkv_tCfOd=q?G#tURT`fl z!~Y1~zpR~X4cP+fGp=JuR}$v03k1X2A$)hwg^QoXcer#+G27=4F>&4mack0YJ07}X z{)-|=+sP2=P({+QY6na|uS3nGpW)T^B#8LWgsNCS=Dw`ygcnZxX*+*o;Ayi9sCi{$ zOnL+kD4c~y@?qHg^0%Iuc|Ct?Y#-|Cu3>%0I>RPWer|Z58A>MPL!Z%d66x+jGy)Do zTsRq=&(oBD!EenZTApe_{%UH2tziaU>TSo=0a1)qCfCHHzw z!J@5+JO1Ym&NdB!bt&(2Ul=Xm?yTTh@f8f2moLR`?+pOSdNX>#aW~ev^}`{HWU8^` zCJCoj@Z&@qn*GQ}f8QE#-KGW z-&Hiyq2th+cqYzZZJ*2?)bpSlP7rQ2z|A-^1s4~W!mXC+qHCY7lK07mQ2Z^QIlcKZ zmgL$ATlQ){nwTj|Om4cvxomOT&@23(qx10R>W$*K8I_{aAT8|_)vsu9?>$#TgN#Un ztdf<{A`P2FDN!U1p-4+9@xAByW~Ygw%!-Uul7=F`C;!2HeZTjf=RD_pKJO3y9MJ?B zW9JjU=~r1x%JCjzVud8E5#NSTE#Ja_xjgTMBXsZo^4=uTZ?2qG8e<35hpU(=N8|A5 zXbC=dL=l~|h`tdvZ1NTA@4lawn;BJvm6D;Lu~L#9f4f+y zeQ6Jj!aSmqm4)l4d;@9Yb7a)GUeS{0U*Y(w{lwm7F&Co}NFT5iA4mq^gk7~z`RN0` z{MO0%Xe{DjeZFYAY9RhMZx`f!F3R<~JPyZwD1e22dhFk(tE|FLdytAE5DixJz)|NyGN*G5`}@RLc(LGde^0)pI1n6O z4kG`&Evs)gf!AYgl6mAEtvePVE$fJO3$rkKP$)?v>(U$17lyI*&XTiv+WyO<*XYLw;Nv z!s)NG0M!qUC|OK<@=K2)WR^3YoJ91F4KId7hi4+`ANrj65HCo5RlztH;3t$Jw)+#r*Kgw!Znv^ ztl8p4%$(`+fRUB`b^BMT9}L<&iZ>Cl zc%Q~^`5wZQD^K7*T`$ZfGMsIJ6NDT-Bf7Xf823`P>Xg3e>`2F9Y>{9O=_?nIy9wo3 zez_9{dS4(e2gYC*+Y6#AA!P0MF`PH$Cui$r;*4)caC3AS%yewVv*&d6j#$)!;idq* z0IRsGciiBd(pgba60O@;ieN$Q47O;;ZZ>--&B*pzPX1;1c5eF(wP%t^LAxcppYAT# z%ze;bw?91&g5!T*Vswu*ejQc^CGuUE;FZQcF)@S8=3jz@@lE{RlLtweeWKF;_6YiY zG`r1c1{+FQAKtWXe|l+20%CUHhz{C^pGzT9-_zM?23B+j_Yv=ex(zC*K`mVAJySG&oup+2I`d)gs6kRh`R8E(&VcWB=i zh_jYOVJ6MTk+Ai^>TAE4AWJ(gC^b6wpSMLk^B~psykZo$s^J(1S$>^nIq7y)<#M8I z;oR(z{d1McE=mgd1VGi^GQ=o&w z)Wu#Q9cO7ig!*o%znzbB?k>dJ=5@fBb>WuNj%>{{Q%E-YC6LT=TpLE;$<}M4`-@)+ zvQp2%=aUvY?tK$`&H4y5?cdnndt2G{!uFG?q+Pq6U0U%5+}6z{_m-T?S+@N>3~B7f z*8z&$8(mNE8$J{}_D5oJZ6Vk{kQ5vZW!diI9o)FRYnXr8jz^d?l;dwhO zkt&2l4N2kFr0wi{Q$u)=n!x~-a0c7-LidzX65O+vedse57Ue(huiFO41Hmz5Xn*hR zMc%=%*-Od6d-bfNzXc4Nwi`#%OvB|tN9Y}YHs$&n2|e-oGzCUam{do7^u``=-HUqn z_Xgv2&A$-XT}mwCQrPNt8|c;;O`l4 zhutWtn1JN_F$l6evft=fWy6IF{k^w(&`vnCBMgi#*&qy|5jY^h0JnGM4ahkGDE zE}SgoI@#+go4`ja3lHwRgnILjgWKa|G@Z9!7;=3Fyz-F}#uNwPRk}->(W1zjoK<2E z?{a`Gri+NXYX#1J`4zIGlSt99F=(=)52}wIrT>&Fw`ji&Xa?pWvPW@Vb_G0M`vdRC zGJ4H>VmXy2UYK7Y&$d5xhbcY-gp3diwB1?&z4?mlznm|VVSaGniV>MNh~~1C4CLju zKOlN#t)CLBF?j&DtTF;dFSjQKmhKp`_b(KUzeWy~WU!E71=F^4;*Rco zT-*8vnrpO)e#IN%AzKCIw!cx*yP8ceu>fVNfjV;X43435(KM>_oYbbsq#t?$r*4d7 z%gQ!!^<95K_U;p+aeTROmA-qkKc|!S?@PFgSw0ZwFHg8-ei$?K9el6QC6YSUtn$p6 zoO6wS|E&A!%Mz&AY$wd`O<@a-4Pn}`7{;;sGX7GK<_o;bNxi{E=9STYcv2xx&e!so zMDqg99_7g5_4GWVyN|cm_w>(0cGnlep@Cb4hM1RZc(NVTj80}AzmLObDvNo0%aP&@ z)zdkvr#7%%aSXBhb_4CGfA*)_A+oK`S2Qr;BV;{WMkdc>xco_0a6-lpCt3w#{X?o% zHqaO3a_;GkqI=2zR`=%q>zTPhhas>qo6!jxhjZj~c>dZ5aophb9BX9@gFPrmbmS?l z(f=l)amEk0e*LR&XNg03c6ZqnQnzs~@a`q9+n0MZ1ex|5k^a zr1e>}_;Uc}D|kTJ*#Ux2!dUz;qzGdFDzX1E)6d@72A<}N3FCPdlLH6yM{;wCKs|@s zym!HEn^GKOunIO z4XT6niPaG$Zq>XEaCL?c2Kppm)Y{YB^gsH-GUa2s)72Va;Rau!I$$%$Qx-=gxyEd4 zT8p`VbogjbWwF7l0Pc>j4;&yfh}pFuEEw1gs*}UW$kp3f&sKo;-xvGq>hu(MXvhu6 zIpMP~xH^{0-k~qp1bZ<2Lu1OLYZLXBrQvJkU`T2ZGbZJ-!Z0z%YX*-MUsG@8q8|Ez z`dm#SdDsNIYJS5(^&{l%>f3Bv;U>@|S-3@4pp3jQSnqufkG1v)j^Ak(0K*IV5eZED zSqt#G(IMg`V{p>QSJ2%tmK~U7$Xu3@hy9-Q{k3;Uf*;MgnnxCm8-`q_B){;`3G%u3 z7dtm~6YMO@Mf2uMXnef_-j9(a$yM1x31x#1cxWm-+9782Hc@YH>k>hEKp6H06u{Rr z-R#~hNv<~-zg4zvYeqsst zCDjLp$SIKMwSH)7@fOt1@T4i$iv7=Z1}C>~t?-Xu{ku6Ie(i`CYT7QbpBxM!$K)V$ zu;nt|IJK3}xU3_7NVA_#P_Iz6crZyF!Q&~TW~jrJAmi-f0D+W;QvlCXRC@yVDj zC_HzC96tV6G$~Jlf9(-PWXW>Qx;F$Y=$$=PDg?)=)>Gbs9Qo1N#T;$W<3i$Og}sYH zky$7AAG@ovxA~)u20qp!9FRa}s!~V7U#F^L(XVfM& zp=EJA2+Ix;9ji*=xbHyTze7YmP^X~kS6fir-HV;8qEOoVBYfSkhP2N9z-ZXE!#-a{ z!b+~@e(1(@KkL?WX#nIJE0a4KgHS`_6EHW7Nn~FuyLZM0n6V@T)mPuc?j@;N`=S z7v6%fxu+G@ZZRU;qLn!9)f*rwAq1t*CE!}MSnlTxYay~PLU;QVnq%wmO!yMLi94+5 z20Fj|m{BEb@yARvKJAQ_cp2sW+t2a=*9)42BvGDHYB!7uI!2}rab$hs0LIFsg?~Np->4D@qb$QESAnS-D-ZFT-{bs+&3L5LAKuk!lYgA* zocl_AET2N&{vO0FSiTv)=;filYZ7`reF?`8$dT-Z2ZEYa3^#SSonX^On7fo47T>i; z*hYQX`C3J=(WaF7RXB_-n6MoV{KpY?U3CEAP3BodSOsDz*g99bZ!9Y(o z&B6or<`|H?kRY@x?S-u3+vFBcH4>SckeONB&)+zGt^J%mfq_+GKEDr|35ZNH1x^Sv6yeJ=Tv=uYLKw0j$^byMGav)9`PPolYnvb8A zO>RBNWH*hmh6&U9usEy$DTf%!$FCqdF?GW0=Wn5Kj3TL6)5IPrh~fUbX(w!~tPqMl zOW@suV!=sHiRq+#<{NR9WQ~!5aQB!TuiGOKqm-50eU1GPlc`7^o%h2_1{aPNSP?jiSZb}sxQ)%QyU&o^P)=vh%B%?2s)rpE zS+DyDlR`|$&!G&ruh$y38bxAJWC(gKh~i3?$3e6&I}lT;hu3L} zKXYDN4X+=t;FYKRC$40E zA#_$s@NZ;Jkyk&LbC1p(rdiDI>8|M@)jc%8ylF#8^2Q&`yw`f%_G^m$wYtQe_T;BL zgwMfh=(DQ;vf@jae@wg|o{sR<5J>u~1pNI`hEH6cLx%O`F`n+bK|AF&g1R<_VJ$QV zDG)Nlk)5VYzxV0(f^E?#jQtY;SAzlsLvfj4{yQHAOekR#QeLyRw_+ejVLyp*{||#) z<$3zK6QAdQ*+p0C;47>k>t|fZncesv_Bkn$^3RH#?-}at`eHB4xPMdFMDq=|`4v!q zkPI7M_l29^)}{9|v>CbDc=)-&pUk^ZDVT4SVtdIszSykuH$s#Vz}{cc7kSXxX?bc80PLS5;CsrU~CJMxe>@ zd+4){zR%UJLPWt<(d(Q?V70edX#XtBy|wU$m4`MmE{#Xf^-~|rwW=a!Dp%O2^qFIw zCK3NLPjKGWHcjt)>m%j6x{s5aQ$Ku^4S#aX%3G1(RgBxIqV?K%|ON%qizXhoNWz( zLYh-|ROz=c$}WbR?CUO6NGC8-avR{modZIQaSZm-^ZJiR3gh}(kMYTqgE-NL{yFoy zFaB`q=@Oz?G8{*`O7n>i;)(Oo9(J_fW=Kpe!5deSFvBhkUIg92Oy8Y?*1j0Zll2mU zl*LT+@m(-H>Xc9-breUe%7@>P2~1qFA}c-F5vrV*k(suY7@HFVOO|gS3Msil0^bV; zqhd&;z6v+;k{!%g_#AVD2+Y3u3Z5wsC3F2by)5e8*t2+-a8q5L^&~rC;>8of(FAjR z*_;P1Tmo~KxU*U%o)AETedf3ZKPG6xx>Ha3Yk11&Ab57C69@Q8 zquuO!kh(pB6#AsIKW9)r{HWbR_x<0(>@7!OzEqm9!cJ32*3Jim!wHN_3f1p*hJh;C zK?W^$!gG~U{BgBhVlpU`)!bqYNli4HxUK*XuDuGiVPna3x2r;MV*{*ysZ8u#8`(nY z3rLsPCEVCwAw2z742P$F7ou(`GOgC{pgQ6X<1gjOmAC6jz0+FZQo1C+((M5m zqQY{&t^H_*+GtuEgK)*3W@t}ZPyQ6yvmzCmEq&O!-_NLI6vL@ydI`^^*9cSoW^QXI(o-SmOkJ;TYQbRI`7X{PyT>q*+sboPF} z8I(+=*?sF9(fi;jZlH~)pejfR$5~phE_4Wg>dM&(Mt0zRcmcESVjR|4F58LeapuEH9rXlD`eJG)K zb_r>vS$fCh9Jn{5j*4Pt1md3CzMw!17%$hc=yQDu|0rp^c#FuAOUSZ??;O>V(fy#+ z5*hwL##s{d<$+L6EXMcHXJiPmRlyfTbSZCmASgm1eisKh0xI@_-J7eylXOL zhV9E2LTR4S?nleW_^l6c&aNLIJ@XbZyDA|J&XnMP2A?J`tCn*qX1ihE-Uj@h>xC6c zw4Se0CY6(aFk$pe%Jfzh{&^dKiP^P$~3fqBMVVLzMifGh6H$>U?^ zuwQ1~(- zSulV4TJU*Y0PCNeV_wF+VGmqB3161@kkc(%ILAztx2~@xpS6`Zm(m7!7-U3NJiM5* zQRzLXFCW!E_t5i<<=i563$IVy6dqGfOVH>}A#|`T+tS*?J|DmLNy86I%uOCtUns6qKKvE14NyZh_*u45)N=l!r? z?U#;H2_cY{ZNb=D$O&0>9IyCcvRI<9m76sy0On0z+ON|KP?q68`kf^QWpdg1Ih)~Q zZ3)U6(CCkk!BEQG!nUQ|g2*O@^M2vgU$?8mHo(JufdZ2rgRxHv;7#5+CP|)Q7PQF0 zqOP|7-n$?#08$EAGWf*^jCm)?@4Jvd4&3i%T_0_R&?(Px?$;!Ic`*zcLUU20XQ!Y$ zB9_}{8z3xf7BiQEy`Wz1h7j!*j;EI718;82oQqRra~*cT(6YSaqQ$u@OD!s#y>c{*Lro3JVK0P^j348BRrr} zKSQW|WPhgi}SO|-F=(c^khwV8DG}F9}Kz{ z1d6Nv;14w!+{4Fmhr$B{lP|x8(_s-{|N4=zuU1P~LvtCpPFrS)j4T&FAp-OnFVgpH zCz4lV`7K8q$!fYI%c0zR1(yLN_&^~}AAbc57fv9PjIRh&=e&h8o5m97qDD5XDu&yq z89*}+UkY{6B{0l)7~Yzq#OOS)27BiNjI^vXH*l&Xzg@qcjJR(g7-&lJJzgTBeVE}! zPV|S5cgGU#wjeBh^Z_m(-$dT(*s~A2XK-~hocia_Ls!Od$~XP{YxR!8d=N_y#bd87 zv8NS{AohH_-X@o1Txq(VcM8=J`^!nQ2QLJGPw+Tm^=J()+tmzOTARtU)#>chk+k*u+H%CBDC6e>a%Ji@5K4o9CXu3!ij&ub%PZRV$`* z({|f|>5yrpKK&L3=YE8I^<(7r<-?+Vv7caEpA9h|!f{6osMoJB86$?Dz*W2hcP00- z=qb%Y(f*(e`_A)-P2RHIblqx+e;D7hD6 zv#;Vl6<1WC*|NM(VQ={Jta8FH3Ss5s4}@ikq|i2395Zok(=3cw_)53 zwa>GNv!0Y7eO-dLq8elOk5uz{d=ET0+CnoEc4Jvd9aP*=A*1Q+W0^j~Ijor~{PW9X z+ERkwfec|v%~AQrVOpPLM5LMO+*c@ztRq-fbN({*<84cBSouH{oq4 z++2igXFXW>tCIQ{CpM1WzhuS-^w;MN2aiDf?m}TC)Cy|b^I)Z|4RhvQC7Ti!OLrUr zWO~*DG`s&6dc@`=Ceq z_7+YqH@LqhA9)uK32%eRq3%jSDrx}lyP<&O#ZI7ecI*?nD=S`S z7l;dUGuh9!s^DPMgnnjCIB#MAY&D-i{FV_J_j7|ZEY*8Z8;DblM(R(Gm3o-xmd`n!vxDY6Gf0d7 zQ=EAA6T~K+AV$juV8@J)FnxqYY17Kd(obaepXhKA!k~pk#EZEue1k5-+78#;y#7&0>O9 z&3^xPb%8w+gB#CL5ATR^jLj2iW5VUhVsV`jUt~ z$x~8B|I&5;av4wig~QmELcFxzOL$AQmr?&c$Buo&xTBP7 z7g$szuyhA%^CAzltOhc7)+n+u+ni{&ks;am{57s%Q$bNH%o9?VnsE;EPEtct>qO1&9`~*XPQw?6_PIx@5NO+cQj`45u;EMe~ z=GrxPc2m_p(5u-HItr;H(6E{nc8Wm}D>v{*m zPj#~Az;)J}@<~wPsE{`GkFapJKhJ+EE3Pi8>}q971$>O$-9O^-0(3OPL>5i$Gl7E@a z^)dpjvM9a!>}2d|H0Nz(bj5;-44XP90G4G=B=6_1!BVegSR}F~Z?>ef9<;}9S3HA8 zl#9MGG8oKc_F+_dvk=ix0_XS{7}Ze47HgVA?9mv#Jy}thxN#9bNI_jZt7JO&I?)b1 zyk?RoZMX2d>u2~lGn()l{Y7V_KS9GRN1~O^a$BUWAUHD-&+ZS#3q5b(LeL|e87a%| zr`xQnP9o9AoB&K8PqUJb-_omGt%kT>jqh?ED9$Tf$la#jY_#W0(z_*w`pXn}nZq?wg6wV>z4!*2Epx_mi<)7?%a`;%eTcR0pf&vWbzwqz2_CvkXUn(l>&YhM3G+gn zA!V8oah0Q7xC`AdB;^5#JRl{Qg;7pRdLnUsyqq)ZH~@n)f8aqsUmWwc4o(c3NIw1P zV%`?%a?UZD!at8px2zYOzh5FKbg1F(!Fga=CeLWvq_X>0xlo>`5vhE99?L|5yqDB+ z@$?Hkn~|^=EJHi+>u()wnA89*9TQ2%YbSPLj5)Bu%Q5KoD-5;>gq2_32s^fx3rb;m zAf7ppxi_GS9eDN(T$mCk<$1ZnpjZbIj{nK^WsGS8H%P_KPca@O3S%&xd zTtHk$jN`OC?BS8E0+|th0@vkzghQR%$f$}B%m__qmhn0uooklZ3`dvQNbj?RE6)EmCWoY9} zPS32+A1xg?{>&&1@!WO2ti2A^_s*M5zR!Jz!u>BWz$%ugACbd#+go76N=H&qp~!7V zOBm969z$!+;e@;w;H>iqn`Rg2ZMCTZvvvdg^LYbzjo#O4w3p}&eP@IYtF`$#dg}eX zx0+cXd|SGboSYqj1I&MdmGM~;V7rZ_axIXUE5?&MoAApLPmnjhjV7HMDCE6{)8S

77@1pO2-dUA#h;ZGQF1U0m60dh5RF@N#ZiK8t%cN08pH@f|QOl$JV#M zVQ}_2GWX?ec4ovD=onjr0XhU*AEr<@O&q(v?W|Eb3&fBe#I7RW0sG zxr{P5Dj~IVB54zHh3xhwSQPvgPo7ccZnb++O;nTc=6X1yOeuVPZlpIgN|`m3a)pvs zQ=;HngEJ<^!_y9DVs-qX&`z_Q-YA?WgHp$EE|NBoQ_;|0&wVW#;4S5)FW9h3Z$ajF z*zmUl2WM>MviEzyRFn6@3hfPOxG*1T8&>MosCuy6w*4@^U~7M7I?3+=CY6xP&zo7d zyPBY%UW0E|f4~byLEup;L;md_quW1#vgvHH@XRf?KHVIKpEAK=2XEsD!*I~fkwP=o zIfB1V0W>um==qw+a;hy6@UqI6BE~%MnwA9bygiQ$#v3fj+X|PBhY)>_B6PT!3a5-_ zke36l2;;Ui0XtoTe4O3N>JG4krgvueEg=qbh989?d!;evbD`dnS2d9R(?%~v#f4L? zFz2_9X2qLaQv?-dX?`Tt5;GCNZK1tE&dw>sZCVIsNK#?YTQ|}h=EQcapUJ(xcR;W` zn~1Kd?yykF1y{;V#;=BjV6tl|E>yqF;2CD57So8A${?;QMmC13an3)VATN8g7#04@^~kSI>2#XDmIPXobMH^QK;m;Ibkk*vYv!EXBMYqTD9g_!(FV9)XbxpU2 zib->b&5Ib!|Dni_e07(!c>iR42ke3R$}F61s3GT&O04UFlc}nz% zB|divgv{N)gwIqj=Xf;_Hkz)~tC&^Au2zeO+1W?Ph}Da+@Npm9`SFlA`hQ^)M>a#k z7e^9)C?#i9btC*NoJF?WQ{p~-atAAO%A9{2fiHC)gXJK=Tb=T3;gqjjVCo)ShnyDl z7?J>c_Z%f#mO#V|1SiOvW~}_}+*@ia%&P zoJ5va7_Ck!5+KqS^|W9I|{WG{Z$KQkF7@`3@A@1pv^Ihfd0 z1zC?P@Tz(S>l17WX?=x)*!&uv-xCfg3PbcR&L1o||F@8@`8-K{VNwm(;Cd96g{>#i zx9xGNxdfj#`Vu+SoyA)J+5#_%YjHw6!2$I_5MWq{-hn@b#GjRLyrLZCZ@*0{wP?uSd!mQ$6-a~VE)ymJ47RO04IHS z3!E%|kEO3JBb)RFRE%emZw@G2XlVdV?N+R}8^%S;{F4DRg9!Yp z(hC+R^T|!?Ev#FvCQQ8h7JuyifD5)zZRbfj;?pgK4;s)-hn(74Winq&c&2U=rZ z>uvN-3xsu=gR$}X6k*~=st;5dBWidg%WZym44kj|lZ?7uIP}Q?ez5%ua;W1zyGF(a zj$KzGs|t(IVoNH>J(x{y6r>7c3L2n9QIq7wG_pxoHb7zGR+P7o!z#H)PWuM<|z;?Fa6Zm9gr65bB@%43G8q zl2wacSd-^7xSJ0G`sXM5)$TAV%Ns@iO~!}a)N5mJhM&Wd**@y;JMC~jSK|<^+egj$ ztG}SXZWsOXhfD9KlO&Zjxbp8;s(tby56m*zi!aPzjr?UyNpHj*=YxSc7LIEgn}wL^ zk6`O9bF^Ianq8x^0i=wQb6cfOqMYVf{z8|6xOevu?$=j)$d;c+2F%Yym3GP>U=v7( zeV{1*U?+Un-%q-hE#s<8J>l@%2dGkc0-Yb%!l|An>@t;ON6gvA-GoljO?qD*J$^p~ z>X6(A?y4xeYb?L^zaiof`GwqMPkTtaJeRnSjm04o|3Kp0OGM^JW&cjlZnX%NUO3~+ zxMsLCtpm^OKFoe7Hibve>x7<+NBEX{S{+j!=l-fJ5Pm-K0JEG;q}JgfzM1m}W+>;8 zu|CqmyxWrep3qb>^Vv#nzO_H)A|_uvoOUblFVJX6!ZUE#3w2$ ziW6dHb5D1)!OM0}GT`Tx9Dk!uu)DmJJX@~98Dx7>p5%UX{~3ulRzHT@-!|YZ>49vh z!&go+aB*(KuNEBj@e-)?M3c35-V3|-Q5~J}GcqrJJh#%+0aolCK}Ib*iF<5*L6n9c zneXt8$#~Wd9dv>c_hlX2cziy0`&TjkHMZd$ zaty`Qky)(mT@~nd`-=L7jp!Lj^?ntzNOQ{|oDls5j#&5-Y4uO6x$8#ik-Ua$j%Q=* z!bli9=QMg&nF*(J3SjvvYxKG)#qE!9g2W#dB9(N1nul(~zsoWdJLZqz!k0L}DaZea zq5X55LhHlYedmboKzW>gsRv4K2NB1EYFyQ^jc{}CHIzS=h|{OMg6ua<*k@CsS5fj7 zqDLLZe{84>qn&WGcbn+MOGA8iLYp_sn%=Le_V4wB=-;dR_m#b)e^R~WB_i##jctDd z&{_znPtTM-z^_en8pq4=BGl2rf~rok62C zE>3y}8mAVLt4`Nh2dcwa@Z1SkEzQJ*YTXj0rJ>dr1w8sWq2PhM>mBr|*k_>XMHA!J~vXE-s3~0TWq;37kw)oQf zPP;SKt%*ZZ*GF*4*9AkKDlskVs$t9$IpOwxCvK6{R$leGp;+TphEV4#%`d5bMrJwk z+*t63llx~82a8~=D*X%_n+_0je-}1j*Gz6uUT8lvDmTF$CY=kwZNn#HD%JU1yyu9A zK3rxuo>>Q{B>Y5f$tgIieJfuVY$V=sZV(%Df#W~I7;!u|0PMU1q1Kx6@PiETSN1pP z8|qJ@Zr))(p&6V@x!PaPZEgmG2v6Y4p)JC1yGM}c;esa)y=KQ0S%BrvAdz3`34At2 zl|MXTsQ7fW0;hD%0U~h$S@bRwM{nr_rs6!2$P5(O@|`fwz>gHoTEid%Uoqnw#5UoOad_|C=wI%JGh43%A$X{U4wTe!3~Th_Yxb0)d#itFh)sy zuFsOwqip}++oMR%zLR*a{s)}R4xo3mPR4xhE?68Dgw@Av(OuCPq*nWh9x6V>FjE_T z??4mr%R5#R1U%MU(ii9E<~=QSW40D2dR zJUI{*sD}0@2_vmz#&LD+8=>dJZ930M#5u|pa54M~iVqa&`5W$pc<OF3zq!CT^F4nQY3j8&` zqHl3BdQE-WC7+2`^g zS=LyH)|27h(QMy01CEfL3-;r;jelW~=rK8zb)9X@r_7w)qsh(mVmvY|1=gHdKmsqM z2#0!_p?(KPa!0nahkGnwy4PMT{(T1T*ws+Iv9oagf-~2svVq?lxk@beELAx8TAT0H z93d8#g>pJJ0icWU=!f$EXu>WP1G;n+QFq@EdUyDW)9nbfH(x-C7>ybCkpVR`zp&S`{ zsE>I^^I|Sc*(9*Jp%_(N249!h2%kFdu<;B0;2Q5itZ!Y%7kUo-t@}FS+kDta4xc%?MuA~n|w}_KQDM( z`CNxj`aVMZaMx^(-1`JR;7^qO({nNcTH(+&AllDHa8cbJ)V~?tKd)wsPjl3wCD>dp z)jP+3eu!4E$@L78b`?A>TXt7c@y;3-$BcT571351h(bI;T3+B zp!|`tVZAt^I<$zHb;}L3^Ls>HzXH+DVWj?{KZ74yEGXaxnQwz#af?WD%nK~i?*g6E zmr3vDLHPSQ@9MmJW#v%y^$zpPj<=VmPDID-?e+#SJM zS?z@NzP+N%_lCG@r7HjMxRSW4Z3`EiM)hOS=43-#Bz|@I3;OQqB-YNA?YRlC=2BUI zpS;>@7tCraL5F*D@W{6sNHOTex1KlIij7BspQ|h^Qc(~@r?q*%(Hi3YmUZ0Q(Bp7m zm?N3d;EXMfe<9p8ovcr%IaOb*pvv+q)@6$Elx8qYYp+2S%U^=V*eWP|@DmIEzGc<5 ziy^ILy-;PrF_u&1VAcf*@{gMecaOo4yap+s9)QTPWfBB*BjLLH3y!VuMw271Y%Kf$P6nLLWL<(Pte zh>1NV%z5U)Di`>}8JT@VRx%1DT_yOa{bl6LC>wTspC)+Kbl{%(&FC^R5Rz67Cz@}i zaIjJ%tUaSoI%(FUmevLkQ7>BC$4u0;jpbrujfGreU6FWl0llxC53*|m=lYc?XEN;;3Xi3eiR)mD_7$Obh8x%IZNbY=Tq}OEJ5|s$*5Qj6jS|ng z8_FGD?GGcm<`L7dV6+|I4aI%oWY)($>@by?-0A@*`e)9$Zth^)b-aJ(Jh42MySTta zcv0%Z{CQ*yx6;N5N{OjB>!Tg-_iKY#F;js(*1_`rtH+6l{g8#iCw^dNFpqR4u0qMf zGW?Y4XkvCbpRH3_50%Y#QCFu4b&iBW&F@Q?WBXBPxj`A}(k6o9pNq`XLK`@lJ5#Vc zeFn?@RQT30!^H{u3f$_}ZIlVGORClG;<0O;U@w_Ub`1y;-8e7FN2f%QjT20{3!!ue zC-EHBvrnRi9n~SL$`VBlIkqNx8+UTi1Ysi0k6&Bn4W*4sg@|ODnKE`1-%&eMd~c~1 zcRYLB|0JDfT#oM>#w!ggR9aNBiDX1kJ@<9q{gmAxDx#reH8kz^ASEp_vO*{;nce4g zQ;}q3CbSFLq@Dkz|Jz>lqEFB9oY#3C$MFS6Fr_V@SvUAH#$9sAp%Wx;B*L2zu#|g; z-Oqw>V{kPzCn!*#%3!XE?LSQ(n+q{nRG7u?HS+Gkv|;iyJbq4!e_c~Xv)kkabJkCL zdGIBg9cMwL6}CWfXg@k{!e(5b-vF9*v+0@v-4e+)V=_@^rSQHu94D@3Oqq0RL3y0H z5dNzGqHZJ$PI6h?ZIf`8ZQM*3wp>QFLo4}98)k@4yGC*MJHw%Dt_uC>JRAMD)xdZO zPtRZ7!0oJ93L7Vd;(%GNF)b*SoV{u-JX`oP|Jkkr2ws=Wd~4<0_CKegvm%3frp`ly zWyZYKAa(JEl0K=*`UWO9BB{`I{+84Gk06^ghfY-=O!SL=z_M^}&#YT;JCz(!wGrfI zKQJ3y^NrMux|;vbcYUTL8+6uYQnT&9gx_P0`Sg!!V$s~?}CcRuCI=acyrzM!@)5iPx)@$}qO@-x6%81a0PMEQa>98S>|cAvh3 zn~rJ1)hpdScSCvh9@#Nv25pe^!>s4heAApH`s<<;abSF<#zlyRsW;I!_tl= zGK60=mGo6vAzWW^PvZTE<-(erg%MYG;ejv<{!52Myl&WwhzmU6iZVw%Zj>SK-3)V_ z&(U||`{59;PN-jzK)0r95zAMOaHJQ-{%13A%&C`f*Fui2m3d$m!2J12Ggb&{OI5f= zw~a7mwY`u(a3N+q9Kr|oQx!jTI1#UGU$D72hd$WAb|&`SkbmzIJ(#e8yJP|2_qd{G zHomYU999i$#QXP6Q1R1SP~OsqHto2`t$LeERyH{aW}{n#4cnOSZfT$}dWO8PchU^r ze7AvUrvIMULn4Iv`O+s+i~)SM8$2dorVADGxFE?&SgzcKiKFh|dWA^%H02XspV=yu zZ?6Woll^H?QxkXYYYK^7?Ii46`$Xt(^#J;RyDiLG$+K!b1?U|v)1%c|{SqMSpcf4a z8iBG0{z72V6*}g^A8yy)l@OlWjW1$PVQgubI|B_j! z@%5F$8Ik#ooeE*XNKtU|9mJ_l3xF+M8>sJ>ddzP-2ny<96p{)VIPaUyOGg9}d&v)#&qez3_1Acepvi zj&5?i!5#Bm2JI=)_{Ja?E$vdsm-1CYac`4+lfw@{!=gw?=;%!zpVjAo)Wz*S>H=L6I!Gf(4`dja`;B|p{*dAEZRSMs^Jl$n5z%3ee z#vi~rm5hTh&Q-Yd>y@d_zDgKy|BWE_@ghebui}^4*o&{~a)b!&nf!y*L&RRAVu>c} z)_(bQ2A#Vr3avcbz$P!Anl29HPMD7;#=lZ}b{7$kz2QPrDyrIzM91@~#PF?)a4u!D z#Q(lEY_nR>qv3SF6TeA+sdy*65BJiD@b)&kJ-dtDBN)%xe>zn(pN9p?GQ3YkGMzL^ zOjjO9*f#>tg~ff zKiaZTfxFk=o%o%fApF}!@5%{=0!Ke#Nunkyty1Gnmnw>AUb22=-dIn38xbK6;%Y&HldGhf-*>>Yx# zvncpUM?q~wD7`YE9P1BC@j~=Vsv)Bw*c_7L1Fz-M!3Qizm{|y{yQ9o(s?;Uf98a+vXvhR>+LjZ*m3l3MY01$z_1$ayRGLEW#ybl( z7C-XkhZn)N8d3PiEN~9Zfs0vZXwGR{1<Zb`><;iNn_I;b_Ks7*b+ggh^kD&4v{;5&dfo`2mTwI9mA<1dlpL$IfkK z;KpVA`?P7|*ZCpj=Qej(XEMA;&oc~vgYE6zw3L36yu1AcxI?zorffcWU$_OHJUxu- z3q8?_eXkk%xCm3*CrKK*tf4r3f#CD&4w@-j@+CIBn6mpg=WC}4bxWn`zx~FG+%UK@ zbXHH-$C0x#yj*h{J(VI&WW5|gE3y!)FWp43={XqH_Mu``hLC5UN(!wu2=gk6B$G23 z_ryO|P=6VXk!vjY8&5zq<9d;&-#x&$m8X4!o?*_@X81el0zDbj4-4%&A*XR44LPVq zrkXDY^OPdI*83>FXFZ1lqX*H#<4?_obf*yO{Tl>lH5F#<@`in7omKI20uPt zReYSVoIJ}20$)=b+K?N8VHst~Pun zDDRY^O(~~Xhej4WjAL&r^JJlO>%Z;-RrD$A$Cd} zJ3v9gTAvc__3EJcf-%9JQ`L$gy>khLdz9d>Z7>_OG~?e$a&HMmaEOo zYQ90xRc-e7bR-*wq>^`!eT4wuDB+`Z5yZKE6%=l6;$G>;!uG>a^w`$@XkaYG?>|yb z4-9nXg7!~>uodk++73HIp|n<=Uf&>%N^PxhHrR58!0Rj;vqrC#<%4Z90#6J6AAo{}4rQ za(=ia-{5I3p2$Ba$b6W=zcLys#->M;GyB+lUOJOL?To}ZwY~VPOX;-IHjFzubv)^v zo!+DE`(%A#ng0=7HEk4*h-6;ntt`{DYO_RTtPL2i-72JfK8-VW5&qihk>dI!dH5b5 z3b*ggq_T?hQN~7=UorI{wcJ<0oqW6)#A70Rf7GLyQVe*rTk9n6&%#njCGi6`2{#gt zNj`)w1LvqvVXO5%td||he`p;h{+X^yChc1TS`q)zv5U zau{D$t|its&LU%2{^cwC{T8bZ;EtSL{Dfz>>DaNglK3mzf&bEox#RtDg+(Q3KTxI@ zQv$iG<|(8#z(=S!IuH$J#lQ-BLU8eaARPM`3k7!3bY)T{4*XA=H*>F`BOfXVv#O+c zqtfd%Vz?#IKN13^6>9X`!Vt_nAjNCxuBYpB6*-?Pro>SvxW^w-!&rXTyL@}}{3!E+ zZkqI2P&;vk3%;}qDm7!MM?gN-#X0d~dYOv-H;v+^oZAey*DF(t_p@;Gqk48rvZaTd ze7L0-mw{vH9xR+xj+XOM$sesv!Z6LB`I49-7?}B02zIXE=54(KvAP#&)@ys*6UOe& z$y#Ect@^~_cPoTS?W18;S8gS1eu5V1rL>>pU~=%sCfIsC11;XgW7-eK*VFS8-X3~j z_NeO%dDv&5@a$$i8rNI`t%Mvp?L?bUr=-pQnI|V6USvWZ#<+vRzEQMwa}ow_XY8=; zNp!zLizIN&S9o*Pfx5y1a_WLN7$zUaZ@X4vdQ~bJG0;!&+Gij+vcU$P+}OD{D)F1V>Hm5@C;+PGCJBdBW6*fh82*LbNU`F-x16K0Cscp` zk4}$!j`yxMgUp1Bbca_zv~=l)0R|~FwLzQQKfD~=3-04}tD~6TUJ1EGg?@ThW~Rix zmva<0^~~xsYFM_tEnX-NS;)8{>U_S8s#x3MK>GX_41aTM=~R_SG+My+zz46=K85SK z8$m4F{<#J(oUX^$!GYjrQ;j=SCZo;YYOqZnOmmLpatgMoWYhRfLb=r+A^Bt+j2@UJ zRIO7KlnbWwZY!sX2KDcV+PFBF#=Kr{%H8oc^Z$JDxJK>&=5gkWR)N?oLro^%#n+}$ zaNnyLO%AZEAM;dO$PA`^GMcy{ktxKc(nkobek?e%d0zWNhVcE^U$b&=c?kO?NB=Q- zbL`R}?|2y9JaQu1zG52wUXF%+I)%S>pMgi^Y%Z-#5_axy00%W4nl)dQn0q9X`4@Kz zj)$@YP4^;b^HjtUMoOGwi$AEz`qO632F#Q`2bG7D=#g))1%*_3zISB-wRk>~oIT_Q zg|~WBiF7=QJF4J(@?yI0?_9I-Q@g?Pze!XqTSJDje3P6c@agMF z^PDepT%bKXb5F)~qpqTFQwmu>HdGK_nB*^dS^#=;`{TXAa^&306d1s#(Cot@m_JX| zd_kquovcfxJql0OTB3>sl;jRUPZ*2HbFWjUt9Nj?6M zZnkqf^fXj>S@6o#$)OtNWawh}A8)dMody3ebGC@q2Ziesjrb}Z9WkIWnvAv%2RBth z11qCZJ+B|Xui`Y7=nB zVhGrFuV=rVuNMt*OKza$_fJBnV=9S=4i#SH9+PybG7r_QbRpV33H41!@)qeM#H3hN zaJcJtyocG$8pl`fXMdaHHICwSGh zf=)a=m^j+_!LY}t&{{VEU*)8c1?R(hcHr4{b)<9jNa5h0xA?V0i_ddV5Sw*Ohzh$S z1g#iLrL~hV?R6i%>To8_4p!jIBEEq8n^n}gWIh?=6bRSr&!Fw&)mTKTVW;99Oj8Z# zQV!TaoO=r6>fFU6zh?7))h$K+kH@$R4w_*2LXKsE>akx@1Q_J~M>St4qKC0GuW zJvK**C`K%Yf-hxwwCEOQxV?mX^=fp!$}z$3*?U;5av%R&r$Pc*2S|9|+d|(KmWzBd zhM)U=tayL;JI?aIwQwBgQ>#xe&~0WjY<_W-1}*A`O1>SSu=fC+Xrx63r7ef^R?pCF z%~6c=dJn3VT2wybsoB@xpJDCB7x>lBlc+0sgX@rdVfLOy_%c?T_sr1|OLn*t@9AOS zbJ~qwDcp@trd^=ce2eaBThF=c0ZcXijE6$&adhxzc(Lv~uC$+u7fw||aX%fp?d4@o zmT?;|*F^Ws>A@hEg_H|c3XpU6{UFR*#dpF z;Tl(CzY55W-Za_sE|%m+K)sd}ZR>0iI>H*D$!H{<nN*2z~ZGY6T?DIG{h3|(z@`Q0CwIC(Pd zJKcrsH}Qs?oy)PvaVg%P%6!!ON1(U6FBg9z5&TS(=%5M5v2L-dxkRnkodf5>$jF3A ztVdmj{@a;{vv=;A2fDQGz6|OxJwKV|OvC&xbL(2{!MZ#huN=9G=Ti2-qsCAiw{eOv z=Op7|j2wZJ+hmE4N;=3D9HfCOBXIZ(!UxA0!p00uLEiyjqm{tR`=sfKFUVm=Fp?eigySr)wZ zt2rW`JSceHHsXus4Hr{4#E>Y~J2X6or$ZIkjci97tnocSZAt<;^#kKb-uV+km)j9s z%sP(R{m&!4J_=h;zl46j3b3g968CJc4Xi6UFHD|u28Zsq;Ij+oh#@*H65+RmUvg}$ z7;{bzPBKPAgPu7(XR{DXH+RA#i-WZC_ATyyFSc(fD@BFv^?1fC2JD0H;PI-@LKfSz z8LWATx|!d&mMIQUu6jkdxHSpck&?d|JW_P!2b0xy>mdBgYzWo12VEW5IXpSlo z<^*csXI~Y*cA%;#=1n9iW7omLJqzh>>x1~IRhl1LCDIeyt0Y=K10d|~SG-%d0Zaa? zg!}fx=pMQWMym38`(4Vvv%Cz>H%Fumi2@GtYOYB`pl`$kV(TlbE8F?BsCRkN)0 zn^&l__B7NE-A;{`2!cXrCm59-rX|f<<^_5B>gGSMcqB1ihmce|p zxE4o^TuUtCy*fnn_{X&FZ0m|jvm+!Sf?O)u{H zFo63PfAs8I{(Bq%0TsWnq|^Z2A}V2>WEAx;zRa1-wFAi+mZyJ_gOU4UVZygIA#6oo zLI124-zw1+PhLkd_}3l~c5kERbJt=}2H*r zOE<4=6ExUe^0W6idjHfn?sSno$R4)F_@Y#7RCx@IycvedSW13o$b-$0zCGG5GjBiK z`4mmvw(H}iKI|QO=??8KYT?dyt^&{I{?zIBX)KhS0l6XL=-}H)!ZX%~to=}rJ{Y4) z=A?SFgxp$;YmGsrLHD4y+brz7sl-+N@dv5-TYI!U+~5>EvPtgQw>;m$*j2yo(KriT z@8=p}$V_#DAH}T=x5qvfm$= z>&NM2bgF0G)^Dp#3wk+7GIncIVsyoa4$xd+V^fmKanwyo{#SF0ZOxs{44uy zRJGv__hE(uSdTh}$7`qR&$ z4V*(`Qe!aHzZ0HR9-(h4HghJ~}WtRA-S=HyL~-h2g9){VxZ2e06dD&tSRz0CC; zU<*&O3xw*6XK>`-U;Ntz?V|0EG>*)a@a=`;#pApje7O(K~z!agNo?4B{a zQiYy)^0fwemb3w$j9N@D54?q3avLDcr+PDD@)gS1|LVs~T4K7Cd@gc@)hRWY9UP10 zy({5(z-Vgb+?z`t=1w99tr9*+N8qj}fuO9}*rV+}3sm@{L)1m>%M;0%u^XW5t}U%# zy+4(j(!9D=0sT6>QgZ6hEdMr|ejq{I5+^(Ob=?YsHpKv*lB(~#!*g#~nPg(ab0VUVpiihA3Ip~nhE zKFVwl?fqvcmvPgKtf6r|8Tn~zd_hKTJsv33LZ=0+mua^N{$on&OxO<*nuloa+9#-8 zzJ%9rF%t{yb+~fISl3k^No9e@?=xiifkPtbj=)`9v}g~erAJXQ;0^9(oapt3*-bdU zLfBOH0ET}s!*vs@IQ)143<7egl7=0+9o6KQX!Q}x3kQ)~5$$l7&AkWaU%mCn;R6g9 z>q#Rvs*nXk{Gi%C7jLU2V9}>?NE-Vb=PXm^j7@9Fm%B@Z-yRjn-JQXAZZ#3zlS6Rs z11)~sw|=6phY5*OTMgxF_37p3`*7Nb-hAq^bM)v}Ip*JPh8s5msPojt#C)wEyS3$_ z!*o{^>+4|V>-RXBkL13G+k&B1q0s16fHjjf;qmp}J+t}^*Eo0{#F)7nYUp|AFAVv8 zlv=5Ga}OAE@RA(M4{o`QTX$E3v+Y>w8=WPb`(6jHYu=-Oh&s8m%m+&PR15z&H9@O1 z`R8`p;=Yg)&hg?#5JxPbt0%ufBgP7{)g_y4wn;eOKaFUsV+w`r8uo?j5ip z*^N%>j={2Bf5C0;9f~$y+%FA)4}E_1==sH{%`n-z4UM->#h;(5Vd{aglwQx}`hK*7 z7GjNamS4aTz2m@LyBD5#*x4^X6aCI#4EEgaUj$Wx8cpJf4~%#XBT~)2DK4%(JKN|;UC+@{S`N_gJ)=$`ab0H25mLtj^ z55mt;$7z{<6gm$hyz%Hs;^EV>WaM=>C^nx=o2Nd+UK_u`e_s#K7aBi=MA=4|+wS5O=w>_{ie?1x3*P72*ZZ9TSoDe+kPUk(u zQKGh9H0iXCgdEpJG=0V{oSfGJ(tHLTFrP7w2QfZ-XpWHIn1Q7=o8b3_n>agrG+GwF zg}GO2m|y-HcX_TY+&8HZX0o?&|AL=}c6q zdo(d*9(9$I)Qq9GQVSQup#|kV8Xnmi0lPgP;^w7|!k2sHuppxnZJj=GyX%&N30E&n zw@<;kH6wVwVVpQ%f-0H)!y7WTJ5Z%}`B=7~9p(ul9djurUvZubxKC)r%|~Osllfu^vHL(1EGVc?pA$rMAB)$bc(8tV?#{9@Y z8P_#@zUDO1Qgsd&YQ7D2Z;+-t4E#{nfH85(_37&&Te!7X?4ZDFInHJ|x{r)CFMGZZ z#@iMMTDRih@bZ21@%K7hH`b01nhqkL?#u#~(tP%k`}9!Y9L5U>0}LEX$4m{wrT6;s z$2?g7r@kiF=a(swF-a6+`bXp7^DJ95HW;(owQ!Q_J&1T`g-tB{zoqODTvR_nBU@kM z)F;k-bJ2V;aMf7uO&zyb7Spi%98nAE6Z4B`$hj~LM&|?uNgkKho5dX0m7YxxPdCiRf!pY%& z8iCb{)A_*$5^+r0cW%nqP0-xoL^G4#V^U5B!3b z8Zl8ghQpJpU{${<^x5raW@GxbfW?Jg)IMYrDK^*y3vVdkV=EhMU8cnUx~Czoh+ywW zhfwB2+elYW*o~ET(tL665*p5WN}J{a^t#lEHS!I3<4F*d+>@qjR!_k*k7`)UO4 zdzBkw!I(RJ-0|e~3z+N`4NLcEV4G=gq58{Eeu?}jF=`wV=e7j6G9`j8YTtmtY!07! z^b!4V`!=^^p);(!r%c!HEx;hwO|f0MKYj45O&AbR38Pu2^@H&zF4V>Wv>QCJ#wZP4 z82i%9aWzi*0FoASc^Gy=k?Pks;PLTC;K_wVx-Y;GWuv9|)0ZF6EsAZN=LKixM^&N6 zv(8}Nxl_65El=EVRE5*O<`2#) zp>%0Z1G*|6nR~f(CWHnOFO`L^d20Xccni?ft!g|(ys%o`JG~ZOf zg|_H}^rSx2?0o~;eh-BQrFwLel1JM#m~ zpC6&=TYm`~Sw6RRK>&Rh`i1*5(gFUH%SMZ8_I_@w0M8j;QR#@b#ESX77uOQ;3vSnf&0y!-ixzqNpaILSW@t{M%Z~FdvZ6ggM471VHln=(L&+mF}NCWmRhq6bLb*x zUheQBQD*p9&aEI6`X=kqWkoy=Q|@4Ix(GTeC7ipo(*ag2%0@qj3LJBV-KUE8VsY9l z!TBiHKd0bE4KY=Z~lDl6?!96o-?+U;n!}6r6=W_iK9mtC_a9SPog&AdkvOD3IC3I z%R{+xJ(d$J_$9noEkxdH3O~QzRMf~!Y*j-OrJ6#LqUv)vn zv@AL_zLQgxcY>xdUr=z*M~C(0aAnpMTD$jz;B=%CWNq5fM`YX8d?xihl96vLeuGD>il>hda|4d%Pv#DI4vT7&*;-bR5A8gGb!u{F@KU?!dFdX;-| zb}86|_~KvHi#X`K7N0$OtT=|Fgr6M`3O6EX!-{qI_(V6bQ~t3 zA-er$U4Kf7v|wlW?@l5CR`7nMwg0-!k!sFq4x_*dR1AQm^@?s z*kfZcuP~N%axoTaY8bV$Ye4nIr$FlTLF)DNnUMNv25(!ZEV_HFBC|($Kz#fVI-xBA z4Hk7l&e&LbX8mfj(HYI~^W;1lx6+vuS~JdtS1cy6+3(KXlb~vGkzN^g9p|^|gWA=8 zJ$sLpLn0u`X9`sal*Rn0e*7VgG^%&(73Zz&2o|5N;Njvtj64_#y$tqapX9NEiA^T> zyt_z!W8-mD%WBZCG@>2{O3`orZ7V=XQ}`QH>UIpb{mwY@mFD%_BHOn3!KJGEm^pO}dT)9M?xvkM;QTc%P_Ttx z8|3iQ!Yu6EKAD#-GZo9%yp{C%Jd^L!tuN;9kztv$1khgTL7Q@1P%1{2zt`(BeHT;6 zO{!ZA#)0)%cBdW}ghYYnw|AI7{*zGkxE>x<%g`GeTe$ag9Uv!>F?tRqVcfED{3}gE zvAA&v@s-^UHupDBt(f~*s?Y^dQ%h*ts$KanS2C|}K{h>i(3TuCUk}doF5s9XV8H6kT(_64lW`W`t5*o!bWP)CkxH4xbO|!baAMU zIcIisGn^T(K+WFyUu}6dpLu0Y7 z!v~H?VsY$2Eqt5AZpvqw#oRhn@*pS^F3Mk`k!H2{;rmLy?6|e~S2Bisd@2O;OD9t2 z8GwUze?jueaQf!=4sOL4mZ2_Teu;_-d|wd>R>Ax6RRh~mE2puH94D;pb6T=Ufx>v- zQtBsJi$BdZ`ITM+d-fO=L2Zz|>onc`GWXWBz)rY*IfhPJqf6G=_`{*Z;+}c<^}`xC zuP05vd1`R;hJGgJx26ai``6*Ey9T`2*HrA)5ridn8hl8?08u-121!5W4ud?6sTpI| zud84_uI*=O#)NjslU~w%T;6VKS?xrOSl-;+@fGeY+k~L<9+H1`;^$SN+;DdTes`vc zxKwU0r}0|@PL3Q%`>>r@NqqwB(q2R7jc1($OZxIdN^j8i(|w4enG?KB`G)F;^D%l< z1+0B&NC(%P6y(M>zU|XO%`<^YtE6kVs_fZ7bG5;b_O?)`mg;eLb!^J(?^j=W{cCBcK1H*RHkyS2cgUXxX zV4)2SKjTa`fAfLi9SP{EYmcYLFdog9MMA|#Bgt2Tvv4lsIxSowpzaNQc+`79&wP90 zYB+qnWJm{&mc{RrWcbXSz0`MZF_*E^5%zlDM5`IsuezhyLHN6~3hs@Qr^^d}a5mrcd7q1>;?rrm zRC4^+CQNS{deapj+Exz^e!>hwk;XBoADE~+I!|(XPG+ayNCH{ z5B1~v)VY%_F0noHtz}FqDf6=ung-1huI$(6H`|(u3bPlGGWNNsst=+Q&t~InO?S3W zHWAlGT5yWTH^cR7eQ89e4-URs1E+jgE&Q)7T=e&)FlAE+P96Cetu5nVum1j?nbzNM z8Sj_4KrFU)6GjIZ^9hgD#Oo6hi242yXkR~>b`^!7DAf!~qhshY4+Snt!ITX0Ioi|F z=ab+IHyrokY&mV5H8GX6{$3;;?hKL0C1e7ZeuYj*uEoQetN1+SCE|vVF`UBZ5U77Y znRV;~TKW8hdDo-p<>fm#aCC$mtDCrGHrv$IemzEmv<1{n`OLx_8s1qjbsc8GfJ?^%#pB z67athEW5NxmhNsJ%=kfRz2pXW1rQD;vH64lYB-od3PiEg!rhlO+=n`wL@8%|jI>8`|cKp?qkMDxt z!hi{cs&{4zjT>uV^rn7vpR^irc$ZAdI+h6`!I^^E`-%JodoywW@&@kVi!HEL!Ize@ ze2b)-F)lmGXorguM$~k|xn380b`i4jD`AL!2d>RH&bpmD!P;;IeW~=-%-+8Zn%Xp} zhhhL}t7m=ewvK|-!BD|RGKe=Bq9Zy+Sd*c(;V|XQb~=c}e#GACEyW0gxQ+Fao6L2bIor3lY0WSr2Z!8EnC zSt#^k`EKJCH1kt0qW{1Fy8A}s^sF?T#TXNw3Co3tZwH#G%P_x(t4hyJ(7Nh0oE&hR z_Le2+!gk2t;x)w%y=g?D!iD`!bg1x(>2o}rW8auj|FnI=oXk&9_KI~^T56EmC|_{Y zNyDE^TSA^N4vWdE9)13P&kr;PM$wK<4LG~^MVR$9i)QVq60R#4^OYktd-VC;ArFua z8&0)0?Zs(t*_(px@#e?4nAIF@hPhGp^vf=1QZ;xJObJRupBWA~z%`Yq4t5s08T0p# z+C`9@6RF(TLM*_^`u43iW* zP9Z~QtrEJ<4C5xPoXFcJnTZ<3(L!i~2A@A$MZ9#vjlA&;fx&rpR4ODA^D4W*`{5;O z(z%uMd^V0`ds9KLZw3|z1i*af*SPEaSlsFJ7A}77Lu0?@anD&sz$9dqpri7GdEY1U z%VW*N4M$!{5{H=c^Ol*4VYB*x+QCG)xMUMG_hSA3GK@o7cZs${=5zDB7egQEA3YwA z$6iq|LFNlK8GRD2MOMR$A&T_zx1SvMn{|ErtYUn?65(Ct1b$s_Gx3bS4w=E;6ert4 z=$sMHad4+JKhf?r?OYk3e~ooeFO%fbY56up{IriaqTb(dKNe+j?k<7Bbe z(U|$$H-lHFBE5LT2X7qs1jkDk(a^e3?(5WLupl#vvA-X)F6I<6No}Q2mHRF~$21Od zOw)Tj9+D}pyr!e0C_BtsNZ4(}@42lZX77zBKjp(9RCfk-niqx<;&0H}v734>QQ)ka zO^D3J%pMIt5O3v@x*)ms&RI#_Rc0_`W!CEPrB zFdOy&2TqMfA?rQ7vF=9=uc~tP%%6XDjaGTF= zPj^GPeqAXfar-Jks(*jfw3@&l_-!V}^xDHoUC@Bn!eE*dR*#8Ud%=00A61_{6lI?L zg>z0est(l)qUp-aE{2auYfDdd&HTEY8Ah@kagAV2cVFtMh;HHo3o zkn9&h9b)&P)1|-g-Q^Wsw#J()y-MI(V{cko#pZ37EwE&&6792Z8any6!u_wSsLt4X zoKnOxa8TWiu1yzlG1Hdi9_xjjO6vJ92Qkm&8hvq5UrKaWCc>NVd+19=AAIs&j{k9^ znr_UdT+vupka@04^G_Gy$n*#>?9ilHkt{D6-VSx6TxrSHUgS}U19-iS!(F*)C^IF6 zL_S|9IPDl{RT8O)9jd`+8OAJ0Sjr2Y13eR2*r!sra zqTP|x;CaBDuHK&{WCebLuJ$GLh>-^AUbPZZS)cv3<2&$sObVHK-Ak|?R$(UO`+@Ae zXu2b#0pB@Xg725IsqFe1Vcdi@pg(XlZL8XgszYV@-Q&_}{sAwu0oiR3|In3|EoR)3 zT3^ORJ&Y4I9dIYh)a*a%-7{k^ewqih*(Efr@*&nnS@1Kwd2#OL94^^W9|oRLrn2#|5LvD@na+ovX9!CGZhT0*|!T(radTV8*zr)1eRP36CRKbbT~$yl8}|Q(Vs#FIxk>ubI=Y6Q5wA@gKPT=mM2H*DA=i z_Tn@C9-uq^%9F@tjv&3X2rXI;;DIk3)E+;E%9MSk zOe)dj+gN_jI7v}BL6W1FS z&1D@a;X(98mIr2)c7xNmtJHm#z#WZT40X@{^vvFkry}9WeBoP zhwHR&j4gS#-y6P`^rOw0iMU_rfPLAksR}=YyVwK@w78VFyOh@?F<({JkZ-os6OQ=!7x1T{;YATveyHxUD#`wH`jzTT>^x zgL}caC#O!v;e+>&QIty|4;wc2=y|||IGCV!h}x?EV_?r1*=d424BPha1CH9zQ;%DRO#b&!%&a_*hC za9JZ%VmK}nDx|K{Y`#<}KYPnIEe>4Gq zX6o@W!z5y=k1s0KsPdX6$~}7CKGGA4-2S8e2c}}f3>p5^uN%~Bj}%8GGW?a!G%985 zO!WO&pU?YB{1xGjdh4s8evLAl@xr)D{}eK1zn74>uODN7>hXcoC8B0Z9JlO*2E5p= z+N0ImvP#-IG!nnJdp@DhwH zLIne>f&8JYVPeA?D{|<-ZuoFLhJL!9iY;FVY!my?=7|kBeiwTeOj4$GxzkYhLMznO zyHHqukE>?B`pZ>um_O$do?|Sz`Dxxg8tynigP-p?UJM&`i`=YEhJH^H>F9<4EZge} zPYZ`r$G-P4>{SG8lpRXP|7{hjmwg4pPxjQLNMI^y<_X{6+ZE0~y$re4KNx3xdP(C_Rm0FQ*o zhaX{JwBBAnPMm|IntUAo{0&B?J;=3xWgR-MVelra|X z?%04UB0V6XX)JZvyBB>vwL-`JWGZQNHZ$~Wg%9UFsUGh}g8KM?q5TQ;-MI`0TuUYO z`5}VgWn;;MfP8rS^#yf^dX7YUHovXaT(nNl=8Vqh!_`fyG~BWg_t!E=Bik*YVGPF+c)uV1woaVGPToy>kxf*^?Nr&xg-7FKFwx z6L@{y7(UK#v?%;+;O5O^Igt;RRNCMvmihhxnaC@w5TQ+&EY}GNCsV0Xs}yN0bA*{K z4>5ApA;v#y0FQp!R4IA1koRo9BB@La1tAE``U51)~XUL{;1Q!bvL+O z-YJA%uv5r~@51|3J-#V}h|gcWkOWWV`98`Z9(>vxyuPq^+=Q+4^?x21t0Kj(NV`eZ zmLpfZc`>|t+}X3Q{+=HN@7HzqWM}NPs^N!$CVh1DCzn>l*iThEh5JWK1pA|U{Nb}i zj84}kt&9gTFf5K@K^0~Xli~mD%ctq~OUT59t06V8H{JYZ7nZemL(6k7dSRg!cQtDb zamhR^#OFrhpNlC(?)FY$k&g? zYRt9Pgu%LCEm}EvJ6^170K3`t^mf%wu6nFJd{$4wVOyWzBEr6ZJ9Y@BYVY%Ps&~Vw zpND()Cv~eW_?eQ~;!agtp>w4%uX9dEyuCJo%xu~PlilXg{r}_WJRGrnzc6mKs3?16 zlZ>=b!tJSFK$%UA2uZbpG_w$uWkptTGN~J=G zTUj=spBOE0B>7_<1S@X^?!>ofcK5fV?)nb+#LJWYoA2WFW3SOSFc!2^FQan6Gm%qi zGc5gv7@OC_bt@PV`8&2kO=lfWex^enwQCEn{8afFDu1BFtdusDT`qq+_AlJLx}Oe> z)8=1yZh%E8tpl1#-Kb_r+oD3RRw!{F%QE@1$~#2EFdd)Q8>50q=Ba04{UHf5b)JYm8Y<3(+>j()v3XQMHh>S6*~#9gotS)R4PNeT z1gA=6I$kE4+sfXO#$7u_$3Dwo;7McR;W_V!lN|jWLMR$+CgOI(tw4JE&v)Jx*KOt5$ z0gFT>(Z)o{l?Y>+TDhwmwm{T@t<=b)19SeIhcTKtw9xgosMBvS3E6RzetkKXKk4iP zFRl)u%8v^WFE&HZCs&&4`oxyle}l9o#&o>tI)0zqIxwks!41O~;%8-9GHsHcFf(i+ z&)24dP3mrHxg{6lm6nlP=XqiLqWj#UEFR>2N7Da$IXuR*+}SEkI^vTxO1|%a!G_F( zEnUWyTe`!Sk}SM_paf+sGa>K^^Ml(cikhz}lV4-agt?>2`SIm>U~v8r?b#TOOT2h8 z<<3~ar$Cy&+vyK>pT|<`tQvehW)~Fw(56|9zeEiz&l1|Qj7Ic!b1E$Re?Bc66Koh$ z?sGlFI#Z0UpKq6bb`WI#QW>}#60s7vl6`^VuQ_<3OoMco3==w|RCqDQD8BK-h=zKc z!sq8cK;@Bis@8Z<^li&~@Lb?Wzg$%2(}Fg@r|MI<^>q^d%6raq`)bsy*5r0Xg~3#( zWcuP|J9_y|C9N{n!r;5BanTVCQldCa$nN8KWwBs5kYhr1f9%E!qgW5}x&u^aoS$v_ z{vJqwvyPVU3gGuyhePJ5GuY_tiF%ChAscxIdnFUOc{Vq}v;GZzw!aZiU2z~IqGk&7 zW}oFe_nX1s&&u@w>^{}2yFo_Ejhdv5LT_W{pI?$g8(pt+D@J(1xTR0<<6YK~Vekyz zZe+PRjd;;Ihenv@bQ@RfRO07^I*_5(GX)2&Vf;qvRq&yH9*y|;h}{?d!8{ES^;j;B z^V2*bs_`+Z{XEFLSshUFSdZNu4D437bi&ScFIZ314qoh)F?kbdFI4r$i6rfn$>+l= z!U0Ereo|Hpbh`%8GwimtJd1Vr_*YP3x{Z4Q=6=Qw*|zSL8@MW<|ufiQ;q=5ILolUI}u|QCc*UPMFHIBgoOza7;!eTLhHfi&}I4ClPr9bN=x z%n(KszoewaVMV^oNvSQQI=%xQZ3S`Sl`@kyLdktbCAc+7O}MtozG06Tuu z0dA_Nax3^;x`$24zj;{f$<`xCis;Q#J=YyTpn2NP%XAigCL($q@b0lXOh@dOkLUWyYU; z!U=Raj`4g0e6TkCHGCK6VeSGyWtdlGTn%olH73i{9E90osodbrDp2mEPAAr~tUB}Y z`WeMjMK^sMK8Z2>n|XnS^qj?;N4+Fl_+s@~k7 zmMir5ihVvXT3&{#s2#(h=NPZ@;TD=#-DP{?LnmlTj;Divuj2D>t%dqhe+CF{@aX95VOysyEYw01y@CTD>tdCGkPh!UOW#oG)4{R-t9?@Vd$nqzp7bd z{>651h!3FG46kvcv)p0c$U~_4vji(Ar9-?|0(x4>iH;mmBEQCuXIbWJ{MPVX;4dGd zdL@y#Ux_DX-p0b>6lwmCQ2^}sHKFul4K}Fnf{|tV13AY)zYfTaTTYLR|HjGpE`<}m z`Iy*~g*Wd%g+Qabc{U{=*d{B}PX7qBf2=kLDT9GmTO&1n=tU{YA4Whn7MtC)s=L25^f#j3%19N)<{~I2vAEYiD z{A_cKdtg+|fAofR06#DEKXBR0@`(P+@a~Z|Nc-4;J_hW&e%4J0c=ML7dEJP6mY9L5 zt=d4gagco~torFf@0g6lDUW5z0i#Pazq^r34)TJ)&X+jE>>55aeFmaLP5Ry>UbOmE z11wxok2-r4`OCxm!GdYg7K<7%>8~RhA(|_UbCTxi%GGdhs}ud;^aO7tvp0fu1--Yk zS2RRxIBDB;j_%$q%Wrz-368!mF=u)n<_zhDlx>%R2 z+ixS36-0^-DNG_(u9m{}MX`LN#x7WwEGFXNsTxWMpr3((;HDO5gcOt>cwf|v7CyVQJJa&s&Z zx}FSz@!qL0lI<-sR{5Z`xFq=%a+7}Sz0PT_cLw=2QUf!5`sG-VeketyT;7YshP6Qa zT?4x8LN^Cl9&p9V8QY68k!)kHp%V^5ZS5F-)WLM1(tBxDT^lORav|ooZG~&|K2%P6 zE=F?3ULVj&q*>N!&n8)VWm7WlF&j=??UJd4xG9%2B$%H(^`vM_NGxt=`opT$RT$%~ zgud5gN!AfV;YrsxzJ0@fSS!OcuIaVtdfkP*va%D7f0)MItBrvh3and)F{^{w{VtT> zLa&x4b4AD9q2X{ohAThB!o_S(UW>s|owr5LGm;_g!I1&qi1~Oc@;7a|P``+X?7@;) zjn@^P_NMY4@`+%XzmPUvNJMY{Kal?LAhjx!=DOnS_?u8U;K$?G9%8fdBF>G`M2Xzz z%ya$_FI$#zhh7|m2UZDw`4b>urmS1>DS_sga*;VNi9&8{Q_n9-<-@c3sQDrnjkyDlpi|oFO>cg z(eInCl$*T$3uBibqI-;W_>E6PfRK-<-;|7U_DwK)r#@XfTZ!AW{|lcN)giiE)PZhM zx}+i4MmU@kghN)1CQa`Zg-Hu0@Q;Jnzy)xo=k8~t#&KyPe)bG)GF!)w_1O*;XM1rC z3Bf=1EzsLzKr6yyxW=b0;CXlfDm|#dWVX+@%Q^~!l~XyzWah`4pg|pb-r~68T8T=w~KbAcZ1HANi_GZHh-fw z93&G$uxe}q^Q#+^CrymE;NQlr8@2_C#3Kjh_V+<&!17l%-6nZcfoz z;e*0qe3WnjPo}Up-Lp81O&Km4^iPR=mo*nWmzVMOr}DvKTLHD1vI|GsIFmQOSeDjL zh4*|I0P_<}>6N%!_&OjKRw<38r&j+F$w+oU?dCxG^g%aQ7P}O-%{V-8qdfTFIRr;C zUU%^#yO_2?@ScpJ`=#IEJv#wjR^Fn|`j+9UH>yN-qKxpeN0IkYSPm*fC(u&a)40a2 z3wk=T>C%6XMH$uapz6^YTI{3D7rqSxqdjE-nNQ`@ymUX?TaSN&tob(T zq~^~jur6$?_A(4k^JM!~JG3ACh^_Ndx#HUCp=nUr&_Dk2W?Avol`e8sdT@pm^)mlJSw;koTs_@AZ z`r)giqHy~}1I~%FAYXUe2ygcN9VJ=CR&^x6I3JPGg1`*j=CV8M3mvQA&3^Z*@VJ>}7pnrgf2`MM|T| z2tiqp{OrNMEZzkH{p;w<^+}lbSd2Kb&*3h|NN)HUWB%Nkmm;+(NAS|ZXgH}ih&~UT zgq1VjfP;z|&6Ta-vVOaOir|68jM?X1VNAXz%n}xyerh-UsvVi6=_tsR4Tj&0tx-IA zCym$i!CaIi&CBl4v)0v|&rxUiw|59#wV)kMI$}Zb{!qH<=6lf%w-&hQ%f6%4zi}>h zp72x87w>BCLp%0eKvvBXbd@yu*64JQQP@Y_UbNvHCl_MwVX?=&?^DYd4$1u#;%slP{M4GWi9bW z!t(TSd`)^T)`tDk7)3^J(lJl*^WoAu+L=IMtUhVma8AU z6pW;b@XapPXONS~{5B~l-cl!$bWMi*;|26?K^yA5upkcG^absjRKDjt>rGp>fbIy0 z!;UPL(@8u`6F*9G+k!a0KJ~gNZ)PIe%nO5i8f7?ottQqKzXau!CX^Ul!Sx?H23{Tl z{dcGpx9EQ(!}k6ajDkwJnNEq2^poW`br$0LIjZDa@D1v*mi zfY_A>7{0YZRH*v~&YE{%x7#1?>lhtUX=5vt53NSIA`8-8Vk79}nezIl|A5$Lf&Psu zEgzQJ56+_tXz@Z_{;f;^%=+Dd9}MEq(x?p{#E+*9M^w2xH{{wla?nomeeO zohn7f*W9Duw;J&M!M<=sVl%Y#&D?4S$E;D1n?DQgD-zyK+Pb;K-2T!7wmoE`k%ooa<9&xG;JY3$YG_Y@v859LB z3Pv;`eHvEZ{|d7$w$a75Rh&%CQg}G=6iyg<5qtYnAVYpX?vouU`tOtinHe%cc>3xJ zuW>jZ-dsIS&HQ)alTmZX2E%EB`kzt!@i~m~@@x{lZeEL~sWI?!w+T(K`X$mz_y9M$ z!|B%2pIl-1Qi$PB4d~m;6kfoDQynNP=4AJ|X%IYf(4t?scbL{Bf?lm!8o$XC7ssfQ zSsEjRlVys0E$bE;b8j-ecK9^@d-(;_RPrc)^RZ}%f;jO>j;ESG#_}SaaOh&ZxXk`! zTx$6aQbPV<*+OH^Yg8E6X6>fK3_2J`#fsdIVRgoltMTwRbz6r{cB@j;?u!2XxAC zn$=6Fl{cdh;E!dT7^IKmi3VhRTlmnX~0|+3zGB5PB5SPm$Tj!4kNGl z(&_aLczrhGvG1#ToYm6A#pyB~**k*Y7VHIsHZUFTW*(kVZHJCXOL}|0f!(v( zP8e1tMi15Q;Qim|kirAJ5H&kew5)P8`F%)Ds8RFc^D1LuXwybI>P#|L+4g~gRt=rK zWEEMzRL)j98)22z0OP%-WWciz%5aSGxAU!a{H#^0F z#PAVxLhc6rCF&sXl|MNhcb8G_*v`_TA=G1)eBt`O*;$xBAC9F|!YRr%M3 z+BUw#Pji8A?ds3UvKnzBt6Vprb^o_G2u{9GqI&~Uu*>B)(D%`_L0y%ruwBDHGOiH4 zR87PHw+#?+IvPWME23nbEO{hvB24r(=412@gGc2FnwR+$XDIuUoqy*G{Zs6@?JURb zR6346klTtMw|0Wl+AZ{<&o1s5+f}~AoyN>jk8nKWAx~kfa*sPVMY}g8gVN{1fxD!^ z4ol)TmlpCJ^s?$Z<(xA+_Y+_P@(H&9m zqa<|r5C&g23Rw3>6J;BogH+>t{2WupE!%nwYR_FC@R@A5Gm*%+PZv(@9K;R(kO*g6 z+^M_iB3xPf7iR1(q~0pA+%&dJq>H`7$U{x|raTs=>OaA^7SBcJf3v>no8M7b(#u7; z7?1@QX9&JQxABpp7BOW^n52cuyy?qc*f!)Qy}$iR`R-M{u;t{j0iSkM<$9>E`-_L? zr{SVkt>Aub3SGNZl{+I5CiN6 zleB_#T0O4cc7EAs;5neG(yRDa*VeP|zBs(HW)W^&s7d}av=cUj1@Ys~9EAfmXQ*@1 zdF)p8CC@i45_;+$an=4jtX`%{<%8O>gL%Ww|1ze-ZcoMLTybLjI*HD3dcaL(Oy$V8gUM zAG_+)gW%vO9cpjz4tsyyfG67@(Y5FNQME>u!E9uOC+bT4)ER-$b%2%jO+16%FT0>| z@)0_*=833?bs~&vj;D9T^?BEJe<)m5hJ{Aa*sk0J5*mGYzF3bNv}Xgn*4snRy>Cay z5fjO13tM46AAq}3mC4=25rW`h%^Q3Tf;C-J>9d6ySf|L z$p6PjNW_4lJ~(HGcKTbdZalW(MXp zI0{l+W7X{Va*}P?-A@v0{!^&{j#+R^R?PR*wCsDM~ z_$|EtCr-QPtMfr6eX#JEijaG*0r$io~i$lV$Z9!dDkBUL`sfz$b#%Bq!sxNBtlnS4R&h?BEoCoAdkAK8lh9 zi*WF^2w0FfnCf*JrMTQqWrk1KVx!6o+usb+{Rz280FtkjLgef1SGEXLQejy>e;e;yDgfj^k@M;5$ zxsiy$OO$YGkukY@XuhBxJcs{wz7P~fmCzs48d1rWY2cg2)Bm%$TNJv%B{`b*uZ`or zRxJgSh6{*3j~LS}7GhRp4b1bIi<7~v>G;4r@2N8jH!w2ToVab6E*$x5$nQDO z4@X<>(6B?-%HOfi-qY(RsNpYd{w?dn8rv*M{qlFC#oKncU1&=~_o;Jz!@uxexkK>( z`}xjUI^?Pg5$0zG;=}85Wb7q1VM5(_eoWa;7|U+TkK~K6I^B<~J~Bm^k>SH#N{)c4 zjKTD$_)1)7-Ui=SPp22>#&W0My26(GVYs#H78-tGUcR66g^34KIZbgDIKN(ZKm#A) zbrj-{WYIHP=D6?IRN|ziAg~-f?@;3lM?;mUMY@3HEU%QcaS~ndiOuj6J#fQj9yQc3 z;2-V`g|Cd^p|&~>9}31qmd+OjTfF5Qv)NAW9ZQ#N>R=tl)5!go3PSA56}$z@^o=>9 zMAf$!;*O<5iPFfuv{_l)E_BCNaQ0vw=+$fZ*H)pR{WJluH!i~DI9X!SWhy-CUBvhA zJi+>CE>ZQ4Qk*-7hpfMu#)<85;J0@Q{dcxcl=*Kd{2p-;8x0O%BmD@wDhAO&nE<=9wu691=+d_Q4$MkM zII#LY{aoOMx75{$s^VxNIYo)TT@eT&2GeOK%S0T%(G6ej6jF_>ry_azzfj|vOivo> z^ZrbmvdL!|)lDflVL~%w%M7BSQTkk66JuE@WK!#OjD!4VJej`LR>-;Si{gKk$Zt(q z;X~atK9lL&t47$+k4rN!uUL}w)L*1hSJv8|vt#}`l?<9uvz|{Vj0TVV*C;i7HQteK z1cw$$dUSdMXCGM&we?*T+8eRMcRV@w#74NeB8S^`)fCQN(;L{m{U4{poyDu@JN;3N zP2UeCBhS)3z17?r18-QA^#l9Z%pgUs-J?X2)@1EEPCw$Zd z<%kB%v=~or6xs+kMt$Qx_UwSr62|I0-;VRb`(VkYd$c4|48vy+Bl)|^Y1E(Lyx_VF zo?Q5js#%B7JK--FO?0KVk}d2)q&wk>-w1kDV+Wtd?v=Ujiv*Q3@uHjpZPN73OyHM? z^2*0!!NGq!U3xDW#Wcjo<0}tnSeB;7PsE0(R#^0l zr{5hbxpLMaSl7M-FP5D~>A8ADTWhA!*nQV-VIfC0#4i+_=n&|Bx*ML&O{91@5LfM# zBASiQXr6GBGYVo(YacnfAhexz@Wn&KK1G_G{7IzvsvZ3A+0*Dnzd4_;?6VXah0aSe z(U$F3OD8Q7CY;jbA1kFpMR(4?e7-Q(kF=$`2&-oGRC+CwB1em!QBk8iuYMsI)NC}V zNyzzzlLvDs2$k7myZvF_3L&I=qF28TSr@Tb=(`5oiRY0pt8$+zGDGEQE|Kpb*OMo+nylMH- zMC_E3VBVV&+8QLsg@_YgYU@)`wQDjeFb|cS#QlL;J>K^e3@%&zz~>j6vFv;t z1aED_v+rJrJ{dKGJ=4eLxb$%8p;~118X~mszm6_;h9r8>6v1$XCa-EMK|Yv2p=Cow z<>!|6g5QZ#)HGR}xBnLgLepUC=CvCY-nD_jSVD)-Q{!gzck(B?M-0sB1;b2;^X^5$ z$jf2)JWP{Z+h-!Y+QIP&wlT2v{$_gRz)9@CB1V2+en?ea{@G>b4<`04SLhA8f?wGc z0Xas}RA%c+%x!D~4J|^OD`UC0J+6@DwG*F>ti`@N#w6pHlW?XYmD_Mr8NBKZ2IhAD z#uG4k{t+7S)dFi>rjm#bWuf)bRKBs<7qrf*)4(SJ&OT8HB~z^FhoCK@yCXh8%Y!*| zbd);3==27#-JQvL+v8D;j>2zqo3D>R0P!rj^1Kf*#7bi0(_dh0BlTZZ(jM+WMqI+CBM zc7o+CS^fzZ1heeysF}+h6otjZS#2At+t)9ODHujd=jGD%eR90kd=HqVEW(K!58&M= z&5*obnx4*gx4R!W2>dVU5A544HUjU=9#Vs|o*0~|O~&n469UE9O{zNxO1E=#{iU;b zVb(XuVSfvKrq4uj`hP*`R~nt+sLxlkz8j(aDXwDO8^M=egY3Iu^w%|AZr|Ds@V9s$ zEhQZo+-^#$9@z?Smw4ldt4d_B$|#}z@HE~spWQ2`aRd8y*snhzD}Ihj6b0A@E|MaJ zGW)4g!v@~$!bV7Td4`dy%W#KFBanI0v}{8H=R&ICYU;Ovdu2$7DS0~2R(Sa60GIyA z6x@6a>EX~0bl2Sjfvy{GNW<4D$_ru^#( zZC);cL25(E(Fc|E)pHr%yNnAN z)j}*}ePrQsqp5xI1nkWH2`hEo8433;clMntw6mU;sl(3T<`+6-UHwdfy4TrdO_)x^ zW9AFFSEV57)n0hvn#PzFt1v5T5a~*MO)n?i;<5%ggO{N^jWKD*tTpj)X0Iy!KbJLc z;~+BS%St-mT#i4h=fV1(;s^XE`R9$vHC!ybyQ9fpmQ07Kl6eFE6Pu5&Yx#n|4@73)67f)BICz;I zz*8~GxL99~tn8U6L^zr7|M?d~`Oj-KAiEXE-y3SLbWyTu^rucvFD?o$6ilJV)^5e* z%5KO!nn=ffj^pf7Jz#M%qTQUwm|~O+?={b`4)psXb-831aq$#2V!R7UHv`fcYawux zCWuxRsgoJc6os;FVZ4n=0`pAz(N;*r%sO$>Ip{L|f973%pFQ7t`?Y9hQVO2Gx(WWM zzrb&aI&9}}gi-n|d|`-O#=8Qr@x49Z8%(%kLMAf~#=oWF-1nFas8|?E^VPgiV&*?M zAaQ|89E;;_eO(4W&h?_|k7g{1j|Y$4pD}CcE74%C1;jLlQaq_WjG>!X=s6 z^z~UaZfIvG-*ZS|V4hEJ)g~(n9fd#J1JS?Nn4GyXT{u?1fKMxng9R6(=x4`scyy>Z z!9VqM*l00MQ9+WNyH`rfs{DBi^9bmk&2mz$D{#%}w{UXKY^q=%$Ek$4LE*nxbV#Vh z3O3JmGnWX*TT{8J`^sQF)`&ikZAZ0;6HtA(fJSIoVoa_T$@`-!tk#&yPh0B;D;H?d z+>k2VVOzx5%Nz|}u~pQy`va79dV;a-mqq3F=3va#U77vYp zm6AyV+IZ)4j*L2OElkYt!iIlVL^V`Rc+c1g|0Mn4eTx=7w2}1%Z21juzNSmqg$OL(bxyV ztc~T|O17V;C+Sd!>UJ~@Wm#h;cA_OK{krePiyON z&)YZvTaGSN?H4`P=!5G)d*~CtL416z2Ry!T1I=F@z?RX2Akocmz<=VNQ3V!>&ncw( z;(tdhNqNj9!LM`@?_C-UUnA`qTk;(KTmBv5yUx%pb6BV3yFSK<*h?2i8}M%m!(iQ- z2K@Xn8P&BI4}XOmeJ!uYxtVN$A)Z+S^L+VB_7>K+6FlB~qR^#Cj-`(lwmhE7i+vA* z?gm0P9nL^&*45r{_#z#u5NIpCNP?{1o<+SDtmC6^Z-nY)jTr2(41*su!tqyfw7DjM zdnj2AXJ-5y(8D!$8IzhDwt~mZEN=E%Q&^E~G_ap99CiTgW=7J#MXEUSUO$8_y-Z8Y zZgRU>MnEx0oQCc$NB38aV0dUYEuEVpx_Pq&N^Xs&hqP7s#?5`Ob+x7-Kk+rbVHts0 zS8at$3p=^GvK=7bx0#-N)s8n5F2n6x2k7_yD~_OG^Y+qGyoQc97>^OBYZv9C z#*%+~*t5sd=Zr%JSQ_#~7b^cAiQ_nf(==Ywy%^sAS3xgdZ^dwk zg51AW1A6$mSv?@`w40ujPvRc-c)$v^o4BCnG2R@P1dW9k@ompt(eD>Y5VZRY-6s7O zJHdeDey|ee&YU1}`cH%G`Jy5W`4!IJiHL`F2ba^-6YP!6cJjQ@*XY%~a@@gq!sqC} z5v9LO#+QuYc4bmC))woaL^xv^IgX-w{*+t)y8y2Ks-q7+w4wuhv&@vV6JpMYadIVl z;9%k=nj+(keT>27HtrJb&x++Vg1o`OL7aBRx1fna9CT!NV~gSo(Fd(okS~^}>OwCE zs89Mj=L`ShZ{u#};a~K^R=EC3msbpxAUDS}P`zAHx%kLF_VZq%@I;3%whje5tKszj z-8XA!2UwkSqFF8)-2K0ue3*|qPF>l7vCFl|p6#=Q>q7&v-BXUloX{T7Pwr(Vf%V3C zsvLR=zjZ7jFONLAPhB|vAegUD^oOz2b*NTz5xP|U zhFzu^RO0?8+y2!(FdBVn-s^BacJg`%A9oOC$1cKHHlyS+T!bOJBX~_HhXa8RXy=nV zC@M(WbBDeY*V5(Ub^QwKOFYkGTO!KOVl^WkkyY?CMKPPvIc zuU^7-i+Wg)Crv9xxQQI(I^nrM$Lk1@yZ-q+$mT;?5ugGXAuVu~T(1Yo#>qcatJPFS2RW4jI1K(i1!v-^5+U+1UH~1Dq*Qp$^{u zcB;b%LBUd^0guX}V)nB{^1>>XN&h0DOPBwe6+ zl`llk|MY^M?0!1hRiDq@9S)Xe?EW8>f{*Rl&HX=B*4t>vHT(>P)r#3P#i;`?pE4%b zqZt#j%@b!GP$YBLD+uE0Q~C8XSHMJ{nbc#?9z5;-4-8jbqr$sjTmKK@M5%)Hr(9gi z$J+k~y^M#XTDuJIBsW3!A!VxKkjTBSxB<7idgza;M% zdd{m-?Q&JVbzC3JH_;Z@;R1bQjY*svFT6h3$(aP~fTyds(SFhY^%mB(*WE-Fj!WU} zqvAxvzJg{f8^nJI_XgW7QZ(jBJ|>(IBX%0=X`%HryC(@hLBnz^9da>-?`>fo;A!r{ zV!Z?r{*fiCf^~)dUUxp@K?;1omdxh!UL@M4ywLMobj+{-d)eQVwVwLGeN(of3#_mD z(gTNXaX~3=@MGd0U=Qt^k8#BkC%a zhWl4bk=iSHbj)BqE_z`IUmDRMTKO;m=Y9`|a=oGfzTd-qW76=}O-Qks%P(;#hPX}< z4Qp-1Tf~t>mdy}KSDSH=8U-2pHZ-DcEBb!<1v`rNQvL6V++2H4_?l6NY6eemn_(>L zf4_uLX*We(JxTE6IeYi*c#Gk3`b0@~n&4<=F4EOiCaS*_1;@uB{1O@qUvdIzyHq?T z&5|H#Q!1&~PqvdU;rRJ2t)hthM6CG~18yci(PW}2igh-DMT;_xctJV)(*>ZZc7MPh zK7(mQkz0Aeze0?gG-xkO^xsCOU-rfsnQliD_EQl#0~7e@OT?Pu!l?3 zrNQQsR60eu472rI$gZ!Jf_#HBcPm4j=$ll~8*6;|*VkiUP?rXkN%;>O7`yv#jXRzG zC7zqH$Q|yL?m?Zcw{c0AG5IOxAt*0SW_}e7~YUT%T=7jcu-Dd-6vJ+?YmZ&%Gd;cJ@7NUhGZV)~oZkD#Bnzbus?Gk8;Z` zV^Z~HsW2v}ovYcp8EV2(2Xqx_X=~z_U@c50t~f@*ij4fODU2NQgS2f3$)bguew zY%%%`CmZ+E>J6W4&ocHV4?%RyGS&|}o^e@+6r=BNCw$tWL|&fbg_;*$eADeaU~cw~ z+F3PX`d0_CFV9if@w<$h^p%6qmxgrug?0>N9)qW$JRQEt1_l4W&?=TqKRVyx`no*f zc+*2%Vs{yJlAnX`dSz-9?;)BxM4l{rF4>5XeHr`h60PAl$ zblhuiyP54$@O6suzzn~VVN7PQOo6FgHO3s&C*Nxfgl112UaEH`?B(ZCF0cg2njX0H z`wCs9*C4t!@h_CsW>bmX`n=P-a0poYaX@2q=g{_)4otgZ zOk(xy1s@YH^gbs~2305siC&ic`IRf7RG3S}g7)H~ias!TS574k1lb;A@5emDL-d^A zT3&0=Mo>)ph?fK}9PZx)W_MV&(K3;f^S%K$xAzX*G_^JwlYP&Kurw}T+NJimJS!ZaPuR)I&wqwh!U2y5E4n2PG9rORagIhs9)ZC|+Th5pR zt6%2eoPd33BvK_8+h+(nBW3y1m<9nR1@sluD<;)EZ1C>@A>&rxzG(8EIwlEIfpVI>~e5S!@(qJ-O zsB;+4kNtK60yPDia<&yet#l->9?cZWFPU+=PSMaK3H0KI?P$sOLbzo%b!bZFBvL(r zANd$NqMsmrlLEEFYVhXRN1{`;Nw5t|sA(vh;oI2EX(B?srKPB^PKhjRQWlO!hw$}* z@lX>GLhElO;OXBiSLk=9(D)ffKsAESYJ zetM`GNy%L%lpfiHDy7EcxsJV{J!TKx z40gHW=~~xzB%dyT`0dM7t^<$-S4jMtVM60k4L+mFpLOYuqr?|Sn_d{;z!p*QvH+?`?>5806P9K;q z3_7(0lM1ZJl@YqakG>$@>A62_(=w*>{Ewq_(r+l;mP6_1Pqvy&|6kq~L+?G^#V>IT z2Zuo=`1pl0)?YOyZQHyAUULf{o^b~rJo`XTjc-KhT1WEMevaV$xttU0 zJ3eLi1zl+e`a0DX7cWpEN{h>A#{6!sXs#ES>OaSGxtDSKwCAw$AM?yRc!(PBj3yf| z+6vFxOZiEEB*|J272)u*28<{%B-1L!2?<;`H$-|h6bdYxz!)9*+fzVH$C+wnNTJCg z2Ex!iNOS9?_}$k$VNcsLjJlAG$#Xkk_zWXDM#IPMmmmdwzf1<^xnhAa*|gI^2#v1B z36i>GHOrE}{mS?-4XfdYsS_Rc{Q{D>9yqwMoJM;!h>mpsg{x=t=ng#teyrqw&@$#5 z=7yzW^PSgFo5Sv^y}Df2N7e~){vhRVG5!p@H5(jt5CYbC;qQ{sr1zepaBPkRA8ooC zw(nj<*B#2lCiWfS!K#+ty9C#$D5~kB{Gvv*XYbG>tcUU0tt{@1hbb(OoG{=~N!)V)^cTj{i-~G@Nku>oe!MLl%bcuR-k3$aR_QNpssn&qV<PLS=!C4()YuZcfPh#H} z0S-ce`WNoPx9xE4RMfyue&F>bC=NPIADUkk&1Zh9hNA+lv6ABLKYGL7pVG8b`!N1G z+7FiswoE`wdVYTEUAGR9(5rSyu!8V)8+|ymg)IB3nS>v{f{`Z(;Y0Y9>Qz8&Z6H|P4Z=p zmGB_9g>Ni63VYOw=((*?_%mFGOr0PrR4RSrmNqViB_p+{MP@rj%f*6Sy8$hn`d)P2 zr~^#aFQ?=6{&3@Fc|t?g;Q^oFvpZ=p$C3Hv)-#R5)`~>wOcxUBZdXn=wjkLjwS}}F znf$_eD`D+#bNYYQ>&5V)dI z)mmuYX~LfwS`6XGuG0yUZRppT1ef+ZQ5*Ak?7kvJ9&ak7e$V%EB4sbw!}=SiYt>_K zQUctbatpgF?ucrtlAu&{k;Wc-i+X=_$y4T2y6-Vw)R&+{8p>3KXLCY$HH`$&S{+J@ zbJ$*;(+8PzkS>`qf{Q+3&pUN}6Y0K5!MtP9@JmgcCY&%v|NLgKIHOPhrVE_z`U2>_ z{CGe=v3X=nWJ(=`SWR)xDmWF+-`g_aKY4WGFUV(#2K1BQbRT%@B||sMwqkO49IR-P zqOX3u5Cwa*f#=GxbfsG#clwkX$?%vZB;63<5_Wf}OLGu5tkvTi6I@7BYt^F2%Jxmr&fU}te;Md*pJ&m*Rk)lDZ!n5a?N=BH@pLX8kvw|rOO0U z%Z+FrElXTg4F$n*Jg;b$1?&BDsK(N2w5{|fiHfs@v{FA#S3!cXP8G@>@Z%%b#Dckp zA-(k>0xjjb;i=_1y1hJ=o73VBiemYwta}F!d#MqV?=yvlOOf1xN@dt~*qrWX+@aLG zYM6SzmJYXeMT@nV?-n@_gmw#F0XU_87Yl118 z>-@Oa8{rmr2`|bgV#G&PlI=HBxY2c=D_^x4gsOCUrlbS^6!R zdcxw6V18a|0K6(Nq4T?rZ;o{|7+Bxa7ZHtm5X-$rz_r0Tdo6vChGvy*$N-e=x zZ;VO3=Q5#V%@$tS@D3c){z&U;Ub7B49+KURX~?J!JhPs4h`27K>Pe0$>!3u6mzLAv zGrPHYabED~^9vmM@G_dOeGV5+Y0^(SJVcjcN0Xg(w!+`+Qa<*hBsqOfMTlhCz=MB{ zNckR9;ZOb#PH+Ai*b%mvs#`un)%oe*Ki-}0u^ECzi)4rmV?%k5mghe!dcn;dFL3A2 zY>fNX1eWIdbgZ;RwA_V!(4MjKyL02lu6?;+Mm3;7`0MeZ1e0%VSK! zS91^1y(c@+r&x!4PO}v{+ZSQWpwZ;=TxDTn{uF-GpEcl_k3^uw;k~`hC^mlz7CuPlgdH#;14;EFTz__FL zHV09gA8Dd-iV~z(){zFBoWTDY-2+Mcb%iAj9j->j3~1mL z6RyBtgF-x$!qhpq8}FA*bYRpwz_k||9jT2g3Q`AoYDZ$5%t=48sj zHa`5I8X0?Xj_}iXlW5rOk>t&qv4X)9H};*C1LrIAX}#J}RJl5lkIWy6O*c>AaxM}! z?AD|Ic}~Fmn9qPEa zC%-vg*1@`w{o=dJ_n~E$9`Ro1Ds&7{Gy4KvGAP*vFO(mhMnKXCrhn_ z<+_upTzMKcIrc)T&0%`@qZ&7P)@uHw`Imt#k6U{f{5o?DrDiH)$or9mESWC6zirG< zu08>^ZPf!hNyDQ!Fq_MI(;Q>a_l*+a)=`>ZdV-rA$uf*a%{cd9J^qiQ>+r|&>%&%2 zlu?KjvPBe;jQe~~W>His6`?`2_fm*#AxXOwN+}JZ@|<(zS5nd*MpH(EGzodn`}_fY zeBybo`?|01HL`eyvFvHB7^|DlCc=%1VrnV+NK`+Y;?(8tY}z1O(flwqT=jA!8|6OL7+>#AcZe{`rE$4c&^j)gWufejBn54oENBdiqYsBJ;dz{1sIjY{&V{i;j7}gd z{xXz)srW#QbrSeWCuo{z;vXtg+1vRdV#;;JBct8f&`dp4 zHFFj&jdo)D8#HfD8XB0nrP(y#o(who{ny-B<*9`;it+W znwfM}RKWX7ufASK54vli!H%0Cvx^X~g$bl_@)o{PoFI(rTNkhRaYX4Q^d#huG7|> z7GV?LHQO!wkz5;ALSFaRL-H6iYCkzZ6uC+T?`FUp8%vN^u{8cErzPgkHI@^x#79TA z;G;B}d|@rDy0(zACC|zAu2lYS7tup%vLs`rJbo!tO!vFfr(%%wC7jB6+8kai59?v-Yt@p(-0d``99?x8o3DJcH2kxstBzSmJnQniRg( zdY1dcS0ld#+u`eMX*!`Im~5|p3tu*mr@JR63RB@0cy5`ot%|LAr|?6ar!L>IL={RQ&ffKAS>CoUIFanALrO!9t*u(L1%w$6y95}%sMl@}Kv z-|_?v_Ps2cH%kJC47f`N_{*S2jl3u4w=$LLJHfk#df?Rl-SkxYL?>B=c2MrHr-Sl$ zq8pZ)`0p-H7J6rs=+r1h+}~ruGLq(@hn>fuX-GcpaLFf+rv~EpJH6PBKW~LMLnfdX z8|BH_iD!u#@9iIO%ZQpwjVGhIcTRGC1eNrt7WO&%!PlsBq}~1^86c^NuOLtM`{pgD z#x)vvvtYv<-_;=nk5hct;~X7m7fn7IPQp5+#_ZS2!ANe;Oz>{f7kj)tN5sK*Q%l}Q z^i_1OzXf3RI$G!4Blx&2gwB>i@)c!~$SFE_aO!NfP+bjuiBARpX=lY)o$NUg_h=fj zCa?Wy=Z@u&{nm!g8MT)To-c)Cdd|`#k97powSnkH!Y9$7vC(90%m%nUm=W6&buy-T zD4x8>k$HEUqDyzq@EzMKu2VIUE|ooezhEYv!1s{;xN@HM_745lQ6P+#^M~c#&E&+S z=cMs?9IP~WPLd<5MX70taP;;y+VFyJi;GP0xcgJZSlwGX94F7vV&`8kM+)X#PmbG4 zr+r8u(ssPtc4ajkWvnEudF_n$ER-N6Z7Jm8^hlUDd?3BXj7Z{zchEI<0{0bE2(pr= zV6){*YV_;_x%9~t+e%Jjw>C%$&Tadke|H>RCJH18hx} ziR|!-2i4U>=}p5%QJ5zGJoBBeg6b}zYPc$PDdYTnS}AcTG{uujr?T-(56zi06Hh;c z*he$Xo4sFb@F`bCHlZ{O{Rj_->|GkP?_LraRQntD|BR&hFARk(o_FqauT-fI!mit9us-DK)hnR7qdCKNH9JwjVD_?p!fDI zLC@wzLua=MH3{E9QZv87?`7MmRbR5Ocar&|(cJ&Y{req|mUWEEwiSzV zrF!7w=2&WjjZk{oCU`pi4(TpTAZLxX09?wX_tjg8_9I(7Z1fa1dc$n8W4Jo@>Xv6e zb~qv5A4|Y4ZzA39c9#6tG645`U81^I|2b;>9Dq-rPNn_}V$fy1^1mTPTiN)i^yxL?$B8;59fJ)c95tqt; zAYFHcN?xuJLTC9yc>ia@u9T2m&pJ^3ZAtC27K+YEs$lbtQ}}ne1dYEcgTw5#ne&v_ zL=VQ}oG=IGYAA{DxGiAgwTxQLX&}8g1FUw3Qqk1GWcZhX`1YVHH1*6-WN76NyUf3k zhaHE=Pv356+%lCKvNcY1o-$w*J6^1N6l~&mXIWs9yf0qMz!-0Huwo~d8=#??TVbki zDBVz7PSzUt!0m-q)WPtLXywlyaBs?|7c2Eq)3(*%6DL87-X)L%=MQk@nH|kHGZNHf z*FwV8lVaQ+KF1Jij&Nr&i|3M%w@UccDou7S-U@BovkiXRET@T=j}iN>Ubyw(E*%oR z%u)BHBu;Yr;9`cxx`*lcM_`hX>@f6q7xDDz&wr)P;DVU z3ogR`xKs3*&lQn$jRd|KSwnj}Wzb9iKv0cVr7zZ;BnJb#!T3cib$M&$q*eAAk_Zy> z>R;8vaX_9M`y94PG-!e%t^zYQt7#s3P=5-l3og*yL+45RG%NH*PLT|VE+7W`IIo^R zR*cojd~0dpw>>oe%_HIQIX|fEy+n?kzDTq`^6t31ZcKS|xs$?R4c@aciM7Pnq25Ee zusN=Xc8-tXf1^p*ly8u!D#)YPfiofXsgW3~U2n%h?RRUMu&7-$^iC@@Hf*IilY51& z#S7u|ma8Q5U>3=mUcm{dR7HYC3Az}T3SB@XiWXtT$rE zAroa;g~9V@lj)bdy=3+}IXv=ZFBub4@6R{6QP%s(MwGq$*dW=*jfRzHcfMpoZE2RI&?J4 z4PK7wd1q8nWCV@sNg%m9q;bRDM>MZWMHn!93W_$CBLCM$iWWz~oA=x&AefL**WSa= zAUnDu?UwNKO%5a`)rqx{iyRZeI0l~FEh+rjkq&ED$I)m(2ZlOG!BIRy`TWeV*NV zX!hkGETuV$ZuEQB=ZonmOCO!vc+x$_I~um+93bb>zt%X78o#&2E(sf)Xyk#oM^Aw4+#MBHem);I`sD>!0 zCzCCB3xv;=xfh+%l=u%lP?xp+(7dVI1Z>|yEmixmjnRYTt z`5O7c>cI5v1j>~CMKPn*@s9tdGWVXFsOXV2UX(GKu_q0r(8dCX{x_K|Sky1P9KH+6 zH>{-nyWW$iFKJ*gIfT~84#%)LI=T_1=8b_QwpGo4L`c zS6_zv>#W3Bol;|p)m6ON+t}O0ZM8A}sbs_E)fu3|@4H}~+&UWau!4N})dzVV59pNp z??gv+`k-R^dD?c;0A1zb;qO?EmTgHT*WZ8Odu@nD78wcJy=$O3ncud4wh*sM?hzX3 z&6F1UlLe_tcsgjYzg||z;vCN_&09~G8=N9}CenDg>NC38YPDm)7D-+dR7CU6twNza zTVY1&AbRh55b?EZg3h5pcZDYlQh^ol=94u0mDNaA@O!=WyBX}s=4`>MY%GjEZYS2L z1Ag_b;m`ULM*<<~ z;|Myp|0^&YE3 zb2|&*@9k0=v_GDB$GYNq*X`NOFRDmq>`a(<%~b3OF_{t%ebIJYyXz3`mHGh^{JXrn zR2mt4UkERFZ%p6AEON!60=GSut|;*>L6**`{O?;R#^KmY<8UL-Ky6c~C|_B&9P(c| z(z_e?lBLJwuvLEjc)BtK36-&%LrEw0uOt)rd2&Yc_gRJdOQZN02d~HjB(phc9UipD& z<3jHJsJTI{<(o-|u^vvXaAonX7NQ??IDTEN!%F6dAmp znBH*IDIEq*p4{84okXg(48oOL4p99;lZDBT+EI_pRPo(V;Q18C(;;lqiH*c~xe|{4 zY{718SRysU^H4neI$fCZj^qrt!8y%**JI`}WKJUCn41Otba^fLTJRmpiel-ud8tB= z-+YiME+rcG?h}?$fei-^sCYX<4{cCZhplmTVxIgVfPi7yLpsFIoA}++z>8W{Sef}q zlyr6}JS}yg>vVW0Rm2atHsB16{8}pd#h*uC8&c_HO;hw|(PFr|yOO;69zpg8RN!gd zG8N;bW02+0E#MZGP1_<`$^C2QIQO6=^6d5{t_5ji2JHOpXNoFgqbRzQ@D zq_Et>EA(jnAIGr~GI;3mOxh&38)-h~S`Ej%Rnr#}+XY;c`QgL9_XMHJ@M@@U>7qY} z^IKuKIW`O7{oYqj3znM&C^fUCQMN7QU}!32ZVaQJ7f&Y{)dMkvU8mNcUJ1{H0Jw6Z zn>;*qja<}ffIsz4^igJjhsLzyZ5kU5k2T*($HE{uhz zh7R;4_b)Y|i%>G-4E32jf%rHKz^INCn@tJJ%nQsCoLr{D)QLJ^OwfW#**&fX6OQM%zvDJfq+9t|&3AyfXHA-@_TAxGbeRvjHrvY!2gq>2=(y8n@oGMwjX zPl?D<%_7nutAUj&9N5d=I%IRIh@QmrJHa#*iXC!Vr@5_$7o{X}2hVIMVTKaEA6PY#B46D{Tu(?I*LX+f9ST|rM zZIjwUtYrpaw{0SNK;@v2{K_9pD*loIGhYxRNk^M?!k!W znfeWdwxX^H#yG;4zdIa@LAypJfZD~~)O=hL>GAi+F>%ltehs8ejv`$ zHhASuHI@;03_aTr1(koS=nV7qBxvXlnCPECvrnh;0nPbPXi13Q#2PYkWd#o2FtFmN zg&wjlP=lj$>}l7^W?~%5K9*Zbo#0u$DE{r_;tl0 zx_L}2+Hr6r)TGptqw9Ui)Ze49YT10IG-Nq4y?7TMtM<@IyBo=~Rb#PDts|4_&JnKp z3!v4?mt46nt*V#~vlP}-A$TUq_&F5UKe|hep+%^<$~P;WB zMgQpz!znMOv44k4kvGqxmhEz6TfcV;M+ZfLd&@Se!Z!iEe`UdNqX=3#NRd?Yt+X_? zV%l|G7MWWIK%SNaz2A74bXENUpNRo9aL;O|@8e`3Gs%{BWwesJ<;K{ubS68STuCm= zs^XF~1NL;_Fm#z~lAp_W(@=>AB;gYG%L#Qf?`N|}_$Gl*{3@Y8I*ri;-%U_mHk3Y+ zOC>S4nt=-5^m&JgU>COr4*$!eYgJlF+z}mYmhR3zo%SaCrYT{q={oGqOe-{sa}4z> zG4#e${{9{+g&j83)30M!IW|3&!aliWblBFlXkAw{v{b57nOiH!{XI?4I(a%hQIahD z-N$il^-#IcPz|@(mnr?!;gxH%n${PwqUm8)nz9Q8x6d1mcX8FuSa%&N+G#Nq7Y==^0ot=z9sO)=CBM&6nurs*mKGkpcd<&6asSxK?iaWdzpNQDty- z2l{w93?6QEp{CAhWQvO<#;dN;DX+B!7ndp|KP;3CCaol7@ow0t_myb5>yZxaGobS0 zk(fVE<#*mru0I?3s0jn!$HU!u%V;@?B^RcujAOmR_=FO&XdD>CX-#CdJn%x>ahlu?oZCe!wC-Ie#7 z)l1-UFJ6i@XPNmf{I01$Rvk-*$*#x4$=K;oDg^>2ud|{=$F2aq@gk%hD3~} zmAZ*`R%fHyTI5)zOD*GjonepAQBr}cbOPL72qT5lS<6QFpURLK0dHiiU&%A%| zAf|5=@r|=qY}#WBbWEX;zo$?!CU*{Y!{;?Hv(j=Cj$F0Dd$`vncEoYCKQs!0PT10Q z4(mx-$saheXD{tomo6~n1u*RLf8^lt8q&VM0)HPNTd{w!9#VOw2A>x>h`Dq+*Kp?Z zoZ7jG*GYKsXq;53$(WB0GFue__sTGJtgj+foxh>i>LTy6y&)Qu(+3BCX3#b_6V%hS z5$1I_l68EC`$S>|9-%B-F>p={`n-QL+|4>fZv?iIDclo2f4?J}Ugts{A5+8r?^Iax zN+)!{C=?#}@{WZe=gIJ=eK1|^DwTQP={SPt>>f!Tpss%+(aWff@HC~7Y+ve2ZZ_!Q zl=#KW@#$LbrN0aRzV*=Exs9agvMDw><;bkOa|G{M0%-1=EXHShAqAcmt)xj!o+SDR z_Y`r@`Hz(6!uy&4c&#o;V{J;w&d@io?uZAK8W=2!{V)tKpYO%850xRg3sQKKr5>Ap zyq;L|&dir-j?5&qTX;Gw3QmZ&QzyR3-cXnUy-zpMehGPUnrku&CrjwHd2+~RR{(f? zlAxQ^j*v^UdSK>*V7`5@&gmRCqkglo6WuX7zq5qopu51w*>G#1|rEB!dHv?2JzXI<4mZ!mE<4OO>9(b@|IbGT} zN%*3?2EsR;q3s`Ah`G5gRy#h8ozM0msiTzeLDMm8g0mIc7ncNm0~2Y*f=lGgM=3m_ z)aTsA}EAos71Cv&pIpiDnPH(=INhkSCbSgCb z0g=ChsIzA@@^+HP`QcO8NwYwak?tsLAMMH>O07n=;Wy!h%v1Wt?hfD6a>m9Kvl`di z!fI)**K2B!je6k9bbLL{3Nr}-`AkX`hQPBhIXojeb_AX<;v1D~0k{XLMooP;y!|mAvE_ekDMIhU_vS4L3i-3zY@bKL4KZ zesvC%bbX+|f|`g_q#jO7oz7nNbvbEl&x6TDr|B7qon$lL45}PfPZw*(3rf#};E0bN zjhN9)POBxuaa}_i|Kfw_Z^U=F;TJ?#*9}D9#tz2&KLJa6bdD@F)50=dE-Wrb4SBe` z;#&sJY~%oyo1w>T@HI;<=4}#=&bo&|@=6o>Gd_v${>Wh6T}Nqeua$5oyd7Dm`-?HW zp;7@??sZ|Vv!{_(9Ys9iu{B#W!U7rfoQMB%D`=d@2eO9ejJma*S?>;4Va2zJcmFF5t zflX9)B?fw`*mJllOL^>oHaaec=Zzk;o^PmJ_$ZAZtzuN`bdO`yL21k`9ixSQ(dcUY zMo^G%BX9Tml9*`*IPdFnmb{+lTPNLxVa^gPZ(AdopTaTr1+d?1bA-%N0Y2Up=%10T zM6Ej$hRH`!(V}_e%@-Nms(XumpZY>LtFQ=g?m+r>Unyx+dIx?TzI0{%V$trSTxjLjN$FZ`uJa)4{JG2$og`1 zTrX$N%6nCjO~785`C~6V(Njl`b`8KgbN-{NnFWfFUk82NDzy7b5}Ew52Tn{{ORaM4 zgkF_3aN3V=WLUP6F`WOX?V8U5)&~$v?sdsHr^goX%=_W;y`V8Gjk4DzB-(cl&R9E{ zbxKw`cAt{L-REx6KCO*tvG#7zbJC{QTvw8V&s!inbi`0?l&RYdb+;{<-Z=g&C?1JdjC5mbO&Ww71v@}SDUJG1Zy~w|U2$QE z8w=VujhyY}p0^@dHZ@BZJy8yZ=fsdon4BVKmdW7kdnf41t%B41@tsiDwTwD>MWHn+ z@>t2=MU2%O_$|`baz6X}DGIsFe*hO}e5R2hb!7A<7kqsu?|*Q;!@FUvQB04Pm~Y38 ziH2+40`<6JMY3;7W5vGXv|ww4P#d=ZW=wueu5Z6YCa>4S`M*Ng+sTid9u*D7%Z)~} zRoh;Zj%!9ZV3{%7WByOL_Sy$_?6sjORn0`DdLR6fnNLsaNReRMUfwTskbdovLq|RR z;mhYI~B-a&)o*O8!^t>mh6G$`%rCMRUZ5X1BN@I2%> z^&8PdlG9AFQzT}S_NfW|58}aEdKHy<6H8?HKJreuL3gU83I;Zdz&BBrYIVIN8dnm) zyHT3{U$4gMiEyy%7FFR{GreDm_=mAR8+vXr5|yTdr*{V3IyI97mCeQ~@_Yks_A0^Q z%M|3hTZvSar;w0$k)RZ-MU^DDMr|O0-Bxd;@==X~`QjYdx4xN<%H|q%hdy50GLuc; z(BqV=avG+VpQay@wh{BrAgIVUq%@81!+lMFS5Zdv*V?xt$&~MK+a;7|LI)z*aCux+ z=fY(77n0!#8dznvGqZ=`=)h`M+~w%Tva!m|)_xm&*Fu~1KMqG0jqBn48!I};H=WGA zD~A=d^JvI6J0a;(J2K8(!gI#0WCk9LFHLl2#y{N1n#tTRWMIqIFSkJFf1l?b$p5H$ z#0O%}w=Cc7a$~k5+ysXr8@&C~Xg0+AIMPQcuy2t!HEfF^`>Xy!xO+BTw``xF+O+^4 z=RPJmCm)ap%f{gMx}nUZCSDN5tHHv4pc8wV$tjM>a$B8Qz~$@YJJrKq`VE*uwE=4O z4Fe;U>2&?=dt{t7-&G7LquJdzMI(9tr^DRCG;FCc(&o7pt%cu7^!r3&S*DAEb~=gQHh#Pk#SX#U`e_S96#XdSo6BYQ58`_2~;F{6!yp zxnC~cg1n|Ji_IV8(TuiO^wD!G2p4{ky07!d)(U+*_EtDs{Chnb+g}Ay=Oo3L{Qus7 zB`2MkV^xk&8X>^9Wte`IYbA;|Gr>lBH+367kCcmKaK)9|^o8CFp)X(&NXiYS4xObW zdB7QH-l9)^%}qr&Jcr@trkU)&h%z*GwG^JY)R=X=ttZ_)D|a#7nMwTX7A%V+VQ)pW zSOYnAJR5E$@1eIllt}7O34G)=;d>CWXrA^Wh#EAQuA@gt*F<@IVskvry0OPeJy#m+ zK01go`HqJnPM`2ZH z8Gw~^s_2x0ap-x)Dj2bJxY*axsv(I#?Au9e7C8xzco)qo<@5B1Q!5$zYADVdV!+Jg zC!mmb``|!f7R~ayNurbHU@!g-b=R-b@%vZam9+8}U4_@683T5MUE>(4I%y@*-SHV- znTOJ&X6Zt@5e5B*L2OKL1CiAoi8GlyJGCH5aF{t3KL2nLbLm3k{~-256}@WdL3(p+ z@sX8d*imUE)MdCB7Cbej!6lT$SAB*VNf|U?%6`%1h&ITySw=JEw2_T=Hw?Qmfw`}1 zAh+*pU^Iy9>cy{wDG57Z&Bt^)IJ||lSx>@pm+V<|p92|Uq=}dL$uaF(ZFD#}7+eBP z>9ZrJ$PNRp;cq!i7j;`ZX>uQ0Zfqpgew>63EE$B)=)16`B7cz=&xlR zK7`>KowQE5kvutIgQiF663vhc#PD}C9Qf-@5C5_z;dzQ!EA29UoA^yw*|`Av>t2%Z zrc2~gu`YHW6w2P>TBo0PhvCN{u&<#{QGe7RtonX5gPI2NZj}KZmS)V7I{pgY&wL>4 zpdDS$Ggj`c84&Y(Aziduk_7wq!ojCU=wQCBw*SLIV0T}M^$`8I3M`){UopSr8ai8; z0&D!P(IL-15?^gSOtv|&3o0e$r3&g8w`#CaXdBv-91cG7yy+sXbmDZe54Kf_sHVv% zA#wT&l>J(T#Oz5RN@~%Nh9#(FgDyE(kPjw3FX_{{O{AV@%xeu?Sl}Hs;VQ@8`t0>| z@~b`M`oMm;S54@R+EhU+dl9t!8BEPKz9I@I;z6N!Abpf{U)1qE0h+)4M_YOJKYoKL zFSB)KieL7iefn8Y){{*ie90yXz79IHMcah5%x;Ipy^odv47 zd>*DI-Juo%ABe*M8=Tv(!xZX{A+@4pxO{jP&Dk77UcQ&Y!IyJr|F?s}S*3+=ulpq# zTl;`)Y1Y9f-YjET*>Qs1Z8dl|dJ1h_!}~V|jKM#w?b&&~OQe3b9)26nb1~fC^#HGc zfpQP zg=x<>!JyLPVm|z!+yJkQ5|~RF;@ie5*iKfJom*muzJFZ-U($T&;+~6~Q}sdLLlFh1 z?~c-8(l~@?Y41WbGVI+12{Av2LFXJ&*r1IagO{==RV&c>f+~=FDam%3Hbo(U3Fi=aSNo*tN9MuzNv z2MfXi=$ObQqJg<;c)9UB=19wt{UIqlSjL12HVwp(YprAk&mYbHD`@jOZ0@+-VohWJ zqihHm8%H~McWBad3B0VA@?9P|bf9_>xT(w2k&Z`+pf(6+nZ!|-q8O*5ZPKv)hLae3 zPqi50QyKHwFXvn2DepcycG!(w{9uf10{6r96}%@it%b9d~OLiK**^xjq}|64U)c z?>hpw&E?s2zXtO5g$BO0*@KxbOcbh|$AZrecd_O?VdQ^MQhAT6`*@JS6DHv)#|_wl zG$j;87lXsTadf30BdxCOP#bxGUigwF8f)_jy3$sP_2(78y5Q?RYc@Z#f!rIh12j|i zQCZZ&_crXXi!EX7#!*4*G^yoV_V;;b(XhD_oeZKS z@c{qbRN`+Ul5ZG{r?2r~Czk|@O8CBj>+wY_ZALT-dGrt}*Zia<8+oS5-3m>%)+PVn zDY$H#0Jj#*r0lvQshp^QV?8fZ>$XoqnaM(s@_9pE8C)hWCg|XQOF~&+W{uM&?o~@G z(`Fen>&f#U#+aNP$F?E~^gPK23c?)39QgONG?2FOr?zYUiL90n=3B`{^jWkT8d<*( zI%M98^@?MgD)3K*Ar*h$T|?Ker@)~@Wz^8TndAiM<9EC}r84hYxz2GlyrN_zyLW3V zI<{>UWUiV+ne0BkK`Vh9ZT_RXcWDa`4&Olm&mzd7O|7IrF&fgpNK>z7UBcric#5$? z#p6|Ns3kie?rf{4MjYQ(b3ID(ksFihR}=$4G8l5dNn-jdkpd5M(_8*_aL|5d(S8VQwU}AJC)rZ;gpTbw9{mkD{-k zQAiw|1Fp)S>FvTMB4ekCyMKGIm-(NalzPsh1b+dHwEazEloURsnx7`MNsOqyfvEfK= zX*hJQvZeuBl1ZGxAiUn~g4m}~?bwd|^Vf=Tc-P=T_{V)$w&tQM*|}C7Th4N2tDEdl zb;@~I-*=bp4*fv1_x{9APkLEW#4n-l=S2MGupV3X`53ySp8zL#cc`gt6!HHofxmn^ zMRiLK2=NCOLU_d+@@rWwIpn2{vu}hl61PWCSfmCYR=LtA&_eFS=;8?lPR#5>5&1f9 zHPp=Wqj$U?lEm@cFS>wHwVra3-jqIwT6~HQS#N?|=52vyM+sUxke48y7>&oj31Kcu zuY~Gto1myHhwe&lB}&e^SUC#L zJ<8xl5B8tQDPjIZ0px4l#Ja@C1N-5fQ9ONr$B!I7BaLTWzEA7UJ`*;M4}@nwmFTZ0 zW#s#tT+pi;OCt@9MavY`ah!rbvo98*-Xtl!V4oS&$>7|N=dbl2d9XtVISyZng!p}X z=!Id;M0WXM*qoL^gC7nfn~zK2J0?}MuTTypjtKWX#yWKb zNWN4+obYq0#(?F7G`ZpG$CH(Mu;0 zZ}$PX$>JfkwX#4x>fvzpzRHG~IT6l)YcA(|Lvd$PDI z9;9}uBDNXC_jg8Ep`L$7Am{XHy2+)A+#Wg$i{2o%auahrY$=2LwmqN@l^c-l=@wt*w%}FI?cXEKU;VDaO&Gib<%?UJk2rAM)Z=3q@|m z>eyzgJ1hIM3@ws)1jnBIp&#Bg5=rxkNIu($L%>(7deq5i3(Vqlu(O< zpM?WaJn#I4djX;@lYOU0j!N_{w-oW;?xKXiM{fJJAAd?&X|qUmCo5 z62vvneo+9G$D>P&>5CyF(CGII`POhVxo&-ctlw9G>&^|Wu(vBk1qQLTMu9k1BQ^iU~qgdRvEy!W<22l51L>sEJh>@Zs9(CX@RnyiH{-8T3H7SZ1 zkK>qpEeigEEcHp!C6)^bw)R%22;AI)4!h?=_?bpA2hQX@2?498vWaHu!oqWjP`j4* zdrQR=y*+&pFL9d=Fi92Wn*@ScxiSqwbwtWL5j-a;(M?b*>Pb(4Bci)vOujQ%6<^um z!o2)+MTfs?;Z4IQvk~96pooIwuzGDi9rihgXEvZSScBYcv zLy=H#XGC9oGA8f(`eD_kSgIV~C}{ScxNBEI=*K>FTRKl zdlSj;6oL51b5ADfXcyXs1cQIFCEcgTZ!7+ZfInH$+&%9^0Y)uQIdCm)uarRTt7Y&$ zTg>=Tiahq$#xG50G2P{wXr7%q{x^Ow`^LT1tz7e|(6y!O2PBgq&%rqS=@shv++IK* zz9Kh;E#mCS8dDiu@CexY27!!LRK%8h9a&tB1zHw(9zHLJI&$UjzjGVJG1d^@=nvKwLDwx)FJmdb(9-vEa z)0q)O^m9os_^!*NGJlMb1IP0r5BtcNU$I1hQ8-{hDEqtdg&-Ta2|lEqrnt0~U=99$ zSB}J3o&QM*Z-~%f$Mhzl-#0daq|6dplYfoakL-mh8}86L-A>2YE*Xq6F4EimyHUft zXt3csym@~HJtn_ zfb}PckYA7#jtd;e(vvt>JYtGVf;`#eCx3;%iILDXC!S^xXeO6L$6#4U2Aw`qos1tK ziT}mkr-l>wQ+-_^)b1KiSA0K8CcE{3UqdWi7Q5al?vE7kR}%5&S1rG}WOaG6?~6^) zevkdoarYRV!uR;36TPrsofDf=XG=0FZ1AUGW#$*M28lAmAm;5zYIr%0RL1>-z6upgp>wyw{keHSmnky?w<($@3zAz zbbyw|wUF%lj!fl~4cSqnfz2KcWmBGLqqVY2;M3BHv`spf7zFU%p~v^=2af=! zys?rvc0nTDQJ#ph@(1IBcrR9;6DacJ{CQQ|61L+=G_srZ5FE$_co%Gg%I2GpoyRT^;8@*yYd+l)2EY}hneXwU%a|WXOOMM`9H5TKx>EU!3c{YS@PL?2J zeB|(XlVaMtY&iOl=kgHyLWTw%ATLrY@ER+nip;g8$YN0nxW|;!G@WKLvU3ccR5XQs zT2)dme`6Sy8#9V+2;YdFzt{#lK8Mn<=0oKD5=q?MSVM2*>Igl@?;wM`7_omtCM^mE z-Wkk&bh-o|D#uoF3KchVJ|Z>6d^r8%4Mko}WNQKM4gSrs)LmULTN@8g_%1_!dn~C) z<6T~#s%T(oig3z35MIft(vF>V5E5g_CpPKhZ_1LeG$enB%sCH@iQ0hk)W-(B?6th@r<`@@{n`R27+0 z$$Q46p5Hi{RZ{7v^B;v**(aefv4eik;r==mRjmKQjV<(Ua?0F#7GB}2^k8EYQTiPO z)zpeM@!it<{6;U+fvJ~mhp5K14R|t{hWwC3#V@3=$xmQgZk!@6jU#b=r#D+aUL9T8 zYKdiw?U`GW)Xfy0Z9lB3zjT&SD@9titsKUyfry!T} zfiPs6DrMToNN0K6V&RQgzK5Fg6APX-dqZ(f#5X0X$VzUa!MGjQT}F`XrPL6+zF z;Lt-Z?DbaaXywvwY-SnqLreJbR1dB?CvK`m! zNy7zGDBUnaeD7OQV}YY099fh6RT3eL#>b6RSwLTxuz2fIxL;yNyRC1Lrh48*&u{C~ z)eecwMgRCabrS7=WR5P3>4LvicH#}MKH(Og?k!Vs@o^%uPu~ve@3U#}))r!S$O8Mh zI{w+KhlLYe zpANDvCKWyxE~ADUUC5)MvUsuCHM;5Sdm-SYKcoizAkLXr$d&Su_^HiurhdH2>31F9 zHkxb57UwsR@p0pD>nI1#Ph`-Ua37Fe>_VN!w~+Y_`#^g3YU+AIiVRyQi_P|5qtiOA5p2$>&v~jf)asQ*jN2?|du4LKWYiHIX&ztweS?1>pVp z8ZBLMffV=nWB18EET(X)5dC)w(mp(zWI!r8yEGCi^v2O+&y2~d=_lb+a;I2lZfG#Y zy8A+ycb}9XZF(LKrO`}Z zQ;0f~!$DiisKpOE;p?Zb$e8Ed|KCj-VtyV9T^>=BBOk~+&2iY|tUU{IvJmq9M&P7u zMRp=E7Kt1a;EY~?m^05)R=`jHlv53@T;cT_f3VE^K~}tfNMx%u@$4nb*+1Le0-LA? z<(ghpskVjOdu56r%=cl+MK{R#HY4nG+=l)7&lJ7883hqT{zuYv_*4D;e<7JsX30#* zELj=%ea^94R1__wGD||VWfU1Hib@ialBg(>d(OF%mVC4`8b)aEMfsiY{rv;?fo{+9 zdOcsy5y$ehdvJLAKlmWzKav_N;Lm5d`cuRzNlJww$Whz^qZMR`;>mP8k?qtaA42Ft z)rZ_e+0C#_shkvi8N^jjnJ!}MLh5kB4e!~dfUY@d2(dR~Y$E)9Gma>|pjdm0D6)C- zhz!5~?bxI(hPZ7t~=Fdgp z6FFBQzp*%KGSa%bn3nIU#oJG_jC~2F;jf<#Zhp;$zBh}>B-)3Io-Rb%J?^w+j02OI z%|^4T)o6ou40ux(52wvEA;BWqIQtO$&b&NALZ5qZc|SKm#|JgUxMvVgWxvav&rbB` za(mp%Zj`fF=g##DKEUKuB|LwQfX>D+GwlZF-w`HfR! zDQx(BpX_<=f^!sf(Ox}u+HE&~f&d>E}rs#Z`BPE>{IJZ&<37RL< zRc?kL`|?^?#5t0j&1G2hxhM(-wPb0(BX7J1%bz)YfGqyE50w1(51O|F`uEcUzWF1@ zKU;)Ri(iT0Lt`7u#2Y1>?YnVbjR{iWJJ5RRD(;=bR?wUgi9LUQ#KnRvST#GGgnV?t zDqkc}%Olf6VQLgT69J5CXgDP%yJcW5bkLS z&MX*(b%*YgcYT`N#F7@!$nC@1#tq@tfZb3*Fo87t>R>1-k4iWD(#mtD;AKY{MEpL| zkiojtncj85*hO?tt}3UPn-2Srrw|SMG+Z9aZhztT$&aM{+{ltZxKwruv1eX;(My@I zphSxtEPBWfUYZ8Gp0$zn7A#j;%@B1&t)m^stofgrw=PF=5w*R!7gRe{!|0PNqSCJh zkN@cc?y643pYHC*fx`*#dx-^!tC^0aHDu7k`U0Xgniwk{68wR(lpeT6-n)(a@-Gp#xEsn^Xw;4EX z));i{^F{Lgra3oi`~jSwz6YPz8N_eCj714o=FkueCwxrf9JG1xfNX2-#n+_SXNo(} zyWXbUx8JJBX8Q!HHa!KL6HkLBO@X8~dNPNlgBO~$;|Z$r zXuZ@jy87KF?!{sim{#CP1kQuFTHF}%O}y#PiP!L;j51POsz=8*r~iGztbkruXwgS&Y{9kA6sWGYo6J{h!Svl2bgKR-QI!AfxayNA z8XdVpo>(PCxgq7}m4h^m9IO(u(6bzFjPl`t+>;{^%Z_Kd5@41^vhHOcrj4LEDsX=wY3 zBd&t!{Irts=ufpDJu{{j1euAV7pj(2ceo3iRvRIELvM=fhdC9NY4(z3cQ@<2#?icT z_(-ON812)>vFzsCq%nz(@o)ktG7xU8)g+B?3$fnzaj2{Q7+JX^iC0fVp~EjX;@Lci zZJ)@ZS~n;9`PwO*&GKYMu{RAJoepNS<-+8yQXy8ymb#%b1(umCJ_}c#wne7xlW9Om zG#ERVY32*3k=E;bag_FNDA}{0oSbRPZ7ACSWp-W`Vs+2P@u+T>3tjZt4$I9_Ko`!< zqWT?{;Kbc(*!#SR?Dg-#ju~rE&Gc2&*7Uxkg0nSR^Pd{^usH)Jvt2lm`7Yao!g0Xp z2wbXpkQ4+La4PMMFiL*{zs zP@6GkjQ~|ONeCp<_W?WRby7($AXhIA;Qc#{kR!atlXY)#&SyA7@Lu9T@Ic=W7aj`B|_%UtifxIV!v7RUh5M2m! zjOUWOS_AmNxI8Eab`X`qvAA=QJbGJnn=Du`1zeoF3jSLyLMCm_$2TNeVPDG>8mraB z9T}eqcjPt+=Vx!`--+e3j->0j(M2GSbey&5rX7*M!6p^TgeH?qrRDgK$taxr`4Jh{ zsL4GV*80^{h)mLq7UsVRhH3o=hULQVGZ-j2wd()CORjzh?I-F^; zm&83v#ar3UZfWdeGU3sFZlEL(-cQgXXDr!Xa5NoiLmfg6wetmrX)xw`yAYqF(TwZemicLl1H3i8GZR>6E`nP z1rFwUk%06;{7csuO?LF52VAe=Z%l{$@|y$Ys!hS%uq4>MeHZbr>&J0F$DpVW&xm~U z4St2>KPZ=TiCkT41eS(vftO_!NaavER@Q8VSDsCwe9cVm($iS@Jn}5@*Bruoc{=FS zkUPD0)&V=}vJU0*S`^mWfMbzquqr==r0TcgF^@&jk)TfE)b+>FX1o}>=3Xz{2s` z&$*Vv|K*%VK8VGow`U`*W_4;|sR}H{u7*dNwFtS_faR(N;p^3VNRD3w|EQ)YvJA7N zV?K1@X!e#VsrpcP=MheBI{Th8fA0UdXfeY}@QVITDW9YnB=Eksi^5=qIYeZ}5Ox_q1?62_Mh7~s;8pI-x4RwDJ=Z4z zjm}&cFMXOEV|fAvQ2-4!JJRS&CipY+U$m#POfc6?U}s-6^NE-Xv+QOuP4CW>0%HEs zi5nBQ0Y)0tktd^r_<4>r(zQg?K-n4>`p6^qDog76Z5HSYs%F_f&7^;P4<^JFmHcy} zPu^X2)X1+Uu!P#=q!}h7)zwAiwQ`T2*`5XS8pF@u59_1b%ZG@p4*mpR*6A$=K zLlSktGzcH!?oTy>Wm}dAvHDG(5mJlfsJvAbc4Ie)PhFZU59c3uQ!NB)wz-f+UCnsm zr0?*3K{a`P>ln+p7DLZRj*&QTOVE1Y2fP!(quvHxc)(tOu1t~?MCP%%+G`u@$1Eh_ ze+F;{yW#3@=O~>u19vOhqTUoM`f-p0OD_b&@0(qS!PIi>WHSoQ2dzUemD;>0yilP&@+5aix&7Uozj;7iA(c;+~z}JC$&@xn%y0>-VjjVUZBAlb^tSdSB zyK$gqc?`bJGFhf_2jMpNE#$-axp+l8+nqx(c{Tq9my@sxTBeAR!HgRGqIEn{$yq^5 zE9-ckM%~zB52Q+bl$t(|<&os2xU*q4en9nPe^{Qx-#)KAm zr0T0fU+^Qr;huC@@HvfCEUv`YlUAYyw;iZee;QZe+5#r#@5iW@aUH6=VQ+yNvDeqZ zr&G${&Xq%??_?j&KBtS8E6k^xS`|3w8yQgN{yuWMcpnbb6hYdnJBYb?Huns!h7M9w z3Hyh|FO)Ok{M-6O>dgbb>_{pcI`lw@)fc|%p&3TOwE6ffelzoZ7cF2vr&%hPr_czs zravU_+9+N!*%hTObE32T{kccyT|mWFL*ZPlZ=DDmPur8gy~fypW!=nubc|S5_i=G^ zir}$BKS|m5UTiam>A^~Z>3yGnJSHcAyt>CE#W)8)VV+P|Q$&-=eQu6rAe{G+BTk9~ z_}{66aA4_TBG>SdKYz|Jj7ZBR9~a7kOKGEU$j^n&xLky_jRoktoTT8RT_bpZR1ZD8 zY)f?`zcm>CVmVH)C(`~|5ZpP!ykMt1gt*N$i6Cpnx9F`i=gQ?jfWucZm>YZ$HwB2G zhB>bEO}0J0TYnK44`+EZo^TKk zix{I67eCq^dku?hHbQ&90UFq43e+8v;Eu{fA#Pihv#eLv^`@zClYc|?AH2;toU&s^ z;7&_4{I`4}f!(QC(ytYU^0nyIyi9J)vRJ6$Tq(ru`-~e=xAdc*oZPWwkvzIm#q#`@ z*?{VT40up8gG9`@kH>ZRAjwU(bdB?T-i{;m1=pr5rtY1o$eFm}e%hNC@^fd815{sKY z*r3&{$IA1SGU$q14c$wok(j`1n78yD{9>0y=DBX7NDeFR6y^`)(3zn;z^x-4*%!xl*xxmmRyRt74m!da`{y#u zO^xx!s>g_yp*b+l{s9lK1Hu{G--PLV?Stuiy&*2__f{CGQACtkhAp|FgAV+$p~f}_ z*yuac{Oj1zpg|ruBNhrz{qrFDv(I3c=6~=h^HY2@o6U>y7DYGj94B`dXMmiY|KRV# zu2en2lkdZ3?7)eeXzGR}@bAz)_~MQjU39q%&ttQYg9f58J1aTmLvdhydz=urM-p>k zOJf2lUA_Q+Vz>TW4*{`V_MF?_#JqJK>=x5mgRK-)&^gAjKyLxBD4OB+WHTXdFJia3 zNEJkHuM-8U>%8FSH%!aQIO+=jeE3WynVb+A$1z1E?AUJj5V{cLgs2HnXFH$S9ar#d(vUYdqbjfzMY?aHx=6MdL+c^4_;Ep zD-Th_T4nxi_P3q!!;gOVO9k&|x}uMPu5?p{Ki8Y;0z@2*h4`GeI}t8?%8@z=6D*;v zjFxBCkPi`Kz+9OkIOoQ1VNTsRxv9uoKA66=80I;)xS(l2U1(PK1I}Y80EYiU!dd$I z$y~T@$1+l^{grRUy2S;C`DE;RS>QA8A8d|vrIYoGux+XUi9ePS1hhATHy%?__r=+C z=*pJ{rxqnN|E&`B)`Flfd_AoCZ$4=W$ilLPe_?0HRr2_$3D+I<9!T={3wi0C4@J-l zc@OHt@SA%|xNn0%RVJhBo!e#Oz@z)?3>OB_eg`;r2|+ER={hK2mnU7Wd5rU$$b*rd%Y?J> zs@di6G(1b}7H`JWFK8oO1vy$FEe6^xf?#{}bYeWE5x+Hl3t#tSlfBlF{D8A#(BZ(@ zbkjf=){>fx7HxE;iG#h|2fPb9{yHe+F$Ble(eXM-dTWM0cwDm@-sYy0I*lUi$o3lU zZ80famB17A6NMgo=abWam|jJi^;=1Y)4h!p?{S=je)YJ}#tDzZ8zXs=DQlfp`9ayYf2OTU5rkk%H zs2TMrzhIHbVU>&sAIhfWByymw3w-w^gCkbW#AjJ!; zA8@f9-82K$+{?mE*1K_xeEI1XqfY!mVoTTdN^b$60U z-?oJ~pNOH{ZOugKZa1gMyl>P?n#@{Qi!beyK%Aa8ZHPP1i)L6_ZaITGSajoi7mUz^ zOU|?>lVNF^7p#1^Scs+FL;29>4$B%nG!9QP5<$-<6JjJK3-a~-;dD1?a@zd}-aMlf zR$kYk>*TLBdsp71dAkVKHY-(8z=oopm zy@PYDJi&75hgs%BFAm$RgA)9Lg}E6C*A&poTl&;O5cBl4>;*uD$9#koU+Da>%zb z#-g5_MfCV-Cp?f_0hb)?CbyWM{TF*X+@Cqq-OVPP*$x$Sty_&oEl37dkJ6yKNHpm@ znurq_R}iwAPo!oX=4wm)VRf!F>w12Gcc?2Nnbc7FC3`z3;-v!f{Ff2~wj(Pk8K6?S zl%4bI@LHDZc)gVMMY@}T!C6Ugi)#uw|FIvBEfPoZw{H+@XaV+Y+Y0-v)ybNx8CW#8 z6&fn)()S`+T#arlEGw)cQ|AofkvHSf`)WNJTx|_PtPjJdhgb&PotOA^@Dd~~;z%!x zEa1tjiz8F98)Qal61eM>1b-wdzJlcNi2I&qlQWTZ6J zjV_4GWGsd9=&Y2dw z72${M{iUIm#9~!HE^1`nG#4I~wbjQWS=Oj+^Hf^u7X>c4X9AM6`@U0^PDyeuA8~@u_UGg_PKc3He ziVOJ%S$D&^t0&0rViU03lj$q^0KGB$89w@-7Mi{~m`)q$3{BErd zYFOYvd-M(P(!EoWeS{$$es2Vn$F7I1_TJ=o&^fGqc^En}jEbCT!+SbL4BdEpN{FRL zMVNmiXg-a7zlg8?#0Zu8#!>ISA5znvU#|hvpwPumGk9DUwtjkKO=#L*Dj%19p`zNY1ke~ zTF^|}Zp>%;IwN~G`tPbJ=nVIQ7t5EB3upl6#2kes^Y;-yIVoK4A%e>OYa+9eEcle> z4@0u#i08>8c!6ju{9`edT2H&q%`D7-zYgCag8yFQef-HtY|pjtzSc zK=M1vC%5TTP2w=8uR|9RC57Fq{c zzMF9GE-Ir=)5+AbJ_&qjPlw0XZY2YUlJRKf2>i<@#4h9zSEdpGlLq8SX~6^Rcb4g4 z$1k$) zz!08NGZ`t?&7~<{tnls!?7jAxPKym~!Sb4X__w=|cy#w+BU=a5oH>EUH8p_zlPm}O zhCYF9tML<-Dg8PujUK5;009TC!)=@8X?(8u&*PRJ8=b`<^pM&*MfsVbOai{V1PAlt=LuBF3P_;*Jza zb~DY-F1Uof`*8=EJ_lMOwH`;>Rem1#9-M?k7Rpe2qzBBm2Ej4B8N~m25l%6eLWg>* z$;<62JbOD)=(lMh@m)KF6~Bw4|BfK~H0(Ie(ifl@cM-wCl>*@6kPGivRFRaweb^_> z230n3^sDC-_4x!|*A)T`meY z0kJGw_)nMm(R=jyC)hW zji9YmStA+Tjc zA=TKs|=hP3iHd@?c7-OZDa|(+E&TSVRP(?g_bnFx*OmB&j{V>@t~6i zMZxqbUNB{&pYZO6uOEYVn=;9s#nSj`oCr#8WBY!FEYOq*fCrT)5N(B{c!xzRY!aPD zGmc#6wDxB}jjOFhU2FjVH)}H5a$_!ynRdQWDPA6(&Yn)y%{BrJ{o}A`W+_Qu*Mu!M z2Ov-Pd9=bHgZnJf0`vt(agFg1Ua>KOdAsz5Gwr#QQ!vfxi%_ff{O=?*W7k|7RVBsE za4dvYKBq`!U;!>#7l3r^=FxuENo{Pu2HxL3lUPT+z`;!8aiPnR7@q0kKMYERh08lh z!KMK$zFZo`C(NO>>s0w;Sl{2icdqp3lqewP_yq0>`bR2Ly0P8N@92=Kh~W1XY4FD9 zBzW@hAf6xjmgOvELHub2X(+JA-r6H@vP%gGFzMucwNJoD??#2#>l~+v3O@$Z2I=p- znn4BR<7`Yv@4UeJr`UWOJx{1BzV`VL+|PO(a>#dnU%V_z`%p_BT5AB6{(tc5?|IbO z>?FQ?PJsO4#tTZ%@PV_5F1lI4(Yr058}@2UKpzWLDc9`)pkyrkB;rpNx#i&fKS$t# z`s*a9(S$p6_dWRi_Xr+jS;XHSOhgXTBIu{;rPx=g0{&9$A@O~^cyW&rivQ_BM@>vQ zvnECKbM<7ZJ2eq#*JQ$%KN1MHbr06*9f9Fzt`onSL!4Z20GzyV0_l@@h|}j!K+k7~ zQ;Dj0?$Z<%SOr&-j#ESUrl~TzR^m#xPdkOZbBxeJkGXVgr5SMSPK3%L`^eK*{aCSX z2?~sJq0{>Hu*oVLRIylrUhLTnZl|$byUT$5cVj;Wb6eqJs83aWvbgwy7$~u-hD^*E z!jdA&Xic&!wTv>yD=x^R1IvwRnW-&MjLL_u&x^=c=8+7$>Cd`R=F`uyOL-3-J0Rm` zC3-CJ8pytt2$zeQkmWztU@fL47PRc65f2i;FR$w``;meWhr?Lz<%0@Wy8hjM?m>Vf z%o`3A>e&qDoP&m+Ysspw+wqpq+GsbYL`5^jK)3lCX!CIv8Ct-{rgop!G;_B@JWvpL8@Ttn)^a6MBd4nNQQHu$E`{o!}6`r z;!g(DWyKkAhraB027nv(M;cJoRnpNo*tM<)f>dYo9~-pNYEM*zVrcJ`F9u^6t<8B z7mD}|Vk0oMt&HreGy!*NKEnC6h<5FKf?qwEf(&Fs=ouzd>2Tf(Q|6y0o4f|`gK}N; z@Cu^K?-^pzt(s`V7XzB~bsG3KH4ctst|6&XHCXD5C<+m6BYjakp4=2MRFz#x>bGP9 zEXi{GxW#n2wGZFHW-6-N5=BphZ3nW-tuReZidw66;ayC#>YX-^9$R&uD-MVQ=}JlX z%h?auErZQt89C%#z$$!>_2Y!m6@3&}2e!ic2l})}u9-{Sl>y_r+ennv0CwnBLL0}qQ5CQ9#^3^ zD$m~t&h9COQjX_HmCJ2xydnTKZ}+6StcS7Qt_7UBe;lvOAHr9dmUz;BBa-E;gHO7h zg7JI52|ar6MwC$7OgCD;ax51SR|3r(D#^@?C-G^^0A%OuNrUG6<<1M%z%@2j#6;sI z-m&N)w61|fFQAL>;*koE1$PszBLlc~NE*#dnNNRMs_`S5%-mBb%_`L3-5&F1f z9yRJV1JZ92;k|47$THSJ@QmSx%$aa$#HJaeZ zv;Jd;#%LX}}OsAf*EWeB21fShipnn+;3AI=jvA-Lg zF+Q6!_jZJLOIHgq`9;QAD8jEHAu(IAnfg>D`$UDt`HlrA#;%3o5mux~3gg2kzQS^N zlKJlA`4O=qXs;ZPX4ZG&pspqq{XtZ)CHw#gD&Ga$#~vZ~Z@Ba};z;sU({srk1RU$7HFuQybZM|vl?lCG=JdBG&AE!}~|PpYHH`Vg8U zn#H;KO@~3UYe|w|5bIboj=~Pnjp?UwTZTExJ?lW7X3Bu8Uv|LDhc}SKUC*!^9f7@l zcgVQ8C;2n;nE$T*EQv8O1@_?|;Kid(^j_&>thY=ZMSF(Oid8STu8uA6{LgaIJZq47 zX|>VL8bni`>EqiQ_0i&&7F06E46G{M0oCSjASo=DzIX@gAKZJN6nOJ^3&)H@5=SnR z6HNy|VUH-9*|dbd8Ct@6+x1XqU@Xm=yc6uIy9-}ONz?Z~I&mr6PycFp(&ByRx%1QF zK=i$2Ar2p4nJ51GnMCv8Li|8%Hfm-;qz3v^z>m5Bc;=TX`T6xSc0VA2zP7HQmGM

f40!B&JF#3ofTL86(c@s2$5lZa4Hhe- zlyO!xWA|1tslFV}VVQ5HX7{nAbqk2RRD=&-8^VC~$V?q)Ce${x{w{@CmwpH{li%yf zqR0%Umzz1v8|f~GAGg&qedB37q0$L?KCz+e9J@K_u@=t#VN0godWkJxAB6L(T*(Fh zZho^>DjeMPf^5D!fXhTg(Ed=4PK%V~zhN4TjatFhwbU9_6F|6Gk?}uvq+d<@kNjWN7ig0dlSF# zciozR?9H0VE5E6r(nAc*iC9V(B$i?2%K{X9Xo5g$CI-)r#JUWASO2XV;l3CPnnlBV2P!h8g0 z;jdq>g}lVmPwZac;7Q~1O}U2HiAXhAgXY`q2Jgc%VAH!K@+m$A%O{UQDXn|NJwA_f z=?{P>RMd!6<3p^1wG_BhPJMN>4o8RBS|CELeZ{)>fELrqfQA$Jq2c8alLG z5zfQDzow%HEYGw1s5@S9o^kb8?P$dmXYkJ^A5NWdikxWf!@qM@BM}f@NCj#~-9h!n4RG#%PNePi zKJ3l%54C)%$g({ST+?s_=vJbjId036&yPGgxFv0!F_K`(a~f_ zI!@`NXry`q)jp90c!$#9{NI7(h1)h9^?np?A=TvSU?Iy0x(bb#PNoyiJi}^C z%j$B}m->E9GxFVB!-%FmeKc7zI<7x<(TH>ORYbw1kb|m!aomXsQc?q{F-4%QS(AtDLBu4 z8`=!M?A;^8;m*yu%pa6VWL!M4gFztNvrC;chF-zXR*gr}AH(UZp?couZ{tv%h#fUJ z+l><#_9on2NY@650W&=>*wVI|xZh)4W8*5}u*NAOCOH{D>##wGM^vcQ0T1wo^``djF0zEUTRByKs<$WOm`x(m-k@o$af5;=!; zN1YH)(w-{a>gG~4*TFA;9Efw%E36Tk1HTo_C4;Wd`Ptw0!Y%V(k=qvs@bGjIH0vUy z_>L_9*heFDyfc*U4NL+TOE-`;?W$nEvKabl=SO$% zD8t5P^5}PvFMV`F7X0_z2tB3?>Eg`MhF_l)(45a2)ZfSvh#pRc#xgs|`{on)C+l{E zSr5o;w;7xzc@OSbl;Wu!gIIFscyvWKf{NHK!iM(p=vbUD)jVziE^aytug(}EQ#*RG z>31VEw|gPAx@*db+>l2J6;tTjZ#%%=ZJF?+=w6bNzX!)EkFt)uc4D_Ek6WD-2#v5h zF^hhL-TmcI-OX_Nd~_4HElwHwMg<8u;qY-RQ+jC_J==c`r>0Iuy$&4ROEkgwxJ1~p zalg>Japw0zBpNh_ZYa~i+k0%$pWI2bAZ80#_a_c!=bDm$=5*||ycPQU7}K!7S=>R< z7`TJflOqg&EVsy@T}uF!YtzHZNDU3KY@9VMPT;LaKFrEEO=8vhv4`j{bjt1{wFvmg zGni|K7W7W0$}6vemwmh8Wl3vN&>Do>84gQH?WfNpcZ2(l0{Cx{5_L}Pz(->QsK-D; zz+*ebiK&hdE(;^GvY01j+(pApn5w;6iyTT#_1cJ z?NdRby|(bP?Eb7g$4O?P=)j$e%B=W+0$H1TfKQcl44Zct-f^Ow7 zEt&Zde0zZa{oWuU*b~(R>fe8~`&x+{iW%<-TjpUkibW1aHap9%Tl zp&Q1Ge|DrP+zH3tN2ha=rSP=zxr$l^P5A3^YG_)MksWnH%-Xd|OV9_%=Vw~pS0eXK`yM_M!2{W~2BZZgjWyX$EN8K4Kp zSuVkc#>UoFnyBQFGo7HF0<522f{v9ph|K1fxY(!#C^3Jb1lzMb`x2lA--_%zp@StO zN@1(!urPn#i+zq-VK9~VSK+oA)WCb9T^<1>X$;dHVR0V*C);#ABP`C z#i&eI51vq_hK^1RrRMJMc}K=gKtF*c?fJldN2W6`iE*HPLsz)dzx<)RlpnEl9>Cp) z^I+YY9mGKYH$S9x96G)olLx+Pz>xXBrs^)IZ_?S{#kQ64BvWXC^lfgJvM#cZW}2UK zUmD_+6wq}eEm~vi01A$z!pc=l8qQjrVsQUUS?rMxObaz@KGRScXr1rn`@FaHgEwz|M>!N3a3SK^ZY+f$J zG|EeU3zTZQ&n{9fl_*0KGKu1dkL5km4x`!939eV7bIDxMo`+QTqNG zL&gP(wL8$JjivYq^I3$=R;4~W48ZMc!BC7OFH6S2rK-z? zyoAebQIz@2gLXe>-A_IOH0Sp?L3(Wy`2HjZt`WaV3Xig0zf>b+{EbKZ=1pcf+e`zQ ztVm6)-GJZeNEml#F8SJ)j)#7VpdZ=wWK9dl-7JlO1wUHI5yLlFyloVQt#zThMU1eP zLk*f}GeUor_JQTGRZy#`i`4w+!SC63`{h`UewknB*tk{|^?y;Kauu0iAT14!dmBn5 z4{XDuz0A+(eT_u&i@DL{de*@)MTpPAH^!q9-xX{hN#x4!8p1g12$KC|5MLTLLZ@|D zhX{88$FcnX>3?`Mu5cWCbN9eOjbyUx7|V@(Aj0B!JISdVrTmYAzwr0|%Vh0bGk{*c zhF?{jXuse;T=MlU{G_i*l|STgN(`TOwwx!sM%dfRKEITG{yj?zYIHVL(G+W z%{$56`x^^R)~5-zXJ*Ccp-x)`$+n5X7Q1cHt^O%=^Y|%XTzepNjnySmW_9>ds|*Tt zj-at>S9l(JlE^lRM{&Y)9KiZ{?@KTpQH2;7sPu$w86o81HKxz$zX0>ZtBA@;O+5Ym z5)^&in)dt-2Wnpf;jK(vvi0#XJi)jXcC9p}5B@fDA3mnT%|D-z?+F9gu4Wp_eicmn zxND8wM~zVX=_T}Q_I@CGr3S*~w~6`nS6H8OMc&d*bSOWbTl)G2*gN$MZhJX|%iVXw zX=Ck(v5hXylPiTw%>R-XPkXWZ^l3<&@d-MaN}P;D1H2gCPX1o1$Hr@&k+?0S&kCM% zW&Odh$HIl&e%y;APchxsD<6^)_L6_*)n1ri(oggXA9LBs9r~9||V9%&A>`vrH8@Ar!rTkD}**n(MQSlYdWtm+nG93LprH(uL z#2>cVt{} zo%PQ7u>1JcdopO6YXpt!T7aqLWpw_Ctf1+BFF44w0Xh>u5bfW+*oARQzRpYOeor&* zuet&nvr32NNbh197g=z_u?%89GZn9#D}oFxI@tV{&(%h(hOYg(Bq!%F29ssbx`Pqa zuQihUpr8yR3xb6+^ZbeWs8}V88h@?BojWHX#WRTh7^exAtxSXuK@OQY={2s+b4BuV zUFcZ-N!T~V2JLRupqj&RK;rCX*l>LoF|$m^j$zSo;jBg>Ci6tbBVQMH>Sbw&H=JM| zA7D*GlxBmP=Xp%$Q$aL``tX$bt|&*J>00YKo>Gh*dL64xbMIaSd7ZmqZJZ;~kywL! z5{=QOkpuL_$KBwXr~saSsUpPW#d> zp{9ep-L&bI+2UaK%@Amw;7%-`2=I-~-(Yg`MPmJM3t#f!Z@AMO(cP_&v6Zd>y_J;` zSpUif6{S02J?rB}6IeD#G0S$)hID^SDbC4MM>(%1(=JN`AiX{WYOHi8KPH~SOTLJs zvgHC2{%|+%SI`(})4D>)SH$Rwp@Hp;d*4}rrDiZ4;~FVJ_uVG2t}F+hk-kRKve>?m zZ-jQ|LmHkq85@34LI?Ru)KcCRq)}6S{_H->Ab0%5&tqt%0;e)PDoK4kt74Qld*`tkdQnVA_21?b^tnV^{E|Oo%fBl~} zs%zd##aCSz;G>-n>(T#79s-x@Y zTq*C=Cr%{H6DkCTlhqXiSmRR-jJ{AqqPFSaws-1C^MwSJU2F_YPOOHj7U+|G>k4p1 zc{;q)@=VAT-+A?aB%O(0&EMC>lOoM&(trv@nKGpDe$F|il**j3GB%fx5>lj6=A=|A zM5ZJnLie0~D=t@j#0;td_)Ox@w~p@nMX(N8Pz z7`PUlaJz(eXWnJ|*0<2&M^njY-WfE+b%P-H;wEa4E0pfZ*_B)I{q-Vd++#wo73E_E zQ7`+E|B9~Q@IVzlle4rnh4Yz!zmznxaUqNz?wU%}3#P)aq?dx6ZXj04b!At^zM+Yt zgZPNjV&)LpBF^WWvDxR_*%rSJdSpc}&;7Z8Z@sd3(9sdZU}+Ex%t}Cutn2XXoBd%@ zQxo05{eih<{5#@E1eF~}P{hn5(wm)R)zI@6`^60(U6^E^gXie= zgDb_YbZCt>*?uq(BpW(KQ_M6-UXwNC<+jjQN6d*6M-l#;aaDM9*%vPe@MU!?+iCLG zL)hDMJJY-QTm0|08ksZa5!-pq7)72}A~`-`uzSKqIw_EQ7e^YwnVWZnN4L!h+PV-{ z8_V4A<6ea?soe5C)fc&@?87z-_OYhCB3gXOo7hwdkfn4;s4eV4Z9zrU+p3c;O1wmF zFlEWBey!+g<7uqB{6(F{c^0m!IX_Nd`fGY z2ar$V5XkNqCVcJI!fS2^O84PXo#ABWi$JLQUP^<8>yaqlZSmmgU=%cI8_phZP*)e7U|H7}Kkz5<$ zD-Dx%SVfOS^SrR{0Z7r`hF-Y?j&IS0vo+6Xak2?{-{lY42DyUbDtjDduvW^H*dJ&` ztS4AQO@lU?|1%K7CwF%EPX(Rs@dICKzsd%8#fW{!|G=dNj__Z59UU4aA(I~{N-nS3 zkK$9d;LRuV*><~jx~`6AW8XQ#`Tvg7w2cPDd+=cBoN9(NJ%ey_fCqcOqkyJn_Td>W zU$**07wzVnMx(ltBtfV|qc$JF#`HO)WTi0n5gZ061XsioW@+>Cv@E;&nFVQN! z^H}F%3%f1zil)CGMsCF0!=cba4k8m>;yPMSy5Hv9O~%bZYguy0X1a3dKg=<6%zs?2 zU=ny0)8|9rWJNulou@?}ng+q-q#eRL?UA^8OSn`AHs}8E$F@!|?puGf=vxBTs!C!v z*0xc*Io{;dIRdvqg^G>jNtXRB=3zJmnOL;qiS-1$2j8Qq+`Aa}*ckp4r3qeRqxqZb zqI9Q?=6krdg%j*AoQQmeq+%W2G}iN@j=qWTBJ%n6p!@5vsO!8f5nWV*DVBH8{UZa2 zgGnfa6s!>6HRpG$x?nf!vWi!C=~YWZQqYG^Z9l z;XFRJ_X4X5TTlIV8?0WCYrjDf3LaEA!Oe+?CZxntrUh+;+Kz?Uy*_Pd-xt(ZA?Np`NQy+8p4gT=h#9` z2K+OcDGlNI8hux=^=uLP%@4vejXaridK+ySa}YZcUlz2jMLaG!3414XvQs=eGiZ+% zIj0l^3R=U(|Dr|^#6rL~KLO?1)M1a{0Z?hk`+|ACcujy4+}cZoNs331?8IZzTieyQ zX*mDiHn!sYR9cqWmwf1`WM8hm5z@jAW6R2Zkp82E*00hcPIm+0}UFes4nVya$ArqiOS;!oHKsS!6;xEq2awMI(m6q_H7ax-8=Ln}F4+)zR zdeE2~7o>AiBYXgHx*r0=zD=iZS}u~3PG!kE=a*=E`d7 zgHh^4xH$q`^J9_w=!1CQxC|EVw}-BmU4gefAH_5Sp3)sP3Z(L4Ff_Y|2&e97Vcp;$ z>Aq^BtwbVwo#C%(Hr1QSJyDUrzJ#I}#1e!pkc^MicNycgBo-A5#Ege*0K`eeAfd729A!k*<-I{~I{t)kK z(dV-$&JVUo4hxGT?eX63wbC8+euXwswjK?=lbY!vy%FT)95YBb-5(h$h2S@NGnksB ziVk@D1M53oW2zZj#4A>P!`Xufmmmd!I<0~ zVhhb<4%5-u2ITam!LTdb4DFGGV2o!nd(Tt!_WV_3Q;r3QhrJXvIrPEWSC_ItzC-#% zb1mYavSj%FN~G&_07v|yY)RxBdMMhM#PqR;G06kz^X7qM!CM_Tebf>Csa}Uu9xvp~ zjXj(z_y@1^Wh_S3UO4eO7>8)xW7TWB=w6;>M!b75$axIi=2Jv|4*CN%eV?P53g_{& z(XW}_s8{s+Rde#F${FNd=Q<3^(BTRp_k_FbMsMqPVdIibOwij(A3yzv_f3$n6W4Qv zsLm^R)2pGN9#cGd>0rAwsAo0i*wLT@JDOwA{Mm|D% z!Teq`Ary3eE)!Q+T99~)9Z-~$fVO(w!Cp=S!S!zgjsKuW(#}nT>glCI?n5Ku-9+!e^hKOvwvy+owvBS)fr z1$bukjOris#BPb<(rnro6)Un<%MSA37!7kZAW=*a-oG?QAEvIrc>EYvrJO@ce0O4< ztIbkP;9I0388UtvWVGazuX&|P_Dr>fD3>*8!njLV@lLH&6Br$F6D7>PAk_ixKi!Gj zjOMYNyW^h|y;oKQ@K_mV-9+uokIzJ!T2H`KRvslN8HtMUE zj?GI}vXj4C#g#jguwzj-+g8#+{T6BxjesDy|J6i%GhsM6&=d;u6cW(>+mG>?3yR?U zx{2D|F(>byIYZ73BJ63;LpHOIOJ`>4_=EVqM*_Px)|mzs$dDF|O184{rC{Q880R+h z2gI2n)|Q%N#K<6sQD_rYuF@dwDGu;#ODkPg#q(c0uk`ZKRUv4bFMd?Cin9>gsb^|7 zKGV+xvqE&y=_go0j3+00RnYB26rG%wS?4pa`Dv%k`E->(p37w*-M&@!p+w_mtXw0Sz zJp9)Mc1Pw7U1wxPc4rL-{gzUcdu<1vV>X99*d0!zIonpoHXSVXZbN-N8UA6U5AlS5 zw$}|M6+r=DvN>CL=4Fr1UW#Ii_?_|YEFJQpY&Qs81OF}fSgOia9sC% zW=(F>m$|=iWC^g3o^j&vXJ2smeBSYw`G~5Vi@_yb1ybFW1sW5R*PL_P|1jMaVL;wz z8iP@a8A|G2jorpCWR17a(861h#IsWbrjZ{-+V5oWu-VI{x3KiVn&fU!2>f&@ro$5? z#LP@p@~){8Z5Vj~|233I_tK|-jEGi?1K5iO(hqtAc@M%MD5)l>Hz@*_YWXln-Mw^{ z*&n>?ZUx)^%}yxT5sWXC-IvZ%xgC8;jPD$ndUG6o-*A?^AM+ccbsJII>mrJ1M;&Vj^|ddhosrN!BtVdXwWDp@^;oB z2)_0hE%M+u>#d>S9<@|#>SRHNFPRO!~!wef?=ld2gorslKIRp^PwR<2{4ceK;Gf0Iegbq5G#i3Y-va}+A!)l9xT@vj5jpXk(`OQ<@Q__{<@8ps-$Cu0fEfi=#{wLD+#Yk?UByg zUA(iyz<&mOey1w#_rZj?jR*tP?s&A!=`lXhs|5MkO_cJtvpV0O-}MmT=lmncanwoa z{i~mBI$p>#R@$L1G__AZqA>UYvzgW<{MV9=TOTOEp!yc7zP=x^(Odx8ArD2Dz17Lc zFcE}|XrZk<+cGE66$)j`gz4jaae83@=PUL~T-j-wAf)y}Ul@CHL4|90e;{?a@Yx+BN+=8Qq{P*|W3>{rY+e|NQh# z%3u#B+9bWz3F^dy1awY~jE)=yDz33;M{X`w@jk(5Q3mf?b|gz3ETQ0Fhmh58C3aP} zWRDB#sm-E(WXtqWSR@lDB%Id5=^MhCE}xAa9daZv&k-)LH0pqc61}r?VEl#QXyf;- z_)BUQ+c~q123JlY9ZN7Qn4(H&U7t+wZBrODD-yMvZN&GpoS5Ox-JHSIkNj*2fv1aa z2$_@C;*EbRq&h(QBzbbp+zFPX4x!2ebjYY=7tpjK=vYt&c9?jHxeb3q7xhji??;+} z_M1}Fr*Q{vnmM0c`w&ih)A-x}Yz9oJ+J=(5C~ooPebaoe82M%}X)FkUB=amGLdG8N z8NHFY@VoXqOC2(!X##AFcuqesQ*!O{IA~uq0IkZ3z)PPlWmewzsOOU3cw1K$TYNK4 zZ1?>g*4T%k>)w4TcXu$UKN2my;uxILbBblTwo?sdW74NXfMkBZ7#n6n4mexz zEc`e`iX(B-hviIdh#wVn$a-^S7jCTEG|lRt1|T?2~0T7<8T>11qr=E(rr;*+bg4-bp!jlVTI0>Sp{)80@+Qj>fGuSN2rZ+g(CG^#Fs9T|cG#e6d zNXl-u`b8T>y7P(rR-VVvR-}~|tcY2>I{dl42}PZKj*q!b1@neGv}-EQ%x0Maj5#Q@ z%5K2xCSQ@x(aHVSO8?OcLhBr{hpIV&N z=?tG!G6lKHNVMAT04*8&fojVa;URKYnaS!1TEummt+TZuW9b02QfnpN6F7;DJ$8+% zf0if5y+h%yxL9QRtq;+WMew4mjuO7>meoW`wbuD9R^;q*42d=Q)Ir2Gim7VwPtO8v zn7dNm9k$3p!-8fSyw#FiF0lh+-8;fpz7M}LU%)Q&44p|@ zI?k99#&&7G7KaN-_~@DUtg)?whFzB>6FJA#;IFzkI^B>IE$|2XmKgNm$|J1kq5>b> zcrKgY$TCK_L%zsSsH@LI>-wLjK91dVfO{Tx?0bMc{y2wzxhzk{?Rdn#zwHzXqWDfr z2Y_Kl3w`4uPt>^At54Shkswkf=jt5btnPDq6U@n{f72n#vP^hvbFM#m9vTiajEbo5BChS9HHFB!8sTTR7Fk1`AtmzV z^<#WLIsAP(3|YDq9e;KVhfFGDN7hu)-@Z%9hJiDnYGIb(JGuwSWM8KS^EhjNc3nvn0c7P}Q!veKDdG=tyMdy_@bb5M^a^$aE}Drdu$Sa-B$cLvT? zxy+^qzoDLbmLzv7XXCV3hz^dNM1DG&!YJL#sL)|2ZgyG1?v7ti2S4GrFm#B&qvO$x z4vIU$0DLT;(MdUm0!r zn@%&OeeLwQi80BGL(uUhn|_cPN#aggf~DhRB!q6ppT7n$`KA&&I!Knxn022u1jULH zRr_!S+mB~RyJ^z{b;66MU|F9cx|`4EedZbxOYbW5>0>I!E;ps~+3TngIbcmdZ^}TL zeN&w%ni>G{!6@?CX8gD{gf)&&qxx(9;F0DvY+0DS5PUfZiyziXZ(+sL)QSF@5ID3D z(@w>+UCz9cN^81o_ z>3p7T{}12DzRU6obA_doO7VkM6IdMalx_}EBR}MV;eOP1A+O8~YtP&G|C)oAHd#H= z7249W>2A&pUzXqrTaGE9s}%`&+`_#~zNd|zaygH$SsiB&Y?g^fCD{_iAv&-lHx3Qm z@C+{tBrql5CXEljhZoHq388TZh5H|)@Z z+y$0164BUmxAAe%hU0x3=qk-f6jAv<*XetjGw}kx^QN3_8yZb7qzoe)r|7|jZ;EJJ z^GaMc-kL@8&abzR<;eFfp%9mJUS!L&X^E$J6H&@zsyxdRYehy&_1j!8p0D{~56+so z^w+GRTB&MH zbd9xOtf4W=GR?+IN)#bCvW4Do;e02)1DH0v6vZ2>kVd{Uw`MlcP|i1QS>p+^OUi`4 z9X>ebWtdc>2#-95&rCYRqHOxnDM6gqcUTirE_x!Z$Nfom!&*3aposqCx^BptkuZPW zU7_)XE?InR3WVQrK^E&zW6#XXtn1i4+Oez$#VJv#525}$-%-m$;r2FX%8Q(FRqSsm z`>~zhd=04|jOE-&;f5ONUo%EJdqI42VOHE{VvUc+#q8#q;)Iq zoSVz`=eJQA!*Rrrdom3x`qS(NJtE4{fG15ek?)>xZ1KX8sk!fhR`NS>Al#8sKlrdb)-GVLleih4t*zZpy7hy$FKF&FI%8A>{3bm4R4 z5v1jmg3o#{V}7uX+U8i0@YpQyw2Vi^lPLCi!r9ty>uIT;0oge}5avG25K4~P;rTwX zQa{+fQ98tM+7wV|eoh-kj3qbH?4kRT8md;}{P2PZc1+;s!?)&IJw&~I~@!f(R zJja>8UmWgJAI_RM@jL)DYdVDc{xP^QrI3By+D;cxBl3B+6Buz%*9E?ZYwBCT(0p_B zF?uVuIkld>tGY_NxqsV2>4}v0=ypT~Z!rmw-pJMg&)}r3hBssRXJD^{IEn{K{+y~p z&mX5^$H3cCk8aapBeH_$f2$V_q#jhAVAsK59FNhd<6E&#c_h1}bBJ!6+>7<~YuWXq zBH?su5RN$eh;7){Me}~E61fv0aIb~eTMbhq_TBU0+1M#)v|AC*detMV6puy zIB_Y@VV#^7dHckO`!;u?&!_j|VWm4*tloAiy3&jNw%0PP(mbK|PAP8vI9#gnD%-1) z&;G&icwfArIM)nc_unklB?5+;lhla;(9AASr<>fTsyhoFf&w~{oq%_Z-7npTBN`SH z%I9H|w+fwc)Rq)>4ubAmal8w?9_L0l!rq=L>X~#8=W3aQ*6o9WO?ebP`Rp3A(Bs+j z^P|Z4EPv>SC(ym+YUK0ZanLzx5SnI|jr$xr#g5s$rkiT*$m>=;&N;k`iW@jD^lK=X zv&CX{f38bB-3|Upi3msE#)l^A!ZfW08Wt%b=B08H@@g6ys~CZrRvnby&McRe;8EQY zHih2}56-nF-vY+LBQQk!@>k(1Q+rlreuH*h?@N}6LqU5{k?2}sFK(@h7{6HvGlB<-$H}M>@5}SyR(Jp!rSb?bQBa5N`b|{C_u(5hvp{mf zQ8>o+;cIYCI(z@coy2vk@|d-?FWu#8O{V_SfsPPkbmdds2MDNedyBcapwUjKMFRir9;F?X>9EP?Gj|Dk!;SQ(A379IxBM(nmIE+WGC+{WMRh zZ7Zh{Dn2AR!5Wr7eZCnX}-2>@^}k6hy>ADxB}Jkbg4 zG}0VCd>BXuzBGo7F)66}&R*R1C582$yPaBp=*53S>ez(uc>>WW#l;Utz~vuL>E4&h zWL;D+G{kNb)FRFB371&b#@}drf=7{mt%2ZZcY*fuy?15#94P8hK=@b!9?AQdyoa^Z z_&gW#rvt(CC>gr&mNn_GqYw4tV^LK9dOQ}KK>11)HP5++uhv<>HMMlXx*!T~m)u~9 zvpea2PZhFW(-9`-X;Fnr&Plj12M&FogbXyY@u^2=qwNw>=ikkIxw@ZokKp8a+i`(e^f z)!rP!1ADhH(C85V+?t4k`hJya$O{+Alee#YKsQlKd}7Z-T;QbvU!FD6jvnr_dOZjF zb~+0CSss%AdtN$+&ljG=69*h)^N;z`qdTpM-D^EKRcVZV(=6=$QCT{N6G54zIR?X# zq-N17P$YD>09F3a=zO00j;NUfuV0i2oo9Tor~7(#jvm|UOv-rYW8C~6VJGs( zicb-1pVLHd7|4>2-Vkv4Z@I8uQwv{@jbawdyQsIiELl0#8T2Nm(x00oWP_-mWO-LL znsR0<-dBEvT|d}Hzv)|$dt2;b&|^6|59^To6E#3_vOCItxEi1SsK*VV4F(zb+3f4m-8hv0h9)3;u$^Hlax~K; zcVx6+!0aqEI6nnno8r$l=SR?EJr<-O{V>e95RWR{#dzs}q0r%4PoEg7k%Cc+;OMMf zf^~)+_S*daGkM@pUGl`s4r0?^QY}p*(mj7X*daNjICKZL+!@cbM!%t(IG5g>Jz;0; zwu|pg=)?}M2&}$#hbGM8eH>d1p?_JH&}AKiYpaXcltSJeX>CL%)1VG8xjOzvRV-SVfvIksOh4~+m*?t(foICr~{qUc!oqB>MJp`Z$yd3=kTW3 zPf{=0=?G(TG0zR6tuh?C8r8_*<3_OdN)npgvJW3I-NTlyNuc^Xv;TB5=LZfwBB;&0 zj5E)e!j9mlG_h2PR6GcVrH8i)wymakOmdubHy&wcL?&JKh2V!LsSBUU%NKd^H~0XQ z%e$pKf2FbPUv1QLrVG*E>j?HsWvFu16td^70o47DLDQ_C;`}=9@ph}COU&$rHZdMe2v|0TBGkK~Cd2Bxw>MOM9T4QyR-ZBYL#~}2lAqyM6EtKxYJJ~YwB-R_| zjV=%s%@xRNFB6z+{QwnS>O-DHgu&&;1!B*&7G!GiK4|`uh!z~Yg|A%Ilg{LQt45HR zZa+|WJ}We=ia^neGo>?GJgN+9R^DfQcWk3a#|$GE^o^iiMhQ&~@yG6qo!F)Jaw?nN zheXP9~2CH*BPD>Bg9IuCq|?+O3Q7Z>xsj4hi);I=4} z`l<{fy5qH>#AGBo$oz5LF(=mg;0WEEm4X+1>||z^9kgdP{~oR249pv8<+8FP$d;vk z5ITJq3RLCyyV93ZkHjPHe*G?u{HAAN+Ez8CPW>q5AL&y4gAtZ)50@x=J;*QQ=?NnMmG^}+5S!HJ;OOl#GoJ;%F7JIbKe^h6}kq# zRmP&oAGLVhfq^h~Ya=b^oeSTyyufa}l3Ba3%PGuY8o2l|k8KUG62HWhH2@choxTb9*D~;}=+B}cx$MuAo0SBqs zT_AB26u1|w8r_cFij7M1ng4}0Y941!e!LUl)IK>na;^>;U8e28z>|eV z@1Po7KmT3EZ_To$!dxxR3>4pG4yU^4L)$*&EWfRfeWFi4Jh(`lHvWd*haKqZn{@o~ zrC7Q%BkqgtGYP@KIi{inT|JUiqzjGFS?CK*#(q8_Y?IGAdXan5NJlOx^~58qIpx^= zxe<)H%5!J;bx4B@zcEcr6HNQr;jn}8QXhriA|2xBDT17)7j$1X_dCr%aBZ9l`c%CG zFFcyWwjOPxXToGjxy(zpdT^pR(zzYyWIKW3foj@+3)h#n4TT3&vW4c~o3WDaMRt3nviN}R*bz1*#*Xe`gy=v54bvdy)^m(8iTyW~FGIkb(gtmU4E<^{0b%#ef2aY5|r1V?Y)vIK!Buzl6hlpTC`&F7>44 zY;q<$lc$2w>t6Axk}1R}Xb7}xY(XA2Pw*z*!Qp5MZrfVV%H#oqSk7x3pVzp_|{Ov&bAKT&N_YHrjtJ#T)o?OJH%CFesYb|sR&+hH$ zgJJOJ`NH|NRp{l`N@+f#Va-9j{Y4xLy<<<44US-2Uj?X%X`w!*I^-zN9c;X*Aeb6n z!0S7IvUP6NDEwg~)<{u;8wotu!1sz;{(f1gUm^5F1mcMc0$BD0?p3&(iTfPg&Ys@t z6rXKPz#FIkkj~zI{)(ilG8jBE^u;UW4at)$YhhaU7W6En7B2)%*fhS8mdIO>s-X)Z zVYQPW%*#Vf6E9KQ>~5+yq8QtIo@e#5gK74RDWqO=2=Cx9Liwgy*yn>P+zxJ`cLNm3 z`&+?~7}+4&wp5sXm;Y#P(90UD-CIM7}wL<#w$u*?6`v}mT$#HdrmM1 z+C~qbHz!e?0XXWZ99^!iOVsb_fBzme2q2>9?VvfA^9Qe>xl+ zEWOW8W_Hm;-r=I2?E*LJ2GOCPi@87HH(Wf|h7L>8@mG0ZM|gf#%yUVag#_IEOhq43 z29b4sdN5x#3k7;7V^p@9dAwLlHSbuEm=#Ch*2wLs(7PO4M47+_oqGCunKs#E83f~G z4hSg67Pm;YOYd}UaoXg1q5w8epVKTpdk?k}NS&jCMpW#;?~W$3?bU5`;6N|p_}Lcz zx-^L$Iv0?l>^tDzt%8qyZ^3`RVvrG4(WBe$;c;V(Va=Ls!NPYlc0FDq-IJBH`CZ;~ zF$~ErptZbTDgGIO5k1yuzQ=xidR{7fqWXX;$jl>;Eo{MJZLO&GdoK!4TrHi$5BaS; zvtuSTkyN{>Dg!L zM|~fXaErjJ6$L`m>OkCQO#_SR?4mygDU$EpGcY;8mM-fpA;Z_JNNyZxNAH%L!`TbJ zv%W)L(LtOU;$Su$RxD3KA7#_xL9F#jVb=E6))8&h7V9AW}lqE_U%4e$Fl}+%ceqT!gnE5Jpr$XJ0$h9 z&6hY6`HE@aV=qI4mH8Y_GJ^YyV^BohV;sbJcYm)`(2H%6m<*7x=Q}%T7yljkbk~{l z95ks$&meL!&Iz8Rn;@0gEF7hNfo(8(O=C7Ylc>$p;PJv#(HMfr{j8C&F}W69>HLR_ zlfxjYYMyxbMho(O!vXN|O+pqnH*xnZ0|>oUPbWSxCI{NNzW4W}Q2l%z@+dkiox^*B zhZ2L!R^U64d#Jih$l$%h!A?#Im1+dx=&2s;*Zw&*J^3$S@fj{v0ul$yp zagXjfCLzb4DN5eG$UvR{dEgti+gb3m4ti2-PR^fq1aVC!-O0Ppwqw%(!}Ji2J=k__xtzMaJ_7HIvgJbW*30I2x1&|aoRPTUWK z8O8mDPoIjhf7Bo84lF*}UfcFNl!hi84$o9<$|3T4~Agw`fJue^l#1 zCw(%6-%75B!L3gMy&v4yaisEc$;lQ|Jnm!x_WL0VA9%)jR-Q4Ln&}66Ri?tWOjYvC zZVDKZScERU#`9JC!iNz}bm|Zn(lXQ)`W3wsQv8CkPq-)ZxXD>=x$#zKfcU)+G{1Y-7;2-)@FIL!DzcBr+BXQueu zf0-+w+j_LX`8=7e^$R}m(u2_QbbRmvuqe)8ap#+Tevyy-;> zf8B)Ah6G=ioQL15AV)02KlsXVZ*M?*wOqF+yA6nN&x3GSUVW zd_0JQA~Kk=_zA5r@FJ5d?Z9vULs8hPUUcQ?8n$t2H`U@yl7FXHL-(|kRBhxvoX@=n z_77`?C1!l@ef*FevuL9S#HwThjDUa&0VTyA#Di=zS%GmewbYT&Zihi;t#aDD~>Hm6#OhNWn68iKk z9h>E3F;|bB^uLALjy0p?B~OIw$Wn9(`%N^5$}vxAvI%Dt1cpHC#TcQw$P|mcwlmqd zPU?`t*?`YnAn@3Jy8DqH8LBW1c3=4}xM(Nf$;nylmUcTe;{L|Ch4%1cUXQqNyA|=d zVFJ%;H>38SkFkRx_s?5Y(!qTc$k=fq&~yHl;NBRCXZ)*RdmnXD9iAf_!Zk4^Ck-l$ zmJpZNKhRQmA7w^n;fG5~q?&NL#EPVTHi0s)Tj<)mKiJ}F7(}k0E56OW=Ul$h04@VQzL-3i8vsriYaT@k78K2C5FV!6G7t0e_ zx4E!dlvV!r<}f0ILqJ}#6P=E|h=T`rFuD6JR9j+BC}$>Ik6$31^{PUb$Q|jtEfQs5 z!-hoZyuGkL51-zx2>Agmv?!S~W}SoJc||{A`PpLJui>9`?_HtVh(khE!AEGK+B`=V zW9EjC-p|4+MrOXux!Ed_F7W(ep-3=-d6 zVL_rbcYw9+F0{Dp0WRIC18OpjbmvTca_Y=9ID6bun71(xZ5dZaKe@f7cP16%*O`~t z_=mxC-lQSqw5kgD>MEiAxtVyY8rPG#=5R(;fn4EigpgHFMehRTNT;j-LpMF3Q~K%? zJ?Clg%I%ck_|_Ybeip|Tw71hOURH#*+Jb6O2Gx%)XkA=D zGnX5Yz$O0RUiJBU=*&T+RNWbFo^wU#z00tL@RXerT4{(z58C1Th}HylQR{wx@uD8? zkv=b?DLZ5wYbX0k{;nT}AFM3EeGTQ{aCj^AH8diI-~Hgfpb^4{dQ~zNY#`xpEXqFe z8lNkdgPYTvXz9Q({N8CUONe_#_l5n&y|rOHW4lDyZLf*%=f|;Xt^;VtYLS&oLZRjR zNqRe8LUN|7NM`BPpw-TtSL1)0ISy>+w=HAR_|F~;uKpHJx}`xZ9_he_Zf7)RQZ&xr zzm#2mw40g_|BdSk!oZ{GqG0G6j;9ZJ$i{x`qWwbqkc{7+u(;HKKD0kaK0f#jh5@a} zGBq80g;ueex;OMH*V~nN26>l~nJBDAmz?I`mp7@IXsy<6JTH0+yZI=Z-g;m`#xBSQ z|D5e;+=y~~Bya@G=lLx6YXixKsvuz1`-DA3w)hT9V(IRk)Zo)VlEnSDW=W0oJkJ-z zXikHhM^#YNydAgIEZs{)GyJRp85?9)w+!0y$8?9GQGuu}UM=mQ*VVd*Pi-0w1qu&^^E#>cvQi!U zzPODhU)Cqasnfx)LxqmorAD4Kjf7tVFjCUZ!U48NxUb_f)mpfW?B_iNy4t6OOwOH9 zzTeC&`ghaZkHeo*rqG}G@x1xl z{+oq0VpDwNMgp7G*-1y`>63t%WzZx(MnAL;CZTKwT-f#WG$MI#`*XEWN9{1~r`cY~F>l~lI2A1PcC0tKR*LdBFwd|+dhbRRz6 z$aC(Bu2A2qK`pU_m}K`te(!xmVzO}8^~=mX{WV>%)`|>XI0D9+-9m?_{>D#&S3_Ii z9Pz(I3;t)O1AUl;z8$Q>Hqk>Ms;Hi-R1YDK_xeL0hZDlzlWWn*6M0gWPSVdIGvmCk=4o*7+5%y--A(k*=st}&&`n2gJ&31mNn%eu9H^~&9zL>K2?7VS z(5AEUq+f^^G$el!Wkna`-{)lD-Rx=hi~O#%eK9&vg4yTjsNB*<@{wE^*ZS7_I@ODdkDDs=!&l_wjdhe$#8VlF63nV z0Kbvwg6qi!-mR=p4oKW!N`|FSIx`Omf!C$;`B>9=Ecd*WZBGrRGBb=w`!o%3QBgss ztTXYIe;RPtyoEmf!t)N)eY%x^6hG zZ+^r+8Ftf^yxZm7;<=!>bO_CMIZNgj{f3DqFOi{7I{v=-7W-EHhTeR^Sz(XdV4H)P z$mzWfX-OCYNs^`Ud!{OL+j}V{*KF|ZqQk$g4R#nfmhn>Wfo~|)atSq z+4R{7(juD0#a3r)=e+HhPVFabu&MVQRYqwPI?d zV;aBtazERvv$It)EoD$ZU2Vl?1FQhj+pNM`$g?k2cXIs$( zoAcz?R~5;MWvytfK_NE3@|XRO$Nq}cPrnSd$#J3 zOE0`(a&9hN^+k)U^K=I9kPpJKciaDur1O5r`TO6vw$h}crKM2G9#Qw}oYO$rGb`hb zj7q~uL{p`uDD7pJ21P{oc|9Y9hDgJx&`|bvm-?R1{rv;p{qXkc+4Ee_>v~+cd25Dv zKHt4OgRIF%@Mi4?;rX>Q$lkAGVesE!v~l1GwthDsLewhg;8__mG=lBq^>;ZB#r=42 z)qVc$b;idtk|FPi9jL1*QB6SwDOw;=5ocA4?%Ac_X-`UdqoeQW=IJwtVeMEDDBVYY z7m9HHIZr6~zD(%Mn0OyrPQxS3a8#>Ri46<&Sua=BgFk1uf6SMlo0BbO z|9<_fNAM(TFnQQYbIeUitKCFUnxKqo_4eblxm);+w;xiObs}ta)f4W;To7pXe8ngJ z*}|;lRW$n3B-@`mgDMmg74Rm-g?QAFaQ@E>)@$?2fRsMsV5vtO^-a(ri?zoo@nHGyno;q;L=9c-uR%tN^EuoLX+bLN(xtVESt>*z_zUb@>U6PK67^ZQ=Tr!yXA zVD(T%Xc%at7f#8NGpcK0f7CBQ|D+;3=d}dk22x?z_YB zu{&^z(?0QhzOI*zCvG{#8|3~JUcMKCeHIOhS(LurGQ?+yI}G?~3MYG+6W@;G(0nNh zZ9Q0v^*)Y*je-`su}__pGggLbr#UAfpNYmEEvM4@AEcB)?Y$ z{}=@nHIRh2j~oHn)7xp?QyKF1g&TAQKNILQNRqhM2#i8%=zmPZ8M(#*PFkGd$`5S7 zsb7P|`?JPE#!Q%p;LOF-R7QCu^Q#Yo&Bz?tKp)Oj@P>EoXXquxVI;0^0YtVxy|sb$ znD~1B2RCkRL1t5L;<=Y!@>hc1P^_!i4tmxEudZ@tlMGO>C+ z8w6jUaSyw_@a=~#{AHHMgd7o`^xG3kPOs@vp%=KAq*xM!q#8|7AGAQ6Cv9au`lr=4%7rG#Aa%JA}X5x$?`@ zV(GjWA{;Tn3(mi~${k+eiIel6@dx(y((WeaAt~MkDG8ReGUXDvDl39dvaivNC5hN_ z^aJs%mcFe|_O1}X%PqQs*D52)ik12hDV2;iUx>o>5rKTlii5Pz(1KL^pMz1xp~&*# zE&S5b6x!A_Qr&H;MjC86)>_k~KtNZ%UHx;~}S>~BGMvJ-?$ zDWj&X;kfu^EZ_2+^})eva;C%qo}79uoLskpOiOtT+M;3jw|+BD7=z%Iw~)qPsm2S= znZjjI+55p4~*J|(i4mk7czYUYzxQefZbU1x?cA%p7-+xa!M|8Zg1P?}Ulx zbEvTfQPXjOO)lv)u}qz4O`Qh|mVe=%e-FWGtFw4DmW#2DnnbSNu!c`r?}T?ZX_LW~ zsxZ`f70S5KfHTJ}hWxvgj4vup4n1NFoRh3qyT#jCV2z?S&6e-Xam+a@89iIW8Bv zWttOglME7z!_k{}ckyR=LwFI=#2D8)h z)BM_r#Q5_ZI1{6Zw$~oUM>e?eKX%knk6j|Xu-Y3MUR@9feLmrxa<&Xjc#l?8EWkyz z5qv1?9=&(KfXFgd+fsu#+L^3FQdgM5);|_#yvQHd?{(*66|c|&HlK6fdxO@|-`tWBE}w>`gS3d+1}->Qg+}8XMOp=&0VzY(HU$wCYfLR^{+5< zcL?s?It2d5a)0(jn(Ub94zv9F|bwH*M(6 zHRtdG8#%c6qn(mM9dfzF73zHqxpVo-L{AyP`MCiodGlLLbmbxD&I|hYhb37jGY7(a z>$#{uUUWL$N6fqsh=(W^irFLTWd`KDyDePa+b2|3Q6qi6x?tt!fGm9jaCV_LfBj@U?O{7Z z2-yq1lEvKSXM3=AR3m>bu9w;esF1Cj+~BCo1iJ3@1@guqvj0E6&u9+QjkkST3_GVOqXCU@ zynZmAZ)80empWDvMJFdn81h

Em+J@T~?~Ylh)_Elv0|yN@g164H>sYV6}S9@LJd zasEpWVa4*>yrg+IVxr3$5GuhG7Zd06}J5V-WEon{_4pU6O}u z^~(66#+fv1(N)~(W(jNOJ*O2^id;D44vKOII14br6F-ED=k1$WQe<4PJ@lPDPA@F2 zAh}M`6{jrIk<^0_95yb8KN!?S%XeE6tYQOWHQxyTvb&y|@o-3fx)Sx9G~g*gOCU9; zl6Hkikytf%2$@&GrIzl)J%1na?-hHfs-y%Nm_VRQL7w)t>5y;S3b>JPindCnU~kRa zV!gt^%aV-Juz}!dfdboSGl+lo1h7+lfG)a=u)b(7NW*erz-6X$-b?|_6XB@L^)7C= zF@jXbCOQzKO{~xCfK_|5xgEXUXy%r4)Ntu%I%a_N;{*y|IO9eRDVjj;*jhtln>x~e z6^Iot?dRXje@=ZeMYzFiA4ED{6tsN$h^r#)VD*W6beoq7(d%aUnz`+qR{H`rA0qh~ ztQVk!@oE(luZPqru7dpAFI~}^uo6{l+JG}BgzmIN}bVd2m?dQn4@WQHrl6gM-J z_OlO19^4PrF=uIsUZ>%GXarBytW z53t?!!GwJfYAm2ryU*euvxdUj%k6Z=J{9uf<7!CztKBOc!JPdNow|X$bYeJO+z}$4$u{lE zBsZS#SZ{!LsBla@-(K%Yv4DX5T}(GvwZx zgH~!L;$uT<_?&T_^xuooWMhdfpx-(I$HOCt?@mK-ypw>&?mmI#&mHGq%?+UY|C*Dr zYc2uF3Ps%-x3KG@@sQ-xNZ*`SA})7!GyOJ-J9u<9e&id?kF;aJigUxrk^782p7?~8 z`s$Kz?FfeKmPFP4Vc7iBDcqCgm;+tta?N}IQ1yv`a?}vgK;>I zlnCh;uWI~A$s8<7(zu9^et4a?kpH0DO|!L(iOT3raO6`a4PySK(^1P{?(*4awTzzp-aknxI#-3-0ItDLzxP>dUGe_~k= z_4Je`Hv8to5xppC>QzD3bjVap^-V`#%0h6Z{#o9JF>lBCSdjD}8^{p03I~>Gk+N4K zV5HSbbi}U)|EhF?p!<|6ZIdKRtr;)kBhO_;?8EDyKjuHoWVDg;cn2 zzo4f(7{hT}< z-j(2<952LD!7}hapIfg%Grk<60nR61&^r&zNacj(@D}cJLgyXWY~@kjmAz}Ge<{Fb zH!kv}S7a!B3C314B;m)oF52cNNo2RWL)xMd!ieMM#6c$(j;xMG-#=F4xJ+G0-`mXY zv*XCuG*>XXLAYNL87M^lu2`?gI(7qpx&M$cuY4)4HzNK+^`Q8s3M%83S5%*p-V z)-cW|mUcwXB;In9K|5s$3dyL!A@7}F-GneId1xs4nX(u(D(h}NZqOx3gR3F_^%7*2 zc?0V@z7x;q+==GmH??5UoiQ+b(JJy*>@nVap$6N2bArzbdbG;pEFM2W9lEQB`>qzSJDL?g2PAr{IpZKN?C@a+Kb`S3 zhL7*V1+Ndl0W%k_<6&PAO#s&4c7>n6 zt&28Fnv=wR%VE)P85;3cgTh(O`KP&g}`}qZL!>3Xup$6&(PhmSWCHxCiTx zY~d?@_tI%rO5}akZgBcyMjsDJ#C3@^{A1ltTD!`K9JtNi%X{<%et9Fw<;$jGZ(CsU z34CH-B){xn0PC8xAo71NK|y;cI@ni+r;RcL8J0(Qc|novEZ7ChvLm?;C!rH39^J(O_k{6MbeJZ&_n#?G}CFf!pO z_bwm~mt1V+`#yBi4Re)=$ie|)?4_szoAb{LR>EI?JCZcGj+eGSorpnWLy$@zLxxayXrfx9dv5<3Prw9X*z` zR_*{9qYRt%-OOWbIt}clBhYWFQoKXwG5^IlmpV?dC*!p-ob>#|jh}u6FLs{NJs1$pf(SF!z6I#Npv!QcKe zZzP+~@l0=Tk`%zR&{x9PbDE@?b$=KXEk%Q#^*A?pDeQTChZZl9AP#%kE|f#L;vxI+ z*X=dpoq5&Q0sQHUEsU#_qv;ze$cOcE6;dnfP*im?c8K7`^Z9%p>z5xb0JX*b0<{nN zL^(wlxVeQWbgu}jtUUea?_fuD6X@98M0a*8lSO&!z@Z?4 z`_SQq)*iShp3fUMjUvXp07!ik^-5+vaSCjI4jzuyszu-@vySm8F)Y_sBErfk2O;I- zMZqY|ZtN6l3k_Ta4e(_>w!M1r?_M?+lC=Q;7Zk%wJnN=+Uzw3p9V=m;Tq;fVG9w1B zZ9ra1fFxLl)V=Uy{3}_WZi^M+CwmVjTQ}3sj;7>xrYr1Ym3aHv!A?r&o>;r+T6qgw71r@7x`*l9+q1~#&S@}d zx-p8#JdGoMXu`$fHoDYDf;1Jo!^Nf=!P9%p!w`t!r|>@2$TA^!u55<`=sK6!xgM+8 z9smEGnPri>>;$kjD~4u{p2_$yQ=w_z5~Mx74?oiK1F4*|R1iLdY>u~wd#!hG9m_8! zVRj-2KlK?IM&7{JrMtwMMi~2j^fDE|k4SeeFuxZyK45t!iypeCNQAE^90dL60y@d) zEH-ga0A+ioCvP4}HeA^uW@es$G={WAY=eNSr%?WnH+Z44GR#qVN#)s{OLD9L?tHH1 z-hA@J^FQqt-~Qevi16o5KltY8!j1f>hU@Mh6YI(KNRj+xcl<($EUGi38h@@D4O_o9 zayTjg%damH&u1g1#~w*t4YFFYblnXV;uvTMmuA?b#HdJoeISCLn3+kZr-`tG{2>S# zUBbnV+=GvQdMTdIvsm`LgxvyO9UD*KK?1I}ujdz`PCCG{%v%E;;a9DmfZsThteRy8 zTP0J_MT=9|iDeTOHU`s=|ICTx`pXcneGIwWD8paVEyTHxo<+k*xThNooIB1PueZWG zKF9KZ6?$l;hXPUcCNRvQj$YE!B|B!@gV0qH9qJCl>pms%(-gbtovRKc^S&K?uBsN! zmewHKw!0yAa>iv0obx|Dl zDry(c!$T>Fe)cdV6KEVC!+CU&4vb&A_! zvK{|5?&3wad+6a&66Boq9%yl&L=73Mq|jIzxH;`K{_ij{e!M+|r-j&jLgLfEDeMQ3YNkeiS1pqm+3kC@(?^}d?l2h zsZER*Xu~<;JmB5oo4b%3QM?yhkFVpAP7httEJ-5fI023s zMr%@mY+pOH0^h4e!lq<=`+Egns?kBS8qJ6|+n2g({RQ33!}c|1Gyii*^05Nju&npX)JAGHQIj0E-3jM{(>bSlFZ6m*u9!hYC&88m#i-d)(JYX&MW5E{m0YE z536xvojy2lIo!dR1=vRQ1iyCZd%A(KLAYpV=$(~HUxb+ zd5;deDZ<-p4guQ!mvh|`jzfg~eBA)sf1WB3%_(kh=3aLBqp3QiM%fFdo)1N%t`%X= z&OiM7&Fxg3b(uNkIfJ+BTJHLeyXYT%C7#1uZx`ZgMFsqxjE!`@Z92YFswUo(CzL4= zcUd<$`FBvDFsu-Fe`dJ}cGn}OP1t4jC{P*wg3e;QcT%h~3}05sMK!o$@75r`l65LA z@V$oH|105_eo&y-w*_Oh-%{Xxl=T{{8A38!+@W`anlSGKo5SDYz~Fu~($lTR+ve*- zzj-rVdfS-%&DsvK!vq|1%Rn5@n6>*q(DQcz7vF8+RfB_AhocdZb2EgLL>2UQ_-QOz z#(aZw+Zf7W2ninI0SS@S0u?n89y^u5q>J}xY$e=X*G*c|@&Gm`f|-c1Xb z-+SIY1UpM(XdGkI&%ZnZ^hb|J$6Z7?(B}|Tx}2rcZuF5ro1GOc;|38CUSU225v+4$ zdAlPw@T#i!d^_U_j3_lDSIZGRuXg8h*Y+awAMfc2r5-AGk?H5NhJo9+Hu^$YlWb7i z31hu=IsL_BSeVxpVm(ix*625QNTdpEWjcI0+Zj5G5S-Mm;Vj>KVk^Hr;#*$hGZ9W% z?GG6Z?>F-ycRkFWCe0OET&3fya2AodI}CG;tHN1Mq)GuJip*yXf)` z=4rQG3twzysiK(*kykJVrE_*DRpA7_9e;vf+;x^lW{L1yfj<;@mvFQ1cwoB=ulY5y zAE?t|1yaFw?@3PM=%JtlY+(INyc?f&G$x7pOJG5hfq?3(lg!8CK)xjr{kg{2s+&*q zA7&h*qTv?g*tdMx=z0td#FpVNN|vDTwvl!#D3IH6?Dl#(f}2CFaG6V-Sg)vhHk8;o zGxpc$8XEgvhnTp`1*^@H$W9oBe?Ls&Uk)&K>vji{;WgUsWfsHYY-MOeMPa zxdEFO&V@M}%jpir1&waI!`rRwriD-B$&44aF!D?o^*dumcCT0qe_CgwY`1irms89* z5^t%AmIHCHp9{-o-xVBv(~lBI1@IO{y>z`$nnWO9sQH*ftWcBj(<;X=Fd8})3&?zq~+LL_=*y^YgyZHNOre4bN7$w zX?5HlC>lMHN;O=F^K&@UOIPmo)-r{o?6|nx73FBxvq{wPkam?V}t$m9B9pXbnkY5Up!f@`6p$$y{p;o7hQq;_9~3zd%m7q(I;N0~;E zlm$1BMxcdFfK3BT!SdE~n)FVcY`d@%yf>zC_shLl?(4ExH=cY#lk8=;p{b?MY2p<# z^3Kr~p0y80&(9yni{3=?SK>S9&Fdm;FyIgOk6jW-I={n1jqJd?kkZlYJzjT`u|7`b zaFZu4z;&*1{N9dkx|*?fTAf^=EG3;TVm?gUS+-!CBtUzv$Kk&cC;3q6$MiwH2uEul zf$d-Za<|5Z-o-w27OJ4>To&qSUA&oaECd?kZX;x`TGj zY7^@cvx19ogZfpzxOx+%y=l1l)^Kp#*G6mn<;k|mZt!6EfM5YFz#?{IlA2tFM0t&P zXrdM@XS^Det3zVX&xOsOiaCd7*6GPIcMF*&EPrzbx$is+%p{_ygK;ok(Zc+<-d!}X zbO0~0^neUMRiVo{bMo5bBzP&uAl(y>@t;5gSo5}tE}myZstjG>ZK5?dmdijhemxY= z+bV7hS=GyKTYik~pRPyRr1W8&|1fmwej?t+kAe{EHrh};fZNSH;D+gAL44B-e4xP^ zrl{RVUVnb$(QyRMkxItGH6;Bk8{Y4JmD?-50S~_&&2Rj`dIoI_iLKu(Q0P8J&o5Lb z>X{nMZ$Azlh!J7u27mB)aF!m?>L=B=c2_j~97IZt3(;l10Jx|3Z_Q{dBsN|mIH1sr zDvWM0E&YRdAAZfe-?=V~C#>zk$(!~fRhy6EIef4~g#9NRfmyj6jj}$2Z%tPO?~*pE zlc7!?%-RVL#_Di*o-R>Lbb*)aqfy{sJ1+mI3Z>~U=y{f*%b&-(sFv4ocMQF-tAh{! z;aeBIJgE;~K6nJG)@|gryi>!KyTf_e8NJjaV;C7|+5`S6ne?S$HD2+<0CI2>7nc%% zrbX zkSDN~ePa$|snT41!hJsozT=mn-a`p^eb+Owh8+7!h3F)YfqyaaXwH_?IIk>;cWXXI zBi34w#MA;fTyP96-Cl+R7g)m5sz&OeE>AWe-VMtO!#P!<6^<&8;|*8$P%cQ0JRd}G zaMEL%{#c9r#P*V7Lg9{H(@b4a-tkdr@r7XS+_IJ`8J$y*CXD0HHHn~u+%;9!o-rwMqk3U zD`lZ&D4W$mhGe174tTaD+2&`RGMULTN9WzbQCivu{9Z{O?AN`dtJ24kWM6ZzDt*d9 zLm{?KnF#TULf(mE1hO zqQ8qCk~bnYrE}n=(o-S7Z8#ZrR|Aq4EI_Vbn3v4b5&HFS(&y*<@i8Y4xT<}dGu7UU zuO>bfYr?5c66AdQ0`Rm`pugEXfBI`!#VzY6$mCEmZX9)=H&W=JCQMt~@PWNqmK+hB z_R%B%h8u!{bUs>hRD?IYItuH~uN0a+H793Oa-i&91lnR>fi<_W+ino!c^(--bZ_hg zE1gvC;g~7t%H#klA6G;zYc)vFN&@>|H_(%eo3v}qOlVm;6xn$l$HiIEyeH$e&W>XD z=$@m1iZ2O-o7yp~vxQv;%4z;R_WjEnLquK|TVY94_H| z+c(iA;c3|B%m~h ziMfEJu5xm5uK2#;F+Q)bi&h2BAa_b;!{CoddbKAAKe{0!p1tFm`muta2YfrDB6Q6$ zC!)$zpp0UW!S%=ZzsW|7BhgGR6d4eqoh$VGoXx!$k%8u^REuYCc$E>kkzfsBr7x)d zCnNGO-xRWzsG@-biFoA|EqGztMnAmh$4UMku=3wS!R1{q@Q+CX2>5jmxrY40)k|z) z{rbDqXgcF)#cv1g&qbWlrS(`ZUjD7?5V0+0dGEj9#u8LF}iGgiF!mknCxu zk^Vdi^EA%Ujf|<@?Y08;j<31p`ZJ$t?;SD^E>wQ!na*?=_e6h)fxb|?rh{rebjI= z(+v)f?xoh_VmG_-7DGuNyZd1Ec>8QKNi#v#iJwA$@r6D2JajgPDNuZNW`Ba zQ2Tfcnf2emc^4-_Jbh082<6Bk8Fv^g4&!p%tXP)z6hGa+hfba#L+m&VN3^S`l&l8v zVV$#yRe!nE8)0~RWd?B7%Gw;x!o?7mH=|LQN;69%b&HmjZwMpWpO_1fAMAdIrkenfdka42{?OBkH+YE1r zwTMYReMmMeQ0y@_JKBebunb81^AvjO#|a#z(9K_1*hO_FD3KdG7s9j-Nvbn+6nVsc zFC_LXVt3?nd}-Nhe(B$> zc}0W=5BG3Wm{PV@y=DMu*%Co&n!c5T~NMw z4o|&oNX&&cAb3bcQyNZv`gVwYo0%3>& z8J1!S9+5@pI}S)K91IY1MGWqJjDAo(oIgoiQ~jwprDe% zDH=~feo2AU{Xr3Rky9tRiwXP}_muu}(IdB*|8Q5K9GbNGI4;SI<x`8MDT#P ze>c+piD~%8IdwQ^&_)0}*FNCdy*F^IeQ z81pZTLH-<@z1sTZ#8Fr9SYyQ*=B1;5zgQ0g^AF$gG$cEGZQ$?d7S_8umTYOC04B%O z(PQOAoRy>v#a~*f*){D9%=1k2v{ng`BN1=%-aXPO2XPscV?7PR)qg zwt29&wuaNW=ZR%H5As@)EEoSz#5e{)aB0>iF7${R{xCO^w>;HLw_TPavsec3T}i6= zj=y1+2}~6=apq$K@SF#?#QK9a^M8saFMzZy--Qx0REU)Sc$mGw9_clw;eo|x`AG^T z^cK^~N}O^k z8YS4fnspZNM9KE~<%n}ro8C5ZKhX&8KDL7lk7C5!jo<+tnc7YRp@@wr9Arn4@R0ymf(SHqo(JcviEWiz3)o9f7E zk(o)%FJX3?s@|v|t`ZUzUcVYp*z9y%u&0bac>OJ1b*~Sp)CTdP9lbP5nlU+B_c8WP zI-S~h0!vKq;op08QB^G&qJGyF<{11I?yoT;-&?jo(c~Ry;`(x&r`yh_?`4^(u&r3; zz(?`k8#tA{we39NhK2<_bmby;|8FQXgtGVMGWH&4jOC*8M4Pa+%A`fr23(xN(E^DN zcKxPiyd4ZDa2QFXF&ao2HL+ugr9Hqgt=?nx#mY>@b1JozAUbX zju#ClUYFb<;%*vEQVGHHwiWWu3f*+Er4iAuMsWS|Q{h1^HG=Pqf;TOWD04b`}c3A6q#(f0*;m{(nY6PU#gBuh0g0I=*Qe- zJp0rmUdfJWyt9pomLh>>Umw9Pb6xU!*BDUm%|rVhityA0L2xy1mGI^Z#_N_p2Yuu? zdKLh<`kNX2S<*=Fd{QMk>vqAj=SiF^W3uO22ht-M1$3XRI+>Yl2ghoj(i^O=q3gFJ zTv|5*S&u)Cr|pa5on1Pp=11nScL{>jxLiTXd`a?swjT`URH98Wud!P?>*CD4MZF$X z~=e&)!;74Kitz1DI)q(+u|S=%VZdcQ$TU(l7au+;a5ON4CwHt~-j>~B7fxu_`KfkT6yV+YWKqY*81!*AAI^1t2e?q#ku#FgdgB6uymZfe5v zGC7RpsL>ZmXDkZB%eKpb`xNF?^JAW?a8Gz~S6O(P-8!8MPQ%FCG3d1RBb+dO476D_ z(MuQf$fY-~u%Kfmw`OBHS|;^Ge0Phh)+gS7Z6M9CiCUf=OKu&R1a+W}WHJ&M6GI2C z7q-&n?7iIc$P;pYR|#ZmTCn6o49!yaQMSu>oO#C%HgBt-J)9mH?&u0_ItAQ^w)MC% zKb{YXeNR*77?RVMIT*VrjDGxSL?*|X!+G=B=;j6X?wB0}2{+DBaFZZubC*J4(*0X1 z<8sMYdl6JQzC-b2OYs`aGBqr7_qNH5oYZ!L$6q|Sxx;!;n(HrmI{rPqZ`6l1{eoc1 zD@32o$id!=RAB7FHX0Z%LmWS>hQFd=+?IzrBzMdFG@cq`gnEVnD77RXHbM zm)sZpqMA-RT~C8}4s(FLZX*PwLzSc=3$Rlr#fR(Q;X1o1u`Ae1DJ7c&2$u##TzS0`aJ?co;s z%YBIq!@G>L#rv?%iOJ;gm)Y<*@rLj(+mQ}GNrt%(D$(k?=h%GyB2XDasUasrIFH?6 zU|P-HJADurJgVYV*zJ4C8fl`COW;an5ZxV+j@4{#@sG#8qx*d)lkUdZAnjBn$ePxN zzGVgTO%HqN1JNKJBjd|_RvGkH?Fqatm2{ys|l*yG{9DIrnM_ffOF8in?p3fzZCXtQztl`p!R!-i!0RKEa z1LmxKMs?UM)lT#VyDE3??l0v6-2V*6hE8_Vau+WHb zyKG^&@-v~QsT!HouMOIIPN<>-@Pw&O5V+zxJzMgzc_rBC6123(i=9nD1_a_2NE<4FjV1E~sCHt`Vv0ym-IaiP* zD@lxhAA&vcjD_a&3ZM43hXmPMH1csZ{-`nzes4U(rHyyOc`~QPns862I{7?&9(Xcl ztS`$)yo_21TD~0G8kmD8hUD}9&hO}s9_Hon3x;`hecXkQ$8hp3NvLvV-oN=WWNMi^ zJn>H}_nK=?NNXf01)oAgpB3QCKP6!6mNxp3WiwAMnFqoEjvIgc4yyL(6|*sagj~TB zqRM&SjxBW9j#S(iuL*9@%DiFHWNfD!)PMXX&?wHwbDNbQZe$fI{ndaCSZ|AgZ414x zszD|?&4aTV`P_uJ*`+Aw;1R1l6`H56>QF1mt!C(GD(GVZ&w z@DS7C<;;>{@sL=we1LfQ^pp!tt_J`Xh|(9_8L(Z}?DW==+Sd^#zZx zv4fVGJj-tDket1)P@Z&|bKSfi|5QH3vtmiA@za3BKEg0+W*EJ>cOn_*JO`q(=OJOU z2ru^v2F0=G>FQO|WW^X~xVY)@E!nvjiN2)>@555Re(anbUAq!_Uq{ z^Scch(}T*9&}1JNIX8_CX?~2qxr~FOYnwU2kN{kkNqNb!-E?q+IcfXn3Z|}d^k$$6 z$)9EkQKKDDTIL0OHm!vDta!S%SA<`Z5NL3?&ZRlK;Yznoaqi>E1J)a|)dT2hBU%}I znFMz!ReYY%febrOVI8?v{%;0jrg7$E^e?Uclmiesiehc9ubgZzU^m zTMaleb_ryFkREA~BK2R~pfvswH@3qUPilY6|E}z&N)M%pr0!fe9vn=Kt<&+J*_1b& z`i^$9VkYkeHqhc-AaMRILenxs_{l>)(1hGR94ECO_LZel&zuujDe)5@z?j(QH^`H_ zI~Kvw>x07i2^!?f5+_iqcS1f{%rDX3!OJVRQ~b=5v^m;9dqfClzw1A|YV8+s-)Pe? z5jOGI3(2t-RI&F0b~wtkLBlrMQ#6D;-^lJzSN7TXj#eQBVFZ@1i9jVzz1Y`F1*#NY z(nlvPiH3{~1T1^SJrU+(o9vn3X!49cWqRqH4|@Tv_uwYJ9D^6Sp5o_i?WOxuRmt(= z9$;LMLL(c4@y)5lyw22a)=6PVWY{kH>Rr9C_@FBBbJvAG>l~3`GT@@L1z@!0I=#sB ziX+W?Ves}Xu2sSZ|D!GZ{Iniw;w?#>ELTJ9d_}67Q9(Y=99|*eRgbo6C*yLhIzBq0 zgLZZ56Wd<|UQ6x~dfApHwS;sfJ6B!|FU~Vb35HXL|+wm}kKf`5v zIN>FYNxXm1dn(sxOm1Is0cc2|#{Q~gjrk-9oMnVItq!$2=0o_nF15U7wK>_fEE?ecDb#j z)b54S*($;Xj3;yRQVL|vjYZ4GJj91@n!>NTMtW9WmDucYhHCF|T)uNUvS!-+|2z`$ zSMHn$jA^_s+Sn8WNXgax2@{VcsKwAENZ0MvgTk)BNqg^jH{8Uo(O9 z6wQGfI~>q%_73{VzLP~k=jq=9Ns<%48rpRq-uh+5dO~Ne2GvUlB?Vu{aU=fl!@jrE zpkIvP?7al~Q}%GPn%|>`lmCfxA0bAvwsZA^E6mI+v5QtVPLfuGIeS~FBlDo@uuO4N zyarb~PK6M?)qs`+p}_uDY-}|OG`d@;R<9YU*}4QK=GJl=Yd!Jg(Lv&wykv48UbZU~ zex`5coRrk?q^KCaUH${TTQ5iUbnb(PNon-%%g5OK?|2aAHgmN1D4rSs{Cbyedem<` z@%`!w&s1b-ccls$mp%zhiyY8_srfiWvz%{Tcb_Kz6ybj7P{3K&xt;mDap$!z{@T1= zYRCFn#_VVMzqcV(WZqYo&q@_u+uowLk_q^gPdmSuvA;OR8r6L{3HsbmB7@ihoLDU6 zXF0LX`h^zEk5memWy8@tgHjx(KMh2Z&*@kPDH8I=9VRP;a2FrV!WRxE^L{Lwzp8Bz zH|1eyw5*`JJz1`BnoPy@YiH2?Sz-9ilJoqWkS@mTVtJ@68|b`OA{;?Rkfh8sv2J{K z@e{oC&q65CyG4h-kR+#B9syQ9Y7Ko?}z;IslKa8?bVH=<8qsp2pE^Iu)`rJe-w z|HJq*7rzK=*}JKN?t&iWo#@EB+qg;bJ>Q$$PMxn>kb7RN14SX2o6@xf2b6ym_t{D4 z)ZnQWPSAZonSRZ>fU{zUL5E@+^*%U=1KTjnny}ZV#-3?GFYTcJd<4=P-HUfBsKIWn zm$Wz3f+%1c@aSpbu1(CxwL!C>t>Gy(99P4>A1AQ&w&PYWAA^~`&r9?%kKAfyGM?R- z)*eWr-?UVS!<04fZ+j0H5Fd=|AC!nSt7O%nNiP|W-;b} z67w_~vwXUvr(j{>NTRXL6wY{EK!fZX3oZI>#9}A2r!G1>`F9XYuBhc5*2psKj zTI`pYq{ei9VJP^Y&Jzs1CPCD09)%QkQ+QX_go~frfm3oR)o!iEVcX4N-n%oLmWmVJ ztChkhZDjAO3dz4tmD7Yy}>O9@S@cwr}j6pt*GFAnH zfd|N_zX5A)HG-nX7V5x$M>G>;Dxw^>pogxm*qo2yJ#Kc>YHtfN+`&l4L3d5OpdL=IMa#c8ZHPd z-!$Xbt@iMG!0V)>l3)-jn0&4T#Ea2k6-x zM(spuWWA9A44*R=NhtN<%3Gn}^5#4}viB@;O#KV^$Sd^I;X2;5S0rZ0_x&*=-Cvf$ z>z8}D0f+akaK)g!CBFVR3-25{98PX*rC0wd zlAGnbVCfEZZj`$UIass?Hr@zA!7Z)W@1Yi~lYK!OnD^WH*)kZ?P|Ho9;)zRy!Ti8N zmKi+JhovNs!4|D8Tv354&dH1s>&eBsLrI*~0dSN~r<$_WxaEo&{QlO=b+MW3GP8mo z>eo$C=2)_G>2}aNFHKKtsgfmCli|;dxyYrs7#A8;^7p%IDDT;ayS{`%--uFfNz86+ zHLY7blPw-flFAr&So(h?U58(d@BeNH4Gl^p+De78SLb=|yCS0^qhV$=w1|vUNIN5y z1|^lyAZ0}3+|T=@WK=38l?G|@u_7A$?(g~i172R7bDitH-q$#)P7(_;v0&Wbr)7I!FV@h}XASWBx%4gnI-kFb;`5OYNkX3Ndi*)6k6#5JLo3E$KalC7BJi944FKfgtBh~cTBaDSXvt3X?@E< zCOwN6xo3!7c{+q!y#5o(Nf<_=3w*(DVG>cF7lo!B`!3Wm#=DDP*WYH4aOVqOM?r^n zHtqvaZ%1~^tzy)d(a$AB(c3!p>xPw@06*z8Gdp}YlHL7-`?05wDDNIZ+W)9uZs%-r zd&Ny;dqoCL(LATG^gm=AZwgrXut}+s9RAX<64s=Lvs3T%A)JGND# ziT;$^?7zkIx}HJxS04)Txu5>NG&*gD;!kb->XURoC|V6PcdTZ~Kru29TMM&p<&#}U zhmf`6acJ09%pBV3jUMZ@az7vSk;W%7`0IUlNUKpMU35e0zV=pF^ihTVQJ;XG?|IFw z%lSyg(+-oZ!K=W+)QdM9O#1)>Xg8h5O?EHU1Rg#M0ZDs1{tlYijFHHO)oUVIyL^J8 z=_dH%v<7l}SQ=;Tb_2O1vCOsS2JChI88Q-=O_n3t^B;uhj%@|G{6Zfu-m)3cct!Th zlW??RexeYo=S&+${U1WW^J_M5GR?W1%|T;)0ZD&XiBgnigNOQc z=1TS&)argks5#dMs$(nJo#3oVw|yx;FV~q5vfDM-dx~jj>Wce9tk%>WMz(z+Q0O_z zSZao#nR_LKoLPzPP4ju4(7Z0OWG?M|=+TG*`&F0NjXAf`1S1L1Eo&ooQ+4skLKpCJ zwq;zUN?FmAAHwdSxBn5e(6gS?6FWjTJujoN9#i26ZX+8~MX^IV-8G)^o%g;i2Nl~X z2(fz7(s~phqy?88n#fk#C+2T3PH_A7ZdPrIGpgMf#l6hzA?j)Rn4>q`xv^(Rx5R0* z?y3|x)6T2Q^fPmeer8-jj$cLlz5+s%;a2Gdc3d^&XysOzbWN9G zxFk0H^;_ZXPnUK+EIxw4&%2J?jHaD(w@o1KlQP@2Bo@8mslml1Z6t@@s+QZ*e9ih7 zJng`@XchIT{?GHa!nGTVUn}9qBE%pT=b4!QfI4jRzv}pd@=|Qa<~2S*2k(z?9ydD3@-YVZ zd(viDJof;TSk}v04~cUB%X&1H4xMroqPn;~KpWE}2 zw$K{k&d%2ADgV;htoqR^F#;8#RFd8QzWy%Lh4m<4jrZm@HIl%T3-mLR6A&G(l!#82XLU_pE&Yde)7 z)2BwXBdCG=%ay`f{%+808N)nQH(*n*1d(}q*(93!48NMw4TYg{604$$k2spcN$+v& z_`-1XXXzF0=i`q=eIFn3%&ovYIgn>pTqb;)shd7;uRN)!WEQXDrCrw~^vNZT!#38DckXVs1VV zu&<1N3AN=9<$%UGHF37d$4HhRACVnakT&iYV>gh9+77C~y4h`{FiQj%$k2}52VZ$6 zw{uWq;zXD%N4;>Bb?CjiHu%tu_0@e^m~(If#pQ(ApyZ5RD@SvidU{CMLz=a5raf9u z&Jgo=r_i4((n9{cJBsSS+fKmm@$!6wcB*s!y$ZKQqu4Kdo}r*2ecE02hCGj+jL|k% z7^*O09(N_NPA6MPRoW-g>7au58JL1eTMgNLK_A=DuGd_-DXiXy7}UR59eOm|h{cZ~ z)J0B!)7uxk0~&A9V6%l#)7UY!3(asag}UjF$vgGQ_-?ife6YUB$S>K7!Xz(qsk3`Y z?pOnSo3R7DI*OpHsyHvm2;M)L&u$6jBkTQEP=*3XQL`GB=Z?aZ4qLW9>;XDE{U3KP zoc3pqGr*HrJGgY@023_V%f8qm&TY=?B~qLDsAj$uG@Y45HY;62W|I}cT)B-{U6sO9 zY4*I=VIq?osDdqzc){ZN)NdTuiXxm

TZ@xiv`r#)fwAXwNHVaLNJXWEsjS(BC`T z-zCWCvlaNo8!)jB^2jCaqEK7re;R}D?4_LfZz3tTc!}ym=YY6)6Qe7B5?OsK7jot` zO_Df7(-hj@H}S9KDC4NL2qMu zETi9Ly3MrB&I^+F&LCz-ZeZQjvVuk1TG_xGvB-Zyj}V^+zG>kn^IYJ~TrD0mS01~! zECz+8vFtZZK#L2SxmwTLWR9&NR_`bR-?}iiB=P|&UcVR|SJsot@gjI#peOusI?Z6I zB}j5lvQS$FdOIk~Fol>-J~5#CCQF~u!HJF6SM6DhVL>MS(42U z+CLFb$W0OA^BI?N)Zk$Os_XKJvdKTB-sl1QEy@|k>Z54d*w>uD3e8*fieqn0EBLed z4B;J1LdTyx6=JgJNqu@}q#R&f7SCeoA9l7zm{8O3F8_n7zz=j%t`PS<7m!WEPtIm~ zH@R9oih?s&f}i_mzFU?7w)}PoV#d3%KPMNXjRjx1L7Kf1oYBX?VaP8%&5WctqAcHE zLQIa?JA`T-{bBj&Y%-8?0|hk5!rc5eB0_%?dChBJVfrzXBqt?&*K!klk&j}PRQix| zr4oE-Z6;67>*I};7_P{^WsFL*(Vq0>kZ(~(g02jq{fYjtSoQ#uT&jgCI}(JLycE;y zId}r9yF|9r4m#I2>Y(-CE#~daGw9cjLhe7hEA+qjT6UfTC?9R-FPTC)vzHe9HD1kv zRUw)Yx>ktEhbZPBOZSITy%J`o+d*W%tAqP-u8*AGCxyLM(XNd9N<`&I0+PMiDCEf+ zztk|lU>($H9N^uiTdObYbm76BG}h-;33{>B8lG8b^Sj3y;v0&0U{`G<`%{ykK(Bew zlHWl3uSsI7Uv7}UFPe!zqR-ws5=>klXAygc@mQf0!L?IQ$e;eHczDDND(*?JuWp2+ z&x?~e_17OsZ+{7TcHA0HhX?Y;jEdl8p@ATEr;N2PYCyq9EMUyDhh&1=8WeQmD)%*} zmoT&|@_hVGkco>TrIX~asOn-^wMm2RyON3;=uW!6VJETuQ-ThMSwn$4$1HcC+g0Dj zf>?GJd6fANUCHr;=#}v$x`76G$=DcJ^!yULxh4liTaAOg=56H3Wlb!i;0%-0Z5W$h z0`^DXAE6&3+@6mjzga`ahF^>$-S5ynI}JJ(w~@%czesb)1CG}J$GfpP2L%^Rf{dRP ztlYX<^!Nt#PJE?37oM7UN39d}RFp9J_nlDrwHQwRSr2(j-)OIUFz7X%A@vrgkh!)D zv}<>flhiNqhVKv2`{emEsg88l{~C0fN3oiH6)1SQA=Gkjh~f+-?0d=;wyvMcroX2td~5iWHHmC!No&f9|7oQ(o?QAl=@`&QgnyK z98~wU@SDEV{nn=ra9q`cZBiDXcX!@#@>=Z#T^vRqT*6`X!bi*s^ZjU{!e=24mwx_> zv`0N)oAz`P-hLf_-!egP#6RUZDk(L$pcm$qeE{t1(#tD+S z^LqUx<;5V%6vJ@2t(Y|36X5nOQi4yh*IA|d5cK4H4rh|nP0|y!vCF^ZV5^+NzhgHM z`?sZl+yj~i2`onwJ1oHOP(JywXcYPFp`F|1PnhjZN0HsJ*If3ZUh?Wm5+bP;-1Bpt zWG~HgwGCi69h$|b-)-K=d*5mGb#A@m{trSG^EPUevD^)ypB))6_i4swZleMHTE2+a*Y z37gF3knVXmkk(r{c<9qcY|2D&&N@qIb~$eHr*H;#k=qNsY$BUK+KarylxbH(3mJD= zAMf%shr&&78E>0x6!LHdxaiao1B&NIV^6|@l?RwR=d{o`#mmCGUg|GN+*(6-4Q|E~ zbJ{s@GEftq8)h=%if2&JreZFi?IC9SWpRDAHnbeDU}yFgA?p$P+jJ+N4ALyypPrNO zC$fYI(>jP28+;Jz$qzIn@oGm8=smAUmYhgHy^778<0$n2cTL3GMD*d;%QQB8@-Qk| z9RUxD?D@Y`4DrwGTwpcNvi1-7=+~|J5OcACeBVqpHxYLTFuBO=ZP#ZF^+QR*&TJCn zMEmn2XohQNDOpoJ6^~iG3O0ZQyN2>!?L8@6(cCT~y^8uP_C|oB)NS5Lfe1e5aYl%- z1|IdONp3Zi{C+?R){VyrU)>AaCeR=YiW& zICWWr4SAJ{R7{JwnR%UL#B>;y?v8-ezkiu;)M z;QD>BApZLjTjQUDj1P{79^E#grA7B-gPg(0e?8-?Ct&v<9~OF#@95}YuNe$5R<;?5XVx(KG2A#M=qIqc?*8 zVXWS7b^Op`8T=kSMuO*_L`NfK;I!>W@_=S26rP=gtPAq|m`(%C`;rO|{G-^$fC^+6 zHX9=7KG(q~lklQ4S5Ol7S)@RHYjs1aq-KA->T4<2zJ(e{TcVJ?15Huy}!QWmaY z^6WZ87HvfeCz3fIu9tj0P2c8kwn4H%6xl*Iq>RJpTgKXqy)o@IZa!rvI54)EwF(-K zYuCF&@SWF12Or-@7hj9Q)5#sg=Z*?iu(N<0gZ4~!Ll5gyIF|e026U*$Fv>U{0f&=J ziQVE9B=J`XHe6{Xj_i26qS*~XSIaYV!VK`oJE5REm-?)8-l5lw8uZehy1w42bo*u% zJe4SBjPH1%>f8t+uKI*ieR63e#824E1P#ie2@hkqQ&hLC*A&5Hsh=dTKbHJU2|$xG zo^wk`4=MGN#1r4Fgye=Mz5?}TF!as>-X82BSpnLyHa(IDAu4E zs~P*fpjc0p7`mimjrFpEy8b3M-#Qj;Gy25ci0mfjG$SLLN;$2II`1=29v@h_0#cG< zS%t&_w6j*jISOT^xugN!V82M2?FcY6-{E8N%HOkkx z9LIiQy89QBTWtovRuq%9w7W^CUPiFt<#pEkObAlAoy%RkNOOhvHF4?~9t=BW@juil z;J9n4a45TsowBPOO?pXv3m+(_^&LiyL7osdQp()-KZ+8`8&1W)mxQz^;k{j+P;=!H zi4iHoSMJIRB+fOlnXyS|F!?2?R@6ztY3BFEmR0cRVHPjL={LLNeYh}Zcf@iCeS3Zi z^aGMeXwP|MnD$4QcQ(tNgxz}F;L8OmV(&_O65bwzVC=@u3@JiVX+OCw^E*fp-I{Ft zz6#>i0~xREU8vvf4|kCEm`!yVLK%&x;O6BygqNRzEFQ^&*t9nCWBORUY{eGPoN(IY zZNedF1Gw!LU`-4t-R-b^G?=uSk>DyWZo%RGZDRC3V-M(b;7XY~+zCVm=> z#1ArK#I=xW=Vjr|F12nvj-g#c7q7< z2H^V({*>3U*ws!KPA^`~`s^x34jLQa(&2lArCIxR^3;nyP{J6uA3zrEot)*GxbbLAM7QfM^*4%W)}pmK2Lh6aQIaFA1KafVI5DW zBDZBFT*>iH@{abgx22DV%wt_7=;JVwwfBMxA(u)FFB{;h_Df*5K8|%bm4j@{B_Z@k z8!@<|hV>sh!w#@w^5zKGrw)IG+OPWxZG6~+g-cuNNb8RTq(^-SCLdbKtA)d8TD~Vp z&-lc9Xp@J&wW+|s?rQc|RUKMpFbftbHj%vbYFLVTch8Q~veEgkCkQS2w33gl5e2b`kb zklkSuv7^F%SXpAoSRF`Wf2)2VB~_nDLBLe3OMkN#?5iO*H1k_DOh3;lQ&{(J(TK01 zCB$By{4mm=dm5gJRr3C+Hlp`-mO|{kf2$jfZdwD==NFNd858j<7gxwUoz7TyI-nmP zu5#LUsUG-M1;6{T225t2Au}KAV|E|`z8mtrUIDSFE; zcO8dA>3)H`XE7Tlxoav2V)d9K@6HQ*v3_#%< zUvg*Dd&rN=Qn({y4K#gh;Rm(q<7wfJaO|E3>-GU?$Kyw?%Ae*?yj{`Aoo}4nnSN3p zGKBU~o?N9ejcoTy$1eGD0pZ2hcQbkyNLZbN!ES!Sk&HxIkO#u;k7^<8rKoD2^d z++$f0%>h)uULM}kPPwQ4G-r34gZGcaSt-wZNaxK`=rZsyusLiiC?bn#hHKd#S;6nI8SGKF5G0e9C*-sxAsTpvGVN-!&E#A9 zD`4GAX<(92#`5(9D0&Xvm~hG^{wIb|@*^+U6kf`_F*u4IguLbE(M`-2rAauR?hAaA ziXj_RO7W&2%l0$O|@HiYBTnE7A019bf`78Raj5XrCU(Es3TZL(5cfy7M{+ zH+#WHiE?6`$8cmM{1149bxXEyWs+}{mCpgYA{TwIoxX% z$5LSkz7syF+O3GYGtD4*qbR%7Jsf?UlFnslc9EslA~LM`li4?*~HnytQ1@0cfNK+We?vX=HB{hD_GeA@bXs{Q%s zH_dwFN7t|xTWitBhqJ(pc0~MmJ00)LbOyPJkD0kEoDhyq;Fc-(k|h}$*sYO)qv5{9 zNF)Gx>&k+j_D8a6kZMG{Kxng2;I9@p#N+y}gSXs8Rx|x6x;xegdTig2D?A14x_v(k z`4})Q;tSZhQ-a8#TNuebr-+N*o58FP&xt2}4{p1(2JSzb!d68_qXpx&!SrP-DWN!= zyEYKMJ67_7F15K zd%f$SiSpI3(5on8R2giyw~~(|G>>564&&C#GBq>{@3Jof7GF(fnW^tk746No`|m9= zl~KY05$2%g_mKH<+6%>~pXap4(05az9J({-5*Ksw6S;eW>I^%Mz{gvcNZr@~bmIH} z+10rDqqAV}Vgh?B(iKg2 z`7X?Qe2u1AKa&IWhB%GnFtKR+qA#3ZYd4YVnvSOzISc#NTxr+D_iP@#qWwiFvIFQr z-T&io%@aesXg5HkcmzAT;2z2lT?W#{bwrK6VY_x50M()Z=7r5-WN|%}OSPgoYtf%b zE}QyW&J+>;u@Ka|BwwiO2F=#M_G=iLjm_jwyrYA^ct3`8l@9jD^m4R1%@RDN?var) znx&VwjJx(3n~Wb+Db2HCK4kwT5vZrc#LAaw@%rzDdTE6$_o3r4x)*Skp1Y`V2w zxfxm-fALFXwDG!ahkz70vLYRYXnX7sCrkUCe6p#hai%2%x&$%@qIV*9%Mot!NH3XZ zHiSNn211$ETp~F!15Nro5%Rvbl6}?^c=t+s_?vdh#B13!ykMmhJoAcUogI77tryea zlSwm?q+ETwq$P;{e9Kf6W}*`j3|Q=`C8xV-57@>tpg+NzNgC2b7j7kUryli_hj+)} zKW7huaceY5@vB4+4(q~`o=j#%T_AcgQNZoJ-9ygzE8>_tt03~!6aG(cIlS4^P>8){ zhJ2)uyalq_ACM{3mz(H(2J~w9%$or(bWE*Bs5y{F61ZO46O4luh+~nsY4^P?g1Mt| zNUb9txmk5^FTZ^x^XMiN`+OBt-QC42`!o^vUonE8HtFooC!4X4$u~H3ppZXtjv;<# zav$uzon=p;5>z*7F+3ZtCp-Soj6;Dt46QrQ{FkWDc8rZA|MRf9EEdCw1_;U%i%ID` zMf`%kbC<6dWgV@lFJeN5P>c8`CxY8#Lm=o@85^(JfX3)pL-Fwf;@&U@e>>(5WsmBa z9Y(8>(m=Y91Giok$Bit_yr>=`QzK}8FIFMIhwBH-oEiv7D=5;fq?f zPbvtVr@avS#?j4Lnrkz&^oD{tmr6EL9%YrA0Fsa6SdYWm=<6eCs4QwFyDroG&UzQf z+`X3BX9nz*Xi@HeUGay8HL&9Y3{P8M5u4QsC~?0U^gn7PlYD5tW|cSe%=^R}bLc*@ zN>+yxd3CI#eGNK#Ss$+GHj-T0QKS0C8KjOCFf*>~Lq1;;g}$|!iW=AA8N`CBik znxur!cCG@gpMGTZOMN`Y$`azno3po~M5WM%DM)vb#&}_f&LOv|IKoxuWxWc3(s=NjXIh?Tx!HIVqvIy5c)dxFc^59WE7V#MtLUJxt_Xy z@{0R{{2I+*`i}x)IxPfsI6e?^;2&lBc=|GH_~>$ve^F5fj|3J$gHi|k>P|Vj>a+n; zweOP(dZ)Xtco>G3Q(ZUx2-2PNPKd)*N96Ho+6OzYK8k35zk*7n>NvH;PBJA@6SLdR z;nAFQo{{+=TakHI$a}TvTVNJ12qyR^lPyN)k^QNE!mi6%IpR2nvjano-~6}^EquDb z2hP24WY_r?qM@%NoJwIk*^#4Rx(}rrR#IL111!mw2XM zNBRAeV9CQ)GH5}4r_=3#SLkoDOj-rU4m!cZ6PH-eX+7xi{^>&O9Y^%>&PHok;L^kd zTVx{RL>B%swWRIS5ZZG%2=s!ynZA3PDDK5oA@(Ly-s@I$2p&_;|0t*u&DWa+cV}lY zGPIZAMpG$QmC{3QrO4vp!?Ye}e=+}Ah#XdVI0tsruVG!v%21G)BUlHOkjXN`=v`0{ z*v=vhob^IKU-SyGS0rH!4x&A8SwZro>#mrooR+O%iL4x&UKx*`UjD#os&|nb1q19M z z*cO|$48Z)YN{rc)e<(#PROlZTDX2$Mm)65{j{;IqB92!Ty2HoSubJ;2tI@UR8Jwal z?YbWk!sFR9kjry|CV2%ug+P9L!8|CqteRi-VcR54j%B-29IHytAN2))} zz&Wmn`c5lJqyvYqH#!JHY=&9mPw^;Yk2=gwY$cYlLn!aUVUQ~L#CyN=A^P=53ldZt z*p6p4Xdv4VCigdz*HtRGS=9w({ybo=#Oy=c?_J>r2Ybj?>V0zTwuT>RLFCS3KQ!-& z91MNvB%m;innQ!Yxm|(ps%(h2{k#cES1+<}-jt(XH|Bw#F3r$gr`tN!`@yAEkGbkL zk5v)`)2)(FQo2bFU*C@*d(ji3Ks_^0zFLFCvZ?GWx|N`suS30s^zZCGjBXYLL4rpW zZ|b)Ol<;%|7><^+{z-39$r)4Fm35cA*e;8g(ww_sIE6`cc0kXI(z$UH`-pdg7T&vj z2UzRV4h{N!|ItQ&Hy4_-dfrp8!NJ>5@S>6&y7&sq8gCOk>T6^T{)ywxxgOBcSyeRe zi!qiu91VBZc(V`x(MN6&L>xZQN?cFZ;EpUgJ}^}W^nm-HUTzv2qoH$2&-9kf!`@-sI+ zv7M}ubwRfe{Ng(H^^>#oW^}p92X0nOBhTq~@aQggLGElL)an|8KHCony%1p&M6iqp z07zCbc3)9m4PJNR}%jh*!E3LT)U=VrX?Bq#T4;@x*wLCCUn9!oj% z#)fm;e^Q^x8~S}*YZeSqS;>TJKZiOqMWBfGP``UEfgc3yfRPI${2B#0Z2rOyb~~E0 z*7}8Lz1u%d{c1Z=e?mR3zBb@22xOK8??6t={t0oL_iPAdo(cxROe3<{^g1f~r3gLe zT1ov&F?{Z@Jv8Y0o1~uXM*USY=q_^;aVXNq&R#ZPnbO2?RkzU7s|eaA)sp4E>2_yg zFldV%ViujyM6M$#LXF~J`xv}W;pSN)dyL0?om84@BYXgvFajNVIm$HzX0qD(pd4`8*sheS5UDn z;QwYQH{MeKX2EpRr>hw4{vZWHDU-+{JH!8>YgZ5$ zM?5C=J_5YYNkTA1DT@u7AC6q7WpZpl7a3Ub5AAFVg{XUFY;&?07VUP2(W+YJoZ@QK zrE`-@rSFvNq_Nm_Xf145eVi;Ee2yotkQOipx>yDARCMfcIk&vHlgvJK25k|QfhDxx zIDKUmx;c&Z9-KW=@*s(75!bH3K^)HxU&%r_H4~uSyp?=m=@!F8dzcZvjIrAbY(>@> zp%$SOppK(nnM3}bYI67lA1j=25IoxXhdr4ckK%ka0Mc7Y)%q%wrLz`(EHCAi&w7M% z#dIOQu#uIGsX>Pq&Vfj=x5R|@*;;(H1MR?Dj7Zi##GOs%1eE&)RqJCEW&@|52a&1Y zPaxzk50&ZkzC3Q2-kO6ULTw`dvVtL==8*{^Z!fYn$I8+9k@;Y+Ot%~MPoVo9ZXlDX z%f!r`$8sW}LL45QA%m3|7K~*$67rOO-U6sjWj~cIS#uG6%%J^j3tGvsqr=GcU9hkR zUdF2djcRR#>gICxn*3WN{niYAp1ezXBqv~H-~HhA=qjT!!vVFT3?U91?bO7p%6CAD zQUp<}q1mDc8#sKNeqS1tG3ed_ncbB{v!fcnvDq$YPHbe|y2Nnueh;{Iva;xBgE3zB zItJJ?-mFD@KC-bM2ZVa>7yj16SL>W%g0C0z$b$AYgvknV_+aBQywJJ<+AE^T$sc_5 zb=_LnWIw`;x+EjDzbf#k{~b}t7sHv-^v^#k%{-z1zv?&7gUa@+YYrO}N9 zE(q}KV-f=W30`c;f1c;T(9FDaX#bV!0p?kQBziI}}LD1ev_YqIlX$2sC!~eLBkakj-TZflb zdJ9g~B(d8woYDDfzl8qb##2@3_olV*E=q*_S1)GzV4a6R-^U2O!!c-g?EvSyo^~M9 z?2Ln|Jv9^r47(Zsph$H1*+ zC;Rg4V>Io%2=#un6H-d|8YXXsZC!y(Pw;lMeWD1=Ti#1zDVKg87b5J9XC9^_4sJxJ`T2Kb$CA)BZ+;_!PD?0DM5ByPHe zFx?7)?i!Lyxpe)#5YTix#K`w+psNkngno(qwDH(k%@=&*W67cIl?e74LQZ5B^LHxK#MR`l-h?-A(KpJV&q7a`5GWw0i+p2X*h;ww%b zaQr|db17DjEjx3LNCak)Un76fgyp8NX3t|Xcu;_odd3P2R%WrIrr{`jbvD=Zwu|hl z`HS8^4-@j|Wj1xlt9JuT`1gQp4xm1E84sAesfLL!v_RgcZgF$^d&%RCV{lsP8VGXq zA>ZaNTyPq!SC5I`19pb$@zPfKkFsK z^4NHG2`>vx?3IP68T9}3n=B6f-~h`Umob6W9BWZ7A>_{*MHII$T7dqiYBJ|4ABVY6 zPB>wR-Lf(so!+kr2adOruV<-#*l`T*pZd(ZCt8RmvHGCHG_wlpUZIwzIS?e$ND6<- z;+kFu>LI_yFnji)!I>#S+3=L?-hDst!;9?Khnykn-otPeZ`kZ6d$Z zzz~0>nVQMw^|yXUxlDZ zlaNl@vs9?P8A!xbwy`e?RYd86hGHu@xpx@p4ursGgKD1Y>;`m@Y!ddlO>JmI{YO{A zyo9@?@s%`=D&7wtqLZ1`-|gvE(GBj_ygqVaSRJ#wcY>=zII(&~^)#RP(C;;qT}ih# z$|ZAYF13;ze#J-ATGzpV(NpGrjVPXw;Q=Pr1asA)iuwgfOa)<7nNm_u?elecAnF5|~uomVN#<3ezf1vjxQ@~53g;ZZR#4GD7 z;N#Lr_I%S_^l~Bt;xB8-id6buOYnvCZKoJxqeV!m_ok3DOTGSroGRDA+v-Q;-&(qT z<2D1PtjuMy>Vr{{MG==E*+azXCW6-{Tc}ucpMTU-8*ki7XvaH2QWE;J*(*?*LJAm3Z*qr z7M#kfnD&d+@w&iWs{cgV*1o}Y#kPW)?oQT3{~XG25`)35T_jXN26rFvfYx(k$gKNn zcvST$%isnXxc0lH|v#j*qZj|bv33InLlMMRSD=e^u z@R`j_%G6uv@mEujk*+1Hmhw^5cT0%qSi)?q(m;!}(zrwE{bY6H7`(ufYA^Sq$agjn z?TviK6@TaEH9Els79c`Vi&lY=UD)a*6#4KKk&}5_V)? zWW?5cBFW1CgqlYGHc{;Q&l9S%Cy?-2qj*)~7QuLZX;k1GkDi(Laf=Ujk!DTG!*7_u z-YuJWqLPzvdC^k(F1XHa53s^3^S;83hzI=P4TgAsR3Xe%J84hQr5rCJ$czh z!Y%%yyEnpxoOz)0DXO!inS#SPMBGyZk6TH(ctV1pA-pp&r{QGkuf36oT#Is)62?8An8(A2L-i1wo9S1&={fCB7^)Fv& zF^(%a$~V9R8CPLJOFVn&S0*Z+C=bOHqiSj=<9$16s;%FQiTlK{OSX>_a%tASu^*`Pv$zmjNZ#F3Wd&f3Eu10Q3MzmY<4e89C zj2&jVf^kD0b7I*(w2c1#j`N|OOxh#8u*Mdys|J%r?Y_uu(M0$a*GX!rcg42K652Fd zOCqNl;`&25aKJH|4Ln>_WSUKe-G2!*1|g^o#1+>3$yxdH*4lKky~|>X8FG^#oLP;VRlwDF`vUn8C{lOwsM4--;jj- z^rpk^j(0>qTm;WM<^dy#lFW@Vd2D&W2dYMb*_N~>6fkoZNPcc4ZP&E0;njVxHtZR* zB*7Dn=EZRfX{J8y=r9g4jS=jg<;-R}$fC>C<8aUD^`STsuH8oY}Fwl4*v+H9OLO~`0OFZOVn1tNAxT~y*!R>F8Yq*f>pp!qJ`|d zV~9gtpF@5~Bq1X{nZfZX z`J_>Vb_jqP#4@?e{s+Ny>#BtNGP#Gu(cD2|9?g%hz0d!rrH#FOIS7yMVDIlMLf(4o z;Fdu)+1WFM)+_kK?e;R}nT`*-EZ)gotLY_e+okb^e>8Uxc9vuxyn+t?YUZB(=p zs^h7&Beec>D(}|7Pxi`zDDJY(XEKZC0`eGZh&y+H)UXX${3s>knOei|>0?QtYC4jkH{TCZt;CaVsbu_c2g}3|lcp7N*t>Qo1QtcIbBjNs zSKXSBBGp7j%ckMC(yKszdIdAd{1$3SGl%xfS`yz;f|!NYLQG!&p9XqT*d-)#t-%D1rdJ0GGI)muO% z^DgOoT7s5Mr9H-%E;3A|2l`?9RhZ*2r&~+R|9;bH-)8rlVLbn^tsp2(3OOprBgHA7 zxDMP!-b85OJ74HFy7DpJN*k&(4=#h(A?fUkIhL3|`W388?(>)JF~rMf6vH_8^DItz zj4nnlhrygWGNSnpjVqx(^Mr6lwOEf$bchn>?6k#)k@Ivj@EUqZ_S2qEqY+8Lvg$1M ztz0-7ua(QGiguGvGzTQ+yjKuBK8$G^9YxWXBH-@pGS+$4Q*>?VYM7;(Lk3&_q6~iz z@V-&SSnjq!lRdM!KSq6ILbe#*GG`rxe)A@$T*`1D?dRY9rJZ%VbPa7YuH=qWjZ6L6 zBm8WcIW_R+h^0_+cd(Qze_v_Jp*G`d%!pTOSEqZ=-U3eZFU zf2%^2u+9xvkn%NUs_i-U;J)!f&iwg>3buJ^4#u}D$R3-=STxICaAx8Fn-CC(43=rb zOYK%t_jm|Z+4zIpiT`-fWBABP&KSnsX{V09YLr}T47&1-q+*j29=3G_{*k-Pho5`V zysc?MtiI`|hA%%~3k#nfBT1`#(d{9+C*t2pezlaKc}CW7)~vN8W2qr_7rO)7ilSMu z&1FcpeK9n*HW0nHl6X~%8#HNYGxv}&yWc;8?A;qm(&+oEsvJS;w;~dKb1LSx(BEG- zDfYHn6uP@|7WkFW?I=w?x_!bL=9?w+LRZxzV}DyARzJM;0eNX|0-3*$N$)X9e0ee5 zm~gzpj6Y|ON`7Z@iL@(#v`)txI(Nd7k`Qw1`V`zNZ3yHlJIT+ zA*261z}N9vQK_XdUY#2+#OMAEc}OWj3Z84X5#0-#xH!TIJeD{!C7oUD-k?cBPjb|e zCAj8hBWPA!B;PwrsIS0UsBf^lXy@?X>7bbSjx@CYMSD(qz=HJg%m;l1Y`XgxOp6R* zyG@(W)lhxd(m?O6e>AY*;XZg%_>}3h^+X*j6aF8c7nR~U7W)K-vGZBIa9LCnafREe z{h2r(qd7-;f0(i>hE#a?A@_kdTp!IC#>*Mtor&J?v($_A3FgoZkzd>`w{{Z62kd)( zk6_xKD0a%9eaQ0X5LfrGk8F4{gj}}!gU@GG6676?-b4>^zLMQ!b+{Og{j(Nc1c>uy z$x)vC*b?;kaqPSL?<(6` z^DOc|F$VtU!6@;N#7C&!b-+uEh!4!bWnX<^{n2f#tKTEE)qD(OX19^|ylL2@)B=K@ zc{1Bm>CV?>G5DC*OA7y$pmeznV0m~fIqsT!NV(ooiHO4`6^C?%B$~4 zs)iz-+3X4`{fG(l;n>mKZ%?$ZyfO?)+yUq2t1#f`+MXA(Y2^Ks@9xy+99d(oWM zbfI?9LvN77yBT1M{C~+tphmEgcNdH_&Z}%6F%4B^w>GzJf z#SJ5+{Sojj;1%!ZntJqar#-wkc*-h42kKq53EmYyBL7FydH8ery?;E}BZMR=N<&#i zL&N(%=Li+;PZBLDBdbDt5DICcG*M>53MF};`+8T15G5s}tRj_$5~|<%zJLFKN8|Ro zulu@Qujfmf@_;QB!vt0bdpcPOS^oR2tbs5jq)D>%Q;3t;9sPzHvnJj0& zb2xEXupdTC97EHU>+w!qBk^o3@2^KDs=L8VtzzyM_QlD{7kL`hNevc?$gG*}qL<98 zGN`YNM+mO)?ejj-GR7`e%L;;Wvlx0(xF5f-tmifKI_a{;A*8y@9u!Yi3E#^bk{Ob_ zA#Uz=gc>L=lkev{Ro_x`!>w31{ts`N#z%zwKuhXe1_=4hJvG!)RN|3ap zOTlfDq`)?NIH?X>333JJk&FB{+*Ub8>_Zmj8IeCZ6|ht<3Ms75!unQL;@Q}?jqPJ^ z1;LN0!Q6ruGqKTxTl{#NZt7D19?#5Q1b!e4sAj z`sCIt5uD6?hf+>Fz*Al=hxM(uXz!1H9P=;;-dru_wnhiw*(vY&0eO~lG?ynCuY7@f z6iLS#U&8r&-tuF{wbSEDy{KUJS$-k#lc)X1?v@GkOoSPi$ z_w<1asS?zQWp+%TgoCZX7s=pzxap*{SYs`vndkf@`!gH*a2toN!}T_j;2PFRi6Z0d zk>eo$Z#wQv_MQkV9J>rCu=jMDD?;O%v265qc zKX9F(NcHUpi0>q4Q3$Vq`Mz^FzNCl0o8Ljp*XohjT^``k;4etY8cwQG1+aPAb@at$ z5iwrX1D<+0!YF^%{k@7plk_R{V|D?ax>W#;zn)VM=1u)?jxXykKF0k>F+fk$qs45W zt51I7ALYzrvo)8tviWw;uwkOvmN(JdFX8xt*&RM{*?St{$&>u6TSeKEk8weZmV~*!)IX zU!_L4iQ8agAmYNVQ#7knLF`*Ame3|Dk&EDpb}5}58;d1>OoZCxM*8*z%jtg%f&kwy z0_O@IYkZvrx%b-8`%zW+?4=p7TJ9B%_oDGkuEY@^a_UPbcRkb|O8!K{b4Y3>}bwyLFL0%XZ5Ay$P(CAcMBdJ%#!1sj$YTktWzT;y?RcVY^fn3O`?m z-=4N-JlHJSJXMykR0I3FU*O8VJ7PPD+hU!JkC7)m{7WG5z8U&L!{y?_gN*N8zxg7loB5-<$65HxPbEki&N9*4bjjJ#?m$+! za_;8u(GJ^@yi{=)RcxP4&IG&>>*U|&7i6fBx2SJ$7(V^*5|$gQ2i~ELw7-G*_T_wG z!zUR|@)F~6_Z|dC=VQn?^fmSkFowffuc&R`STb^#8`On7;zWZ!c+R~`Vx3I?Jq%kr zU*-F@eWDjF25??oFdPbvq1?Xx_{NO}o@Y0mKL!$HlhZPov+9}f`6NT){Eo4I zqcj8>X=g?Dyqb zb1>{b7|flvpNR*i-4@TKh2|gdoNspEJ|vg^oKk^nUrzvoF!4aPuO4Qa9=mm{h+*Yh{Y?M6Ff8rQN1$qz16#`(QXPQ^Hm21mI5lPVs&1 zex)oKbK4iPPe;%{GSXI2EvrQ*qekF+2AA-{juu{LYdhU2uT9hs*um%8OM>0MexS?$ zMf1OJe4>s$)#Ot8T2V~tTXb=16mBw;fxEMre(K7SKOcQq-{=sk#Mmr6@_a>Qu(OV-hIjLr#4#NXq!A*-i> zc72i|<6?b)6optGn9lmF-$%fooK*DbWgEVhIT@Bp)>Ap3(PV1H5-?m_%GK>i#kV~d ziD%TRdE>Ct)Kq>5W5eENe#Jk+?GW-Zf(}lu#E%Zogq!G)?ea18SCr@`KonzUqZ@f!*2Td#)OZMe>z`l|lf|KlB&!0o^So=CEPP8S)<9ZuZuF#RKQTwdDnJ zA6tS&JC?%6f48VU^V&5yZwJFuPr2>qZL!6@Oul&)`~G6gUfFlbqH4)zlp>#i{XRSw z&!Rgw=99<`<ZBIKAEjGa}7i*b07f=yO!)oI+ zpxL02UUeT%dhj+dd?(-vj!-mZwG!VM+ePv2Q3Ph#!P3MMI(t(r9y)R|oPFF#{Xh2O zHR?y;+_x_R|06t}vD^Yop$+-wFyF=RnPUD!k?U}hId2;Tgx%u)GuVQ&O;h=_P{vX) z8$s+&SVLE+C$)CmgA3P!}-#Iv9Ehz#;*gy$qS6g#fv#G`(!klobwPHub&5& z6JOH7l`@P$=MAH8>2b^Lr=dK_lXREGG5Ru5lC11RU_|q1o|Xp5(OLkyP12~c<0MvY zGlV1a8tKwm@9?(6o=~Lx9KC$=693Cv0(afB=&tY5WIWq53~I)4x9l8o%e)M67GvRS zNfJF5Ltv*1&AzNbf8e+7M4_229sA!)a}<8vMksg&PTX#{$DzfXPcH-W0#uDBEI@>Ao%TRdi+K$QJ3%& zsh2C`lKq$P)EVQ%8r#O6u`TQw8#hLl^DP@rLY;!(=!0X3n!LtOznQ?Nv{!WMt}&$Z zp&R^c7jZ|_eR0;+D}43)PWtupFkJTVDj#y>6MasYj-ewEcP)kruIqnYLu#~c3PrIMQIyyaV1FV8=I>BcUq|A(<&b&h~$ z=NPI>&S06x|M=ZAI_OH~|9O0CB_!EM3C8YLCy~s*db#ETdeHwB&zqqKhYcF&;{o>G zRDTAlccYL5>q?WGxd665tf47u2k;*IBQPWQcgK=De{;Yvu8fv`t|rZ)&Y~FhZMgZ> zar}0qECi}|&=_eMQf9&KM`!;D4g3vBM9^_K{L~lq%({!8=E}mJ{w6xJnf0dm+JbTM zR?bD!ne9KN#PjO&H3CwS{t`AGI7a(B6Y%t%qv3gQ1J%ASO%ii_VEv;bmXC=cFF%E!CuX?J$NZrBME6eH=(rHu9JG#frP-Qwzw1mk!{UHRY6RtZaxn!Oy%*>Ovl z_?EGKI=6uSb$=9NkdA+iU|o9;lPGGeBp2*FMe^P8=;J7F{PEpSvGxkw7$>c52P~ei zKt;>W;em@kctxiUs=jCpSvkZLURL=D+%^m+3yTQk&bW>S=Gc&zY>tgr%M#iI8Ii@9AY`yXCG5?-h9zL9Gk$PDxa!r4d7^_P_Tbi!da;L<01RI#e3S{KV-@N{r*rqA(A>Rm$Z87 zwnlVUL4$QNT*Q?l-}7UvSf{YU2y*qvBIq1n>3c7>N_B?DWlbV zHIX%6FZ$yC4pm(`jxP+C6YH}xl_Jutf4n^6kI;v)BTSp3z*5r>t^byf?SIO_#IH>h z-FCuum!x41`+Z@b4@7e8E68BJ_w(#7Gbcm`Zu&G(jVn?ltcUfnz6-VtUuH<&mqx+m z#c60@X&aVi-*-L3>uFADGQJ+O7_Jvq(`Vs&*xxRlZ?)^DP|9|yZh>rX7D-R8uEZ*% z=fLQxx4Anzf^jjt;AI$>)iFK7GKr)&jRpCqE;vesmgs0S9gWC|BEM*XhIk07D@6#B_}9>=Z0 z(9v5%Yf4zZfL8!~*%;1Uo-hU7EIKcqfj9lvi@7U{VEM>gsu>fG7i$)X=iZ8yvgA<1 z1!!t`fxVY-f20!1!DzR{81q_>E5uj{3vZN zjmM)RUhx(3?KD~xgtgq%U>nO{$o=fcKURf8*_gPZ`fse0;#?{yM_oX^PK?7pUK7To zH_)Zum5J!bHpXF?&s`lyQHQ3A`2O{an%f3UUhiVYt=!NiP zlnl!FcLI+KHHM9k8tAwwWd!QCiYB~H<4*c_;c~%lkP2%+&)?T#$NkI2dRxIVFCR9t z+_&O6?zNmFR*lU5{~fHy5VGD1L1pYZTJd@`Sw3SG40}2gJ=v#D(r2-EL3tTnFVB;2 zYn(*0jLOlf-E0rQo-u3Fl0vzNX=KaBt1z9-2H&4#V#VF6Ap5w9?zL1UWBb;C;@+j) z=B*v5Q%6TU16O~UO=doP3#Dym={9;1&z!CgJJ~)YwW=Rq^$&o^7+G#)zaa@;coF7b zNkG~R`hK8tI{ff|Mc)=`lN}lEa88QnzBu?`r)uWUWP0o3ISkLcmdM|H`-#3f(T^?b z7<+_itaR>Bt9!aZBISBz>=3yR9~#%fYcrm_!YgU=#$!DMRlE|OU8h0<^&P=_>tbYJ zBgF4o+1(s9(`zm>$fm?bIG`wpnrb%V+zbg=uh~Wad)|+?D}+JMxv})x?bA3nX(;@! ze|Zs=AmfW1K#!Lc%$cY{=6_lP=5?`X&#lk6OIja>*1e|RI*mwm#0zlPe*!)9$-tT6 zY;IvWi=#^haMIc^uwTVE2{&foKRBB=UfWH5H+SKF;VSqYnNJ-jR$$rJQy4=pi}U{! ziW9Du@`=GLGZHYKScpnMFscRJ+xHl|{B;43pnN*nYybzbpLxovlrx*Y6VJN;iGQ`S zlMe5fC4)}`;h0M#jXgEgD$?FjblqJY>zuoYxA}JRJDC5+FHDI9o3M_C^pgS=&+o{x zHCDW55QL8*s%LYV$M^}|yXH8~k(7r`EPoovOA>O)7hL29g`*gYJ7wWXPzv-zTHEun zguDXGy3#}sxQR&Bd}+~@O`0fWvJ?KfT1Gtg7LA)vjFRi%;f|wJG&KQ#W$bjDc@6Z# z9!YY0lrI?n3bH)zY)J5&lMo$~hU)d&@Yjn*FvGN-`fXudHuI!KUc2_ApKi%mA=eI` z_XhuUQ#Vbh8^CqfcEd`Dq?fHLv2E#GIK25b_t7jEPu%^Ie?>ZJz=|P6 zWJCZb-4t$VpGt19@8V?30CYw^4+r&bfN`4Hbmn3&96PUH++p;TJ!4@k=U!E&z;c`+sPBU+LKAu&@dP7FkP^IgY__(PZgy_0(VI@;hR?b$99jFd&8jKJFaN@CqptyIUQz~ zT|g^;r{D;)kxaI#P}@h`gz`pX8o$bi-PBZujwn+4?B$L zG;ITuD`{M7uq(bf{uV!tW$+h|)F+~o8v#ZHQPG%PxctOO@Q7%oJ%h{1j1ymAQsi!7 zFY|}wI^2bKdt;E+Ilx<-1aP?P1x;mnz+?*_Fx)nVJ8;|-ea$%|-aq`9Fobw@VptlV zO@Dfd$aGFxG|o8-ea=3ClY&jenw;GJg!p>9i{AZA1i7Z}`wT>n3H4~TE4~M6QP4orpo%vPa2xpv^a2}Q&Xk^70{$X1e zb=IFj246SAXvSMRai9I1cqdV_#Sk2pcoB#DPY~}P7G_l9^KEgv`lA;iAMnj=St(iXFYfi?=H^NuOyB?mk86W!i|C-#aF@O(;gu$Pe zV`)A;hUp)g*$gDyKaj6}$KL3gc+U_E1c^DOfp`T&~@VSyOs6KXtt2s9VXPy0jO(|7H8kOSr)+6 ze=4jRoz2yEhT@NUPxxOa8FxC9`K8}%h2b-Dgs*pvCl5!Ig6gambWZXS9-FZV7Fgs_ z>w*E?RUZaxM5SDc|4uCF{+Zv9+DQ{w2HfM+b|_{$F6mJA{z`Ea1#eZyH;-S$9~%B& zpI^UIBtb$Bf|X7RB>sLwJ1Wlc$&WwLUhOgDRAe6H6g{DpgOT`Xvpgu)wNvYap`_uF zFFdg67oOg0NO}rRfm@Rw`mM-3vC|ddoNp8L@)nWA$12r+fs=~6xoAA zjVrC0QHdJ@=R@1Y+uSCDV0<~`6<>O^lXkidAu&!1VEw>N;cUju_|@bMYxe~pZO-=rm1Jpv1Dy;8k-w0boYgQ=YV4qm*d#GQ`OtYM) zLVn9S!w}9{;K{r5d+IuR)MrMVCNx3R-*{nKv=OoQDuK;Wr_p!D^Uqmq1$&m& z(2i`z0?phb_9}GCY(t8zwRG99FZ7w_4=jD&9v0oXLsiyP;1LpIprSdCTeC47Tc{TC zEAG9g#?5Bryi^lh@B1TgWOpCOX_p~zcP&~pwHOPI{RacvZ&PD-kEmDL3$lF`oLsgI zzIHy3KmCBQTv*TDf;+zOEHjKg>{BMot~o)7%LJ5nA|4+wZ{(SyhQ_6tkvhH+CU?z6 zJ6;^dN2}DqRkDqaR3E@?*N(zcKCbBIpdq`t-v9}nizqoI1&?2*1rvQ)M#e{pJahMg zHupJP;Z`A<6*F9XcZ)ltND>dRUSrREDtc~8rdrlR@K7%#+Zc_nH83s&o8{)|58&fB zkAmRySHWB>*0b96xkj0k02aP@6ajvXt#T0*1$M&+e?jf68-t!@Mp! z`9A9kaj^k~9UIxdLlGH>l@!(WHlo}mYD6+F55_8%(fsj35}fBOs`&K;?YrEMM_k+k zg29r)-%8VnOGg5{f8dW+9LT^wIW-6rHByVe$|UWE6C}=E!lBFUNH|4T%uiFlZARRS z8zG5#`+E}~kj}ofqU!N~QLV~F>_2xR+Z8ubeWtNmU3;K;v>bPY?fn0jqcPD=L`M%Z z4o1QZ@L*n%C0)wIJj#i6O=fc<$;fbsOF2i|{OU+ut%GPK?na)hvv}X8cK+O=PWmrFi7XxG1M)lCgeQ;a5{*E% zuPAXr{fCP1AAuBXY-pm*J=00}KqELmmO)D%yWnI!Nx0C}N$;_~-O=-ofx{GC)@x=? z8gJ)-@2f!6GU7B=-6tj1@Q5W!L?_1^dYhF6+tV+RQR!dc;(C32fPBH}!zaU`)_NM= zXGCaY9jwqhiA|4|j&Yu%0xfYy{_)NK7l{Q1Kt-Y>VEuKBD) za^$Tcd)q0&u-tFxXwiB8U;ih1(p87-9+eN1XFj3fdxW^|{Suh?tb&s{6^ZA@DS-cx zcABzZg4l_Cp=MW~@Yi<6Xp%nz6AZSa#|3$~<3A<1w6ckAsh&t?J24Kx*&wc2Z7tq* zS5}c7=k)d<8g3~E;v~?Q2CV-rE^FjGW?}O_3inKd(kgVzR5Scw!!tv8$ak2NH znDg_bUVYz2M^!^vzFdyukDLc=qrlS@WTFgP_{7?EZ~j1`}Ne*0-O?Rg%a zaB2bQY^tI9?3=Elbswl|MR0%QJyBczOFC}F7pjJOvCFM=0S*~q4?~Y7(}?i{*us22 z*leierUu*KF3G!mU~?DMQB@)B$~)n2&{6u*As$b)Y3B82wNsJbbdufF2xFz^q9Y3r z<3$M?Q1P>sZoDDH_r@%RXitx#|MiA^)Vu{@+b*JqTT@u(f0S6aOIg0G@ZSs z#Trx;Hqbd5fmk$Wlz7JeuDX=OfBgb$6#|8YjEkte=RW9;jz#-fmDH-uj1}X|I&mt8 zkjM}pFtQ!ZZCGH6ep$zeeZOYtFP_P~zVmNpQ3ZXLC6|&Daba2L{nIEsLuDGwUBbE) zgC7yQXIn(WwUasSQ!hUBDHP6~`+zpDuEEZ(D`BWX1~om&W_6ZT%+-$OvZB}E-i`UZ zPDdAg!}2)!*)}k(c|CQ#4@A9CR&=_w1x4N+PGn~014(&8H5v=ZK`%#lme;c2?l zh|k;xa5!;-9$WE%U|VO=A@jdz`uPjkTYeJMyl9|OU;A;E#D0igBgdt@GbFS2T!kgJ ziD>eoI{aR57Rz?A*?W~H8EWVO2W<;EPg@`CEJ)!m9`2&$Kc*3D*CwbhN#*#y&<2M!pk^Ux;^J5dDFK>H1y3!^dGkucN)Iueb;o-)AFpp=7Bfx(^`Z* z%)k9;U^nxNZbordtY6@av{=KZ-I_)e{`Z_~%b*r77o5^B2_>>!%&RHHLmQVu+54}; zi7MvA*E|=5vv;AJ<)`p)@r&n6q0>2z^K{yQcWQs<1M=7&sY8k+Htd4yt;gu?q(RcKb&V*0z6!3Kd=alw z?GbCZOz{Mw-Rl7lT2cjNyAw=2Q59aCp5{4(R-o{I3!Jv3M(pi#+p9c>PJkRR5gYd?g77ZeJ$O*?m5%i-W%1 z=5-RfX+w8Eo@9Cue)LAtD7Q*{RuRF4Gp51HoUC8CzY z@V{R%I3@V6Si|pJlpyQ4#ZdUcMj$m>jVQ@5-jQT7O81{eRGgbYYui=fu3RHxcDD>Z z&pm@SZeaVFTx)nCsG*;m*!(l@An2@%;67SB9IGan5;P!qnh8_dtI~L}RsNBZwMg{+z}l zJfv?aoR7IHn7FkFCywG^a9t~!@j;%XUh)D-m1J(-{mt0_eHI_s!q~92!-)3pg>X7{ zBh@_^fNK@C;p~A{+Tp!~nCX6nAteDq4R({wmwy0}TVqj49*^JeV7xemTKeGlKV0zG z2QJ%cbBS|J(f-U>F`Gig_YWRjWDRQ^vS<~^wtKO}*Y{%o#%etUa$>*>?4Q3CF7wbM^~?9crCqK_>FWb*&>#)P(M_~I zo&9~+HNrD*X|!jd3s#*iCDv-K=|X&KCF=t2|0zXG}D9)x(CDCz08vo48`~ zA}HVdjE-RQLw?9I*md286V{qzvw;8C>hnK3uxFbC3#t}Q19V)E^Vi`Zj2|M2i+i}Bw0Yhzasth7x)$IF5qE0ns{Bl3&;1B zQj_oqtk|yzuP?XJZ!-Vz;Xpso-`^_~9%ucez0t5idIy^QB^Re9DuYvRBb9kRj-=PQ zL(!T2+&)Q1Jba40I9oSo=^T>Ay@8>J!e~hT1H9OK8TfP$L5p&(;$5NR0N;Bwg(y&&G{8%!hpI5QJ4nQe_jy7&(t2-7|x;>v}M$q2?|9xOL58n0z^c<5Jy`S_r#)-1to2nSaIe<(EUDQx0`duD}t=4iFenWo+*ji+63KJ{er`OGUSL#JjBM;q9y+o;d`T&gY@+jI`(frUK(&1 zlKU&U{c<)q?`r{Hss52}V%f20Pgw8apJ000G#-CdY2%-qY^S5!Oo;KQCTKFSKniaT z;(f-NkbAY2RtW}hvw9?0=U*t&(l8=Z^)o^E=OPMsNXEH>(SVBHP@e`lvVVj(oH#g> z+odH$KJ_E`Xx49TTq;XugcBGXokP7$jmeeIZ=j~%10|H6#kX!6i*>km=>Wd16A79A z-vyJ}A7CD_zTK&N+<%g3Zz~IeY}&Tfd;i(pEAELygP$LB>>kUzAR8gYMc z6#I8DnJ|jW&@e$&6V8cmi051T@KW;yFnil=Ix<#7M!PDCwAW{&fWOD_n9}LsDbYaV zMm!|Z)ovm|OcED=_yJw`t+ zu;*F%FqB9>DcrK$l%!uyg7&xm=w|3`d@*eVcpq-0`{gvq4_8lEy?izIpJY4I8a6?E zLwx<(giKOuf)SHW&}&r%XV#Ld=L z!oTBFcwXf*9n1Qju1YzI!ZJRf&jEGRff(Xp3Bt z-^K@c-+Nj3k1>`P&o?1%yPBZmr4+h!XcNwfk``-n`8?J;&>RVi*XYs7Rc7R+=3SUZ zcOg&9Q~2##S@`*+o!-46NAgztfYwt*!DWagrB6S>&}U=tn1!Elpo9_FSJu;XBV*z+ zy%8SIKZW+H-N2PTi(!9M6;)V1fP4EQ!Tlu51+O;8r*iM|tCPFwOwAA2&D|MZo9EMR z_B{J{dBMDwAGvK?L-DjVHT=zSopj7L1ya>x3pc(+3n%>3BRB3=K=+Xr6dcR4TK(%l zz}=>I;sq{iwm*bsHvA#(*Vl;-ty9H9zYEyD z?Yr2^VbZTh+R{A0*C$C(`?m)@m~m08)zc4YlLhD=r2H$PMS)dB?&DTbMBqEL)hGf# zuU3L1-feWs;X(XEGnVJ8g**7G(aY2JoK~Mr(VD@YSG|Fk5mcYWBQ}U&fCY>-PK=gV=SrAJiP$ zYdM?k%*U^Yh3P%%s79{^Ul}n2^zXl>I@)?$Z^}LhrW_-wst3lu( zr9=mo$KdyqB*Yq?eL$TY>f8o9`Zo(I=M5(o>sNy1_9T@2(wKbM-2}fymxUhjMkKJg z0;C_FK}YuGVl}CS5F=GXPcW}&5@cIY6g$KHc*D zDb}>m2f>ki?#+W^Sm*L1-sACmTG4Dw5<;3FQ}(wY(@=(_OD4eRtF=hm?+JFZ+z8!? z*;K)N0Gss$L4Rl!cVMawjujR1TjM{{4nukJqmA7ujtA4yVWs1H`L>f zELpJH8@A1v!5MEVLJyv4iuc%75wc|CiUmwFbEv@Bn2e2QSH%OKC~whOJZ-lL9LQ;) zBCiMdBV#A#{A)pexEzmRwWhktbu{UuESbmN3+TZ$?$wmd_^D2=cz0bCHi4X5;>&zi z!Sr_bPF%QsGz^n(rI~IE$>AYiU`vUgaOx2w^2UV1=Kffu;!AOM=mJ>k@`7H!!gfUN zzR>Kh#aWy)MH(G(VqQ>pNFNq;TEmAex2gAa5pn*hBwBJk8%2g4$Cf9|z=wZBM}7Q` zU8WpkTKWO;&E;6tZUyA$rqc(HSoik@ALunc&2^VLU_-e=UU}q4Dx(f$(+fq>yM`9D z<(mrmH|rjZI9f_`Zr&x~O3tFJ%tz?P_kMh%DhMF;NuhzMDVffEjJrk!pbOHsvHcBA zs5EP&kMdbIC&LrY=dR)&9c)AVzKP;phkXY7Hd)XF7NJqJWz`JQq*4d19|MrX!8pwQ zGXT>g4K#<{HO@2zLG*Zeu1?*ETvxab)0ksfqw57WbDslmT3*uPd1}O|%LD8`=W_}M z-nd2frg(l%ur($_8=D~4>pFK+Lka)tPUUxoeWuGaCX*8e_o1P+lzO|@5a$_dMGH55 zKz-7z2ic`tyz5A1|L8FC+GTxL8|}__WuMUbvSQUNIwYcHaYs?p-Kv$SHhdt(;h^-D23YamNRO z+Z63`F#XUeWTc(O7>|qK&e;mutZR-V z)e3me@^1P)v;%)_bA~MIJeu`HhMe+dTPM z%740K(Nhn|`F>519?*m86)%Z(_{Y0Z#mDos)tH+YQC=cif-OVY^T7!j; z6d>QdllCpLAUWZUuyi@&x)@x=Ge!EaTJ(l4-@x{4>;0gvf4Ajc#=)LYdJgIt4@Xe& z4o^Bi6Q(7-rZv%H$vATl=u58T%x$k@kJBr~Ub_X#ugQd6M?`V~jwm&6EOuLy%}>ee zrUT3mAFXi&p0ypPcezR|FtvuWN|~Jc(I9-k@11ylR@=mGNe0W|@vaPEo~j|4b6_7d zF4~1O)~92CPbWxvol4*20g-L+5N(ZU}aRbudr zDeMN#I-pBT)JVO#7pN_A5!5-de8ltrAiFpTJ$5lB!{VC3>&|6ic)k&Fyjle*6V9Si zm25nmL4xP(sHCwh)7>n61Qwu3uB5;n-HdFcVc}n>&X4c-OP~WN_2kkTCDz~9I|1g` z=W_+8kKsQ-#bO9@vsz>z9EDRR#A7qrPW~bDx{FpA z6OWK)*tBvs60ARfWim%H4sa{o&vFkM8hger^nwPd5HnaA<+qvm2A{&C_vexepGo|&K5vaT7u z)sU2YljaQe<99#&AnN#O?pC4${+scD|7ZJ=#=X%b2MTt=l8Phr&vZ&87z5;K&s$XE zp+f%j+=KaZO6i>JJaWm?Nfh>5gmf5_pG8NSvztXK5}vv`jUT-HnVQU+L|h9BAZ?(89$|e_>OaFt#cULNzwaX~{*xljQ;EL`NY$bVeTj*9ZMP(3pJ8 zZU*~nQmCnABi277Bc7jECJ?fJFWVar+e`l>nvv_h_h7fiZj{}85)0zwz&@v)?%pLs z+C06X?3ujaMa>z~8Q%rFzm3Acea1SzCNM((4K)ogCKZ{@@S*7xib_nyzRY8srCmYG z2F-BlD)xacgh64+&)PDk97CQGEe;MBzr+`Q4D_}z&Y{9l<)dL~hVL_D*E zvn7$jh#WoQF~16a=Cq(ZnHxC7)gC76##8h7O49V!O=Nc?1+CiVhc()N@zDmI^yjGo zd@Fc6{9P1Go5xm|-PZT`p{DKa&{J%cS%^O8_rWHV~SqYVl z3&)p}l*O7HZpxlvhaI3N^G&$rh9S{)jDxRsJ5fr_9sF5W4R(e#QYpJJWcV`=hzbnk zCOSD_uu+7%f2C6yuZaSLzJv_B+L34K|cWqA)eka|=8*gHF8RpLnKDHK0Xs+-Fr%$FN?tq&PUMRUE z4J#jX7SF>Z2*^7BZ6b%Yap-`(J5F3Q6k1t_(Gj-0PLT=`^MdYIL}LjXJ>S7Hy(>cfCq|@iZ8fY6Ig8xy-NEm6FNQDQ ztLcaTeWRI#h`DXsgWS+CrzY`EqxX3)t}$?epO^CKg{u{KmF8p!y?U3EKYI-8r}&VqC8xFiUx#fS$YZy!P|zSLRA8F?qwEgYcV0r;W0G*F`bMfTHAt#S(Ra1wxia$_mVpNCr$oK_J+t43EV)B3$D0ump{6(i)D+X zNCeNi)FW09U{C0(oq1#f+dqugeTbA481q3R1nviv z71rH1A=W3-pvX1=6&c>bU1eIZ`w8>aOjadlY_~yF+;VQMOdC4M8;Ez#tKtmE!jW&l zT`Gd!(=j7sD(m3)r=6&?^gN#aZz?piow>Zr06v66ps+%odoja^Xpc<+{P7yvR{tE& z7&;%`?|DhB%2mkMY)?43IhT7<=7q-wWr**Cx7fT9?ArnwB#E1`SrKc|bbh_VXFBc9 z1hO*xKBQF^Q{~MyB))5%=#yC|YF6Kk6AHeF_1VjTJtsQMiyK`poXEa~7jjXM^dJCj zURj7A#wkMZ??$?IrZLG`+yb@VrBMFI4R~I;EJ!wV(mXRv3ft@9@~}NLN5hPSs~3v( z*?#v)oWDpxtk3t1qzPecrRVi>g7DZ=($c>HZ7o^AUH2Yj3+_UTE?XYVi17TC?a zvfh~~IDN7mRNr|@3)Xd#BREua2m(<*XNFg;F67bSZkjw;i;F6j!O@p#^h=-=8Tp9i z^!46zx7tJSwZ1xj&HPRpG(v(*xq#qIaHMeJY(4U8Z#8WD+Ja{J-NkBY8)0DOE!y#4 z6*1EG5*>SyiZW#U@Py?9;!eG#8AFJ*{64sIGn87=e)89RlcKPXZ~247}JNTuJIy8)Jq?ma`{R}-}Or$@zwsAEc zA)_SLa3d)T^6TzfKpA0ltMwIJdTk=?UiF6F2xnZcT7OU;*kd{Wj3L>OeF2KAZ=krh zZ?Vf63+UVanwmw8Ch2!PVCS52?u+s@e0=7A@Jy$ge!p5r4AVkHieJ{CWoBb>`0YF5 z{l?F$12{N{`Ry-8(Ky#i+|jfUY($xyiD?iPrM2^(tamjcd?=Y_?Et5bW(oIf)hB0m z1c3G%FVsKw2LA8S22k9PPB#|1VR<=8n0b-?zx-xgh$*2^K4chO`c~TNo81vnaGoaq z7ZQyxPm}_eo$b{8oHVgp=nN|YmkQ7@b<+9A8D8k8qP>TViK1yMG=*FddK4NF%bpro zUvd`d_2=LMTRZSOTutZvA4%68R`dJ6o1{_+8BvneRN156&+|kjArkFSLQ_j3q(zaH z%qWtOD3qwqb6%%Gr9w(O4YY^#p^V@2JKul(@xEMF=iKLh->-WtAHe}@Bf#-h3^!|& z8%oyrAiNch&KbmSlea?pq{sAyPB}j0HV@K6o^pR(k74)NQX!t7_t7CS%I)AkY1ruR zE=e-F`=$`j^E_T+!A%z^dyz?PJXrV0&Il-}e$7?Ot;V9Ilz$|ohZas@c>dlWoYjuf z_+@M>aMxCWhV^6|lY1R|2lWYg^~x5{vjyX zBF-yky*)jyS#SdG#wIz}B^WBbDNj>8yvMxKvM-pUdgbB!oZ=yLr_G10Q=`bd* zjYfv7CS$dRK(W+|7xq+}glH84lDUZdL-O%~Go~QtTt(MDXS->m0$}dV$y`zFMf9Lx zH2;fvFTFMC7dG;>fZXE`=Ji z7MI}CE-To*>khrZ@_=`L`@{CeGhCeW7Cc&-&o_A9Lx1GUld`YOfBrL=`cB9vJ>Fy4 z&SndGXCOzWE_@DQJ}+phX%-3H<|x=;Uw{l%MsUtb_StSP&HZs)msm94gp9QbcBJmDDb%PpM(GgCW$j>T6H9sj^vL`laXu4JFI7G1Sx*+>FWb>#I|)06#RL_ z9pF50>VFS~8c4$q9ipJs0g=hKxXJ5eu*=9j{;?TJFQ`(}skd$v=?5f&w4tBX*hKT9k3c66!yn7cZxT+C^t}QUY;VpT5zvf;lI8%)S3^&5((mNCxvusF}C+ykzksIg=$9;3^ z`HwDl(aqQX;fv1^G+IXU#4f86Q{%TnJtWCD8&6uW4Xy~%sJ&+u;U4)4;tr-Eh4tR} z)`Q=CSk*-x?SJETyCC?zA&lyN{zYO>Y!_7hk;C&HFX2m*e+xT2zjRI|A9MDAnQWrb zu-X7xQ*e#HRj;46H%}rTdY;2PlVY0o^%#DZ z9H;oBDEbJ0)SLjAd43dg<;fmPTS#o(#)T6a=3D&j$UVb zzIUwmKto3f_u7?h$$i}n{M^@6Fn=N86){g~^%L&Ik?HvG)+a&_Hbui2eTo3zDJSWT zwH4Umj5(wYKjfUJgktkMpZNu>cSWyRoWxwS1IG)Gcqe4#Nwk>_++``Kc=LOBMdmh` z)pwT`E?!6+E1F>UVL6nl;fCK8iNkTW3GOdDg1t9I!o2lkDPcV)rq>y^iz?xZTjTKI z<&r|K{wP(HxPD>Ve`#h$ZW|c?yx##SS=V@*d$h?w)jPP$dU$eG9^x6lk{q`f+ zH6#)|XPn?_cI-ks7PQmJZiDoI{C7P2f}@b1SNfLY?`t)| zD(uy1r(eT25kJ`>h?W=QDX_kg2{WID_{sjAAbQ z(Q|xqtqJ&^Z9`3$U*i9Mt^(r+)pV1rI63{t6Ur^FbEo!f$2xV-`6Y*0H|a%DGHrnQ z+w0d+$=tno)*BU}j;+i@|J71ND|% zNN$~NVw)6GILW>t{OM>6+miT<`WL*w@8hhXcXTS%+){zFu9(B~W^ZmAwZqf6N_u-!G|6zNatvFd7?FFqx?|E<1*w*U0Q&4<35EZyS z$Fx%x#8)*@<#9SB-;VwN4JAO-r1ZEb@Yb<3=0BcAX$MzJ7-OEfa9m>t38aY61MbS5HMhX_IEP4!Gia z1~o|D#v)rSV5QG1+9Ya#AG7Sk|7$7bsioNEj|q%2Orm(D7%`9ZfP##6ZgNgIc5$lb zi!)!MSEdN*k7Ic#%NU;b7geGxQw5Fl+tG=WSyBh4y;6%Vn-YnLO?r|>x zhL8E9iK`yr?70&mHJbUFsLeF? zJxZ$pv#UX9=y(E7zBm{DDK*e^#|oTeZ2>Js>kNl7w8*yW381$>4VljPfb*hOK$cY< zom$H@lfmh*cK>d3pD@Km2V!iI0uW`L2+izS7Fb$QmCKE#QZj_RxPFawJ8C z?bj~|rr$;7$r4vPP*u@DucXJ4M&De}e^N}7Yz>It>?Vj7#b`5ok9*8^h2CYC<-S+d zCDMEDgU{UnG@_M;C$aqzuc$^ExkHvj^|-?mQ43D}dpio3*X0Kv?xAJ@+GIrUBXm!V zrM)k7$>E$@Sn$yYm8V?5x2tr77=A8#1goS*LE0^8uAKE#-9L8^>Ru%y^Xe*mekB%S zxTm-**mx85|@>p`0*BJZhq}P;Z&C){q#cHo)Zr0o3(UK0d@c#$}NN+PW|n zXWy5F0ET-uy`p5oId52?KFY{VbLg3k%g--|>s_w@06cgl~F=%bf|tMK^ZO`!B7l`dH#N&>cf z!AL|KH|1bBE=q3Vk2=C~AMzq3f68j`AByIw*{Kp|g=&~!+>TC-&B899whMdpgI9au z)%pMUho*MXYp?#`ed7*6{*iFH6)xhxga7!Y4?Cy}`uwg&N^%VElu`tvr|mQ}bQmWsIRMXpedV>i)*^EAufxt!0Z6tz6W_8> z0$bNcs#hULUO73y2k~uO_u0)@)k;q2yPo}5pV)de1E&^7`xF+C(`#NsvCMwtH$MSi zOPmMq#Tr;&%`nclI{@Bx2MkB$X^{ry>u{nZ4P7a0!O04S;9^lnv1U1LwNQb!lTqAP z)+LfZW-FN8cuh6g=1wQegFh5`%q7H5!*oiva1(HQya;*sHU@eQpJ5x#OnZNH0Cv8u z;oL`#V7dD}{2Sl9>GF0}BA2@lrajt)S~fJ`XEo>Gbaey0eoUXNWI11@|74Ma^iFKQ zND_3}JB}K=Cu+qVgZvL;>Eq~gczxF>i2d6^?V4E^w4En}O|~^M`%jU$mF|H3tkZ8{ zEYl3#I$=@Db)M5`9b&z#7L%iYQkyAOh3isO-@}sBpQrEi@Y=1L=`KUvvFJIJHgV+mXS5LyJ z_paf)>%Izo*LuE$Ej|ru}g%^o6R=hj#$uj7kzMo`wUp}yNzCQ)+b9+n_$_% z7M=pTO>7)_2}?y-k7dF$Y~X4J-{-%kTZ)JAjzb5)ZSNHBq{RhP;4IBw$GqYYDMsQ? zJ3wFNQ(DVz#CnTWz~gcrH&G)Rd!{Xcpg;Ar&t0Ewe>cJEPm{R49|v*t)RVw#_{{EW zdH87`)5^YIr?qv%xcSThn4Ec*lO)#Ie@h|%+~ppsD=SN;-|+;sO952ulq~tPI1f%A zD5iRH`XmH5L5w6qse74je{~&1W?#v@mZw7$W76S#OaRJdn~Xk+)8XzMmL1lRA=6nW zz^5p4PAs(@-M&3vh|d*+I;6Fy6AV&M(U3Uyj@DTVp#pED_B$Ro2kJs%Ap72h@^Ik& zbt&zKxHZfDX57*Rhp)uKSvHo8S8*bOoho#cw{c(3VqWqBad+5%#-Lv>Vu65JL zq0EDEpbKhRQ@D>v8q42G7v^O?ew#@a$M8UYbuoP*!^632*F(_acigSw06eYzJO5;I zCmsAHLZmvqVGq3H4KdHKb>ms+M*Gmtv(IqzYz4NF*F<~#bcoX7E|}{u3e{FRV3izc zxObzA-pW});^P}w*N`9GE1r+t6qt|}CVOanx$S=E1vou9WRU+dI(yiPF?{K{MSquLObkSic5prC` z6q2UK@M`5$$v@K?_~hJZHfg zMsU=uLy(ggM%_a%;u)f%5O}MD?v@rM{v~GcNi5Q+@o*oCT9PExOs*>_5i^N=P+U|* zv&K9lX8+j;4s?_u$C@ZStxOT}yxVEvwqYz{76L2HzVQx#7C9832)nHV(3k_6c$NDk zc)F;O<{BuGc0G5n@Au$7scy#Kr^pMv*_#gQ5pH!eNN+q!fA$!VZDns@wB3FbQGFG+ z+}41H{q^)r$S@Xj4T0q31BM%mwaD+wiST*qeY7s91wXuPB;?!M!ppJt(it%BM--R* zGZCxSY=!2Huj#wpdPG-~d60A;ah3klaE9Mg{{Qzv@37!u1?>&MLtAJY5$aHI(Tn+9zB?MAKN#rfxR=z*!P!h8+}?2Gh?kd39X&zSLY{T z=5f1S4^Ftxy22J_(7|_6*m%WTzMXX^jk%#imaOWAxb)vfa~vf|f97o=$DWb(44d+8 z;iSxMYN5x&A!9ed_SuQtIjvQA$}jW-FH@p%%0y3XH}M?Rbzwk@3+&096Nu_I#QW62+F$u@)x*HBpZ@%LVWab zqKtny;;a`KrD}2e;Vje1?xFt$|gnuWY<-5iUtLfqm1fXlcSf z9L%;k$n>k6Na;45@`Ca&GLXo_+v`-}a%~ZIdQfhdrUc$B*hu%aZb;JlMFTm@X`s zPcGXw!HF>(Iy`}gmkz8K;&vnZyVI`^;OyG~~Gp`qOy{dp3PyQ1gA*CP$oWI7KQvy9RY z$G1kmnKoi^JsqU>+(HtY-(Z)+1e)Wk>Fdj5$m~*gC}>RQ?wxSQd+W3Lp=I6l~c4RZ@bO?VYuBe?Sar|^3Q1|tF-1pMPzd;Q=)iSMM2Get0=SPf(mz=`q{6uyJnt~9PGH+f-O`{K*F^=vE6MzSjo>^k zfIj=cy6&0x_H9T7647oqpph*?`ecyh8YwNBz`V!q&@1N7Ek9?4XI01xd3C?r ze4?Jv45H>m?gY7+d`MI{(;Rshe6usJvT@X^cw!k_HXbhWW2J-DXI*E`w@iUGasYQ9^BGxjYZwzG(^jW8d=%{HsV; z*A_wFq(PKheinbuVtypHTQ{2R5Y4UegwLW|jMjh-`MsbQ3eP9gswkY>Pgxw#b6d4J|H&UUxz8bx~oQH39JHgfAJJis66&`)^1z(kA0lv=`A>x*M z;p)^tTBQAl3@OFUv9DPf(RX=*4hKlLYJfSiuoBbyMa17rtlAr9`u6#WKB+Yc^(RxHItwI zw1?WO{lOmFnNM#dmCj%u?*(l=khR(yNqs$qInPDV@%sDNndx(Uw8^0|3cIrwV3 zIlTPYiY$f;@a6fY&|&bFj@klc z#8}xK^8tws-|i>6cJfUJjmLW)3m`DyhVn5iC3V2=LUW za&OfyAVIM#f6~_;nv^a>;&1H*o@Nm(XE`Qmmh&o8$>(Z)j$^UlW$=sT@?R%?=K1>ue;_6ly)O@ zE72Y|sK|mP^AC%*=HZeUOCU!j(E8yMI7Uq#Or$z!D9fKls{4R)khoFfhA49DTPLLK zkjG_)JvjFIawv|kr}9U2$XfkAkUx43ol8r>L!))@W2vmNA=0oPI}s0lx*A>0TVN#SnuTpT&ExorLi5f zb@^!Wt#}K=_7g@&gL{$k(El*`loI1V={ztiD5R&`o)Y;9_JXXyGBkcw6n03M0B5(f zQ>~4|cRBL2aw&2t61-`7C05xQ|q(Cc*rLdq7x1p@|Xr* zeB>tNCf`S6Za3rPWVWX{zm6^sD93j~)M3fmW1Oi*BA)iw7M7vc^v7ErqGQ<%)HZ{2 znlKF?|N2arZG6t&F~`P-!l}CV+>LpM@%!LG;hoXPM~ZCP=miEdpYwLF&?1ibI26wf zMqQD$c&q7ouwZ}3OH~X%*)#tQN~5XkUGU*uqd}v;lit}df)gg3fSQ+bbl98ri#|`%}Ax*eeL{!XZNrFyQu(UQLd|^Gs^^E$rP;vqGFaJ$DCs2CGq2 z&vX1d(+PgQNu@~_jB!^O+rQTArCEFa;hT4TVeZ`k`nqp~6i>AmG=z`GG0zh4QqN!f z9Hz+#y7!T?Ng9I3;*scIQV@2tQxWPIQTNu6rN)EMoIR57Z_YL>9`V3H@j6l;Ny6Sz zvmrOBj`qJE!Cu50lCNrTr{3kFaC>!rKwJ;ySYCU(&03i8<}Q5_!~6*ueekZ?8!g;$ z3b%+ZhVLKhY3H&WoYJ`#0`9k>o?*bXjV7?e>oq-;J%aaWc*AY(GS^|V4OdSu;HxOJ zXZDRJg^UO0o%W;?GrVwF(M%!6R;IGQ%j9NAud?F(D`)!lhjP&UehIy7%fV-oEuj3& zYs#?8@eKZZf2T4=&HkC*L-f`$T93=v>e{t zuBX!;>yW*3n_=;jiCl)m0G@l{6u4Du_Q;RmcWi^{?S*q((A3S? z?BPrP(Ec9!IYo*nGR`(O*N2W8k|xm>Ja}`dh>F?hklsg4kZELyHZIX2esP&_YHA>o zw7H9CEuR767aM5z-O&Voc|gl16K?*YHk7(-A^#8Rp@S@U99Py1`|YFX38tOemNdb3 zmAx#-a~^x_)Q6NM4b;h1o9N|cz~u3)(;)Q?Ug~55yz4d8%4#%GckzIWp=lg*8sWNK z&-rKP^w6dQf#gQtJc0eTUQXo77%bkL!N1bpPfa>!5LQPAH@X~Lx{Mv#GpmZb%C0OL(;KcD@!MrPrrGv;*1x*2~ zFh{|L_BiyLEQCaK(Kq=k$hYnfLJfIQo*prwg^=jKA0?-qz{h13Ac6JSO2>@go=_i{ z`dG{;Fak3j~7t3Si>)p6oawVv2sHaH>bx6xlKkTeIhsJlL;CNSS2&}E3>&Mj- z)$}ldch7D#Q%WC4&MV@N{@q89@+$Czjn?pSdJ5A3hp~CNH@Ipyakety`0u%oLX357 z8AW25-#~2QIo=FC6_WS84u)wv@}77XZ;iJFFOwUTmbv3yuf$-lZzs*XH-gjJkAlvo zaB8sk0`{p92la6s6!8>^`d$xs+IG>XTC5lCsJSWBkY8+@K+IQAcyC-t8_KfD*>HP7 zOnNC=!S)9)uAB%tO>Hzdau~};9tG#z@4Pi{v@@aHbZ|=x7$+a0Hn9fewR;WB+7XQM9$vwYN!su$j_s~y z592%6kAm^y5JTHiEutcR3rc_9M-k3VxY~)ppH;OqaTmKCPn!*E{Eu;+{Ofo~!CuIF z*Dlo|5nKy^S_UT#%2;2TWxiPF|M?JYl6i;^IhzXT>;HzaHvcGm*iy?)d~gV->3K!dkilXkqkCAF*k@pPGk#UB>sj2j(V+AR(a1#_iNJn1#jPV=g zQhxDXmaE!5g6l@@WxMUZ)bRQUncn9hs6I6wo46!kD~}Pr>)Q_cX~RBJJES3K6^%qY zC4=x4T~z?a8=oCABi03jU{N%jKZWf$`{6sV?otfvmPx`*!?U4qXB{14w+0&xACMK* z;7m^BqObR639)zcm46uRTLouVtB$ zlim=#g->;6mE)zKX2J4j`P_?>$MAUB6>#_<>)Ji9Lrk(;AY))6Ct1^vAMH8~&t7~+ zL9L~Dc=rytD|?^nP9DLXuaCm)mUCRyn9X>?-csRRZ_0itVwu8vZ(cII6-XG*^|lst zE2`ikdug()mj`DIi>MRB-iF;RP?%qezN{C;S#)%~82F29iEI4Z*wEUas-P7#y)WlRtZ;pZPpzke#>qFfXQ%e%w$=hV6C<1iw3x(;|Ot ze_({)e5{j>_zq(QWgn<|T*=$Pb_DKyx&Y6=2cbiYa&WHV1R)OZ_6j6%)*6Cy*EsYP z+2fowV*zD!QIGhQhJpi+mduN{C@3*%7s=M+5ctu@f$3TpSOj{N=* zCKx-k8wEep!+Vw%@mn7D(G2FX;n`V(Nb@af!@43>vV36v)h5niS~xzq@)Lj0=5ERl z6D7Pwme9QEB=7eEwyCtf9-$(p-x(D$8b!&6@JVOrI9D~$*9jYpmB6RsyTcGUwo$n=6UsW zeZw#wQxOJ#D?F9e*16IF8;C*EceR_=L?^@@;?q|n1`;FJ}-6;;h z%KPZ&4LW4q#8%)XW^f7zm9eOPp0Ha&d~1?%(q zCIxR=I_bDdOl%ccf3lJzH8@&D)Xq5w!u*F&1nVk4=OhC&zqPZSsZm7ih8Nf*Z#2qS zfXK-!l7c<2GI=jmbVykB2WWU4k2X4|;%D*Z&^hA;6kB9)(?&*7KLvcG9YxJYqgSTo9ie!!@&Qi;=*4 za8R@c*$(93)c4M8bL2K%zW6PXiu4rxXPk)^`5EKBw`KgGx?aj&^6~QNzVP()UOFak zgk;Zf7R1z#$0}{#d=8C-HHN|DR!+lg%7C}bYcq2;QRT)73IsESdKG( zytbH6HG8OR&NyOv(-V$9+(Sn3_#bG6`t?fOOVfUQY2g{z{`@mCWF1!LMZzIuX&jf-WrgRc zzv36k^s+AEQKYBJ8zLuo(e!)?WBJot1@BB$Fu!CBnS7eUw9kd~3iFM-&T9pS8Ad3! zbPG|uKLlC2dU^e<7x&4p$KXCO5UEbOgID#cfmUWcoo_8k(j7b@Gu)V)ZQ6=fcP|#^ zTqgcgA$l@R5dJ-!zB|UeosO+=-_aLkXr9N}TNc1(xdwVy;T4I#vQx0^R6D24x?a~+ zJ%%OODX2880?Q4UK(I2~O88HL6lQxs>*%{&W%VBXr!k+u#-)dL4FnK1STMt)zh*Q?0%j21=6m>p(f^wM#eU9eS0PK7Ox|`X%T|%qTQ(d{d~Mt;RXMJWgi`1 zQG%7qtzePh2DMINJ_lKUuxo7MG)ls7X-F5JZttdx&QB+i+Z!SAS35e?ehu zWUAkvN1RpN1Y$*3kyhaztm!NPtJtl_@ZfL!_9WZaSQbIGyd{m71soN$XH3Pf~p7I68QYdr*H3&z$TCrZTUo$XXp@__7W1L^C;C zqKsGX&KG7C&Dplg6)OS!;tQzd)Dc`E8v##@>bU1^A$WGlccDgcQ$&*N6Y&Nc^K720 zBl``CJ_%L34j?s&8eH%p9{wcOQ5Tk>>wMD&B?n~C@ku*yW9JwMo7+X>2__xO8sN%D z2YPntTQX;=qfn#RcJd4kI3z3N&tX3#hz-j|{V=vPy4h(&6dy?nc1dOObU7VToYMv? z=Uza6-EZS1l53%6PceOczl_*Q?-J@%puUI}ua z`F>@`4RXHgqj3G2M*bPL3I1$a9?8xN7ib@g;dV-jv%Z=%P?}zYE+1ukkxkCv^D2ev z{@{~k?RElVX|`n`WsG0VDCbMQ?4{#8hq1n^Klm#7(wCLP#Ao+5fp5%soG6umKllFQ z-~8G^PkZ{2=S3O+^fSLdoOR7*7J%cTMD!p( z5j%>_gI_c1=n9q-(a7+JQ_nQG??0X+Q?t23UVZDA7@1tP1v)Ap&?656h^D=k;6~zI z-jUy#Dryk7R|8c)&6DqMCM1mJNXLwSpF3Mcf?Yt zX&f{h!4|3!Fn)(J_f#q#ovKsd&wJ5B(|Se|Zka!{NCQ0`wPn_0E$An6ed=dbD=l9Z@b>hbQj#~xxCDU*!9zzn0_@IzjNCoVDTt=!L%pMw{ z(N@+Z@b?f*wwj-p!TS9UcxOSCXCPYCl!~+FsKcg0_Wo`xK@1;wLJ3E>PbsY^aqKdF zu5%9+@0>=s!Uo8R38Nw`=i)!H9X@>aMSF_kaL($5uyugpSam7!RdN&TywS!jVeg(r zd$J%v;WqnBzQU_7n83^>Z|V1+Z0Bg6C;S<8hf6!X2Y-p7{C$4R2bdZ_vZrVZewy@g z?HyA1^M8-|g?NCz>Qy1QOaOOZ7SKb>c_i??jo@@!4H`e)504%CC%pFsGR|=2YyhYq ze$7jIsYM*lT!E#v`%zI{HuI$`!TFmFH1MV$Y0TFY{JLX=)Z1*ar-{7Kn_;wJDUtox z3bVp}>HWg_u)Q9a#TA#$@+F)d<}r;Ix!<3UN}jb-v_Tl$Ku6W z-8jw+3%i)Mo@V}P`)`o>Jq``rO~J3e*@E5IN?Ik6M!3I0tmM?tysam#_1{F;P5 znjlw#SLbYo_PsY~nNJ1IY+nNvW1ezrZinHmRy};rkZ#&;H=RsMYJwo$4m3(*4_-W0 z62!DR>C;rElcYunJ#yu%B#q@=!vr7rQ}L6Uc>GCpv=FNwY!)SxvaO-RGs@_KXE&V$gV9xutp!wP%0e>Hj{PnVnxSPS5m>5h5-f>tqXRIEWBVgOe(ireXEAN^ z;Nl$+s0E<|*B;<+iPPcft$O-ts~q`|&iadjwsWV-EO87T4_a-V)YX}JAdh!I5$iGI z@10MglHP-6+&*+V@iOjBm=9rF>*-?FA97zR5*EEaWH`P?i>&gz1BI>WC~|8pzHZLC zF0J0t*AeAdpsoq$CLibaX!OknzwSQc;lPAxL2BNpbA9YAAO zRAZ+d7htq?9sRzUX*CBr;7O?rGM>F1H`y~y<8~+A&p2~%HtYSH>Ohs$tH|;OXMx4X zA=HM?;Ek?hVLi+Kc$JHjv~OPE2kVWlUN9sjS(1Y9OEP!@5gl?^rUTxrx`3RGZsWR5 z7Eo}NWp5*PASaDMA+Lt$YTUkdBg_rDLG5+^mv#Cwv!Cmfioy$eoA~QLvYy+%0J0@t zTkyMNAy-bth@9N7EE~(UVV#|Faj|@3@IhPBdoTl?whm(nquW zSifsVD_XsI`+{pUhy=L^%`k#J6}CVZi(}RH@+9mYXFw$v7stWnI z#@`J7U42E>vxYHYSt_&C%Uu3sXB_WR!r!sHht3O1%?oyW-?V|NxXgzBC3)W%YWb?tV*V73ycw6+g_d3#pK zv8!VWanJp25R#HgyX@E=Hx~)XZ{oNkN35`@MJ0cWBjei=lB99=Ubc_pPSf{`8>gk) z3j7vK$E$BkkvPf+w?&0CWGw4Yn$`g;lZ?>!G%Mowa|lkY)y*^alTXBtMwOEbe#0j~bPdWBR)U89Up!0oE%Bec7;d*KOnuC3qiQ4Kvh3KA0rxVCdrIC|6*A>W=Bq(b%;2tdQJfEqKb{uW>>NSAt# zJac{VJ*@FWU|7Yg!o!$g%f`A*oFdv&e zdnxo|EKz)gT^wzob|9JljjO?=H6ox~pd-#IrZW^H|L3S|T)P={Vc{jFB zCusw0JItg5Jvh;hcm0fqvP<>UsA2*6^QRHEB}_n0s(bKPBT1ONtdl0?j9@F@NN`t< zppYAnB{bPq?6eM=H%XFoI5@D5`WU03Io;@`<8A(q*ZtIGh9WsLQ2-@l3g~@-0a@(b z1b!b(QN#8KyyNs_D79&$TX@5Gv1}CJ{Qr1A|FJId@%Lcri6FEeJ-`74Dv)=a-SSk% zl3hO-$F6hcj4xW^eG4ZDy>sfRY!}kIHJnHEk zrVCXqi-LhYhYhm_S;vUPJ+NH!fQ`u2;O=Z=u$)^(w|bRh5vm0@R~+YFwE>Uv%m4m=H;wJNR68!mNCBM6yZTQ--9MBjGII_`{&WXN? z+oi-HxT%Bg^$x)Mt!BcVy=`>j;sr$ePZP+^j)IhztPjUbt&hO|A?aSZg@WT8?G33g8NnvXo7w@R*2PtF?Br7Z&DP# zf5HgDme;ckK6}^e`UvMfC~@lPz4$}?Imk%-jE*fksI^LpwqPK@jm_kySdj@u&Mih5O6 z3ORPO!BnzXr2$krL+OlU9r7UY6KKr!N5^KwVHs{Qh<&W5+iiZ5?Nd$*8ck(T=1pxP z6Q2V%mA8>W#S8r6>}nW;D`;GWC@F~c1cw(Xod1M9*sn>z7fI@&c9Rd0j~NRERp~#t zL`y0BcPNX$&USzvJ~^HE%q|3nJ^@WU^PIS=*$9R&Rw4gCdvRQ}=>Kq=bpi241;d5) zZ+Q94H@n*Z8t@Z?(al-e*cD9?;Aqo{GCvps4aJSrYd+$g!5H**yry*d~hSe)uIO~;RxcR?+A+J7RGm3PX?*Pw}=Xmd)Oe3ZuAK<7{2TC(-!^-n7f;78% zDXAC`OYvqHT{<3>EZdDIrjHVG@2F@Ivfe%hsM9fO_WeAzdL{)2&bL!FJ6Ylw#X2X~ zpEIfo>OzyJr3!O}|Bj9$70(5*@ScEvIKjOADQpwxs|m7_iohB!Qy^wx8=Y4k3*R3Eppf26*y@fxtX@`6KQm9Vg2OS`@#(PPG4{Lg>ueenq&z^# zwg&4euLc?EDyrdHj&*nGK=$tAocgK+w!!BNrh%38rne5cJEapAI6UI`K2!0nGCtpB zOdoYK*C1VKh2V1;=q$|<{LAea;KTKt?%{*@Pt!2};-+ru$rmMEN#4+S?-9?5@$Hw7 z&p=_+L3S^=iD$&^h6j6Y)5{_3Zm!)4s%K@z~6#nT%y#4L;?dzO(o<0S8CNQw5DZir;D>5g@!6kZFv9k2 z4l{t_IGl2B{SbsR~w zggjieVi-H=9uRu%1|~g6&s4R9cplGmlKFF47XI`@YBANHM2YGOyajjB+`$w0hRF(; zq*G5fv8|jXY_q`Ptv>hucow$&xCv^+S`j!r$F>7zP`kI3sxhtmpyUDYoqdHnJjDrD zu6V^?(%VfZ9F-?Z8~osu|1NrUpF0kGJ6D)t(aO{zPy9MTt!N8RSxtw;tJOk{!BrG3 z`v8wyzzzrZifKnC4=-Uk5o7H>quJW$QDOOb{_?9mwB^$f-sS5ABk}j?_R2^sb&3OR z%X)gan03va?qpfENn9-32tZRg?#H{oUO zZ~11Ydg&-XDdIJFfOP`+(kr9Hj5|--3s(0jTzL35eYz zHjq>Q24TWctvuOH`M6Ql0`9txM%|}wumY{gLwI$799FNlCC?f#`phM zS}KwDFj9ynnNiPu-zbH$C6YuEEfpF@g_ONZ(GW6H*?j8U=l!Ilg-Y6+c9C7^cYn|C zf7iLX^7K0I=QZ=?(C7aQBl@#JK-U-&eHzc*+u0g(bFjDY&jLRo#!LU~5W88L_*o0g0nu#k= zzkwq*@K6%@?pDp5#`>QZG!HcqOC{}h!`=C19mBUc7OD%vPMDZq{F^SwseQtiGE zks`hh-uEv;4=W?^we4D>JAA_o0p3+;56;P1f=or$QLLK=+xPE70VmRMx1uiS zI91dBbU9KJxC`o2*!sy82V9-0D#G)PvBpG6wUg-{8GBSDh>|`H$%X#H*^%!7Yf8X zA-(khSASFskJ-Ts%h@*lzN-eLeornen!`L-MgshRXB#5)2Di5?7zb_rBkD)p5i3SC zGQ1(*IaBa9%8)Fbe-4D&p(xNN3H!hC0R6lh)Ge6lo?RVK*rI^U(p_-qW5#1M&ScUw zj_hh{fMV;7)KE!)r{1uK`oU_>R_8QU6CVY7J6h<+NVe^G+8bgn+ga^7q(K~dYQX8u zDZ%v>EOYm$1LR{bqc|s~iO4R8VHJ5)o&QY=tj_TjY)^S-@@BNi;u}5b-%AfTmg4-> zRS?vaK&>ASVR3sekeSoLy?S{B{~O&ZB!R3S00)tOFU47i4$TN}Zh-<9-1A@l!i427)Tsa&_?b0i^QBI<+5hNq&)vkJ z$b^r0bQ|rzcpN*-o(~Zds_8bCds1iJ_>-ijal=MF#=gT>Lq}sHidB7%*IL-ZTkqGj zk7=Oa-9zEru`8U(#7)@FphS3cJ=>SD9!cie2EabA?euN#4t)KLfr$5h&hiV(=XFB) zl68VNlbL2$Sp~JHVfy4Udt9={BMq*gUOSIM3ePnP4DufZw2=)yURFTmr6Z74b^2U}`w1GQ$hRbec^ zqhGT3tS_6nXAvv0O?jE{*ZyvLWxf=-v}7-|+V7&u?h*^sS8w7~<8*N1@gzL@mj^t{ z+(BbAj2RAeg3Mj!ZTq~GG>d(Pp1dhpt6s95j(N-AuC)yMe)0yserXcipI1fq|2Ks5 zR(ZjK-}AYn^Bd8~DV)gHw>wRPn3%AUcI!j*VzMzgq}vI#wgJd`)j51seU1pj2dj7z zWwwqdyY&J7xPV293JkzQ$3 zv7gw;&gR!y{^IyoGI*uhQ{mjHeN=y)4w;+z5^BYGI^*p#qUPhsH<*;7UJYL?eMAC` zG}|de4d7*3p-|oSPN2B+fM>=UDbL;k*a^#q#fd=|%7moOol`v+jpiHm5;_!Qh>?+ha@zM<(lW@IYsZ#j`5;CwPou)@V6VJFY- za9aVs+iVZL&tqxy>Os7L?LgINHgYz6Nt$N0DH$mmuE-^s}}p z>0o!ho$4YKem(+AuF@7^_?-{gSa#fU5r#YK88O}MJ|xHoAxV=otY9_)CRkO|)&s+d z3+qN(tGt0TS8>1-cB+XmylI#*!5eEJXh|TtH#-J*W|+fp?P@wqOn?_ISq|yfuw|(v z`^?z;5VANOwHz(S=Z4$BgKoBC?i9yLI9*|i?Hek7&Y1YT=>lWNhn&h1EqpB@NBE_N z;r74D^U?t2*w*a{t8<@cF+vBA>3}vwhXps2>SOKlGvE@ zu-`2d<&Y#i+1eBK4ZBHIjv14$&;=}fhuqG(;At;Lzai{0jK^E}llE{KXTFd%^rCZQPmkBY3s`Ct>Vuw%OesM5aW~ zk4XfE1gGp^Am8>7YJxK@Pz+yx0-NNT+N4T-b zLvs3(JUO<^7gpW*kIFCeBQ@5hyo?juUt4pWale)#&LnP@DS0-r9&V2_<4(jq!e?fz zfqkzUky_<5j8p7D{nTrklg4f*-vf~N_zHKyY7=(WdnQ)-9^0!e(PK!Ll3v*W+<*au>cd`XX$& z*@mX6zrZKcHh{i#B0ZDN`0eje@LcyIC(vJsO_shF;qz(@F;ds#1EWv7(NXsj@tmDI z;GN_SIwj4Rtp3&ob=s_A3@;_O$9)02(^Im%bF=WaetU?Bl0gd>uq=jPvIvu7PW;7B z0=!`Joq1feRU;ZLg+&>|QUgt59>(@+#lvW5Hp|w@b;HwPf#}okvshDQER$U(&9WI#XwE=JR|YVPW;$|rD)GO9~|;& zm_%b zonKqgSBD0CA}$8LHp!x0*Cx{TP( zb>xTM{X~a;pT}D+%R{IM^Zq@QCDSK*LA~B-D}UzQKYQ)Ah~K_dGLmeoduw_D)l08le`Wr9@R_(y9ThseYR^;{9EvJj1f6ID+7K81R;|<_praQ9z=ev zqTMTGNlG8<{f=DE?dq_{mfO|gV2>M6%hJ@!3-| z;0)VIOkXpIr8}ab#Qu=w1`XEFHZ22I-AhNC89x84Tnq;nmQuS}EMvtqmzM0uobdS- zY~;i4#@{9MfzcjP5MsbP{rbn1eAL9LNiT)Xc|G*Nw8><5e;zz?71AbyK}_C8!`ti{ z?wwZvM0n%xIynqy5K+i z6h)l&*C}(zF#Q@ZQ(Qy8%D*F_%G>#cd0)_5yHmJ3O$nZNG}Dpa{@{TTK2R>c*y=eq zo7_~B=AQ=L69fh_toCMGLVhvm@%tNiO!F!TUYbwS{%uA9kABfk+DF&lD8@&l*^X*m zJiTyd5XV+{LDu3=+|Gz2xKy!Sn9e%4zo|YT`y9ggZtWx715AleTPd9Bz9l)l`4}o{NKb>10i=7@xfn#;1FGK@%3Xfd=eOG28Puj2dPjUi@b zB|X$QfN$+O1dC$~xv!?rk@7H85eM={Yd9%h>J2Sdo>ALKA2NE8DQ^*#iu&uL@l`b| zSU;kgcDEXn`6l&{ZEDJSm^{K2?rS0ZNh7k9dXD1{FNIqZ3TPbbFDmmp1Ub5KoNcf( z{$l@5xOhhwP3V#(uURf^S(!7vAn?G}_ESZ@c{1V)i0vLJ-l1Z*V37HC4s57{$`b)*g?*qF&#_>>GbGGnx$ou`ctlf$Fy>k}oxpOD(V0GQ;g%~+jQ&IB?%TkF zmInTwl7N3E?Eves9#qS0FIjCog;x+pAs>$3F$F{B_Ex5yJ4d~?-BH}up-_angJ6V5z=OHSV!@5H&dte|j5Un|P z7O(s_7oP2}rf=U4l98ns`Q9yxNK42xnr{MFKP?sY?&9%(BWxgQOaWctIEZVGdBKzD zBu@M)3tPLoXzEZf>57`ehmZTo#ZQpIevQvXm~1c9B5R)HLERLf4-}u0#b2HH z8LQu+uqWQwGer_^_qEX-jB|?^I0WlDN(E&dY}aGgb?6KTL4RByVfm~v;2BpqzBP0h46 zZvYD?hKVxZzvUWnl=woHsV}1zZ;i=+FNeUy>k>-tPR5rPZU!??b|0Tv0jM;w8i+UI-tAz4DZ^Pzk!(m%~8~spLM)o>8 z@qf<$LJF78b)%1#&K*hoj^x5*U!Ynn z4<#$r01rwRpjMd(yxw4p=r-=2&HT(2nec2xFnY}E1#aJCoBRdnP& zcr3$PJk(*}ayvciqfd_KHbcw(z4QaiJ13OXL$B{1q)9I0Q9EaXMsgKZW<1HtyP0sg zKOG$mFT>Gn3wT!iJE|zncFKBo!7}ehoT<$fmP2#{t@aYCn;$@)zBb_NC;a1%?AF9v z&gKg9n6Jj)c@jAu^$NtxDP29d4_`hh2LHp@KM^daP{}rHma&}|wl{G(>JsEG-;W;G zU&HM)JlQ5l3KdxGB_~6t@(PxAsB-!yY#={U#ACqNSwzXF8V>5NqPGp-kos14{+ZHe zB(8A^|9&wVTEtqYTgw3EIUkUIWNo$L%SE5_15`Qq9Kd!tF%{;vs8CegAu-AUc8^#f>g$vuSQHRI@{I$&+A`?Dxe&`6^ z|E@zA5#K?_#bpq4<8VHF-C@rAn;231kO_w76)5S?ZQN7q1T}qe^r0Na&nJEmhVAL0 z_s6pBt<*4B^E7~(r^RB6a%qStYoR$Wl*y_5Dsa}DJq!lrj5xCs&ye3AQ&Im$=6qRlRM7`~ zpFX9w2Yg6Rq#2*|B^6Ech{gtuR^VUBwjr6Xc+H#!_^DvZ@xq7LGG-kdztM;qRA1oV zTOD9mW+CmB9mGH5!=Nc7j++_bj05JEiSFTp*JVi;?*omGoN2zi2TqnVgw1`;bk|i( z&V@t^%<=U zKa5S*FA#Y={;G81i4xwpktjJ97=M<#)gl{p~a)axn>s_zW%vld~55XGB`Vg`mnbFZp9B*zeO6 zD3q_F&z}w8(ds^M&eVdNG`9gIR4x$l56W%oWN%*s48$Iyey@y)L24gZTJ1smzMjGT zi58%tz&PX^1Ek8~62DDK5v64sk(v91@N!Qox?d#3v(;^2Fh8FTYZ$)F3ZtROo3BfA?RP*L%jdP7^V?aQx^+WqWrH0 zU|}z(v2!i1tx^{Gr9D!NNzT~@uzcuF#|9V^1-Z9y#d{xGwe%QnZ&L@amCZC^$sl&8 zVc>CJ(n_Md9ycFk|1VP+pJ`!2cJC77i<>T?7gv+ znK9Pi_*VG0y@&2TUx;m5w!n@ZH>hqU%gaQBfpc9Wm%ks=c9KCe-Is%j>x(KFbqmuWBO~&7#X~6a3r2ev z+`~G;i4ejxh#8X7M01-L+z(&NRjply<@aicdPgU8=n{n=jWBCp07c5iWb?^JI4Qdq zl{H_&vpr_P=aW^`_S8CJJi8y9ztmb<$Qh9X#t#9Z43t{<7C-v5m~jGcXh)S4G1c;d z7kUplp51BZg0_N91H)e9K(c++RDS)GA+Ew%6R#S~6DmmeQvZ7s$^FIoQ0PtRq@DY4 z*+y~5KiWad_1WJ`x-X=qqzSCA8K>MuZDGV=yT4-AUXj!P1uN z;LOZxv>}l_+mroZgXSmhlhzSj{;ErK>nc4?C+FF|*dmF;+;*nR9L#$Fv#cu6&Z~Fv zhSW_k`}I{CusfS*NN?j$WG16A@dzLEt`sV6>!IJsATIq74wg#;DcTW>M>fiUSAGkP zxvxwl9crK@Tn|Z_`C*w;tPhs?qPMa;LGfE7e7IJZoz1w2jH0(tDV~fv-o@jwv(12W zucR65Z!jq%97?T?INkQANadTEsPlg)Lx!Yo^aZm8PwC~=nq>8Z76@r}L=Q$s^M*4ePLw~f9UJx-if-K!8$>2vkYbOBuONVF(Dff1p?=&|6u$Nr z7A~;^&3{6A{^vOqHA+*2y?Q&v7$AdUpCjZL$S- zZ%zYBeY8l#Idu219-AqwQ?WFZ_Du^QpHimqJzi-@xaSOZ^_~Y~ORDJG(?TLs;K2u^ zRdbhF2GfG&O_p|~qU(A>?5eXE{tL{fk}Om9W0M~gD zbF(7g*26Nv19snjak&WzOGD9YgNL~E<~VpzP({aPsF35mb)XT@%Nd8R!Evgppl8Rp zK?!5Bz@Zf0rSC(J(;~6q8co8?`X;rbU4p(hi1fQMX(X3Kqax_<* z*PDGA6_h67>6%+$#jrQ@sFN`{JEIw9r(|=pmm1@m>{8*xnZ0xg+n!sqlkvA(t7(D6 zAU<^>0=~Xz;zs^CgwHpzWCioixyMS8lGWZ|HtM{fWuyv;F{lGi%^H+&q85M9y#kWu zALvE)J^s+B8I&Ff_p-b@qN^FynChEuN=qIR|@ zQ}%Q$jQ!O_qh=v83#wpQ2%aLlyXU~gGPo0qI5uXFoB zs9I}TFxH6NDR=}$w=&S@{t~R&z8Laf71NZPlB9E*7wEmoL1<{Yht&jrh=M2C>LA9v!( zu11tR`6Sj~r~>+{nyLPM)=j$6A8KdVSPgp^NS5BMfowbyXIwTXk5)?aWc?k%?{Ma2 zZR&^Wm{^n{eG{iDt_O?O*Yv-cRU~EgVgAP5eaPH)GwMa_gC^o-O=G%qy_h(0Nk5-G3uH=WJyVv;p9c&in0$R~m z=`Y32$*%x^uvhYwT{B=u4a?$bFaNRUe@vWpXEL$Da8Uc}y zj5wc3&yaZDbm2VK!x@k$L&hE64OxLtsg9!tX=!c&`4NsN;X)J+yNKXdOckBWc$i=8 zooKMvl)Lfh0e&x7&vx7zk=K-Gcuw+inCV(Tw~rab^34%&Q8S*)EZd03xmE}rKe4{G z?b5_?jW2BFooIu?cI@=V2%b%7p#kMqB>uD%Z?MTn(7}B8+IN~kJ>n|*AaM(eA6x=c zrGbWAD8CF-EN>?TH9ZGzyC)N>kr{1>?~YZEU_=s;I`B5=0j zA}}~xO#^oX5|m@eXC7S7?H^(ck9`abi)}-t70d~?VHX^LP@mGap*Vlv3 z#r^cxXMaXeOywKzrlFkQr*W#qe9%8rMSU3mp!_%oo|@c7ub&9;-j$2NVC^fqlilGS z?*6dpYZ5ni_;x(~bcqnjb<_O=TBN1B9rRwsa^oDNv3O^eaHyn@&Z*TP3KjYALrX|) zE!n0Ed=;{`p&km?_j1>Mtj78*Z}>lamSx}35fZKN^5b^8Y$EeRPACVj9YM(2ED{$> zYXRJAqS^o04#<_mFyC0pN~*IGf19xYZtX6nS)Huov_OIn$h?duZBD}TC$l|^{t_C& zJc@tWXYzUi4yzku37fJ8uyV~ zKTW7IuaExTGJ+Itc?A(pLi)sxb+g#Ef;?J;GKPoaz|3(XPB@BMkux<_@O3Lkp^5dd zF@KTGT6wfz>MlMQHW~h|uA*1&4I`eZUT}HmDo%CLQmp(@Q*>ErQc?H$V-^5?Doj`%%5)PO_w#3!JTG=;TBtvQ@+gNq7W#_7&)CeJ7TBbOko{ zR#NTFY!f7$Wlzp%qsQMl{MNEY_%)LCjav-htYe3v$uy8Qy_H&Ue^dm2L~=Y1N{PX{ zgu@|zeGBz@JeuSwvJTb7dPu3p2Um`pBGUMh_Au{31lu0Us?Tn$Fe1BgIedGQj8btt zez|A5h|^d)ll5ngI3ntT*5CFN4No)|I@Nd5*c=%$UM>)Z_dTWNtvV#ey&E>Ex}bkL zQF!=9%s7)O+Q@Dp!6vq^G0%)!yYvCR^4$sYxJESW#8WJryaL{970@27L40!PFx+#E z=e8zn#4c);LQb`tZX3roZIyS!uj@`!X`4IFI&Un>jJw^nB=57N_|XTw1&$po+y1%* zF8NZ0aX3KV6ZYC|rLV90kz3AF`RU&yQNQC1QWaDO|LoMWT-ol!G^bpc zbT$~RJ8>N^lBK`(IYbdNB+i$fYwD zmf$RD_W65`aP4jGc(vx+hqR6z8z+?p?8*jGQz^(%B-eL-nWzIo*>FQ!6Na zXKYRm$<;#LdV6%Zeiyb~C<8%v+Nh((AU6GX7@AYd1*M!3+4MLSQeF0=_}dR~_B>s1 zzgb1|R;rLo`y1d}S}(V=WHp{WLQRC>jtsAUEN+F?lI`@&T*m#rD2LSaASBB&`_J}j zL04N7HD;dkB_>DU%YG><-|dxHddULF9$8Gw9%&JQb_d*%jzq;yN%-P%H)xfAL(Obi z|CLQEU>yM$zt9-Z$S)TL7WdNZm$}%i(G{lNNTSPjF->9W5l~2I<}zXq;f}UJQFq6U zeZxqyofnJ~KP#9yawO3{&9;CymLq5D8e9>71;S^2pc}`r4#`oipgo|3micYPGK>Bn z!xt$}C$qN{!d@c*ougJt?j7I69~$_Hns%SV=Ds80y;n0`ICmJas@w%WOQWrb&PVj7 zE=_cATRl-AH``yqi*`!;SO&yz)<>ujUxf7dFnld`ya>Y&EV3jvJyjsP#ELHXmyK-}g< zv=NDt`3SRq?L}Q@FXGm*bD>j?_3)owNyhv3!!DgF%Y6n$q@w*P*ssq-A?piqR_|gc zX)U1cffA&VeMczoO6Sh}xQzFvxP#o6Vmhz*0NFh>gO5Bbg>=O<@e1`q;Y*gU{&icA z96eJ2+gAzbVU0c5fA=sbNnqUu(*xVa9N^T>p4KJVu z)6Gc{>m{2iTf!|H=7#z*B!tFGzR|3`%wIY`3c~Vpsmx~9!PUJ4a(o5cqO*sw%b_o# zdwZrpo9MW*p3=H5EAO}=+jtaGVAF>0N-Z(|&sd|XM-o0^l@ygJCK*Fr6A9M1b* zD@^&!uv&Z&e^fdOP22a-v<#^QEt-e6Ytm2@OxTB`X`kn=L; za+97SDgT)wz3*FsBpDay2bw=0Qi)PE;@jQ|XC&95g3C-#S0o^=RYemRMpZk11gd1l z$ya3J&srN{^`u5Lec=-vQo90*HD1%xjJJuIaTJPQ#&d_PHsbY(RU)jO{FUw8P2UY} zqu0}f^ldn0nTg1cad`QB^6sS+U$NOsu!-p=4c#B1PyHI|ZoP?R&)CD$r$8N9PJczX zC;uiz3^jc@i%ij| zr1k2ocT{^HRK1wTMcURQogh2m_y4*mZB!=4evPnFazEu1{fXZ#BYxD!G&EfIG;aQ5 z2^BU~)TVAa$=+NCL0(I_dsRk6Tf4hyYbN}IoGK(S1_a${0&vHHb`yk_GGIu@1 z9h-lCCwx7-n`ZTEkkOMmKM*{={mxOaRDUm6D{Dj&n(x4K;eOPi{s8l1^*}SciXJG_Ao2c5RYO}=$Y&CZgYzir&DjSr@@~k>|(r^Hc+M0;%6t+Q3S_#!>ovYv0wSjWK zfV+Rx2zx!O5N^Kpzf9jtEUxJWwN;7q58KF7Z9WPmVlCX!o`X2v@1Jl>Z3lg0AweYa zz2S@08Nmx}1=3jZ9!~VXMZ0$-V?`+sh}KA?ciFqD8{2aUEElM|LAuUR>`N((XQssh$#4ENQ0Nk`ko+pf}9*h_ZT9-ii)X-xqrO z_R(V&$@qq*2h4fpOrzY{`$%~k1T3^h(mTTNyA8S^+ucOBm(L^57;fL6VM)1hYEIo4a-Qk$PL<2K+^I{jg_X9b)5AqthXl=KT0pZGb)RWW z-kob>-Gf1BjmbrPQ^Eq$x|ybLw1Vu+?1vK?m6qKWMr2grbC{f+iDXh<;cuPR;CJK| z{Tw7t{Q6mUuJe8Fz~;-CuH6m+cZw-q89~l9&Et*4!K#`o=(5pGJi~Ak z-10A^*Q%zG3aEphZADyUo-5)8B!pMIzS3XE#E6_nG|aTjqn=`e_&@bvwkgxjl{+8C zrsS&#!yCS9lh5mVp}(Nps_5%KjM@9k($y7cf>H;TFOGv0rg8l0pGN$e>R{PeEmR)G zF|TaB2*cHb#fYS1H0;j|rT>0Zl3HU&e(V$pyhl0)AIOvkbH+I|45^UhM=dZva}vs` z_Qs@cs))z-W8T6_@pkZg-;n*g-G~gtux;xz*HONI9B$q?1IEm(q{B81V#&3UkoVS@ z8>jOWx$K@L^3++UNRpd5{?JJtQFAqQGV|jnF#p0fh^HOHFRBPE9H^x8SfA32Uv1E6 zGL3V#&BQ-Ou$)V01M(ApjNeJDggmu;I(+3IKI;$(ZK_wf&;K^yq3Jckh#B2h)M&n_msWqES6`Z941S%?kpj zC9bq$Ni0rYMtpJ1F{E8Ijr_@A7@Mz}RnlujhTX`ABf=1rFqn+L z9W;fMUzOBIdJyj&!?uwA%;Q|2*P-FrOGLN#iJwYj-e{)7ZVsl}2L5E+7i0eC=KJU> ze+mcJS%I-R%hleUM)KIU*S+8+T;_KpB9@j9SKRKP0H+t2+*u40t8(b4p#i2j1_Sw) z%y}xi3Jg-fx ze)NLI*gu>$UWErgse{Yd4!V$OcK@yDfN?i>&;ydpC&_kX;!1;&#`L4O^}G&ru5Y50 zWk6)M+QYTgg_bb*9zSng1nUwD>B2}wVjxxnFD?e7;71Ag9BhN74kc8QWhngDc7X0> z$_X`$@azh-^+C8pW`XGLqJH&S1I_T#q;>32C z4-AbyEttA$IH^=AgV~P7DB(;J4nFJwzfu!uBI9R9q7Jxipo}_H-LNn~QN*82*=I)P zD3!pKux#39$bRNY_V7EgiM#szEdDxcG#uK}Ol5wGkx}3c5{HjjeY)C;et%0Bj;raT z7Xy>9`C|{rw{fO_{EW$_8yygvZ;iwh!f=tn1bFqTiJAmhkhRL}{xqLYPeo_p_s^EX zpqm_edE_?sbDIifk(G4zX)zM&%Q7Ha9k}izcKBWc+sb5pdNDCtr1fn*3@q72s}SpX zcI$wTmlwRE zy=$2kFY65oW74>B&zMFj?g6t`7Sq>up(OXsOkVzzB4N2~yYJna1b8id2&pfN!IynKp+`B9np*f0 zv9ZSdk!?08s?!N;`zu2}>m`_|YC`4-t6|LcrS#a~GxFBSk)PXHiGDpej!iPuVcU%+ zx~5_PuN@l-M>7{&1?u<_i|q*m6}8bP7T2=-2_40Gh^c6IskM@97?RXfwkOS zVCmsPS{G+VK6ckZVOJsNTy2i}oJ#3Z2cCv`3h*zmhu34yQ-{6*>^D0U?mD(}_7aD& zQ^hxt-^0Z3ANJVz6xw|%(C&^l++!XOLH9n;UAN50&cQk;U9E{Glv?2ylLiq_vUZKdudU}Nj+MY3!pm6eg#wIY+H_2m60w$Pgxy#V&7SOyof8a2x3|Sf z=8Y`qfFak$Y^SeAM0Ir)Z2NH?QRz7BvtlL`kEo=k>^V1Zvj^|{!#KHfPtdDFvqf1I zpH@l22kn8>)|UuS#{(-=k$n+L2%|o99d`?Y80( zk4;6r(~1dmi3Yp9jmPg4oM(B`>krw_KQaMLWBTvv7p(Uq0jN$&4$&{&%7={o#mU>B zMV@(MM7uGK4QJ^@2jVelGEQIKFhrRG!8{;cO~PZjb;## zTuFtRgIH@zC>(d0&)Lh=q4U3%in>0EKPZvZgNIdzYYCr=565@^I1ZojPBD z&Di_SR*7W6>BUB*a!MK$JUf8;PiNxz+xqZ=@v->|qsgpyjWDXAn>#ac6&^E1Lv(vD zY&Iqd^E;v6+>`#=$b5G!b7Z(b1c{G4iq{wF07sgrqP+mCUbhERlS0eb&oju3y2r3+ zT^`C?`X0Y7UIenrg>*@RA_1BGlq+iihW-2?|h_{e$b-a(x(@nype+Q_!Ia70%?_R&7 z3)HX;8j3xHORFb<^}!~}4b361w5!2w%siU2K8y8(*~6s>ITWsU8xMvULiNr{s-iN4 zTc3D?p{hOCIo=MhexM`by)zeR5HeVo*jOV>oL8AC)Rp^ z#-w6;i)dhz)DofQr9K)_uS=c}7C}}(Ha!>?fHkY7AYey3eP}g+$FaP|ys&hE8rx@d zEl7l!^9~`?J(saqg(s*bCeY9&PI!*K3TTsdx|F@M`@XA&WowsEyNl0A4Z}3a)=Ct% z{y5e-rvW#@n`lev0Crw>0Gx;0TAgahooVJoL93sdZ1EHRRuhS=4|}tlLPqvIVbW(95~Ll zV;b8z^f&@Nk5>Px{^Ehf&!9iJ0;SAr!{55%q4UHCy1>np zAgy}Xa8?7!zO}-#KO2SW61}vUJsYa>%i-_2d9>zB1^L#!o^Nv($4}iZ<6UVZprDg^ zxy47btsClUThjgn-SV3&{8-aP%bQh6{ML5Z=(-MNIz?js$U=Dif@zxROvm}J z3sTLea|7Emu*X&xkbB*LA|~C#I~XrFNrloSG6MWoaXH8Ycyo7jHsI5f>P6g$mzEgO z%Vi$R$t!74nj6kPWG2GrJ8pAGK@H0aP4*O6L>QC6LtU_HPXc=O=_Xd#unLY2@U+jD zC)2F9@jhBVxf}jx*|Od^QNKr@w=7w7g)knnl^#CgnV-oyJGvR>$b_xCmnb#z%5)@{~BsdoVW zjM_qfF%N3YQBMdtznNaU;6q+_8}n+Djv=-ArX;1k4!$i?$#VQ+L{5GzginQ`Xsj>^ zmuO6b?-MI&jp87l8qKzf?#<`&$JU`GefAY!O70vgg0qPNnl;jd{9t!` zd9WS2$hKNml*z$W+cqjIE5NNLD`1XevS7nhrfWx~!&bY4D1ImdrzA{*LvyQWgX~CR z*2;Dq6gs#-%az!4ho%Uh9auj+VYh+gv+Xol%b4)nYT>40D6%_q1ShT^3!bx@=!VsU zcxX#Bth*v@74AEO%pCCyX1nE~AIr+I%U2s1n^8ckn@122lRCIs5{$~cuHqB#x4~`q zBAT0QOx_H2!;e@Y7xBapw?D2H#%uP`FFz&7+cj~J%6{h=euKD>ZN%?LZRKW;K7hTG z#o3lC+b@v&hv#qdfxiYP1u9!5iD^Iy=*qo9J8mT6-m9MQ>{J51c+r@gknDjxF%@*= zgex|CFcPk?-^p5eQ<9wd27b^i`f>0KJ~d1QKFBoF@JoO3It3r-ymi!S$h8ISJ&`H8 ztM6TuWB^=&p1nbA}o6-Xrk8RLI2LoX^S6h93$dJCJQu3iF*Tt-t?rk%ui(? z-vgU=haeaA3;4yK`LOY2CH*mBDba}S2Zw3pmQU>2%`is*Gb$dSibuIP&D0JOlk@07 z`UmS|c*7W}yWHzT7xD3+9UzxmM0FK4u(0=yaN+wtnm2J6Z*2K<)A-~xF-$u z8`$3E;sKod?I1W-rVEU#3`w(XGPLhKgbWW}!X?r>!9*^BUYqPg%34kM_YpQ|<@5Ep zzD@;l&D-hl5JS@Oz8cn9+EGoLXT){LiO(CTL`3H}E;*+O7N?r1PA1E1m>z-xTU)C; zbw1?3Bh9dV`UpI8hCbOkTa1sgx+XXS#^l9>e^A5>b)Jf>e@Vp+!i7b2{8$s>ZC($% z`(AUamzyI~&G$6pC{KM^zUD5=fTV2h;I8b6z;#Q138#9n?eg)d^S&pR6^@+RES%oJHh^m1lk<<9c$)z+ ztY&)|C)O*9cn_VqqsToA=EF~&fL4$2!p0knMZCvXd1Dg&zLvdPr68dj12q#=?4y8tTUW1~0LU-kPhu+=tEKI6ZEO2!|gS zm5{@Em-yVk=iH$;A91MeRS~}t@aYa-qTvKGx|isRkQ!3t8O|r&I*jTb+GC$-twO`k z-PD-zV~Gn6K}XUSYC8QAzIe(Lp2xb-4CGISwNB%`FGVBWA;zoA*F(rj<*XSkjHlgG z4APeSQRyP)bC8=32fIH|yUC14WzWD96-(}QeJygixLm|n-_TVeZ*Mfi-JikK^QkYH zKHQ8S_?(6=pFN2)FJoxvWbZZIOhfrv2j1a}xvf8qh{ma6Sh4#q+G777e)P&-q%)4N z8f5z2A!z@7ox6W&8`geTDLlu#E-%!2bcYWk$2!#>=&{f%KD1vJBL8x z7;nHAZYb@5g;X5+dx42>gRTcl*H9Lnj2u ztP}6r#8`B%V&|^Wz{fy(p>6ooQ>T=SAyLQd35gEEo^9L3=*jy zsHY*z9L@KE_VY`);F`tQrDKe!zck8Ki|li0fee8cy~T10Zn?eC%)aAhJU@>uKUu=e zj7oaJ#E!gI?}ta{OD$8@8WA}mh1=5~qFbIkKFqo+GjHe6tEUHWK&m%fD7nqOyL|zh z!48-;sfgZB+)X~-oz73p6+>GNsbh5Ot%#RybY%NJ<4fSx{wz9qU^kv^Bm+ZbZS*Mf zBumc-g9lqO1Y=mX^!khIaOKe<^nu~Io$^k&?tYDKO;jZ{n`$AM3~&uw*5hdpR7IS| z^_5e}?yuFLz08)HYd$4PRvY+pl9g!A(`c-{P754XH&H95(=~4k1I1=rtDDazkoKA( zm_GNaV6eoP?b!{%g5&XMq{2;{oW2z#W)@Q^rUfLnu|A^6*W7J>I&x5`5b+pKCMyuF zFLAK8h~+yh2eI*yFxXe!!9BwfxLa;Ogu~H4)QKnC25K_z_&<`aJFdp||EI`|DACYB z(N0lF-Pd&)l|+Ri5pA<1Gc>h?kWCboQA9=aT<3Eu*;3kjsf0=%qsZ_2p5K4ZU*~yV zPv^Yv_x*V<^BU(rct&Lo5UUFG#jzbv`FahOyr`gBOe^8)8sPrEDd@vgbL?`xRTwS9 z^5dbV=)TFJXV#UG|2o$5*Ejq_TRP5TgZv31o?Pxfkyt-&1NlQUQO1rPI9NeX z#FOJ%49J_S{jl2RV}TOWxDUp#te;U5N*s9^AM=?H>I0SZPG1(EN1sDY#unJZvCD#seR@!@#G!DSF$Q$^FF9^hLkTR=Ib5tXjFjeSm8LD9uL+FR>{ zN2WB3aCr5wKlsWhUubbzMJtqD@zm^-cA=d+XRyUBO zAQ?|z?;y$sh7Q$`2TGxQ)RVDD>P;-#s-!0JP8-G!C$VXfu+IsoD?flss&>H)$FH2g zAOx?>S^*ccYN?^{4e1QMz+a2V;htNyW2d(N$6?*1yEtYe%Y836PrEj+#P!$Pg#lt; zXzE9n$6OZ-9TVMX(<(7C4_?6SFiLG@cN2-oIlRh)D0G9}+oz3f1l2t<`5XV~kQeIj zAoJr9v|>~OPS-YqU|IX{uq8nlDn57bj;uw<^ojU z9K)j7diq2=J`>zV1JX|VfR&Fghn8Kh=+4e@Wb3JV*w}s$g`B#I@i|YB`S^;qCGREU zG&Om{#8Jq8j5a>qSS#{)Od#Uq)~_od5n4%&)sEm*N5x@CvWw1)WxXy8XBvWz3zA0< zC+%0?fyVS=wDM0mwvW38hc(M-w(?$L@oF}I;*1?~{k0jVUXm8^UbXMKq<(n`bdAWT z=iikPy?fhv&9XlzWN$3??2`rEv}SrNcmR*OvI|}=J!al`ss%0g$`HO^+Dk96JNEPZ zS1@v#fcn_`lSRRryxrOpXxyAY>}|z%k=VOH$C!C!bx;jp^Z9hmF&%O&5+KGf5Y6#V z!B*4tAlI{!YHuFE(-V9_Y?(E;&fgM$$yF9{;8a_AvUG1NTz|ZS#xd{K{`6i*cykzK zTAsx_Uz$TZyGs|VT9Ro|eK51B#4Ktv>p^k>2tJ>Ij*kWWM_>sn5_yVQHs7?=7c%AV za`_A6@J8V_aG&;?UTaq*RaPA!)|tc=eUZa`+usYzbb9ErF{&iq_8t5>kx%~y`C-)& zqeM9TjO}xs-4Fuf3)2OI{n}(VNrKWJK}dDyb8MUy51G9m=tGUkhAQrY(rZ9pe=t>1PwQXFB_{6CtqLZn-&{ zt4d6t{DoSRD}qzyZ2P!hjL-RX6>S-lj4Rzd;lsl>)Wwy(D_v@WJwIP?jc1KeMqU-Y zedQ_L!+Nny1FwRWaW(ztG>Ct&oJi%CPu%U%q4+`Lpa_TeE|w>DIp5$zRkwN7i$Prc zEEnFduRsHf+i>8Xo84iNoZ8qCA`C80XSt<(gz+{NGEZTC`))Vj(IR%>;}1YsdTjGI1;+P0q$+F zMnPM{ar0IS5e{b`y+ta`-T8=LcerHf2Y61gE2N%iM1dtK7)LFK+O2t1U)2foWi3MW zC7 z{}?78W*MAFH)?YFAD-ay61HJV1OCa7x2J1i_+d?y#WX4BcTG@MB9q@UlIfKnN}x30 zC^A2B1Dh$%1%qdmbP9VGZ%YUPmv?5IU{)QfJGWZIhaHDxNcQGWFe535#^+5X(=WC_ za>YiZm=lBZ$zl;EhbOTcY;O}}PqgADN$3)_cO@`)PAZB!oQoG4*}>D=BI>zf5WCz7 z5%tt9Fv!a_} zdgF4myV4tvG?fzFC~~zhk*cnSk-ydH&s93aQZEyB_ynOD#t(4cCQX<&rHa z*`9B08+T@y9ri0%6!mHRyFZOc_twG+-hob-%Whexn?bkv2SR| zRrNR6)#7FD9Km{!&OU~SE+Kk;{4M@PEx<$b8BH8Bj+6|r{?FKhXm-XGthLx1Za#WN zCqK}_NiGe-bgqYv>&n5eGq=E5=gagf%K=q7uIFDWr=tsZ593DT;UMAIMd!|C_#^8F zo{x_UBwQuPl_l>*_^ciL0SiyY!>iN}bR65TP%P5o>y_-$@L`*A=kJLSX4*k1^L%=W zm%_y>dGwBA8QJBsi|=pzgQ}`d;m|8`5a!=Z9gPQY+Z;a-gdH5zQ>kPl5*t|qy2d7SHQR#_lYa`2 z?ggThDJfXlTpwiDR8o)gjK}`JUy^_ z0H4bD1K#8=x90d+{A%5HSd;&X&RU>Ibbfb0NPH6a@3$O2FI6VGS3KZUh)Ux-*fB1j zhScrGr;0{_*}V?BpkM&Y9S#L;#fO4544?DzlVO-%Flw_d#`Ie}46;puF~4Mq`;7)z zPz@r=t4O1v67y-nuXRLFc;mB-=+@Y9gHVW%1EW} zvc{6P)eW%n+j8{LfORiNTe5z|YFaS@h~=kneq>KE_u%1uym^#6%s$_U ziqEA1&K0EH*N;CK5rHgDt;e6W+eG(dKQrbbPw@l2Yb$B*_AU6?b0d*YBV(-*X%Lg- zb0>HTe&y(rk+t98mRYBwS{!nZ>D?x4CQ4c#-cYdv1s<;86scw{7Nx0 zS~Y_8KjhPZ9M-F&vIib0_HcfWg7L8Cl`v^a9kn%W!w%usMOd9N@jra_8~f+%Dms0i z4VK^BDXeMyOy4nY@U+xW_%O+x7SA5SMwu_6Cs#mEy_X?2opoTCt%>59f8P6A3%Jdd z%@2~(C5KLwf{9`v`Z4tePMYSxZBxnmrU9#eer?Z~qtEHfEKNVHu zY%FxQg(po*O(HwQL+XM~?WuEQ$Wq z2+3gwky-8)EFrcHT$a413cklk$yrmrb=PEc(o+k6&S(@q_2{9FYjg2WF?ZH)c7@86 zQnGiM6F>3g12i!r0BaQthhL97>5_>9xK+U)&NLnuln#iK7L`)b9ph(c8Ls#h4-3pb zP-!`Ta+LWe|A*CoTwU<*2a{l(N(X&!&irZBr66sYM^$|(N&d2)_bF^gdk-)_q76Pvmgd)!;GhdSdyq;7^hwWjXKYTAd8?l1( zcC^5AR8>V>`ca%LDZASU;g>zBT!tTkk6OHB_CplD^9-)Lh`wS{TOl3C-UX5-?S;M@cR6SN3_ioQ<_An((RY;!Wb)K5 z2u@1koJ!>I8IKRb!)({YIZ&B=Jy60nl=EoG!7NgBbQAw@C=tQx-PrrwXh^xnbW-+w znHU}hk*gmHTKlv~xXEqM_XtKxcF%C2&2><3Dx=6ymL$kEGB5pajx7!0!(XO|ywhWE zX^<~^wGe5&jD9LGBG=drWTp37G&?j3hcdlb{ZSKbW%$XLg@LuQwRvovELkwC2Of<& zEqKz-?zFAq{ORgzsHyQLc75py%EMmMISf~ojN9Pm$X8s#6(bZkw~m?~ETlJgjv$~ce205k$h3MrNyrW zFWq|`uHPu9)=|2o2(^J%@>I0ndl60;`Y6gLI$c;mu3syIe}ma{kSitjTQ>2!JO80& zedq9~hm&CbwHCVjnF4W0`316v3{c?OZMbx^foQ9xV2(aHk@o|%irNc&)pUtgb}Mu` zB%|z%i@4Cl6x8e&tURH|y{h^^S7sCik(1h6g-8+=#-)rQm|MD`37;9u+%WLS(ad^7CcFkmBZRT*!r ztmW$et-zInE|Fgv5?P->OqdAIkIMYT^2=XAtDk^+WKJS)D(j%6c{X~uhjr4b0Ee;ykzw0)+_}mauH{!!jgUd?BYq6}v&^}fv=;3hbPyU${Y*C>k|r)n zo$xU3FopD~B&MbvN_sY-i4rkbS%0Yr&-1*PHZ9u*pE9kuZJ6csw|#)A+G!|II~&s> zJGP5mNGGu^Fsq+o@M&2R_u_y%P7P}mmMvgCW6EQQLVGWCoM~>VYb#xI%5yZ8F@Yii(1CF zpWnxlLs~Fqd=<^SGL}SHHNjtvkKB;8Ev_j3e>~U7QzWkTwQ%6s8oH5bf_3*>;lbgf zXpKx5{_sT&%rcv(`?@t`qRKahT^{D*#(G40aW;63U~{*q6lXlNfhNtDbePmQa_V1` z=obCh?h3x}ZYu=UzoI(vyUEiTTKq+qk?8YGEqw81qcEAhr(1<(V~Yi@(0cU}-BTza zkzwokgv;lnDd@qD8ixGtOiIdKa?D@!UBTap!So&E!Of4>> z@hX1g(@`z{Y`87jA`j9t-Q*d+DWvBT3+nH{dq1fWETcO{VB-^BGrT(CHCJ zu;RU0AXm{ub0*IrqnV#U#bq9yaY2VHa(@PEw+5k1tz?{THV2M=si3O*Z?RU8H8`Nz z+{63J@WldEk?+oSp)9H6n}EOLNhALFkxA@#`akY1@#i$wI)q`QJoCra8xa%K0Mozb zo2_R1di!jif%=Iwt&@mSUIUCLzqn{+M{IOus^~WIY@0f9GOdMS)=R1C zK|?YpvJMC3?4?ckN%WS%RW+}O+zM228@E@wXaSpG!F9YKvTIj`safIZyg6S7k z6x_WPJFlN3x`*tI(<7fA{)E(s_JaM9Y^(iF8wW+KHMNOTV= z*!dR!D6oe2(@)YTu2RIOs0~I%twdgTk74!u%i+lSYN}Ydho}we@Q+K5aK10o@U}Ic zVCvt9EUu+sZrUoARm`Ug`pZaS;vRlvbT~@OScj`-c8L6Su4Zqs*-2{{tkZjhU4+{XnM~ibi~?SvfCV-N@ax3=;4!tAJFXp!_p!c_?45Pg>#ZWWgFeHxpHkdb zgI27iogmsk{QLSFp3{B<_GDDj^=d|B{JMImcvr(IU08u@b-G2kt%mUHoCxk%XSOf;o=(Ed_7%VlJ%z?e6@m*=DzFr{R$Hi z51;5ehZz9vs;ZKjTkl4fgg-_}3t*qB*ayX1So5XqEcf%!5 znnZV!VNIh6Rc(T?y)m5TFL4|mQ7ppkRce!n`kE5he>9)&dBOIA)jmQ=o;AAv%M;7) zoB+`Ikxu@&h{RjefW5^Gn#Odlme%F4^`#Wz1Zg;VpAKB#Qc1t8T7@6}o+j$Gd+ow< zg_?D+{oQKn#(LN;$9{yp-ht>{Y$z_;I|ICLH_=aS_Qb-tADYD7&3Caon8}7**uB5a$|^mViUw`9zfa?uHf6AJK)`Z=Art2m<;Wn%dc=8kF+^W4Ck6f z{<_hFkMY5sZt%YIB0W=o5Z{xRgo~ruj$z;cHflTojTd7C@}}Y>@k<%>jAy#x)%SQ} z)paP|T}EA!c9SY!9bRRu9cs1NgqO^d1v0UNTK8y?>ZlKJ;dU-Pbv>7$E=L}>Hlc$L zPU2;(i^H(FiKc94xYTg~*4u@fSE)6j_8X6dft!1&^j}GGRp%`eSP3L;x4y$xEwyVqeAE-+e>BUO(RAa1d%e5}aYZ1Ur`81BJF=WRp;cC(pkD+ZUHn`xA2HTVFdM)qkABG6(E7 zT^OycTN3!Sb@=)(DPi20*B2(w>}9M4ALu*J$SIH8G#ZeW=X{RoH|wZgna zoNeov55e-fi-J+C!}D<0a9*}F9_d9U;NoUam@W5`@d~zCQ_%sXQ(kl1uN$Ea>5U?+ z9&>OsNoV~38&uNS!Gn15;t0m^K6CR-L$LY1Ver2@$)X7gWQO!0d>8bX?_bIKpWOr^ z-`$QqiFml7H^fR@rejlBA5?n>bnKN!3wcvKy|hbMefJAhGoDW>_LW1|x@_8!$F>h< z+dxBHC->U$9Bw!v3#XT~F!rWM=7|3VM@d8UrOz9ex6OgvIjsBf2h&ZGe}Ufe_5u~6 zOSWz5fNs+il-F|sH_bBxnbk}Sv&clPU09?iwgcO+xOWKdC#BIWek|enR=8KN0x7s1 z!~VI}u<&3t9dzAIu7>FFKUxB~kX32e%GV2CI5nc;vnkjl-4@y*pGrUNBll%u_(w&T z(1aE1aB)hf2)8e8V_u!L2jNKBD!MVp1wXYmhLifObi3(n;&V`pw~Smbh+xl3*Q>u^ z(b+_lu8@MyX}G{IyJxgW&5+2J*Ml(EgPYiX3cVC)i2NS=(#44Qj%Y~sDWI|KY*()2 zAUq20mafbWVT$0KPToLtIlrhg@n?wgkN5GA>9yCU-nw-{PdnNykz?$W3YsU38xP2&~ zEi6yxE71V4^Jk-$Le@no)d>?^Cg(3_c`=uaN;u8@NLJ`Nwu+uF;@%#kDIRy&268+m za*2gC=ymCOVP;J?Rrir0ic5MS=W;MTm?B5ommnk+NeJy|s)^Wp|=d_6Q$L@`^2BLVrNQgrN9yBfO7<V(_ILCDrQ6yG>B6S`hCQMp~VM5XN;Sgdn3H{7mEN^j)BifMo< z{wv0-?JOZyi)|A#EpN-;Cg?l5A9)_VjMKQCqFc&oy#R6~crI`LNDA4_*Tf#ARdh?) z)cF{DD0#p!y-PG^MlRVbww_;d?H+Pkcn}|GmW1=o9dxS301nGM1PhX41O=VL$oWqn zMBMx3>k@3a9hS>lH)iFW08qLbZmw{l5phSJ2(<$kw);wwJEd>o(z$#p zzIZpWe5A`?wmyM!9|Yh&drc9xCq(NJ%ki~v^SBXR$#w(9p1uI5k-=!#`XoH$$Zm|O z6?7Qu*D8Gw0K4YcaMc@@;>|zQ;C5Cg{qKnk(ZK8-O5Tg!zP5+VcGu_Qax&0rozqxn z?P9peZlwAP=a4x&nHKyj*UYMG6EQUu=iN_#Lj2-fEIw*E^c*js%6FNsqlj(g+_=Z> z4nB#0wrz!@62W1NKlQ^B|$vD`)QfU9Fhd#AdBD+_x4x(kb)K!x0=IAs) z^e9#2{?rE#j2;IELptbqwmXwzvl2!+MF%Q zw!>fGt-1udP`MT-f0u{t10A$Zb_OZfSql-{7E@Jm19H5*4ip{i(Z1D@_yVT_v5HM} zp^pGpoLC8~8Wqf?$I6pfgF(2u<-B0)IBAm0a>R4rgraXa0XNO@hNs+1DqwlWFZa5j z`{rxzOobt$eob_EXCZZIVjbXZ*FlX`QkW&cwrC|-{(Qu3EDy%*UgFS&x~Nym6jIvB zIC7ATfK^zwIm<&U#{{-%jAxZJAu=S7%S{2UTh3gDO-KU0! z*v{0;-*9bydx5_V^H%9~!K`~Js4?LJersb69nO{Xzgg^-;!=l4|X_{1B8+Z&NmR5F$pXV@~7 zM^6s+kq>K6@YxG4qo!;}>_6Bg>N}0|W*jLr0G{gE(jHS6yvxu8COWh-{-8n1RK$40 z?~VeK3f4WcasX;u6OnacGM?$S8I)X~(e^q6qV%gC>@T=;)(c}%%%RyrSN7~1JSD)+ z4_CtLV=?r7-vAyXbr>Xn_j3CZgK&ZBYH%s6qaMx8*yDPl$Va`ivIqA%C4kMu3aT4t zK&q~?-QL71F72r`PLup9;^9NP1UQa;H+mN9(L)oe$Qp_DeEi7~IL_fDz81fg@w#=i z!*eoGt7?aD&bp|LXV1;oUC{Y>a{lvWEGxRd8oXZzA@!_y{J?zyi1}91wnJ>s>+(ui z!A<0Ty4IlG>onvwfGvXu6mU2e?$!NSj!~%YPtE4eZH$T?i z1%dI_T!;nR0zOa;3ikKWu*6jS{k9bp{L7~D69o8-I?FLx1aSUWT(R+$R#E1~Q+h1v zG;f2*jFViOhd55T@?3Nqx5`YwVHMs`V`WEs;&sXBt6eZ!bk0PZ^yMH-sKN==^32)uD9ro^hNss*SCp(-Cc!y`1U{#J(!b)Xb z%<^GmxO}+?&vQabaGD#-ZituB?{j>~!!J5KzttA)Ji8IAOq?vj^Ta=zq}!n!6qIu5 z=H_e?_S2ESzNQgfopBOB&{lxR@FvQ!&&TZZ-HOA_C)6|`dxLBdSASkKf-G774xDG_ z)7#OEt9R=2YrIY($*BSOf{~U8&jZ-s*H*I@(ry}3`$uf^)aez(E(=B~%1M}>pUd{J zDyZ-@+s$b>0&9-ja2qO@;M(-*5LnnrmvIw`@}y?AP3cCZeEi6S5BmIoO$IVK9g9={ zEQXrkO1eS9fCR@kz*hNOGyeG|@?1-TSO4@09a)x(uQUE8)m=b~k_Yg`{v#09eUE!m zeFCcoY=g!3p3&8v3dC|uFZ?)?!s&0Hj5p?22`{bgrLBdE#9pTiyybFf=R1AkvypX| zS*f6(TYT`z-f^P4id#tm_F}o?jx`a2vobm)*6}_RdxW4Di6`(n)omayb%|~~phyC` zdLhVnI7+iwivu$hM0j4*szyQ&)PlMnq2~m8BwwN))UE8$sG$hFbGj;c4sW6oYV0@5 zZl@!<70kh2oeT!1K$dk8dQ=>RQ-yBur)Z?$5PKfEpZfxicVkeK?hUNG&KtbEUeMFm zbji@hZWx;IhVy=Jgbwa%rA6DH(e+-V$nN+Xu;zOO-EmrP#(tYGgOK69r@?Z;G35 zeir#phT@G$*qBPV74(EIV$Tk@U#kFwot(vmIII{W2lg{s=!VKDe4@q;B7eqn!}`7O z-z+1MzIl*k->!TZfXNfv3np#QC6y8^=Q8a!Iz93No-=}jgnpN1Y`d?1Y;?1;if|G7be-Yag56x$cmX1F({hMqiekktI0%Ny2( zaAAI__{{UIP-fMLZj4I73X4}m!moTP8|8?l^SVX)rlZmTUgvcL^lfbEs^gpRq8<}i zXw^#T3w2_?M~vsg9R-Qiy5yS9A8@n1i6WRk&|1nBrj|XULvi|~dr|{<`?zseG>y== zpQV)RK1+Yj6yT2kR)Il43~l%`fIloh3eLWLoV!~Pwq3Y}Wo_!{*_M2=ecc&8{b(9D z{X#Q-e)T2@YCF)}sIS;RJprzJmD2)uebUO_3&K+>xxb67@lm@TQU9vfBmutEyh?=g z({d__ajX;Xer^Qj3Zk&b12_1RW=D6VPa@M-w!+<1EoAaRm&n}i276Vx{N@$9WTrta zM9BxECCB1%;GKoga=ntq@q@S^H45|{5oh67gHG9R6sE5IOlSONpUH4()USTQqA`=n z!*3rUws!;4ogIx2ds@QEhDut`aDLU@ZfKQX!9BNS|E_tp@TlNEnl&sH8?c@6@tN85 zYUUu8Pl|#CS;<_RhAW<_)-DY4XPfK+QTX;Mclg3kZ}ewOQ`IorkMqpP}{Y&#?S&E0CBXq|fI?;fEvKq3X#mF5%(@d`fQz>^Sy< zUfi!p281n8w>+KW6K3P4kL|+lhdp%4qQAIiQUXjEUQTzG0g1ir!Qb-9KzkP)z;n)z z0`#GSDsLIU_NxP-Wa$Y(xMUQredPw*@oMyQ-8(EBmjD$trS!al57G3|6JdKK>zXU{ zmlI*T`;XbgO|lYPb8=|Ju52=#eIFFAHKH2-6L@@qBFr^uqMI34KYl(CHIv1y;MO*g%9A-5XCJ64G^Z9VE?C z_CLga*Q{IBEr#t`O9sL9S*cv`wkWJqkV~ULR3L7w+xCzi&x_jaP@rKhV2}b$4va5Jb(=Axb?DU}<^? z+Q3C&$0P2bS`bHPw~i-;5{+Q5@SSrCUW3c9BIG{mp!bEU#NbRVNJV41jOmH@^y{Hu zg)K6>9f4zqtHGi#ja2QxAP&484Y!utn7{iolgMAa4F%>!D9SPl--vOCsc9nxr&OfK zXHo~N%7W1gd>t#Xu7CmIb8230i2mzor5B2d=-;Z5WT$xo=pU<~Cn5&1*u!XWO8mm* zng-*ElZK1%eA?_Nob2EZJC-||Hy`_nn>7IvQ!CJ^FZHb3ClMx!eW3Xl_K`O4*}T>M z4d`^jLhRf0MJRalg}o!pBf}FaA+P%}J#g|pIWpCYcMTN7zWQ<4+II?cbvIMtxF{^I z=?;dW@mzwk7p`ReA-3i%bdY%ud^!ff;agk55#}5BeEk{Lhu=n1@14h^#vpjpTS2`u zc(PC4i!Z1ejV9m>RFJk*bdx!xK7c)L2ExoeY1COd3M=Tl!}*ApoMd4bzG$)vQcY^8 zmH#X9>sB0}^{JeDIhy4k|7;WCdD`gPI9AsIydng&zodr5)&=wZqhe713kRHB|5@nw zq?>9Kv#p|;K@hOej=q?)344B@59a4v>5sUXl@UAc*`4ADE24LheAed{OzG-CZK_|fR6-*BIbKf3DCiM=mS;Q~UBTrxF2_BudqsDc z;st|PIXoI7pLx(xg5 z?Nx61QOqCmrmYU9x(B1!8S(f-hAHH-tSfmwi0^-h2C-bk*;iDfq|6o zhvKRI0`b}j(RD=1+7tZ(!e~p4sglh=)nmkLy&o?I*kbfIo z`JM&u%nyeU;wY$u;;L$NF}4U#Qn7|34V2m)jl^z#?71`J7q@-zJofm!1FFyqmO=9) zm92C5QAwlGvxT$qN0|;0hSy(8#jZ;>f?nup+HnHNJ|!>y;>ir=gWZpvmW&3|unyXF zasVgP27%X&69R=e)^&D|{rBswW*g#f@iON`2>)723-<3KS)4vUqM-h0u5G<~;Wn-Wq2NJ=-d1I@9$3%@2l2TUT->LyPg2l`}7(>7$iE8ak+Jf(n_DRtqDO5!KVsB?mlMCWT@6 zB;yDiSf~d1DUH-OdnVC%c?aAqiV%4miNBe6Ky>g(f#cJ0q}8$>7E}kLI>~sv@QOD) zd|XU*`i~JYhxvTRPi3^w*cmDBkP<$Z`A#o*jwCTd2@pss=*VwDxV>vQtZeV3hZ7_5 zD>)Akmv=N@`t1kKQ{W++uRw86>ah6kM6hx#qjh5Y$e$&eBHT_{vJh)=Jt7`Xcg!Wn z>MFry++(`yKq>h(VjKT-Jh}xzMOFosUd)rz+r0VU($UEK;UjcDeVIrD z^;p942!DcLVO1J!j*i5}J?vS${w1ds7lw_t+d^J&4ZZGifMmZi<~MbQa1xjA;b@H= zunsq(M1^GhW8GTOExlc@hMWrv;qP=GNAnLm;Ae-wita6+nI`pEAsGH_vZFU&Zp34I z7Ql{*R%#YEg9M!wVcBK z<2bwBO}IxdNyN#w-~56@LT`d*d^xpZTy!$u0JG*)aE%_zvA@PQ5htJ4$C2vol;KD&P5XkLs(L5E`QG6Ek9!$^CcEE z!2GAd=s?9a99ywSq=)V+u10zRn}ypMPd3Sl#D>Nm&^x1FV7o<%nBoSw_{jCEK9^A<#Hh9K5HMsPti~71Mk~2@* zU}S_NeZk%r+}Z8Oj&Vq(6(QJa!~f%Un^iuUuyhNr((uOoM=&9CmsPR%wQ98YBH)x0 z7I0}=KCOKoiPaoEV6gfZw>g*f6!q_btx_*&frcW|DU z9l*)WH^AGrjOIRnOjI5?@q1G4pwfx^@s|ywp?M|i=xZFnE!M%H({Mu2eJc_-upQ)T zuhmG`?k%>|PK5uCmeM%~d`aX0t7Ik}L8Y-WWBU_z#xAbdx-qk}pfT z{p;Y_fIf;|b`XCo&;dwlqW)(!iK1sMOd8Oq_gM$N7Ak>b$|2}@+D$xmy9umSt)RD< zhj!Jn5ctKf-zm{Zv3`!dm8 zBVrLtxnOG;Y?mNL;?y z6P{%XshRJ1;m7q0(EI+Lu06nDce{Xcm$bqLs{QuB=+|41b7)oKOP!O9u?NXmQy`k z-tpD=(laISe%C=qhbfcK4{M>PfTMSr)*q|U1hMtDXvy1foE117-tTOrqsBOq?zP|H zUFswA$Q?6DMg3inUR;D64n<-O7f)zR9w`XhE=BSx8lm)62)eW38dhDj6=rWJrUSFW z$@rcHym*`nIx%lO+8;Vjcz1ChJ>DWoW?f8#eGTRGift(ozrUTIx~CW!Jqp4q1+4$7 zs*~OhjKtHuJ)t7N(R_c*4?Iu#DSZ81fo%5H;)0uraQa~>mD=b}jyP!Y89`2H-ungE zZ)>lJhr25p5vEsfqqwmeKZ!m@1pBk}X~p0KeXo>Ps^>&vtrwo6yUJ?IFuZg#+af$)Lr3Y~!za*AsAtbj_xXct-g`C>q^HZPrgG z!2x3Y<)>=|o5b|UZI-KQes~Lw$W6xDGG3r>{G1+(&}Ch7O(O1nv&|6Qyj4kmUXEkA zRB7V$ECHmWD(G`Gh$CV`VBha=oL=`)JX*t1gyAlc@&v^DK}TymcVeg!JBlTP&yNmt zviLKWoqP*?*Ot?OBP{2*uL-PjD!Bd@E3D((FSI=QnLfL2P8MD(2iu|tbZ}%Dd9`8# zU%E*GpDT{U(M&7f!uF32t(-tK%Ua-x+-&469!6aLGv;LyJ@O4%PI$iw*<}(D06TbI^tmb}!@{4gKy}SWReC^Qvu1M_sbvdLSucTMs z02yWz&Ku2c=TzBqxzni${{4A?oZhBjON-?IHd%CMb_u!Ewv}Hs@;K_P+Ke45og}$>)t9U@6U|=kEKHhg-Dx!j)&xOK&&4 zwn_%JZ2Cw~9Gpvf@793AmuYn3RUI;YFAwKyL(o?7dwAm`LonqksO_Q^xN7%w5fA^H zG>v%GeS+ziH&7Gy{yVOy4^FoRqaZ#Q4}UQmI>VY+zr7`SG^QUe4s9?OOdzE2aSeFt z)F6Bhu*AOQpdierPWBh@wl}_@_v$4*Ag)MGNp!$hrH7pG$Smya(e{=zQb z65wB9Dcy1;i`|Nyd7JTfP|ciuIPv8eIF380KsbQ2RYIX@(Mf?beT~2UOazI}_cUOm zJlUVr2Gx%w(dS7U@Ve}&BHUIvuR+{us^GwyYr?!|wde&sG{o}M8(V-ky2AYw zm&IrP)QNE0#7~~6v6fRZA%{LTXTQPvW^mY`jD8sI#3oED|KH8T`ye9q{?(9cIfni< zV}0z$GC|Wn6pfobmdvcIhu*tAoR|D++;n~#O#a+Kce8hg_uaK{WWbzeny}~ohi0&} zu|rY5;rO@1447oyNLdJ&WNqt*Zy(dmSD=|>y?QGA+**XxOjt*aN;4S#3PCQG*RaNi zZQxK`Oc%KyBf)qf-z}wrKKyiGGS4`nnq3byJ|s!he~!K^ z55mXxNPN69EpAjhryVenFmdF7M;uw>m+cw1G0{6AIW3u%dv2k)tJ#U8R^krtnS z$_d$?T!1%!>J#-u8L+P7al@+Mlu9Nw^eH3BO}qI0Oq+7~eFj&IR)F-S&GaqPRTrgq zLSMQHdK2h@4}LWk@oh1I7P<6!h>gFr6)a#JwZ!xr*jL^`j=Rp`!|w^KzgR)d+AE3n ztWdu7wLI$feT3vLTZ#0|ZZd#1)I-^J>V4|)GZg1+wukYlY}fUeBH3fq39kxga(1`w z;<6>XVDI=wlsqg2yXLKjx_ANoIFv`Od%N=sr}-hRdu!R=N1q6vuO~7s#xa!T>+R{) zyUtiK))adFw9+ki)JS8k7=L5W8bP4A9^pR@<3rSv&|~)bTbAyE;;nD!xeLrUZr1{P zYF#<;Fhex5txAN??r$cLOZyX{Pq~8L+~a+XxZ-^>6ialX{e9i|OwKK+oLWvx*ylfFpa0OIk`wo~!UY-MMf>KCUlx%b zzjE-5xlcd+DkZf_8~K7W61cN-Jo!@ED#B!)C!xgilL`Ma%_ILjR2{m(!3VfdL$jqeR&)In`8rV!pD>*z9WO@w(;N2MkD9doADLJZc&G} zT$UIvnDJJ`vHc~-lWM7Q*ncRO&b_~fSobr}v-BCX-p&mde3BL2v^yn@i0+LV7&fFt zjhW|d)}%sss1}N@UA>EIUmJn=%nG{wv^CC`nZeB4U6h_vA~J)Y;9a^Cef71M`t zhg*h0sAi;j-~Bpts54*KajcIXYZ51AGfKhrYA!8Qlp$?qEZ6@-58YULfORbBiTvL6 z>a&R1xmq~Q=}}wO@%ReL!0~km8lip@+mtPUn@cNbOE23=j1Pl{k5+L*Hwf;$tO0Jv zy6CF#sie96J6u2RM^Abylf8?+!k5)Mk=CP=I4#dogvoDNPoQ=k+uzxpWA?(ziF`~R z!H+-Ni7wB}!CL>>gVh}Y^%^mVL+*ruU3MB57k&c2u=az3X)kE^wlQQ4*8q-BE^rL(eRN^bRPv~!g5_wk=>evfg%-4eYpF6?bZ7_u^gYPCkmj?fwi_oMK zV~F(JFEBqcT5!pDJPB}YgX4?C(2~zrairJ|7^p0!?^%Dvw9}gW^2yTZkDLRVdSje$ zUCURR*)f7l_{}sglXBYYNlCl76R&If7Dr6-P|S&zJ0h)8(bvGDXEXJ zuGtdlG=}1g{MF#2T1%63?qU-+9|-*0fG)TuPaclG9z^&7qTan*ZJ$o{oh zFtcBzOLi3w;GGd+@HWSu{$AmXenbk6=^09)_;gQ|Y%2_+4}gJniW~IcyIo%P^CzoE>hNYOPjhB$pJJ6lEA*MCBVX&=IC1hy5L|vtzgm=#%ZqmM z*_OxAD}f7+I{I0(DaO8>c*N$nB5tgDO^Ub=e1HbUTpIas583CX&EGdXgLH2HA4%sO z*5muW@di@SGAdD`L3WR@*_~+H-Jg)2)5{GyuEg?arr^#vLv9K=klF@Ioz_v0J3i#4ln$Tu zI1QBz2H>PUv%#adp5A_JLK3-JP=34A{OxB<{GkRW_*9{+$rLLOEeGSIO!{KGI9Y_d zz(L;+ZBe<*x<&RuM$ND=>Bu%_TqAO3l>pR_9H-H@uJ%G6m#nf@N z2@(3Q2K+o{p{$+0cuKw`L@KsXccVYp5`tk`;hEgnR9Rwja1c&xZ$jd|?{RGReR!Hz zK<|&8K&GkI!t|5E$k}u~-h1qSS{=e}C{N~8z?hqoMaI^nNX!;N*iG{2oO)jdn0P$meGzxVNW&4qB~SQ)MQ$@mO;A#hQ_hAV2t z_{l6ysB`R~|Nh7mc+(GE&im=#xT$1??N@MFvlD%rdj@NrWZW&5(>%*Mc`K*1fb*dY zv$1d15i!lte2jZ5T5gk$K$c@lqnXpNBq+5D^=cKD{#JKuE3kB(+g{-BI*ckaaA7iGbDCVM9C zF(Vg4E8%4HSbEHo^)yAN!L@-P)NPTACB&lPlvyEd{Uk{S*xd3;t&cnX)E4WND1+4H zHu}gyiHwr0fqh11)SvZdiM(%yGaqe{r&uWN*sc!e&(_l$k7kll2b19D{(MyCCqeeS zW_hA7k-3R4$CJ0H1ybh)ql+hQ;=2mF1^T?&a34`@*W#T6Wsv0GwTRvwFPNpznxnaWPcP*Ue+-b=s>JobWoaUD{B7|Z;48{xMSrAp6@ ziT3MSIJ2Xjo8MrMm+$+T_y4_+Q@#%2@!28pkh7x&*&FatFEhB~)=b4dOe53vMxZ3Z zCU?a=J#xKYl;2_$i}a>Gz@uhug$(O_dWs4)x=S13#Va*5Fv*{EN|^9d?rh4=VNBrHSKKwO-45T4_fvZbNup5M0M{?sAgh5e+%&WbY-u^&E$Ksi zm~YL{@f_#frcExNZi3{5C+Id|tj+{$INhI0N6dYJ<=*Yw4(0`^nD^9o}So8ai_*0KfjFCD3+n17o7Ok?C9Q67wh* zOgvWC!@J}vmP5?JMGsfNNAnCCqc28Y+jfEpd%5mn?2gO7SSN4vYuep4m3$HX4jE}L zxD&w|c(&EoJWaJ8y6xa^oSGgDlShhZeZCP9`&J7^*ECU#hYx=RU#?*G*2xkkX)B9Ce@rIT zSSv@?uBaEx-e1ZNFiwJjV2?d9Q;ob#VLb2<9lEfSb^lE$hp6>I$n5%kEVf{g;QlB) z<_~V}2!(x-Hk`UG#?MRtr{`wlCy)z)-yv9QC#{d4Ol~!|fJ5gNG(G7wzO-}&?EO$i z3rlr~V`wW_MrWA0Or|X1VF#DJvgt3@8MIF*4C0R_ap$y8VFfpD z*z5k5h6{_6KWg<*GwKS5ohIM~z-ADY_}L)v`&YpqYRK|Gw{8D9NZcb4dP;jbmYARk!BnZ1KD2A zYKARd9i<}B^S4@4$gU|haBR&Yx_BL92N|*5SL+&-av=mCRo4*gMigyklBSbSV2x`& z5;h)Bf_3^~(bzM&KBvZ$@h4khvU@P{9KL~9jP(-SALl&UOCEgG=3P$9AdO>dQI3n0 zK+nIcr{UI*jNQ8LJbiZ=NQ}Z}b|cO}u-PB)NgE6PMQyY=Q;O7-{DymC&F0ry8u9dB zX%NI%>rWEP@#2%wV91_LM?M`UpVk=hV=lO&PUZRd&4qr!?%Jt|v80w)K)LlZYCV`q zR_%4&KH+(PD6tuFx(7da&$cuYIy!h6p z9QU)jA){ms$}1be#KU@eJ)SStalUn(PuHT@sOC zEBS&}92!IB`FDVm*$VX5GYIR9a)6?X)ig6uiHuwE6;z}(xb}q!c4U5Z`dyCO2sDeH@#x6~bP>qV~WzX?bmsAMMU5?=(hBwdyHZbD0iLk|Od)qG71C zga(~tpJ^Bd{Zjp$><>R|e`5pOHL0UzLyE-W{Se&Mm*E;e)?(2G32<1s9o=Ug1nZl( z!o+tMX#WkCPe0QJrIi)jMPW<)DSsf(!MU4;HJOrJy>h6`e?)bf3dxk4uDs=4Q9Mn) z7e`qa!hbed^oW8a!Kc1}%0D&q{L3*iZ_yk+Yh+V)!7W{)c&-gn-Gb2R>Kj<527}wo za(ef9IU1_kD$wvdD@Kv;FIph}jTeoLksu2T8wDDE>V6nL^m{eLyep@{!~2LD)!{9V zp5=sUwaHPI_uMA-6a{z3VWT=5_V1?BtsggGA^-1r&0Sq|*H; z>Vmw(9X)ix-f_f#K{?2lXHeIlhe%g|5#MQh8ClMB#cIX>(`})Ddc^Qi6^MFGp;@Uq zRH#4AqhQF2T@%X=Kn3lM6bO8yhN+f?wwiK_Y7m2 z38m8>B{6b@?*e7kkG#c+agz-8LC@ni)IwU3#N~8COxjcKjEV+6?fFfh+X)AMVR^F{ zaJX4SM;|vNw}xt=K34;MQuo2-N>b3E(MHRdpCRCS7&O{P<=(b^hvkZ+;cRjN-928G z_(#@3e3lSWf8dCl1C-$O-BxP(Q&% znUuQ8kgKn{!6afUU8y*QbuV_qjwjpD#}#bvF>@tYrkBy|i@GF7zXLq0GtC}{tz!Ls z>>lJ=gM6|dg#qJ^vBr%y2VJ3bPBaorE6KfR`RQpS=!It@^*c!ir$ zEQg0!)>Toqm#!TvPd=$tLgDu``ueag36|_&tb^%DncsmkCQg7GL#_1Gy#*xdc_qBl z5TnO7>5xLm1nZDswDM{;epea|#dizn)t0ej%FzZ`yz?998)t(fS4;=@=r;OmSb=!| zt_BH*g|x(1m&_m20Xo5UXyVckym>@Jurpcc2gLrFEB|5obk0P6CRzOADSSVWk6Jk? zGADijo(4qa+Ps%0)o;7NtSS`QM_tF;5AB9v*Voj0ygf45Bb7IM(Kq_8G8Nxa_5i&T z=c%4bCOJ06i8m$BQDXEl?7U4Jq|Y(k?j29ERR+MvtI1sUXd}K>mkvoA-yl8pa;&&4 z1_Bos(hYa^l5>MPyu}A6)ckTDo?Z7#;33g^szV-aVefH1PwC%)4D!p>kq^DwiVCC7 z;nk_r;6+{o{ii#T^qvsr_x0+bPgZW&d*cFFSNesnnLCBVeP_Phu!5YJBwb>XG6;h& z9-_?53)s+?W%?A#XaQp^%w|lCE?<96C+#VURb4IEnY5h9#jV>}{^e~5eO4ktY?Asw z)6*738wO!T)pf9{q?*oloa=idFS zNa}36A=Uo^I(z#bc6Hvy-UVJ!t0KmeKhXhm%{;gR$QWs|%!h&hWjgEWcrv^s225j1 z=#J^R*koiCEIO0H%}e&fCbb*k``tRKX{bm}8vlW9Wzt-#b1e>(N@N?8cGUam9+uj_ zjd9N|&{r&1vfHTx{_U^iK7Lw;K{@|)gJt~p%8v4Wzke$ z2{Ko*31%j#p|tGVbMm+FkT&;CwJ0aXC@LE zt{Gk~v856Q-sFCv9`D_ohANE%@Jmx2$QEg!S9%OcaB3~cbS^eu;f%?m(~U5jt46(p znRxr96(IL0jowchLq6^9f}kyj(KOdH`23;mpfL$(s--fSYxn~+>r=T)o$9zF@>|{n z#uA@B^A|R>kAcVDMRaMD0lBcK7Ak(Kqj%NbINMYTYKB|sL5E!SGpuGE5Kg%RtZ%}g zZX2YoxcbL3>3j{XS8ZXnRz^rk}|)Z>>H_Pp*c7!ga_s zClX&M{hx+!*3QKfC0Rx<-`e~^T_y5*Mf0NAj2iwR64&*+Lv#Bw>LV)4xb6+$v{DcC zhxy{5PlkeBiiOJzGWJb1;8HERRY;el9;kx3e}d45xO@26M040Ms*KjZ&%smHTf=g! z%o*DtT(V@gK*QCnq=|Q2H?;2aq|4ZMd)kDrkl3>oslGjh{aaT;!O=3h_mVF8{-YD> ztg_6iWL6QSBf`A?rW#aU`w(kSUI7K`o>S-69IST88oqi2a}htT;+=Oxfg7l%j}6C? zrQHos^XoEq^r9TzUj9Wedk-#RKF_O_VBy93zS+$sqM{St@0yP6%y;0Wt^d>TaCK7> zoy>IJX$&1+t3zHb%La}HBb%Gdb2uXg{^}G^hg5N*=G7$d{_R|8gKz4n3Uc&z9r8qJ zbPdctvVfir&?O1wolqlVj}q#GvCn%=(3GvG32!Lb7~sm^kx=2hUdcVJaj_*mU(#V`~g8jW;ZWB@>(I*#UJ@uuF(<9ov`_ zN!jlt<`0}Td4x(_FW@%6Wdc2aQ=(7yiPtf<@G*{i^b~bxTMKTK7JqW^&>3qulo&#v z7M;MMR-Q2WYd&Ww6NF8@9YM*whVtW-$dA77aCEN*cT6cB>mKoj559HC{Ae8B^K1)T z+ywMcqdqyLSO;Bw%^Yd8!&x&11$~hV+j8*a!`2}2YC3hDwH~h0J4S{qX{v+dqmgLl*n2pA!FE_{_KHe>V5|T$_MD|2oVbiJnymbVWq&WzMf1lK z@$s>MTuZ3ooIg0!Gy+`i_j3^ees~7j1no2GsozKh{?Y0NiM@g5lZ$FtzeXa<3biAJ zHTQ67%y!rqaDlGO*Cj7Zx?twGD(?2BWq85ZzXCqtHmP~cw_gtWg^4spyO4B*xbrp% zqIe(uhMUxiVA=Idx&R`uYJeL|vx(*gl5P>s)tw)&cQQLUT9;fN+XYiagVBMZ>)7hW zVt8FvMpuZIqq?>o0#D#Y*0WrDumdta?WGHwBJlEbH*mgQz-_@{xY5QIzFJpMtM7+N z+pr1m{PPm$k-(l8QeBYvfeVJY3Q*D5LSsCbulTPv*mIVYa`j8cpdL#C*zYL{9dwd&IhG z)D@eFot0KWW?vdL9Sp=bL_NXfS1(u2ez%*_-9d%VqP&qbQU6>AZ%ku3?HTI$+OZzN zp1d;XC*HOr7AAfxq#^8`ViBo>x6{;-MErhyGgunRlUiv4pMz^|*ns#mr(E4l5%__o zJ1krfMGN|+NJ(%V^s9_;DIeG2amLeNxV4oozNkVXttz2^Y%=SNU>x=O8W1jWKpVv) zaf{tJ-o;vU|s#zAs#DSc${2TN^; z1nDYUE>jp`V(aZyAveox;dd)?#Y2Suo?3&7yC33duU9hG%5y4V_Xq#o9SJj|o^T~*SMkHXP!PFW zO$(<*;2YBJV7FU=i(4p%+k2YwY(0AEidB<{OKBzOv0J%Tur7IhuUo)HSys9o*Swtw zZzi=-y>!;slgI8XS4LCKqdLSzI2WX*g|Hs5EWD#625v1Vpgw95IC_dZm@U}L$!1yO zz-h+ns=aQG1uKbC`%A6Z} zCO)lu4v!u4k)q;Q*1y&Z32KqKQ$L1d=Lk2LAt8(=Pr8Cfj_-t5zj-=oxe~EF`vv}X zXK^AX_GsL5nY@tj?^GjMlyqHLkEOs*TP+#Pr;8 z7?M}CnV%dC$4iUdp!JqF+G0|QW3^(T@^}GNP1-}WEA{vtlIzhQp?O&5{Gi~D*(t9@ z(tRqR>Rb{{%}yuR`q%UJw_DNXma};3Z57yjv4L(GeS-CTd4jk1buMc87A$YD2&$$x zQITdfA|52fuh4DCX?>wf()a#jzL!TRt@S(}SZfL1ZKX8ztR6X|UI+L3j&f!@o+4ib zTfv@OMIjgaZezSVp-`&b6^L!tc!HW%K4;9I!2A82pu)L^D*8<%`@P#>da(*O&=!Xc zhI~MkuS3fiTi(Oj9V9;hHD=kX&nhh2mDa@Fa$_Cer-t$x)Vitfgg^NAib#Ndd)B4v zgm2d(7;0*!zU=!W!oEMI7HK(8{U?*COP!FXa1I?leGe<8?1UPZe7b)1Ve(>lHt(tv z!*$3pUd@*#IwX9B-grNbc-6;(p-u@s?88`30g>><@fR1U>4#fSxPW_bJw3N90*_nk z4vx`*=3-VgIQ`i}Fm`Q6%O14iLnt0D>?o$srynAshO_zOl2g&(p@PSs}ze!|Guq!-tkd5r0y%WW8Be$#~4R;*?wsWuUNW}B?`{}9FBv)9j>o1K9pHLTI-S;2 zMSN)>Z`X7I`35-S7s5aDQfs}oLJaY`C$yy=f2 zR1X%_*HcpkJ@PP@J@-4Y`Nq?T6#2J6VPrL$)tiOg7BQW?kU?ji3dD~ZJYl4>m%A?- zfwwAofD&WkJ+GA}g9jR+!6%NpUZ93k-uLEBlkK5--+tg2i#UO{Phjs{GwkZXcd;7U zv3Ni3-Yo;c?^@|bwsUq=ISDC?&*m;>-q#Pw?r?qJ4DEU=MLt*7!?(Z@ZsCXnKJapy zVBa#tc&e?;Ymv@9r|xVYqH(zvHaR#T&5Q^xWW$%$LI(+O+_E?V#(@!tpav4=_=y&GpKYCRI-xVSnj* zG^6JvmU*-ab}lcYQobw5#{ywKG`tGko0EXAYpwu$o2PX8nJYMWc^F)?sixxR!`ZFY z9qbn?a2HEuach6GK(`;+OeBMUDxpm{m5QMQ#9e1LUzhKW!c4Z~;jl@9T}qViT+++_ zAC(`YsKId^vg0a+v0FmW%H^4O)rweH{_itYJ{68vWVyq*FMGI#xz_k=!VG~wP&1S1 zHtWc%`E5!YwSCEBuUWjxsmo|I3C58(W(#zCjYKXvFX6^tM9SPv?HNRE`U}8E^U>Hw zG2(i;4^BHp=AwXbygkkxKB@|%1tXVni_C85b9+e_t4$&E*v_+fR2FwVXAQD^Ba?U9 z`x}*BE=rbcjE7%ui>bL~4tX(S3tzh}6`9^Yia9DN&~5qEtH=?HdAzW&2IuY-j*myU zL(B$mWaLu9D%@is3l&hM^Lxno@dg4f_qvR^xJ~*`-k!PN=)t~OWM_N@ynOSRdNrn! zLcjHV(CcPYa_cNEx;tH<+jXl0v0k+&e4TimlPq?{O*75F(2n&2cg!R|9}4jWKJ__= z+28nRw-LCY_!wPsKaZcQEr(;w-cauCtA{W=>IWS$dVwzc_83!Vl zN@&M|Kzu6A6W(OL;#@;d;MC~#V0WvAUK}-z%3`-5iHKg${tp-8%GgFcya~ zcKVeUYz}u|+5F{okQn`i+g`o~`!@d(>{UWk{^0lnC&799S{jt*h;4l^Jb2nn9ohFV znSBrcU$>2}N|Pu18X>eO5`A8BAD=qz1wZ-Mbg<+wvA?g)f9s6l-ZvPbXYMVuUH1xI z>@|*j%#VWv*%B)5SWFypckn*mpHXSvQCyq38N{pWsZ=%Nn{giCc{|V?Kd;8t2ObG@ z`_B6oTwWUwgSy4kMj@2^F`v(;$jn9xkxTK`8^eNZ4s|jiVh78?_g_4D{uA%wud(sB6f|$Zmj$_1Q% zNGKj_Y$uq>)1L1o35^E)UX62{!~>SKyzmV+2PHE;dOS{+afDP8)~~dviYPgs;7_Dq zK=*%b#FuyX=WWRCqCr>wp<9gYjL!7Z{s0Mbm1&Xok97L1HjsGLne(z*x6!tqO*n?- z1?rtskw({1z7q`dJfc%NzEUW-`b zDIuCrmfJ!3p{Zo6?=N`RyNPOK93x|W7Vr(50sRd3#|LWlpzT*Z-5gU;9?TyWY zm_0*sgn10^SEHNhS=cGi2G$(Rp#HVt_}XF*=%1fO-`GhLi!qIGxi^**MQS*FYp;N3 zrFr}ZRf^+sFsVOV&>z>2E7{C zqVR|Flvsxg#wZK!m`NGa$bYF7aP+`4D&(z8yu9k*N|ysV^eh6O4Nw!z-fwLxkc2NU z(By*E;n?n{2h3W!l%Ca?Kn$L>v;G$&B+Gl_n0+RK+hyyZG7*uhfvX2*(PK)CGnrfu zuls^g?zy{|+kjznJ7bexVBO!g+F*LIgI;tC#~b85;Ss6LJKtT}D*Yg!$6>6=>*UJhm5J30h)L>Bz(@IJe+``rOMt zbAWy3niC3KQhvCwquGqpMvj&lfmZ}QvA<>s!&5(j4j zjBTfj+LXyM(gn#;7W8Vz6C=i*5Ye+BxipRGy!_zL*Z z^@!#lNF{I6H}H{J&FJc~vv|@4RhaAFK>we!SNmZr7*D;7Y~QFlu&mFz^=!(LhtQY94~tUOM7jAOUG*H&<#cMvaJt3avI#XfmnROG2#v2Xwbw>?XbmF`G4~|4|P%H3Ud;gUJ7#q?$d8e9kJdn z0-t-D>0$Q!xyXJ$lQPqCe8^-%Z+wMgiRaL%wiGNH9}2~;_4Kv>0TOgmi;q@_=JwPX zqTf|5f<4JduO!(K5)ZD7)toY$acd9n;x|41jP#3+;sKW}Fno*cS}Vda&)C0F{{qd) zylTAA?lGJ_(T+S*oAJ)o2~e6@MBht0{1N$gYI59);#VBk3FNglIrVZ-4YL8DJLTP75n|$ zob3T=*$}k3_8P7$T?&$ndALobilo{H@rx3*(8%9Xbo;>`!9G0Zh!8OtZiQtBnU`RK z7!he~0$cUf=*QAf#&5KT3qck1N$wsp?XV&LtnVy0BUhIUo#+7*sTb(wwm6*R;0S$t z(&?D$N)o9Z#9zt3fX2pb#9i{g1vB>S2P??&;ko>(OBLJ_=fCJqRjEL$2N`cFCASJ5 zG9PbP&jhkrwg$fUnxOmRH{q1MQv_PAe0LU68L5JOM{8KPv_b%+i)}Fr!h-SqjT%Aksv7z^ zX&+7;B?p1`TIsF;2QubaFDwrFom*!ej=e3m!cEsG8t_??xNKnjoO6G;8IlgT-9<&9 z;s4oAB@EmFaWPM+B+F&@O>cx_JJ%t9^$5JkNJB7Vi*=TxI|p9o{ZQ|tE(gQ$)@pWt zmtRIjCMuGvpMJm>(FJJJ1aG_t&w+>68faPhG?Fo+2J|0l(tSpZM;gJNLAD`i;om#> zCX@927fY$ptxmFfe=z?^V+k6!)tq%1>j1CVN!Qnkk@V75Xp(lOx4p-a&Cly${jdWv zkU5Fn-L0XI^)Ci~d_es7yYoigM&{xUONgSM5dZCWDe5{MkJT?)!S78^>8ioc@y*?R}l}!InpA)5}=XJ=j3LZxP4nbvU>9~4+9PE$y zOr3OA<8Xa7fu76gs1oGd1F2t@(VjG4ve!|YH@$TQeYhWlZFgwHzri|sqc@8@o9fPQ z)tbgtXzG*Cd_L%@mZ6ntqln*%9;hD*%Uz}wh7ZShz`Z*{C_^I=w;vA!S&v#eE`1tl znA-&}o$|O#Qg*0RXF{I!@9)&lMTD%%Pk_seZL44Wg1kPofwvn@LK(J4u!zlgU~W8W zb1IHJe0+tkw+rX0)a$TPS~e(Ky+O$VMOf>89EhI%OdXyvPWYS_nAbKA&CQvEZ4Ues zbWB%Nu*aZbbIj zBr@tP)5Cwo^jB6OUbAx}(DOAkXF!3>e((dHj?&;7f*1pE?IFQjJ$kb)34hfn*nw=x zvBe_ihVv%9>7u5~&4^@LDcnAGk4ijShs72z20w`wx^tN%d3C=V20t#$J>WEsq=nZ* z!k%z6arqtmk~~@Z}8x!`B!rf8;y{5PdmL^dxZvWl_bSR3DB^$m}-yy zOxm-z^I1Y4(0-qzc<}=_I6TroC-_K{9hpBM{NY$mHKhudYbC+rTkS}rwh7w*+bP41)Wl(4oC-RFs zLElpYjT*W}rr!79t*j%m`^p)+$-58q_lBU5RoC#md&|IUcNulosvvLmg80N^vytq( zQnY6CzC5?@>|VK1h-}!}4vYTnq*BZ`DE^rF*hN<(XVp+Ve0MFJY^b2x>PiG}ZiAVV z7jY65y5t!9{ISc|AK2Ig~=1hnCHK^)hb~hnS5D*`N%6HtsTn~XD zR7&p$b&}Q{A^iNkOORc(8Gc=?BiLP=_l+Udg{`pPU?W{wCrRR27lz402lV=EB;Gj5 z1`ZdL(q%pOi9(e-|FX-_JnKFo=U0xv+2h4XNi6|um#l`YbZ;%ODg?x*sZcR-1p{UyGl+w+rT?26xziAFO z${7}Typ5gIiECp8)XsZI_s%sYLh99^b=egayGLQUSu5_ShWaMc- z1Y~G%=cdQv(T5KUX6*ZE6gS=vg{i^~^yqF~LXI#W^0H>`-7Z_aUQ!7D-{YO-xsb#y zD1`yNyHrJg9sWGU0)`D*=yYwiN44*Ud!-9H z>#-dlFHI`a`e6YQ=S(%L@Y0SX`1YV3?dkl2m0c5I?aU$y)%(c8O2%A@Qbb!Kmf*5e z!tg=nD@}AaAX}f8!&;kI+HFP2&O|5Pa@G%|Th)Q5E0;p(-3%(_C`N<=+ThTKnP|)K zRo1EP!9U6m&;Gsm015Ba;R6rmplxOBc7Mo{&&}y(&&Opy zVZUMuI_evbOZzv%@QzHHlwm@`hHK!5{x44W{syelHkhaTq>JVjj3()=KfvQw6sK?e z2icdF<>|QeQVX@Qq`wn9Udd9{->TH6BJe~2~qe`Ijx`hVq)*zo(R)Jdo zM0$(OfpYJQ!9_k46_8k5qhkh6TTAHC4mnc%Wi%gfaD-bMycGX?JzH?2)DfRdBCqto z^%4iV(D*PpJ#``f!i}Qld_U|H^gj(xWd6^`?JSG*o0!k~k0a~DI$@Gt4Z1#%fn~1S zLEgu7x?E!v*;U&Ea!U`RQnfocZAv&?x?WAEdr6RGe`;Yc>OMF7#!SY(?$2Aeg0Wc& zd+`^X{NN8uNGvtF@Pd($_Q^NGjf&4g3UE>YoP{(UL7*(LNlyN4?(v2cd(|u1r&Oe($I1Lk&qlvKe&=@8ZKD(y5BdHpsF*ls^!D zI+}BOD}(JyJMz9-_0eT}Wk~1ID)>GznI4z(CYJ`Z`Qt+FXzCSD9PO$A+520m&>Y4U z_h6iaIU@9Rq7G4&c@6nzLQ%=|G#n!n4?|*~=~0#!h+N$UTOWVpHfgNFmWk@HTfLpe z1WqBRQahmF8lv)|KIG$l9p2OO3X&Q*fn{gt3Upo;nUHnt9_PIAiunxITRpY!E!_QA zhPv3?a_Ms~col`^TJH_PP1PQdvya`Kx5ncs!(nh>O${C9r;>V=uaGr6kG-Q=qb)Ng zEPiGF<|Y~Ra#rz{uaey$eIrRbr|szca0QwrLax6&VDM-v16pO9EqXs0I>#5_8yDjtV&D@!`B9D>kgkK*OU2N*A`|RYJtDYKYE4ih(u}3BW>N9w_ZYCVR#C8j5qQv@DFWl=^M&XZL@W)sL;|iN-+9wr~IZl|b zT3nO!M^lkJdDsSp>erEI(pfx`W(84mOKB(bhE?P?gYHc~?!HA5>d$u&a7#q(nJ-Z- z5fo+@(_Q06k;g85u>0gnG}<%}XI$L`r~cMZ9HL0%`hG)fs3y1kTnzra?+94>*C8Qo zii@}~i0i1Q|0HzDrWegH$Euk-wZ{hc?-hbkE4t`zuLVS+iZPZS-Jvn{4tUsT2|T{i zLKAOEkS><1@)KH=TOTMvUb6SWX4f#(o|ue#zl1^Hx;pw%*oQRV)8W_MdcgIVMWSmd za|J!c;j<)&`I1EV;#Nd|4Nx*~&PM)bdk%UPdjw~W^@RLKjr7ArX(Dy#7er1K=d5m3 zV%e-G@FT4qt*dFo`9+Dqr4~|x_L0maEq>!^MWjDuffs0t2C2_7E1S?<`(6apfh8A1iO^kFpSd~Km6MR#uqXYC(qY* z!>R>#DDZFy{&j90gpE{CaiOVXV1V5k7A?H71QrJ#qB@iEgP z36iM={kor=u+au=vFDFK=ZEhMp}kcVc|Sz^sPcF*5}?X_$cd?R$W)Hdh3xiWW`Y8} zH{#!EQw95z`xDg3PgD)JtS8djKxN!C0v1O3s4D4~l4plgKzLh!(DH6*!mGDwCiFQTk zkm_A6a7Nh?9c~N5cOqv&hh!afH_Rvg32uC5=6bGQt_(e|$j`Id&_^5B4PvQf6;RJI z_|G&X$*|)WcywF~tsiFZ3s>g}Zj@$MrjRV>8j#(tPJdiwpI_MmWqb(gxq2Jt{j-23 z*-~02@}87k+s5U`ddChQ1$_e#(Bcb+(a(AR2rNA?hxEDowiAn_<$-nu=F`?yt9w!%+uj(Ox%!t zg$H(!R0Q`$tyHE-pExrvrERbU*5^q+nMUU{KtxqT`geu;RpLo3|ws{u-+o#wC^`}eqR@Vk%ch2P%f`WIc^`Q8;Yk)FUJ%6fvmisug_a$!jw z=v=*QE@!DvMn8KG7N?k>>!v7)S@HwsOb^c;2n)tXIy_h(%`n&XH4eL83>Rqol*@{w zU4-#=^0T=;CDy2S`oz3fqrTD3^Xz@u^dZc6RY*sB8IkrowXh;z7fl;;2uE#|hAn?u z==k}g$z!u$aHG7+{I^04{@0!h;&b1ifYAlGLq7o$i#}0_#d2h@vJRfk5JUT2Ot4~< z5Xg&sqaTFWEmDqona(B95NbdSBN)?Wp9|{AK7-|@)!|=xJ^jGunQIn5Vbm`bG)CA3 zZ}!3hZ8u6#CO0I6`KDFXIbkam$O6fBkbHU#rOZ2v*IZl$oOCHQ4ALbZWZS^8>=+mO z?lG#WUMKK}H|0$rMb(KQ#F#(T>LTO_+ws07%h8K5fw;TG1q^I!X&O-^yQ~JmK24KL z(~ZFakB)+QR2_;`cz|~w+XlA+DOGl2U7wY$AhNK9TP$INuNezNtWy`g+-6EX4VJ-^ z$UAg+lLP*xycEX#*FsAUNRW*tJuumMQLdEvcv3=Jz;k~jN|H&&fjh!MQ@@VBJARCm zJvQOfJrlX3Dv_wTXI|bYm2P@quQ(Z-nh4uyA&uOaMJ6UV^6S$x(7V5f8N+`oSbS`x zm-M8`DYpS|yCcqhR;a|s&pn0cqINVjt^wPsKZH+eg;c_E9~l(Y;T47z(U}knJg)kG z+Wx#im)vMBhyKgawA?S3ge~33A658)tex6$!RJyCDoUqsKZ}t~*SkP{gF4dF-$CYY zGva*?tjTVg=1ul5)8)MevXFJ%72ILI0^Zh^QV*7UI>hFIS-?7oZAy@Pu&+SdUmgC9 z*Q7OrWQ+%m@*hJs+IB$oQ)@JA9)d-49U;)Hl1|^GK+b8l!-ZK3xCbM;Wb)VnaF~#a zY6j!5&2twp&&{MKwT;NSRjk`6?+3T-^LpGl=AU2>({sKXZ+uV&F&z#H;`38?7YS4O{RD4;~9*$_H zQrp5YMC`;6NLU7-YaX|-9~S|ZLe;b=PMqvwyaM6Q`nqr)F1h?Hj&%#YGSPfqW}BbVn3=JvZRN8H8LKvJ+8 z{o$xf=(TqE9T$qOFT0J;s4j)MN~P5AqbL!!XoYX0PITz41SxZF0te=A3|_~)k#E+( zM8?THT5yMCANSxJKkJ)I95y9&b*x9G?>(CJIRTrWwFevHWO^~3G43At@?8rrp%U|p zc+WrtOut)2uYZ}ux|>CK&nbzV*F$N%ZBtj?l~29&(m^R=8B+!J7oSnHn7!ogI~`u6 zY76>!&;zIaPy`JRmSauOBOMQ_;9!doRY}t!5)SWxpBaV@#-!j~QVHPk={M+gMNX_;wtl{0nGo9L*d%eH^`7>xJtvegSYA#Iy6a^s3+Ee`L;1g?Upe{ zzlGrc`{+;ds$}zc_C0wRPZzSzg1PUi;m`g}D8>2=E@@VWi+Ahkr8nR4xY_m4d07@s zO5KF@P7=tP(@bCU@}%I-0E9Rf<;Xo!AkS8JLgSI^$l^;BUV4XhwJVm=6W17XwWl4b z&iHeqG9IJ#2b=_Z7#XbzMC$ZIsBtQyMcN_+S@nU^kL75%J^E}eLW_0u)B!!n6hF8ZT2E|wMn{i|K{MDu(i z5?&5D!?&qkgCx1L=_fSTnCIFDu)o2@jW9tg3>nXPj-zQfD5loZ6;j^haj+h*`~Cs< z=~@K3a(}*HCZEN+!yL{%gmZTonuAXR{X~kWSPnwS zS#fUl=?Z*c%QHx5ZAT;i_1GxjA^6=Xpf_LbB^nJn{Cbfos9?SYz7rz~Q&qpx9gK1P z@pm~a$$UUdF66OH`eweA{6gP-TQT^RfnG{FjbwYO#zmd5J7*?(lj=d@ml*JKM^ zo;!7o6eILMHk0()qL!XuT=m`w{5Muoi&;~M-sNu4tz5)8j?yFj&4W;IDiwt}#$k<9 zn?aTFsVsU8h^l`re7M%fl^d_e+cys96`k#(GtPG7$6Aa*p%cJ8zBY)o##RaDbK{ev zNz9un*t8~v7TlC26Assdm8uCUOxb`B!Zg8r&X>#}YmQa1|B|B_E7`4(`N<_E!q9&v zF?iM`1jcJiXtK&zyy9sM+|?@Jwr5)4w-wrg-OCQm$)xpPKM0pPQdeJT@{ausC#G#e z&mxZCfu{fI_G5Nyc)z#17NWiP-ipxgc7FfA*ST_? z^M0Q1^O;=ZwvD*YU<%CHTTizcDU$`0ilFL79Q~Ba`h}F6;FyUu$_@*{De*H!_j&s( zA;HY^)^TY#G34hqRRfK#{57jf(_ zhO3apJ?t6kt3?Ypu)VpB&0y6Vh<3cWiNDCQGP9a|+OzBsTAb$~IQUhSwkgPvH^nV5 z&w<_KBZre&A8NpC&1O{nDHsA^*7MZ-rURWa3=Y1GIj|i&|Xu_d&LCY?ng|UrQ5X>lV1&-NBvoU4>(+XNYd{(s&JG_WcLUd|*azY&l4l zuQCwM-*W|BZuP^{Vhos%tDO38G9*Xb%b|PNCEmXAhNQYV2S&OUA=@D_l9G*8k>`ho8afJDg$mzL!+qUyZmGwS#{fp9}uA1}#k;C(3L}YYyReUU5*W z{FzF$8jyQ!WiUZW7p;&wjN2!V5#8kOVe}`un5FxN8+)x?Ki2x|rZ;@5CXxvyBd&(ImNJiXbUBh92CePd4;i&zb$oszmQ0^CWMG zL{W^BU+lIPIveuo_@{d0Qhqa7ulC{Q9*jq-Io2ZGbM2F{q;5wX%uxA4e-E`|?V$>& z8Jdr3Kl19H$Zjla`gy<&oLM_<4j-p()8`A6ds^s@J#s`iA`Zky zd}ds9I++=2$uVv8ry&omTTm1m+&%%nc&wXmbamOgDfiAOR|zO>yZt|B1-k88Dt zsppF5a8-3;0c@AepU1f}Pjy)FAly?}0vPl;e}YZnzVZ}Xm2b`V>$kp4DSBzjEOJKA81RH-%A z8Jq+s9@o*OUXw|VbqRQl8%w`U&?9xnN%?#wjubyXIn7X^^TvSu1W$b+n|5yew4KKC>|hlSl?p>HDkY-vAr$8^(^JN z9p#ah%U!UzsT5UhdxixXmdyA5j0WYHlNE}bP;0Re{m{9Aw@(O#-%-W%RDB4Z#oShE z)24FQ>Lz1ydr;t;+esgLM&U0d&afdloc?!NkCaNZLaX5nMC142{tx3tyt>}IRpd3} z)erw{{1AZ)poGr%`xuLxD8liy%xNgTuyt|l|6jjv%?ys%U{WpQwXe`@hxL-yWz7>$cpSHrET2`FQOb?WQ!d_7E zH>NBiTRVKzJrSPJD3RP!am(_Dy z!DUMj8a#Rvi<_81V_!Zsvk?+C&O!KW{WNq##S5L=;3!bNs!AJD#mVV>#tYSMrk+Y{ zPv@g8IPCq#jbr`TV|_M3lFK*xKK3SA^wwUeV5!gZzC4#4R{RBF-##G8hmUYqf)%XD zPo@bHU8FGMj8N7#7LD8Eh59c$3feVN`BVKy;;ige!R&=yR6SIlIDRRHa*afK>+%6| z`l7xta>xd`jJ3o0mg;avv7Q=E)FpX2#SlDwh)-B{?8fyh_>&TZ)JHtS9j%XmKRbt- zR7jH*#%*w^qLVX~T!lx*Ys34UjkN#JBZBQkzqdMSd5}!L5u@)60Wl{ELx$0m1dQ?1g@$=|5fj*f&vmEl*>L69~LwH`< z7#RMpjt=`IPRoNp+}T$F?_;FVL!mL2 z!V>UrA6fda201ae2zaAo7|!UCAFE11#(z87ek>ecyTm-Yiz=w(zBasWTqUegAA^*> z?!Z$6mcr%aTDsRf1m|nn!I-^V=0_71GJTNUf#0vAiQ;GR8HaVCUY<|Cu>APNYpu{# z@58;C6^~9$+b)M*KNVbMHZ>QNyJ4rL*Vs< zGU|0bo6O9+Bz%EJppz&Bo#|U3+PGKyEla#BO{P&8ZIt;&lx%{ z!CB*^A(ORa6sgQ2cDzFPHu)~~QF=jY=Wi4G+;2nYNG(p^UjQo8p3|6qKfGjx1864S z=E8mU5c6;Y;mp;mGj=}JBzo`uDqeHoDsjtYq z=ctH#v02cCf5+BqqX(kpSF1c{>~|ETWDMW5@^FY6u)>!i|^J zCwp)FftB8AXy9H9cD1$x=fsyZYo|WZh%bZjlRG*6wOg@mvKaik;l-C;BJ}~`!bvl= zP+xaHI`_C#pl;JmPY(v;r3rSh%w-{UH&i5}P(2je&P9LBt?~WO8Y2Dl#CA<$;#UG~ z2gcCk$!vRQb{RA!2cZh%Xe{fy1nLd*sl>%b{3W6k6#is$3&oeBQ6xgedN{qt9zA$>1Pf=I!szG1$ws*5a~(2%9Eq3Q4F#ub#Z=>WF#cF*2jM|loN44_JoEQ&!7aHiDx-IZY`mc@ z^orewPP}!+k9RABW^Wz+czz{0Y0wF?s$2LHzTJ3WMm_Wyy+wbnQaqUS7=rV&Y0Y=$ zX?bD?O!lcuU20SeO=s?vJ>MlZ}`bQLRvj#Y$fxpX-$z^Qvvz{W8KHTJ{5ZH-_?AiLqqSWb#%$J!z<@?ta$iJI9Ln7FeT ziGBWy#~XCR8vj%L&jo(iD!~z++5P6K8iVmgO?$Y|crPA~?9QX@-mKe-<$_B*W}#gkUbr)GECe2@qj4PTJxl0=o{0s#jkk;N zni)cP;rI@H$Y(o2f9=5QRtUYHCQmjcl!CLXBpS2L80$1kz`uRu2U{kQ#C1iGyz&7p zW8GhQY)7(GaR)LP3d47-v|(vSIsNZS8=jR{1v?VQpuSx@@D|@?;NM+Ki(az~X{{Yh zU&LiDbQ(im46g-b8G)qFoxyo#>*0xxH<8 z#l0#(gY(gTQ(t_AWxn8EIZb4L^9S}fryRM$yR_#Xj+)>ry4z2!eTj>_L!e)$oDRJ| zLPFDK39l$jM{sNnE?Oc5c`+?Ca*`<#xD`Q4#7&ww#tn7MvJ=?vkf4S_rrq!Q3HC=3 z-!Ul|zkFo}CZV!uf?*-84ACTzsEsqFgoA7P=x3CHnK$XU_4B5 z&!fL{3yAkOU*V)D1qgBuBJPcYfc0hZ#aL!d@2nm4YDb`<|4Q-M>NvRW&HP9Y)rdUn zOR?Vhj)UP#@b&M~u+xU^+?8vSw^mH2-VjC0&C*!cnYGX_zXfewUV{f%ulwk}G#a?k z53dwDK!f9LuFHBi+0|+w)c?FHV_u^d@$s20%o!;_F=m&s0^7^}hvBkedL-Ji941c> z<=l>bLAI-oiEeeTj1JsZ#P&Ds_RxXNet7?T2aq-S$kl8Lz`BQb0G}(S>mrm$ibNB1 z`OM|eOnuTFI|N5mo})hX80^G0ZZ3wtq_#eK#Di%@U%fiG7m8cimaaI2WVg_(mMysb zaRsQo@#U)H`_Y(z|6};N+F;zFVh@MC7gC?#v1Czp9avLSq&(dk2Wx18M1CEWJg!07 zs)}LB>(R7|@y311<&gS22w6;tW?f!OKw(KfU45Ymi~lWy?~1wH8TBQ2!WezfB+bF;M|N&M#n*mZ4Pale~8Hb&=zhk-G^T9b7ebj%J6|-M`NYUNNip^WE(Z}Kj}2% zy0dKa(VwE1YbjPvcnnt_WYZV#gYm0oJ8(BR#!Y{)9-G_!AKP6tl}HK8QcZDuOw~gU zksU1Oc)v3e;T3^6Uq+V|b(GOPQU_3p&`#hM5<>6A_2SsCB_LgzO66RG@tzL0v32e z3y@NS8!9~KAc!7Nrj=?#IK#LOqN6s^57xnW{TF+nr@nC)a)NM&|7K_l`9`1HL=yA& z_Cn1>UEZ*AQ}U?jH?)d>L`#o6#A8ov1=C&0O#3S&^VCiX=Q&(Q;oIENdND_Vn&mS- z-$ja;cDKQ%8CSX4k|Xh@Z5<+xoyH6&sgfmdCM|)gSMDRG)ds>d!8XW_XNz;xCW`QU zoFnt}mR7(rb#eOSlP0 z$6mE*0&(m30iGk5)Baf=4c`>g`@1zqGBEi@#G zZE-8d=Wm&WSQ!M9eC5et)F~ZJkB_VQS8?~G}k<{-gf*U^fsTK3G&Pk|% zoFh9>*10geWadmLO)IAf+w1Xy|4LzWx&jLNx}DwL%VC*H9o>`>jGrHJfM&{NhJP4M z)+N`%cC`pJyg3}Zmad0WoARma!$TxLaF%fWg;cJR<@Wb~-6_KJ#U-Q3%#8`)_a=`z zTD9V3Ce?8M)qM28(ifk&?f`-8eR(6hF&?=)fOgguUUcJKeCm;}h*$SXPRGwighGW> zIbG-GMHHUQ6lR)EMNMPZuugbs__v!`w|WkFqhAcxCO4_Y_yb5h-%jv+i3D9BCQlU3 z55h(#%vbdf#!JRKhZGiy4$@;bat1!ZsQl$3kv4ilOqS@a zOn}wv^XRF(6rz`HE#$_hqRJFEB-rC1*e+eh{}djKS86leG>tQ#b>+lDz6niw5-PNw+kUU zCyhRT=ZgMU;x4Dnkwv(p$`obxFW*G-ekC3{+xxzDSw|(@ZOW3w!4TLZKMgtfR za7nci29Aevlc#<`e`~x&H@Tpt3vUW-fVkOqv{u{?|H*ZPJ8M63iCO_TC~YU~zEDg@ zEK(v%r!_;t#kriZi9T`3787o}@f^L4d4Sc~rj^^Vm-H6X7RA*oMK?KkZNXbP2@t!( z^yqzTV|}rhFfQu?H{kXIt=n2Iy2-uSP9=|N$A`Zxr2W^%5U*eLFvivttwdY#r_GZ^ zcpjiNiFh(C^}5Pv>avXaUY=LN`Mtp?DCr(9Zd)euG(O*4hb??cA@pDtcfSl{zn}Ud zJv3)iFuqaX0G(m)_=4REq+lD{>Uy#R^*=d`cS_8IbMGpsyi+vMK42$w`u>u4J9ROM z)cOGzz01&x(udfAtOlXSV;cEiBR05N0og^nQQiLQxOe|)2sJLIcI=jxdG83f%%^e% znVPsvZ%A~X50`7gh6eF)ZEOxz+u=q22Fw!biS0*!Kf2(B(yDMoyq+3mEGH(%JE1h7 ziErZGh^O4EfKF42UbF6$6sEacUYt#5eGJBH+2%rC8WpvimZ$whkPpEBmfZJEM4>``Z7btHEq3ISq z_~Xb@n7k*I?zNO9-|p4Hh!kyf@6JA4-n&S2t9y@}M1r=pz{#gN^xQ=~5}48jmsv*R zxy21Ugjd0eclk7C*a6gI;UKuYT$vU)ijf`58{u8jW~z862-_xEiF}M(RIihoL-s6?oa;&bWypj>VDXS$h1d;DWt4?R=|C zRvrHgM=k}Um`6$Yw@xg)@@Ba0s7TZ|NDBqurP0iomDqH=4jlX3NV8?t$nzh)5E-+C z#uX@%>S?9mc5wl^jD7LRYsRp*u#9RR)+5FjtKfI@MV=NhB&8|eVBh`{ROs;+_s{5q zV52~OdAKw=%ecG1YbR06Ifmisj*MeZrPESbfBuhZFkkYNd!}T89we%WJnBbSAEx#F z1jq==rI%e<7W-5ceAm)J(qlaFjUS58GNFzR-z-TsD*gd!=~CXu8HKpq_mv34uU7_R z7qS=Ry+Uc>QF+4ct$>sUNz`)E2v^LMf`8k`cGD)1q60-RQxHwtY*-)Nkt&$2z7u_4 z5Qaf!79>TLQ5Z_yf0QjRi@i1opUAl_f{~(V< zL$3aNZiFJido*Q1VM7~zuQ7udZz_Tn+wM?asR^l9EQUwB_M&?8Dh#8F!2Wa^^AugF2|-mv0kGAq^@hGyMD>AE{=K_r@frs z8mmBxj#UBqvIEI>9m3_G=81ePC%o^G%tAY1!lIYFe#^yVOmIJ(3}d*x^${*Uyaqn3 ziKPvPtMGzd#bA?TjrQEUh6S;wAuzp&UY@3j#pT4{A5T6`su9N}#zRa>Ha+Xcb~mQ! z2-6bwp@cuqSS40fbbDXBxQrzI>;%6Djr{ce^;n!#K(GlPCCX=F#hzH`8_c53%$s*@ zyO^*9k3a_|ti!1Xro*a3^|ZQh3>kN@7@~eXq&Mi0Q?Z#>qAR{t`( zsPil7S>-1boY>F#{N0D-8XW{)MIm%-b{8I4R0?wWDRft(40#b+56j}U(U&Fr@B|qi zJYl(sAe$NF>6k&7x5kuhH0zOc?;cnP4EH`n;#FF!VbfX0lRw#qbR!)EXWPcpTY*E^ zFtZU%S8t}<3G?|JsDnVSjfig?gr&}If%O^R==HpOGuGVM>}D|t*cx`syrS%)G6AGSocPb6e*U# zv=#C6yOS#UHlZHY6pTd;*?aI7yGh_VP)GMMTurd30gZHVdg-GsY1jS=FRFu4*zhF$ z{&g&Ldu7w?oUvqWnzYdExinHUS&6Hgbin6#BRzbYWnntnAi#7nmCaNnN!QBYNc#e` zM&1{9-ZOy=nR3=w#yYD#Y5-eD@KTr_x|Hpij`>r9Uf%A2TJ^ zb;i5~CZE$miynI5V{BJNd2SumYWzK zfFjRr!&<*rfSXYr^(z@kLNwVv%ZU$}3Uh}OWxF!So^}S2S7BH~Ya@8Zf29dZhls~b zUEwK-G|qlR9Ex+>BN#f@O7Z(qBqHSrTvy7Yxvt&#EbIDvn#G}KQoeZIY$uq!yOQ>a zk0r4uf5Pk$T3n36T^#YjPsE=@ZFqt6euqN0PZ@2R;6eOYhIiq9Eu<)JfrHn{Kv-}K zm3m@K)@?6_vlk+1#Mu4Fe~@A6ISCqlO^OVKb-~T`^Z0G2%!%CyJ>m2VA5o-w0#wJ$%Zj*^^ZL_?ys!v5^KR3kTgK$9SuyaIIHJBol{lJtkNCL|Iir2t{fwc&Wwn+PnQx()(ZH{h(7tatZ84cwV`n%k-K z8Qs0fY~nCQlnM2mJ%MbQ z$~>{zBWV-6?YSd0FlAf_y0hXQUKz3ie2?bSwYCj-wofH!>F07?Gch*kG!S*z?#PfK zr?`5s{I!hk+$K+UeW`@QRoju{(?gg@%@^_EN_BUMWRRV3)6;a`&W(%7qj3YUC9w=` z)p?8`^sWU7E{=Y=UX2Y(N?@zXc2vLh8kUPc4az}9^lzsuXH}ZkNB5%ns>GFD9^QQv# zC-RYFYzF2EV_B{a#7KI))rgDS`;}kcNEqAUEW6 zgmRXV=qx&gpGE46Ztu0`u4o#=#(($r=jEL^(zXVpx z!a-1aXgrl&IE4GunxW(6W}0?Wn#lLEjTOa>sGv3wE8X4-;l(M3FQr}?Hnh;bxDG@&z8wcUzv#GJSJULV%Cd}O_hTONA;Z=KeA?F$Mock*g zr>h;nf3}z&6O1K7<_G($vjEBM@WF9jv*AKV84X>>u>Cvhlsg>3+qBD&j9FL&qy0;f zTgL#dGVK8+y#Riq!w6FNVh9QiLXd;+T|E8UX}B<_n9fTcL8NzALH2)7xCw&QXn(w# zh#Q|a>nBD^i9lxNQcqR3u^3(pX4iF4yOIaq|8yLP&#I$F1MjhZM;zGsWzjDA;p9zf zIlQu#Ko5cqvHx~y5uQs(su7#GBB)(;kB*mMnd1Gmu;kuOq#1D<=dtHk@ab||n%;~n zE$iS<$ryCC&l->YZU#5Z>*!Ch;Y81mwO}uNl{vd)I0=+wT_|(TqN(e{@Mp12FmU!O zy>r=<>?qU~4s1!~CWXZ!H9s4{d)HQ4q&tdyvq}WV`?*xwq6(kXD23-G#^}AL4{l%U z404w$*}lUlVx0E_R@~9#T&_i7L+g_wJnxKpj$i+G8ticyO@DlZ%t<#8T3wuhZe*>- zn`X;G+IPl>?=&VK5=-E1R3yEe0n4f7NLprp7!1*~+oSbJWUM6-ErZ0VuJV+t-cTa%1!fblEiFNRv zYk{nhpSYQ37zbaL6LBdSlcteKsba>Z-=>Q^j7aU7V%WRb0bRIJfyIs%!&|2`I-yyL zM11Xmup%;x1*73z9I%c)4M!=6_G_W74y@y4 z#BX?)dWOpo??prTm4fr;-L!wlUmRD%zL!ghRGa0;eq-o?tfW}yB3D^>8V#R98JIQTxBOSC|^9~p^m^0`(r zWdD{%n6h^{onE3qdWPy?>)PGOsK*Oq*7W--Y1RIx@0o33ITuP_+5s)#DKjUr7FKOuQr0(W(~1|AwM z4*xugE!XPsRr>_EADu<5Ub~YmZ2!fN=Zai%oUqa&bx@D4qwB&=h}yw&D6q`uAHUsz zEzZ}#)#C#6ZQ)CNH#v@VUS(15yVB(H$_BVuGr+YOuEj0mv_;wfd)=dm1{6c`!x&mr zbdXfC+~PQgNK|@10Pmk;2<;QgsIH9(`M!a5FQwXM}gnM@zi&3KRzE=3%9zgol~Pr-b>U&f_nsSxQ!vv>@Egpu`;A3 z{S*6&^})Tk0RFN2GQ=%&0H$;Vpw+cec-N{h_%WiG&SKu?FHg&1&4W1ZP0T8U2Gj)I zkK5^sx_;b$ED<){%Ax(OtUG-adpG~8gMwEc#QS%TXC2G6bl{vM@pBg!4m>L7IsbZx zU#*S@rwLiKXXP+rHMRo6#3Yb{jv;=bAOpq~EN9xRLX=rYL|yP*Dle}`Ce5!0)!Dm{ zx$$YN`#~4XoXe^AhXyPs&-BW`(ddnZH9j8A_6@D-s7Avu(jmc~W$~{vUG^xDHP7q7 zZT=P%8Jk;4yk)ZY%Pum|q=9CWt4&dX!7=b(CW9 zT}5#9uL0^c_Q5&NUEq&m6&1TSili{l>W%f2xdFo{ytDVD$gkqwoQC_mPlNPeDJ_(B zC&#a{Tjkpn^nKQ9tePh)(l?#T49IbdV$gecjh1|NMwPOTf}}^{bhd*uxqaXVG~Qak zuh}9)HWW3&a>F2`^dt^nHV*^)YbCUAs|v9#ZGhOz>pAb=foOpV5_!&_6i5-Jj6}Fp zm_z6L7?XOI!RcB)8>Lk^p=ebHLB-u7zRqH4@|kh1&!0+iwpA%O_vTGFy7)cvRV%;) zf&{2tluaK?Par1`vJKYEPuw{H!Z+p*gM@=^^o;maQg2iYA3bi-z{Q5-(`(iNILjX0 zzg3P$$(Dd%ej3$2+ly;ztH54O6+MkqBkrbyknK1!V@;158OUn^4FfOaEVzi5?%u#M zYx#5myU+EfG{DBP(_CXx9vT+pCzw34jaKP5;*SSv!FFH=mAk#1tUEMUcrfKAQnK~O z4QaN(HIz{O2o6>%jG{D-75OlsP3f~=W4!gU)QhT#1{P|@$+`ROO`&%MOIv&@-0?Q@T zrf&pM2&;u{ojZ`m2rsPfv=Cmttf0fpj+32ej!TBk9THPh2kwC%(U?_icQteq zB<_x>!Le2R% zkitRMt-9O@$f`2BaV*=9b1jFdPd@PIbtfcu&`}`&ESP@(*@`{)m4a+rGUWuaWLbAB z)GgCN`Da}4f0+mjJgVr^QBz3Yz5!5gHliB@dSu6fpK!P>1nIe4$5)5e0M*W?(>@vz zo^v@o^Ss7+Sv#WvgS`U%t>bC^r62gkjym?-CI z!_>%v$*pYHCVuhgi3a4F{vaI8eZ?~AF}R~@H+VgKM)y26B7USC&d(D=|BZG=arKUZ z?4l&T)|C;s_vP)!lX62y8HvTruR zsdx!m*r!XPb}_G4V+i`=m4Ho);$YdCEIJ{x1s5(afxFp-oNvSm9IvMjg>#zd`hALw zCF+7Twk$WKrAUsSse<^23)wE)aojZ1RK$(jBTU zkKLK3>9iq$Z#+YWG@t(oR+RyWXAp(mW5Zx96w%Nf!%6PGYDoB)z{Sd~Mh|T!h&mF7 z=S1O4%6lQ-IEYRS)+2XrHG;%9U34kW9dE_T@UX9z+CGycZ&)6-`EdpBM!{SBH8>v5 zoc}}@O&Lb=ohsqUd|T!Nvv@*@vOlcENeMNJ4qW6qqxy=G3Jot;9XHmZ>K zer(HW;s(y)K_JqbibYsG(Nl_4h9?0#XefW05xIDy45)<(YPsQr3_KkLg;R_9a;8#5 zwyzHq)LHOkQwml=w?tUIdG{GS@$X&`E)1pt!4t@(-VS)*lf~UzhH!M<|FJr>WeSmE zof7lj+@y=e4TybvFw5z466UWJ6%{e-b^d?Svi3KE!{RXR^OQWa-|(b}1Glkhz%9Hw5mv{0 zE+L^gbA)f6GOl&GKjvxKgNbb^ZE#j0nXW&f$DZS4ek+sXgNuKwNSJmH3~1V zFo$v3U#W|2EgrF=8j7#yaO&%hAO-dgUf!%s2V5n|1^YT!UQXDa@^DhzSq-_24{=9c z82wrZ4r-NDS)XMRH`)m=XQlC~Pt7N{k_I4y7Nd`kAK?MC2@V#=QAg_%ymw;}Xdx@) z9(x6kRtksC`9;)n=33(YX|}Mcd5}9EG6@?$7YCcmoistS7B4DJ0C9;dn#j4625CK^ z_EA^lq3MLn(El;KakddT{iF=iCV%1U9Ie7hwk&5iBLlhoeSr^%$FuA56Lm0_A%zQ@ z;cwwD&eVGie%|x{+k4%@k;GW87;+3B&{qcn@Q7d|XxmdpIaMRl#XS6;vF~|7!<^9r zA1A@9{ULOVQwxqbSqjTHB-4Ud(q!G_7RWT4iJS+Wv1>Gj?We0~b(ki3S=Y~cp$(~* zDbq%u8wekT1DZGPI(D3}4#pbi)6V}4$>S5{(E0Exm-5^RNf|haxRjFJJ^0T+4IC4$ zq01)t<2TI1a8&X$=c^oupNj2(2aeyVte9_ z;2zQKy`0^#7k8Dzndw8E?g1zCpl+`~1o*NcU_XKKZv76f^z#^%-VFLT-_; z{pdUN;_4mzcv?7oxLrhT%vr{8c{K#J$8#~mR->p>69p;`oz#%+$lO(D_%kJl0^_yp zPBz00OFbmN(jA+qs)#VW^6)Rbfo1eGT)y$%{(XZNNF~6*4WDSbJ5 z059{Gh3XaUG&yfP+1yqHY3fn5mGv_}bYZ`%=G~}bODJCHq7Pw=^G`3V!f_j`fS09! zk|%hf%&YbS^DE-?nxQ;#cl`k`wcckozh=8*skIQWc8$G{+$W zVc0+_*EH=h($BRQX__%!3gnB`Q{a4a=o_aJe6q1vbcfH|p9^ zPk5B1$)(P}gU=5O5b-KTjISst34=oprS$G}H==n`Pqk(`=POEKHoIxBo?~a!_R3_Xy9!)-WlrzYMWAM^BlI5 z9@7E!k2iB&eu3!wb|Uhnv@}Z+58bB_wljxH))|loz;@X88KYaAGrF1LB;v`<&P$UQ z^M8RtwG`){{tT}wxCN69-y@UIQ0&gOB=&X%(BLl<$gHW|AXA;q9jWE8S@dvNd$Em{ ze49)uuq1 zkk8A@NR|A#(+ZYZ9%$IJ3z+wNBj9QIG@D_sQgSnhg|qDEj$E`P?WBlTS52bb zS`3*hE9u3+TjU4Jwk*p}<0Uwo62*jm_|aW}LMA@K?{{p5=#DtbpIe59mzTjWM{Cs5 z?uoMRItYgCP2`t(Dw5Y`5<F7bQhW+W>hA=NXtpKc9zmo_9fU9Bw0SMd zvT-ici!Z5`(^N$R^7lYF^nd=tc_urdzE94Avb?AKnD@hRdR(7~KXHx>!E(-aEbnPZ zt& z{E0q(-;Q+`SAp}0GA=W0Irhjf0OJEq)GUEzQbO!tS4|Q>d5t3RP^lAP_^8L;SiNp8 ze9bDOUt(E?cXKOz)49w$z1fh=7+wi_j^#*qUN^3{?tvnQll%kU%*ZhJ#li&(-XrmX z+j#p?_HbNUM9sa~o|Gxeyd>yzQ!bbz7lz@J*LP4X6@@3-ID^f+AgX;+k2sQ6nDSB& zv5o?)R-ppkCAIWt%U}F+q?i!>EaK(qyupeA32;yK6IBZe!RyV~-)!yA6+0T>r}lCn zBW$PVKa3-nhZVy?=Q~t~eWnZh%*cQ}XylI&ENx~0YwF6V>Vz7cs9OtTlt-anc`xKO z-BBF?X7S7X=X!og5jQ3l?FtxALjb+vMFJj*2H7Q&_ z{}F2b>mb7L3Bwf#GD?PAs~oCVTZnxdiy%HiALUwkpb4S&f)DA1{7rcy$xzO3(SF4J z+}rrU-2f4n()lt4A7391<26g^rh)^c^ep>-2Wz1zL*{t7#&G!6*FrPo4aj82a#*N% zov!}sgnC+>1!E3NP~|&PWb5o-uwnZ`eo&Jiwi~dA8SRp2EXxM^$=kv6d5M(Rk0DDm zs$t5#m0a;}XjGlmH~|i5Jq?d# zOX-a3hslp4+QJA~eKc;1B{m6?72W55GW+qD?w{ZjahmZ_2T{x{reQgH((X6?SYu%+ z>{d;nO6|e;1+jw#T?w4na!dT`>~s;YGM;U3Vwq73b;}WLEe*y+3+&)yRWbK2 z+XF8=$^*we%rE`yCfW7SL3nL_8t+iH3300IgI|{4&!A9YLw{>D#q!;m5| z4=n^bYAjmv)Dge>Z;}Ylm)PnPA7MGHlF8$L*;a-f&Q*Y(Upi91l!h&o5}>pFBi+<0 zMYf!7h3^-CaW{KbV@U}ek=8k1PM#$9G2dN5G@b8xlBjj@gy{A|WOtA~bE{2Y$;>j^ zXRS}ZWS2wOtG7J8Vke~T?<$zFG?YdjZp6Krr7&*ZQ(EKehuv95;A&Mgw?x$$S6^QO zlLo5j{PmN_rpA6)Xly`#$as+QiN?YgJA`Oz&sDtT&Uz@l@s<7+*C(%&%VCf16;3YG z2}Rkv3OfCiso|qeoO!Ai&cC*xceeQ9Bwq(`KA6j?M4rN}%XUEk+Y|Kt?;>&Oa1d_W zJ%jhDGYkK93j-ZqITcjvk@t*uI&kMVm+s|+{3p5!=z?Un2-l2t_mxB3h)_;-({Oy^ z_(U~Tn(-mFHFMCWh&v#;9A7A^qh`ryq|RdgiX1MNNFDDX-Yr}3@QWZR>5xW849 z>2NX_kJGe+hgl<$*qF5qL&L2%ieyoP7T`M`&@KdN)xJ2Y9fC2KVw94{wbeA}Jj`gQ2yy zXw~v!%oe9WPb-y{?eE3U)EZ&4q&muEpZSsH^8Vqr!Yu_-#oh&^y=~Cb`tx{2nI#0u z<9o(Qs-aP062gw*z)kIl#CJg-aO6k5yhuFrYwoq}89+D~8 zgsn~F;9uvh@H_L;Y?TqFm0#lAf4U>tH}-;uu^#k9*bn?Pp#=8qi>JAnY`f6k4)m)M zxQa2B_`sL{<90!j9{I40A*z1Axsh?`Z{ToQWch7kO+I~KGGLiisae-LP+QvgKYgAvHAT;B0jvF-9oob%E4(~ zE}ws+2K$=SLwqAeYqzA~c9jIs$oWXKK#F8Uw1SVzFD^va0`m{(h;Hu)+Y#i_Ql_2h zM$^4+$U` zrBEG}MEl!)v68JL=*LELWBi@)Ti>N%HoBUA*PTGdtp5S^tM#bHC{Ge$Fk5&y=@lB| zcNGU*+5pwQU+H*5#;IWh)^s8f^DDUGZ+kqdQs|8T7pu@iU;vPdsmbT92 zG@VXipWxjvZAJktIJBMUmgosj)%{u=YmkNAeujZqUm5k*Wu8W>3Rs~1n=4`*xTNiV zQO4)T-4;A`Llyjwq_Yl->ifF5fP^#{l!XllqGF)HJ^R>Qh=mE#Ens&cDu{}m2#6R6 zV(XmQqkbt9q`Mm_gVOiB^ZVate1z+seb-*=vm$Lz^1DMHXb$-;-NRjjg5X)oR;=(h zXUEs5Qnz)5*t@-$xv+&T+p4jnI@+aq}X)Vg*nMjeb7B~X2;u&@oM7R)Bj^}E5c z#}e<7BIe!`MPoUaY~@5v;dZz=&3IdmadE{YW_&A5kNt(e<{cJ&zUW2sMmkE?x&0uk zgKxkU8iL|4IV}4&?*ePzijf!0gfC0xkw@aeQqN)V&sK=v_yi}ae`21T;hDGFSW+nL zAfA`K;pjnq=^nmoTL-LB|BG@TvTUMvy@Pz`IMfSIWxhE<;Ih;Sz5EUfhO^CJiB}(- zwx@|L#=f-4BoAv8Z?Y?#&AvB!jAVu5O>*OB5NO^p$G$=#vtC%j*(nvcdx1I;c;=U? zIg4lXl3^;J<>?^9X55w}erx9$1f#C;{v$)atMm7u8l^R8lbOyM%MED1aaDMz-CY>E zEryt1agnlZt#Vapn|&hg-1mu%!YokZoSZ@GW@J{AH(BAiRXWe(+HSxx$^T|}$@)ZC zVikhj5&3M%czwF^A@{lcN*9RQd@wtpBHg{`&NiZ}mU0GWWH>V)=SFG|dWrpcZ^*@? zvh>FF4ty1EDQdFsP2+33aHYv_!ZXf0QJ;%o3Lb zHn1PNWa+4}iFhOQ6Z^BwlzWVev2TYt`KRJe(zbYuXP+z*HE@=WQ{pf5yCfqlHh2Pc z&;B>VQ=)=kOxISt4@cN6S5<25UxzH0t*zXQLdAc`;QJm&@t`> z>R-ez^XE;UKX1oQJ+!fC*P=!fs!+x8206Qo!71T1PS+@4A8iBZtIb9dM{83ecgz-2 zRr=uncWxTj^uVn$8Hug-8DXS8&-Zct!F}*HCU>$O)_50SznTXueq#{lVR9W6;)Eq& z3)aSCqX5`!!0fNZg-yb@jl)k_x_(T2+pa06|tP(;pz8->I&nHP|xTmEleV$Z;!utPgOg^}hKIko; zYH^ZzI8}m8WdX*i#IqFz2Oy@*1!Z-kgq2#ZP5{=T^xY~oCwQEhg0lqsF9Sc<~MlcY;I76|tXb(N$t`Gd7k znNxy4=H&^+|ILIgU;j758)G>OBH9@@4NMTN|EI_InRb-Zo

p7(N)n0{>JHS5>m#f=cmKa#^X z%~7Jqd#dnm^dn*Dxw*t~$q*?EaeZqG&>v4Q=ha76GHNd^9AGYq9q=G zsbKq-cfhQ~e<q#-q`EuB$lzfRf`s@w~e(argHj zD}tTH^`CmNLmTDk7UdSycqe|VwnUk3^s2-Eg2Ko+!xK=LxdwkcOlPNd8c=UijYogD z3)L)!+>y9RJ%=Y$i<3OC8+EGzTB?I8wb%~e&0;D zxWfAIJlDa^rMP3CBZ;_{4Trc+qA>9(^XROCncOolEU+)hj#Htl-#4IomFyd}%i45i zNez05+=<=$Gcaz&DlFNN!DcTGpozDQC9MmR1wYNtB(>_OxMXZ2vsqUPokOZ|XZJcL zlUxd8U2}10`efn|atI9D+_C#i5esNmp@ric@zm@I!o@aSI^a($M)*dPMMp&NGVV0G zCGzjnSKH{bAR~$Ov9YA##|psbeWY57dwDy=E$l`)|C7QZMK3a2;J3){zU<{@n7+0m_2WLkGrDHP>-h@!(lQ3us#LLsy*AMSn@3Ch=PqLlxNkfxwiPuiPm&cT zH=(m^30~02U}rCvLt$7QF6@&ooE`2>nw^}*d$jtq15^J&o}?P}&JgClN1b;dwql>k zt>jIbFO2LBQY|Gg@Ctof?gz!4T0A#Q9#?d31nVDA+{Jjy6QA&J1w`f!4 zcRVLPN}DXXx)mC(3`OzmN_NlHl%D5$xaQ2SqNE3T;Ch^U<}F{5y0K5;xpy2E%}-@! zF6z|TMMmPiUy=0Ry8vXpO{M#Jop~P`IF8TrtO#b#dC@94<=AV>Z1QjYA+Ye9jF+1W z*o%dxH2-oL{;K-VM(?&OX`kmSuDfxPwWpVZdtCu;@p#NO$;s1x{abN%yD^!+(*+dW zXJd(D8QXtOhkicXisgnzY+qmionAIYQkDIIw0c|whv~K$t(d`%an90^rZS{wFABcZ zuH?#DU$M5J$E@Zz!c^TVocm)T%jxEKSUCq=AQ1LM!r-!&kM?xz+rfYGzavbs23ghAs;n2 z-(^)Us??N!C)UUHAro`$LF7A9s*T6=7U<;yd5K1?78^!PX+~)ouIxEU*1|og|MUoV z#HO+*i83_iWEa+~XcN9Hml=N@W83R+ z!X#8W&mF%i($QJ`&!2rHe4j9v>>52(x|3g$ZGnZS5^>CqkL>>TZM5^cv1IG708+k| z^E0&uqGcjy%yM30A0{VRZdGWraulDvmHhMHm6Kl|5%#WojAnyU+3J@AXh~!*$)G!0 z#K7JZG~<+|ew81}+H}j8JUl6LgB9Q0Mn}IgmMjq6B-VaGFeh#TI=dG#{9X(jO{%e? zw+88Y8*47CKck%JE&(c=Ga^ z8~MJ-PaOQJSTvmLIonNp@TXF5AyXj%zV?ccddM$6`vTQ-<8j9HRJJ%NSDDG?*CtfK^hq>y(W!k|E=6)g@ z+>S~2cJaj$c;8-)cNFc}$|EJPgXc}=xlSe)&WAvLr6*pKEoKSB`_MIdb?7v0oM4fr zM+a*D!l;b9B>&l4s2v=FSJ&jTmDRq~>!^_=I@*Nf3|j%df-=r?;M~ZrpHQjt7o*83 zAtT#^%)Yl(ytCGaO?%Y>zJK!ZeAIn5$aMuo4l$D6I_-{*rk*{WI5uV=>*U(0^RqU7 z&pkyh*W7?tdP{LiT{;`Hrvzr?RO8z%UxXdTUgU0zlQ`*GKX%rq2kLKC;d3W}^)*qT zKNTvmDRwovpY03P+X2sAD`D~ruTVQvXGwiUqRkIeBN{lU5o7F9$(*(rFemGAtmh-1 zBg=#xkNJK(+>U&k?N81Wd5E{TC5Wa{o}Yc%jJ8>K1h;1fP*Bxds*TGv7J}Z1cwF&3 zg}vo_k;R|_%$=-F{BLfB8FfRYyZY?MrZmpK9M?VnDmoRP2dagoczWY2VvdQRJUb3g z|4d;lkoHI@1gv(NDz??@hcOpIWT7CLm+$ucz8nnjio&aMoZ z%z0J?>~VxCE#Fd(&6|>JY!h6G(QiNT+!3ePxS3@TQCNV-ljE3GsVqH{`U9I@j3KvI zyMSuc9Q<5c#taS&pliKb(QNY=Ht=^K-8+ApWWebpa`W#6sOL<`2leSJe2OW3v%3P# zvM&miX<$Ry{nKRE5oU3)!Kas?;^Emt@CaNAkVl2vmDH;ws2t3(EEB z-2ZyfX=L)?2_N4GW zObJF#>6GSxRLcLs?BaY}_9dF#xu8OK#2gKo%)v4@NVj1jPP>8eaGKDPn88BIXA|6{_%VK$s&)&Tn z#~(Fk^4#;;IGJa+#g^n@^G^5~WQE$3ikOVY9lAEwN#gofUC_8^PW=^Xaq0Y0GTpiY z?#^$-sQ$Y|otqos;PYxU3ilyJpRYk~R47jI&tWqDinM=H4MtyiBrJS4o74{&D(#-I zZ~FoD{}ORXzmM!osW0_UG?sYr8~gN!p4>A(5dWO2V9_PrFxX#C^1Dxg&48Z`FlA9S z>bR7V;2JU1Jb#SC(o)!F*Z#C?b1%uoBuz4`YAh&G73pj@wAZ4d1^HMTbDaf>{HWN7=G%oV71{!i3Dpf5B8Ux&~Q$E6;{bMgtWcuOcQ z4a;MOM4!4ntwEjp--W|Lxoo_n3Y`?p^X4rx1i5)f$f&b(q#nhT zj9yeF>nVP8|H$-vaV>oU&&6boCr9}+U&NpJBUU9MJKJ8=J*X2kC(8hVFopM9{VCKV9aEL*wiAumG)MN00ra<>sl@P5im>+BN0L>3Oxhops$2@<-?eys+In_Rz63HJvKcoaR^zZ*kL2eKJ)ysvZRFFY7|icDB>0~Qr8lg|0+ z3ko2Ra|O-bd=z%f^C0p`&SIF=kB#cn34W$kIOw}ITd+c&hHw@^+{V>paDxxL?mYu* z(@I#h|0Sw8)>*Rp@Dm%he-urh)_@)@N#tX849u(Ah`T!(b9Vs`1KcT|%EbLfVpHsJEw* z?cu-2lz>W?rpIG0|IPETmXLxYXUcz%af-9H!0f0nVKZwAnS)9tu?uo1Hi)T47OYVqXV z9pqco1!$OThyU8sS>pY%obywOQ=eTF@@3t~&42#l3}<~NH@Fr)kF3NE59YHuP5c=i zAS1E+?Le;IKLRtj?)r6a4!e6#pJp_4BKs9@9r{s+dOfVdwbLJxVU@|yD>DT1_7^Y@ z{`oKVRbt(f9wFPnjU?#>h!fhLi7p#f!ux5Z_;~RNA;?k*p4xRuwe)?X{=&RQet$8I zX5|~Wr@E*JulgyH#KY^rICYd%OW)iuf}TEHhgK#%qG`NWsCr$cbhbZ^y9+j-j zDq|6)FgmReZ>nbs%S~oLt%?O&eyC*@cjf8hCDnNOJtV*}0mgApZQ^>nFJE2%? zEoIyK>h7aTF&2{1Wkog`C(UVMWF5NPD-Y z_%9Tf8|AS1zM8bFs{@n7uY|V9IV7UZQ0gu3u4#hoV^7iIbsDQ~^`%qg$4ca{29V^T zo?sh3NIKiEX?4T1HaW?IVFflyRyFW&P6c}2Eh3Zk#Sk$i9wRTMuuuyHx?*Mxe({zi zcMgq(nixgF~!xndFHs4H5lDyBVtl2g@VG zwrQ@^$6{C%0X7$%@$rd+Y^R(l6}MI5KRSU}zHlQ4-v)@2-AnnK%^&blXva<1ZIhP! z7{nv*NWF*~Z+?ce9~1D*npCz#z7IXHs0f8M&xMBztl*`VhLp83akxI6#d~uO4ZFnV z*>XSL#wr}yu$6q>o&h(u7UKDvPgsaoGi>Mnr~+jJ5|*q=zeKm;OkMdmQM|uCe{(U8 zB^$}lL7`B)dyRC4Yv0{Vy;fOBly7jI^T9`A);mb5y*!;*0%u>$}*`|QoE^qb)I-2yD#6U$5U1Klu#LxDKa2F30RQ z>1d(Bz>PvxOn#?X7@D%9yS!=IeR;D zeyblDd(>O}=TU;_{DI!IkK`wIoQV>q9?*wJ&I(drV$_Fx5UifyuemAAs-hp2>@CO5 zHvLKezYehP-!Rm%tz>xtyhk;kzvqg+iNfV_AjYE{HCtYij;jeU^z>s~;FrRV^=p7n zviW#fQpWSe^I=itI9&9qnteE;Kx_8qWAVRRtRt>3jeT8;#brPyF5?XCj;T27T>(4G zZ}i6st1*64vQ3UIw0AHm8s`krJLciE zQRPfW)R#VTGhk1j@Vv>|N+iSQvnfimY2=?N5~Ix9#A?qGxLnJ5cR4xCa<4A;i+14BUvbt4 zzW1j;>?$$M=RTRaAp#sOy5Pc?1h!xc|M`rs!Kl^$1i!^@#71$uI56qCXx;s8a5Csb zyB`;YosQkGr!6119*<&);YxJ5SuxKFDH5;mYr$sMXw;WfvcGGGQ#YA9G;`<@4PVSZ zb3hF?^qe9>UNmg0jl;dIDa>bEDU2{K#)j*eg2F`3@o?qeHLJ|njC>W&ovXm5UnY|; z+B@OxO&jS954FBczjZiC_NAx^8xl=uQcIN6ED7d)@-aRZp^8*gV zX~tEsv_6CBiP@~>-z>7^y`j{{;!@NI0jke%{+2YBmf=Io_Kuar^bH`>-*|xek-<{E zWwX&{s^#D*QLvvS#Ftk>aY#AtG%h4p1O_Yb$79f%6gHP<$@7Y9QRS;FQ85_{!S__L zzM_fMzSE$-oQ)PBxyI(M+(uW=Gm~t8af_(HaoB1&NxG9;U1@_MZoMS_D+iHoO?UG0 zk&F1P@K4mCB2TR*{zj8GlDA^+XRtqBjYYnv$*Qd5oF}{S57JJMsqR+U5Wh`XXy;@;k{HI746vXjjoXS z^cu_#``-)?x&IhOt~!Ic!}HkK_jBM+KMgDy!TZ`y4X1JP`M6^GS$2Rw&&&Dq9Nr<% zW+--o(Z1j4_TECY?YT1TQ`Aecvn!MY?~8)wsb?@hHizBs(W9<6yYO_v8lnF8VUqiA zp7b8tq!IzXhAx<9agc@Zn_V{NYfYIkkxbzk4I&B@54>0^I$QDw0@nV*jv0S#a^W#( zi|$~6Q8Leseu6&26HHM~WhFe<+)-PE4Vuq|{;F1BRIh^Y8v(jgNs%G@#a-NlQJxy*zUI*ntD=F%x3m-8+Hs_?O)H5-$oNH_DFLXPcvVldYSo-X;{+^)Z_Pa|Ww zALj978>fzu^aD1c^Uov_m>2^tjhk`n`ZzX4oB{g;&XL<^$NyemGH<-MSZ{8ENI6A; zj^*t7sUb1Kn|baQT(!~3xicrUnO`}ad^&P#3jJiG+0P5P3N!49y!V;E}pu4J^( zlv-rf;QDpxqMTFN@Pm}&mxnJ&`Jx2q+4mUJtob`~em%?@n2(F&%Y+Bk^P$1U97Vlq z*ytbf^h|CZPH?=%l4APOCB4hAsSQZD%0aNnpNdyq3RuVoQyTEB26t8^+gx&XBTox= zhzAS_VOrIN&}3eSm1d9F^Tt-lm{E>H2M#80k2^v9viZ1lLOC1au1(#3Hlx9mk?di% zI+aZ0e*VWUq&YksmK3f+ouldOCGVbi|Cjd~_q!~Fy>TP;Q+A5yDh_0uS5|@TrAk~F zIgh;?H-k1@o-FyTaErt`9s&I=E_iZXE*oO3OQ-Pr6xDfbJ@Jwb9sIHu3mP7hp$~6E z!xC5gx+;NbZ!)D@n`^PA>7NiY!j0UyutR*u_JwFjQ#%Y8*^bSr=Y;b&x0CTP&SGz| zJ=1FJ1P$)d?beE7t8Xb$Res;>wMUT%tJi|hvN6(~e4Nt=nq}RHI=6d77wvg&sJ<5W zZaB?*L!!aM<1wlhrLb++>YyyY77u6@3#X23C)FX&Vz-I?S;Ia#n)A5|Lt0GPiz8gm zxx(L}DkhVrgFB!#Ou)T~oRxjy77Z0SOY+0iggGD0X1-eKsR2?>KEtna zY0Re6o30*hDp{N1PonDFp~h$ke)Owg>oY3gq)r7+ttlX#79y}~iN}WOWM;s7*!6za zaUQQMaqu#Ma1Ax7#uAsVPBnRlNZ_bzZ2T@is`JxK@?Xd;BJ<=JJP=R9+)D-Q;D|O@ zqAepazA=bYtaK-@&%22$C--89A99UlP$w2Hc>lJI@6V2JYSG&=gp?jV4ignOO0z;o z@^xtS&^jEy+f^92Fq&w0c}u&5b|op%QK2s|4%67S|0=<+tqspDuputFu4KEOt5jo| za6yi)wD^Uwow~x-Mb|(w_5`X`6pe@DXP zq%)Wjk;6uCt=Y-ql!@fe{DzG8zfj>*kInB_aWK~@QtDS+k?;{NMLof?xD@tbsS?#$S%M$@ zo(mz4)4?J@Q<~Xt3DBjUas}8t{UY1X8HTrK)?v;TXHp#d74~!A?3dFC%r~taj>xv- zlD5G_NluMs9{P=+hA6xl-*y5X$vdFc&k{jfEd(58*I|xTI?H&li>@lRkR(q0BFwQ! zBdWS5q(1YHAw}?cUW0T$51UyC?fhPO+j26==e=Epvd-eH+)Po%S)eaFtW*!rKXHx4{vKO&@(}DZ;Jrv6Vuee}%V48utaQ#N_cEk&7I$E^ zqb~cJVM^b%ccK2L(cv!=0)2M@vX!A|J+G*f6@>|$$BRra`uytR6j2ny@)<2B9fM#UL<*s9>i==l+JdA<`WP&%n?8J-^X-$ zcYNP(#W*Thi!A$Z3*6r^0^KZmZzKObzCOrvK-KA@;76H|tzLmcXTBs4+aAO2CGn{I zBbkLLHADWJQXHmOBa{rB2WP#<LF*_e|sdv_RfN@unW1 zY`-jc?KB71YgVYl`Eu3)l@Mf8g*CzRSo^ZswBLtm5_kPOzP zLdy~VydGlx>~lX_->Vvr8{a2I^KOF<&&&M(Y;QemN&`RF(kP9GJxzFF$U>&P6>VU}M1z7D6$-Hlz07E%P6lVtsYAI_VRM|*6 z+jZVgrD{Y$Vp^om`g7mH(a3tv0y<5;dqsiUm&dsJ5!WR?m%sKY|=EsmezyE?wu`m}(v43JOS~?u z5u8nmIbW+7FB;_#W4pI7eMth2yOzw9yXC0@HlVYU9C00E0&7#%q`q`T8+BUB*%an= zS6T8IA1b7oN!~uVNjyA`!GcGVd53!eGo0KEx7PQPq|F>i!gSrq=PGxx%OQRzT`5ne z5966!r}uAH%0XSy3K$nooZ&bzsZ=euQzDCZm=7k6NBgub9T?ldIq+=&-? zFUd_Y&lOI0#7wTop0*iCH=Jt4w@-3~gKuU-jFYC+_hNX&ke2PwN6UU;?B3D2ps>^q z8&s;K-v@MdHpsV zLlpVAE4f{<0V65|Bn@>7%U{x830|zFP zhwsvWDkh@xx)e5P%L!O@(*ch-S_dsTAP7GZ)xWp2@8%tjA{= z&ZJ`57x;0m5LYNBFr}4saAjCMp1G$>diJZ)1f@=N>r#00e*Xzr`qcq9XO#%2uAK&p z%yl?uXgXW8b_adE%|deXzfVGxdK%H{JR$X>C%!5KpUws>Hd@d0#5rKIFBcW`CX%hj zfyC(h|7N=>_vR%S$Vzs1+6cWyoq!9|d7en3Ll)@1f^)uSaCc8G8+6#4E>Sd-oK_x7 zwzn;X#a(Jr{rum@@6fTM0>|FpE}R?UM)v*X`9ZNCb3IcFmwxfto*%Hw-nSIO|i(Lij~R@p{lZfu&{mrn|kybD2rF3jej~@Qq379A4e46Zp+z$WB2! z=TnT3prHpFS{0?Y(Xa9+;I0*a_6+y3=28vn5mtgJ8@0&ykz2seawPT}%e%s_n9^mm z5i7T3h}>6yhe4JVsPyp#ahmWLcBIB*Y*I4wy!Qi^{3*jCuNpyS-(2WDe1degJFMWJ z&+`lMl95ceQk#zE`bN?gN(?Lx@Q#4#IGbzH>0Esx)d89vn0~AF-vT}ppA*z zcz%K3)32yJWVTOQ;LOxYJh6N**)o4CypmmrVRq$gV`~s}9CpO7PFF=9C)8-qqC&Jw zb|!vjIG>GccLxWjv-tdRAev>3MSJU+;e#@$SFS|)k8{{MtvS>n)k?CQMiLx(1PVsG zxKM%Wb1z3A(w(4@%)jbfZTVPFp^fJ#PO^I14yhtC(FI ze3O1}a*-JRQ58;?nbVf>t*AS>f&|i1nBd!rUK@9dPU>dEs@1ue_I^F-?{OJS4)A~1 z)NH0)(~mRidrK^eB*LBinPiI12&wPo{f9cxKKUGjSEVwUQ$AE(%Up8hW+3tV&kb^3 z4aH|$D_ECF0R8XBVM*o8HNy6UBDkhdie-U01(QwyH*uQ|Kkxv)X{P zbi0wizMf*8>R!yBGxy57yD@(7hqrY*dehw3^;lvTLeA+Qhi5*Ur7Yax$_6ygtrcbN zcngIOqR8dre$srX@)JdR_|r@L-an0%2lAguRWe-~t zL+OD_`TV&(!+bB#0o@EcJfBm=ZVhV(qsPB++sX+d^Dcj?vC>7Nxv3Y-xO4|{L&7lD zFoz}ctjfxhj(By>JDb)uhse{f3#2Su1=nuqVlQyTyHxhcX* z#5t!*8L{gIQ3uZjSjh_hS0BNVi&4_O{r!Kbu-!cohxbZh-rO^(5#We_=UWQL{ii|I zdo3wD(Tw-`cC6sJwig#za+E0@`>qjZ>~|sYou8oTaUpICj%OK*fAV*|-#C2JP_mqJ ze(+@zHg4$k#$1;`35$mGY{$XEl;uiN@v^xi|8{+S~y8Mxa<=)M&MCfyD= z_LdI$VgC}A)t$i&FLT+iX$EwubvbT1TP%EkzZ8Bos7tw9b1HqQ_t-;{1#PP2-Fi1N z@|%bFz@lyJ#`+qt-cW$a<6_vYZ3iJ`9q&d_ixmuJFNOW@O>y&vD%KS-nBG_ZgK>!i zSYJDTs*^oIGF~Q`ymR1vH->i7IUiwL3mrqdaPa&BVf7z3vf9&AY=5UeTl1nBg6DJZ z#9~X9Xnzp?PH@7DkG~6p9(%!w5pyuyx0D%b>r?IOW_+=Kij5kMpj*va(4ixVVtE0(y{8SL6y+q}?RS!|PJZO+4}bCU_(aj4eofFPwG@9Yxgboa)P?{0C`osC zIqehhf$!MC&U@K~X=?N(&-g4#RVSa9Y=NgyBc*rJ?d6ot^N^Q>`!AGnkYYdG6;M)(63Yg_~KIMa1~xGqt6;0S#y z7vdYQa`wa{2p-JXibH2y6=nY8-87s@Yk0z$EHgL{g7aDol1*oE;Q`du(MS@yG*7S@ zJq~VXSxfi!v)m`S@>?}#9G%BfFM86(>MfG#Pu>&F>ch~v(E}?_?C=6ZuW-+nFKd{V} zk&w$*h2uYbNes`z_@%C4k@-KtlJ{3GoqC5^JqQB7M?Bx15F~7gUd_9Mjivd}{2`NR z_*?}^=Sem8jdxY(TK&MmZXqOBatB`QjYrKiai}gZ2N_q)P1G9#D=K}6JyM2UP2rG z2&^FU!-`G2J(K4>b1~6sJ@FCq+*WBAihHtHrlLFz+}eb9BOVF51~W-) z(g>+v{o|)v5b3|bg&L{sKhBNm^EDTbX6O(_BR4QSY=}2jS1|9#g>a9*Ydqko@{jjl zL(;S-c-}aft&8P5*pl87;}=?_*~l2ycd1Kv^-_6Ny5b0b7h8UX1)n=eYk8+_WW@ur z=<-ou3#X#JT>&#PDTj{9zp$&aA9*v)ov^ju;z9dlSjwp0bc9*gRTYurO z4K~Cg+?8ZJ^c0&_XNv}E_ogwl8_iV=gb^!G!Rp<+QM)~bctr5N&g)xoTvRNpjaQ|F z@3g%Jeh?C?XTmNsEgWo6&jyYjLd{O+^Bi9&oAYBf=w4ri&|1YbTialgNF+r5p z*PC-h9VKVBc9Es^5pbh349C`Hvl(}SV8hL=cyP-*o8|$BNO18&sYg94qzks}dWof% zQdt(+OZPuAlO*>#LP|`XV9BnX_|cf}?N9%Jx^@pv{MJiwk$D8nG+KHyolus-xjKos z>uoYy|2YUgRc}STcuS$H#S-SaYfESQ_=DV=6v(^g-NV_28h={YFh8u4!s5(w8Fz`0^89{E=y6x}%m!}qSo0~y~~ zy_OICD>GhlvnfeP8IVc_I-Zp7?VG&0wro_1JNDSJLqS<^Z9yK+KRSW*`{_%5X*-J@ zFJ_3YU(=#DcgRYf$k_-B%K46`%;)4fU9#dfXOCtYWDV$Y`V)^e_GJ#7C1~qrA$c`EnGA@(3fAeXP<~B16B+-2QG%>w36u-s znQmmqNpG=+?f|~~{eZcc=Gd!&wCB2#ETLWFw zM?qrj)gUtZ{0+80;5X<$&&jxhk6>D80=mphW^`gTl=UgX{Vz*}CtKz~bIe3+7+Ayl z-sBmaDksz`9m#ZN_2>NR27G*dHaUM_KX~l5miimV7Dmw;QzwafGYDS#|B>9OIpWt} z+t}s)ylc#@5Hdb1-7kIy{&9jZOURPn)J0OU}&C6IKM7LBT#7={`TmumqfAD)G&)*{o%S z2mL(9LGo+yd(y^u*7cnyzWbBMQg-sLy)Gx5_il*w?0j{)kNfKB!zkiu^B%M@3@_Zz zV~bn-Y35{OiRHn`96xsyYzCjj!OfX0@N*BGSCW;$!mEO6s}H&R!dYy0YYn>t?Qq$t z0B^)buqzjWAj!lTugRSd*6FW?nT{sXT+;bU3)*L$g5+zvDqFJCl-ldHpx>tuGNC#G zyg$X`!2D!Zn)M6L^Ba>=Popq0!iRiucNW+F)Mg45e?jkGB}!tAdFO&MWoNnHjDH9H zvkrui1v8}k{Aisxs;qKIVpVS-6u&p6n-8_%-&v((UEe~8SJVan8DxPE*EJLb59P6;_Kxt_LO(CR6GV?Jewyo0zn;T6BXKf#)`BxXHG zi^{ghN~)qYNW8=dOk*@~BsajF#Lx5FQR#rnQ@*o?$*T08 zOA-E8w??=xA4Rqpat{gTpI^DfIgdzK<*!UY~$nZJe?nNscJ(PO_Zq@p?BLq3766Jg~QfrG@^1 z_3?kvZla7ZVaG$z{~j&nE;fx$fy0NMqIFaiHD5DVP9eT{hjckPbe_OG6#6S}ALY{73-hz81 zz200}qC~GeslsFVn}}BRN%&j49z7R*V}W}O=+!?}*ysB}!SZto$+9{n^~1zgq{C^m zD)eKvtY#F?It3IUKA1=((|pJlCC)5OP8U6GRicYW{>J&UCJH||-(Ehf7CqIj5WmXj zoIx6fBRNafN@f6knqGv%jdBJ1drRQzVohnz^r~hCq;n5&sQ(UO)lHu5J>VFL8(*%*D3f&d;Y^lF!bhVsm9)! zBG7z!1&N(yz39-suaJ>lfg6uLCz_8Qg37N1T-_&`-IT9{{(B3teNBn*?A~nnG1Ef2 zpO*--^jUl%hF-hDR>!K-noH%Vu+D}&d9x2{7THLBFUozR=+QJMN!M-=md*G;K7Y#* zYdmXXTh3*{cb7sebh*#Q4X%csjAAUV(ZUoc1y9#d27%Sx{=D(Ooj|C`5 zDxFoC6YoR(sosWXY(j~QRs>8QmVkdQB(s7kZSeh9CmO7(7dq0t$u8<5ozJB^yP?Uw z5=+93*!K4d)bnX2ze7zV1)l@Ja_vmiUQo=S;33V`J|yWs%|NJ_XhMg)_<^Z=iiifk zSzOuJisFhLBD=fAkoI2{8f&|fyI~h0CFLw0c$dX?Z|zNWt~cY8sz<_vm>FaW8zuEC zdY4xNoBk5*kEF2XMs4~gHy?+6)gh-lTwsR5a6GY~f^}ZsPN(({l8kIyF9f6q!(5wC zGgiPm?ptp7}4lGY0=NwgOE6>zS zP5L0TC(nSMo!Xe!RmbMG52VlE=i~m>A?zcW1%1A(#u`x-d)2E7+Ez58#y2BTjNnPz z-))tg8r?-^ZMqHBch2IiDcS6_XCJ!UhQGr;oF&9$A0*A*OQgP+F?&1U>D^bD*pb3s zy8F@TFN`FsTK1BXbq+ATY9}fTEMd)a|AN+dImx-`-ojk*1K70aF8cIOCV_*K!87M6 zPPIv9QP=cnzdBio?Avd`i2A7z|E#Zc56|-MM@JbHAsZ6TVh8xsVdch>(U&5Lq=Dx$ zS_*Np@?&PXv>c9{=H8)614!Ei1-kcgJI2V!zS%ZJff`-odtLQ<(tFiOSa@v%Ix2r- zCn5&Xy+!pn_t#-ziEIiP`RbHZW63=D4f@WhLh%?|masV!T=-pVan=N)rS46V4?ByE z1JgxfvwO7i^<_yPlOiE%tSWue(1eeguaT1jpM%M)vshi2!{YV(QFfL02L8?x+|`!A z+@G4#+^Bhb6^L?s@ZF#w!AjAccpdf=H(U#3Q_{+z;405B21m2Od*$foUrqR*y%`y^ za4|goI!>yes~hUlM&&lXi)u0R@a;5Wnx(|h`XiYUcLj_uuEr}5zOk@wk2b1&* zgtQNCq+0NkG8M0MH9?hcH7?GuWV6jwsYvn{*TuMy>_!iWub+n=?@QUUDt#Ka<2P=W zpJwy+S4-Rw>@OZ>!ItK&uSd39jx zSB^#>!i7y6bfD#A9~?iWnMJx}f?3H^)a{+b)+|z`*&|D&GknUVP4M#VXcP^uWc{Ao z&`C$-B_h>2QFz!_kQFL%@~h`WH18pVeNMoOuaej;aRnSdQHaB>ON5w*vti*03zRjf zVFnTzdf%iFw;SAG!JG-uaisybKc7YJU)cxlyZ<-C6SV?p`B@Xmk$4Tk+U`9Wx;$6> z^gtWCXqgFxA%%FnHI~_KsDM$=ITQYx4*Ap90k)(qLGizG)_4+kJM<|UVF5wbL=l|~> zwC6Iv1YbIOr?Eukj|JIw{RkBEd8i(m$vg~yLiN+Xn6G_NXe;(4$Ge@y+m@_mD#guk z*{uMxyl%6AKt(DORKxWaCF0a(2X}sqMP-F5rtdh0&imAZdR20qalyM(n%c2~dzB}X z+c0!b0!FS$W_2z_&`-Y_Cv;~ED>izP0sHy=s7;F<``isz?W%G48e`VOGiz^_R$*l4 z1R^&i0M1XEC7ts&nOA7bdRNK+k#yeiShnvUCsDKzLTQsWMVsq9&Q#iaYulrU_E3~i ziOjUquBTl}+~M3E>CzX>CL; zsvgQFpYn5Idq^wZw>l;o_A!MskaKuPqmZNGr6CtdTcIw{u@GUFWJJLK4YaGn2a$8>D1ZY5{;wV zgxj}#A)p_>XT9(yKU?3!n_X{s&tp70@p%9}!+XRW<_;hwVtsg)t}LCy4{?2az;&KQ zg|Ws*L+IGh5?t84lne+w0}*m_rE~b6Q`w-_)`UB}Rmj!{_M~@;tN7pLUM!0H;kTx8 z2Kblg7@y|e)OAfWu6XQE3Jkpy~5@y(cAqHD7O8c6hq$Yy3 zUOCQNvW~6j;2sai!J*5h5xaIr!T}HB#&t=eMVvLQy_EM4`Wpxd9*R`6Kj(HjgcJ4U z?_l7Q%c$X*$$n;O(>2zWsJ69Gn16Bwyt=C*-KFHz7sBp2e=x9@m+;V?d+K7{#H+mz zvGz}e@OE-89`C-#_WYBht^aW*Fz=`MxN|vJs~bvpDZe>KQSWgxrVUVG`ukPr7XI%x zs+S8fGYE(K7q?*N?<8jKnFJdBEBQ_Et1!^to4?-$TwyoIG+?3@-Jw{4?bD)3)a_qz#r-nQjn863 zcO~$a;xbHKu!+Pt*pt^eZsK~;OOdWu1srYVx!sAuf}fWL^c+%>YPd&e3j7Orhj+Ke zF>z%-s=BcV9X1RiKi2I4)!E~v+5b{i6Y8U-AX%qaDO$^tAo*}577vIbi#4CZljPS} zem|Zqj4p&zyK=ETB2SoeX939N8RL{i6>Pb$46QEB#c7AHvsv<*^txOddUh=(z5Px= zfFY6Y$yX%Yp`m?jBs5kKq60q>6WJ`OhR+wJz`aYkSg`XkJ3X)h>Pm~zHbk4$F5eB+ zzN_$2b1|#a>O=8jCB}vgWsTU6DxNGtHC0=poE-p#`?jIo-$d3dIY~3*jU^{ul?dyP zPlBfTM7lE%f1MBYs#O@z%$Y)49!zP^!c$sv$)!P_aNvRq-ml7Lx{(8^V8zPj*_~g0?TO@WsF{?BnZf2q`YbX`|DH(bFA?Upr?On(=JU zA<+)i6!@CW`@}D8BRkAOKrS#4@9juu;YU|du?~@}4N)RmVy=juq4T5A zsQ3%Zy{<}chH_T$VoehB)CQK`7>kR>mN0{U*$_6q1>JLEP35?5A0H5ahj=Gl$2{J- zR?l;$Q{vh5q-I$CjPrv2K8$U+KA0Zk9qSQ&7Lg^w z88C17pKi;!CqleU1s26Bk%UVQr25!F@moJRmNfMb9DCk|k3L1mG>znbW@8!2(fm+S zuI2@v-)!*Gj5HQ~K#Tr()qysi&cfHI2=eywVd*YK^KWk|-xH174{_b*bI#YoS}Z(d zOg;?fT;)zTv59ZC$n$I`B=v8_Z*FRWk-sm{o$gW%@2q_c`JzBv-#3%hJy4{hHS#e@ z?vrqJ{Cv)hSCigDd%U!1#g%LvnSOyeU7ZgJid)botc>kET?E~-wfM?aU!<&a3wq86 zVr^MEGrP&>2fsF)ynBUkVEJis`od~)%&!{ui|=5VB5fwfxBXAU z>vUCUkwp&Xgj{ABdTzA%7|-du-Xo`%$HOlDJXF?x&YsRF0JUpXILAbt+)J0Iy`Hq8 z+^}BJIwlHKLAe55_wFF0?R>#x?_87t%V-Pr4gdADIAG z3(7EQ$6D5+mI@YCxfrE1oxHfl`|tMHi2r6LieyIde1SzPx;IW0EP}ZYs;&%Q9ta^9 z{ojJ+h(PQz&14gtovGZJ8Im5msbr+-3K)4oReJY~(c>MLykoII$wv@-*b}Ey2gUDP z4|8Tz0bJvH_58v;CW)4#w7eOoO)(%lo0q|^c0(*ZSH{++YtXa7t#~g$h5cBoMf(<3 z;uO(Il63P5SZ?2nuHi{+r*1M#u&%~KU%m+@!Q3PL=%AP#*JPt_Rf3*>8Sgur$&9=f z(Xh|6Bqp2*DUNo4i?PeF_COJH*3_b2n|Xg3%r>1Es7d2^FUGv~k7TIt9oR6{79X8` z%1CT3{5{=)hEr`x%?*1p`P)J9e-~bf<~7RFyXG>I>q{R9bczOS9MMneZ@G9q8ScqN z;%cQhc9-{GpLy1ah0Z#})@M5;XO2f(l~Oh=WGo##ts2K$d>0vgN`%vL{M)Mh19>_9 z3CQTaLA_1!?7zH!5N4l;S<|mG@6!HM^wuWCVOk353E=L1}ykZApve-^M=g&rV{C6!RzUMdbeYe=ZCkph`fhu%- z-RxOe=fPTD>p+if{^a_Jn-JFbHEO?$XXEA+!I_

{#?~@Ud^fLnl;7*=z^Woqb3= zD@%?Y>h1J=iu$PG- zQ_PM?8M!jk?m(H5E%sS^knNc83l2M#OZzESw%d`x-Ur2Jr{{>~|LuWCle*DyuBM=_ z=?mNSPD%IPDKd{ir#ldBJu}$av5K5cl#h~hiSX<@g=39s(te5onObxx$w7Vp3+$2H zd}yoKBAvHSDi_0cT8{bI&9JN3>Aic#@Ir^8R$4foM80oG?!-~f+xOlHz=&Pn6>Be_{* zL5Ty2;J>5N#3WJQHaUt_E%>o*itzh{JUz_c(RB$SB&os=y1@>MUp!`3$M(^E!)8jn zrc5O_{#y=Fa|UBcbv0)t<${542j1*`Mi^CYPvXuT5-S)SVY}DogK1t4PHDT#z85rs z!=6I)4INEL>M}@MHVp$J%Gg%k+x6;p1G+g3WML+QsCNHsEH&CoX8#L=7m8c4Z(SnG z*q;Mk2ioy;XR5##Tjb5|!(u&aEjDgg1sGo_#fckduyM1@>6D+dCApl6mvYttB6}~F z>h?0;owQrE13#(EGM)EMgY($S@NLouqC4~sOi{DN0)waQ?~z}S8CQ;rc5fn|Z0t!u z&;NAW#;XKEWr}e6yg=dVm&0Ux9`6KPxrm7jk|Ch|9XfoAWeautQFEPQ{5WtB*?3|* ztQ|f<>PwvRcQ$=IT3!;>R4VG?+@7ZsD)E&L*X_o~oQL)X;|$`NLwGe@k*UNz>nnv} zFAkGC@z&zWZ&lfTza9`ma`DQEYfNT;e`+z0XIqAtkkvnqL&Fk~GPvyeAE7%JPLuo{ zHdt`EAR(c(*<$g?7Phlb5>)-j#ryjnF_Yzuuxe!kj>#ECqV60f>RW8ZKUKR$6-{#V z$;NU#Sfa`7v=u4k{I|$9OET-eKdk$;9SgQ6vY2nj=={sZlBV&+Lbm2aNVbRnX?sO3 z_q|u+oNMOn>yR9n!n>90J7$yL?+=p2{?_748xutfY6ei-)DCQX@X%!5b#=O=sTI3B zpOeKS#qhB`5Es;DvKwoi>Fec_B`=m3lTC#lFsFsju0k5~Zs~!UW_=`2a&HLRzc~;g z*hJ76p=J^mMK>t)&D zSCgrnXBYR?`xEEL8_?+R8g0GeS?sbVu(&8A=`O1kF6lTBT|IlThq5YDlx+u=Qifdv z_1W&1e2#rsk7s0Ok-%VA&ekx;W8ZlHV1X7j?_G;6nZBkkf=5!kQjWc2lgYTm3~+02 zMgzM;qD8UEpnN|ce-&)!ER$e3vL)Z(>dcn@rtT+m-2&ubA@W~{#K_@HhQiGU1d{_3+^r@ zy4O8ndya|4N)TJ_0w_AUwG)gN1zUORaJWa8Zdw_~1pMDN$X@%hi+B zqWzxa;8WcT?7bp|q|ICL(s{lo_bGsEsKd{*^hM9V=7Er(i*vR2k=vO!z}h89s^_;K z4x;Y)e=taIwV~C6f;wkZ#*#`E5U$El$Ds1S{>3?v^E6exA)@0u}k(KRzY zA&v8LH%4a*Mu9$%I&QaguaYKc)AZ0<{{PKG=$IW(wmrTi)$;?6KjHhV3OuoREz=oa z3BzpLalw*>BL!plU^G42uu^AXj*7fy+m&fc-Yt&;l zK5`#Deq)y8e)3c@+H5(jlUGBcRKw<1W`kZ#Cl+*h3Rm-s$)D0Dahq{7o5C|nRh(1( zY{y-8`$-dAO(@3U>&B42ZHt_uU4v5Wj&m_&V=b8nKr|?%_VJ zGz%Qop2*a;@o!j_4s6|-D#S)O5YhZ&V!xHzEa^fCeEv{^R#%PKrq0C_o|;ICCOjtn z_S-|F&kEdorHDPWRi`h~+Hgdgv1wDl5ZdQ{6`uOYyEr%8hKwRRd^Yqc8@%WT)amj} z?xl_7uKsx##eaiZJJVREoD4mz&--86?g<(6AZglYBeru`$i8DD^zV$sij%SIL2qB^ z)U?EB*ZhRaux+p_bfVOwVzN_{_UX#O*Rx_o8`v+ntyqnJ{XdXP0gu3<;SB~=#Ie4S z1+ceYAb7KazKL@2SGxYjjAC;sK(1 z#abL~(kZHU?L~j_zLNJhhp-z~KHz<155CYT6TS`fhwZ0!-~zQoHlWFqPI)az&OfUY zWOhw}sqMUnZgn+tTAT&)q!MSSE@VY3N?{!DP`7baI$V1JAW`2 z3h&n7BM)EUT#f^|>fL?CT z9n1_KHiOBsQq)_k$3~s=fLDjCaf9$e82fcUxOJK1>eu<~mzow`a;g@Gp7u3Oy01eG z`j_HKmjtrlL@K10H{zrKH<7kn3Md^d0uN<+Zh8UwtQ%<#KRq-YQo>%o$%bAdy6|-3 z7gNudzOZe25Gs7}CHt>&KIf=+IL}luS zWbxW8nfDVpT2|oD(4}PEdQUi(U@EM2 z#^CR*U)Z0vee}udDH1$$lAI0R4jEP_kn76Is9e8oZ~w z5|4(v3sGm|NYo5}>D}|B`VW}2p#ocD*06~^Sul<>E>_mhAr-G2NZt-dvGY*wKMdnt z!~6f>xh2ztNj~y)U3@hreGMhX5k7D_e-CPJyvJ^gQRe+(`M66iRmk&Q24*2@(k{8b zZb>liLOpia9TygUE+U8Ro5h>zo0wM)-}{}+Mf36qw%w>6MvpGSH(sO21hb`Zet{91 zurj8w&Ii!W5~Ke+D^klGK+kFAqE4U_2~Q4%!FRS{NMs^gUz`fJ{hG16AVF~7HXUTc z3HE%iW@Fom_;Xl-^Z!g|SZGdfbeKrge?20j+w6b_ti-U?B6iY@KR=e1xYPH6NsNvf zjc6^yoaRV!b=7U~33QO|SU&6gfIH!ps7p4H*{giP<8lysc zW%1v^a(N{h-iahVS0BRX$!~G2R~(B(H}Z#b-NPeQm`Q0DSh74cxO|mqH+aKqSxYR> z{vecGIL7@OW?18y%bfbYq6R}eBx=cP1(jMciJqD(9<0#9Nd&*ZjNi&XIX`4)>MEhp zv<83m9!|d5yOGPcY{Y~2c8bhDayA-gR*Z7cWVtE4uSC}p8&gV!lhG^Y}nd@gq9-C%(Vs&r$DtmM!QbrNuV9URd! zl>b&hlIM1ha# zHnX90iD@yON%=waho^vCzb3ri>MEKsJq0Fn#=>~nT_h(f5SFbD#+0HocIUq)c-K{m z&z&QL191W=bDtoc&l`Vw!-JugxFg?%En72ynr7snuv3lPe`f`cwDhI(`T3>k@Hw;$ zr_ReDLzCWs{MC2ZIWvw;990WJ?+dU>yFnN@P7kKPA1vj!Xvp}0**^Z9@8`_4I|FFK z+FW$+10)}aw%cLM?5h{) z{Apg2D_4hs#>%tMSIG%ChjFhF|NCM5@0(5gZJPS!HnB}QF1>FWCESE5C3ZOKf*U(9 z;3wp1RAcpMLt^3U0JGgrNcB9L?>bzoJ8{P{bz$r^Z_qh-S~{zzDn0~zt6)6dlg>W% z_5tNXmPodk2`koe-5xLm)#Iy~e!B(@Z^}XMKfdhfDFP<1Eu^#h$fJ31->M$})r=E; z)F^~ctBSG8%#}oJybc9JgE6TkjjaY%>ffiAWU0XO{=O&4?iuT(dM?gtg6rZKG>?yG zQC-e-@+Jd``-oFy@QH1ZT6Y31&+z@*_ycrhxu+yYN(Ti?ZYsW8^GST+0PD9ppo_{=-C8TNjz;vFKTR10)MJK9Ix!hv(9DG>F ztcoR?Y5vk1=--dup*^q?*{rq9AT=F+O(;ium03i2r6cjUw^y1KdU>EXJv;CZzTIjl zxNerG2Zq(+r+#7N#1J1?8e)mB#@}Pca?11@pDoR8QUw=}rSPss4aLUQ%+x9gJX9Lc z>E&^uAfbr-7}UbELd{I;cNVOb%f;QBBiO-#)ewPs_@IL46PuU7zI{g0-HURyH_TjS z$uqfUMb{nF0J%zh2_0bPIoI~wOFG`U!SvFRkVsw`m&muJv{;qsDg&cz~czi&KO zQi0R|dq*TY9zqS*^R-rSEbn9^xE3{|+w(?&EO#ZHoI$s4cZ=x%fRWoE3fX zhFOCxakb=wVCjDhqWrkF-^*o5>tE8T-7`f0jb+SOegq9#(k109PUExs?U6E)s~rJE%kCP?4Sjdl@uVFgkue_dT}<$WM-FQl^OO5gYjEU(eni1=3AAZ$ zmFoQ9k!@hSoO?TGM#qSUo&}jLd+}#OI@5g3|E8Z6j^FazbcEh*BHTS8%?*VI-hhB_ zc6iU+mAy0m0hjnpxM;W`8R={f%au;z+BVMOe%cO~3jS~}4cB(T8`9-H@OBpW+%0+l z-#-WA(ii;Q@zNV6pSQv#2h0T5R|NXpA0pkWkKp$;vMUdF&N|PQybvI4%{J+*-j0bAdklxq9xv2Ij*(HY6nmmY$d2qCECJ#Jnb z$98A;r8|^c@mYyTcw}S@7j-qIdzeYwZ(sF12Wz}8v4$iu$lvB2!QY?q?&AVrM$Kqs zs7WeoWocXY|Ma|O)@ca0w82i>ETQc_e;$rl;qY-u?5mLmRdJ}nkP)W@%WJXZ+>-$5 z4OH*Pcld94HBKC}j@1omg1-~wBui$jB8x6K@_V+kxNuvVXvSVS>Xy|d^|b6*E>E*x z)!~*yVWj?(H=KHGh1TRA6OSE0_m0cMp`t`VS7|BqJW`xcEFJg z%n5;kmOHR}Zz5YfI|oKO|HEO?nL_dWX<#vcV!c`o+tFD7gVIWI!`^HFY|Vo8jyzr&BEDD@CNK-jj}x-gkG19!V6&`3MsiP z`^9srINL*VKz)s{HHZ=NJWuR6w}pK<_Z_U{^RUq60W<1T44>>P@S%e?ajJ451Nh(H zbG$<&_v9aJb1uUZ&FX9(&uKd5S>vRaWkS5WAM8)wg#+Ca*jzT0if5LicEd#>(?=ir zmCwhw7pfUqk^<|Gm*K5kVAl_(Lo(0e1>sCGlJ73nUR#Of{eOt!2MwTC%zJRm>qjPS zd9#wD1+ex#~V`{o>MPAU@aoje6@TZ8fNt5mkTIUT}}^8Z&2 z=Y+5#2hwrOMI85OD=Tm;gGt*sx4ip0Yg?p3OL+c8`LjB)>bn-y_e?`Qt1{M)=+JM| zIx$K1kEnI5D-AtnBzgAg2PwIG74)j!a4vBiTh%8O0+y8HlO-vF`4#TpFmRD({0HrB zfZ_bszv+!GyQgp(971dnQ=SWlkGa6Ik<0L&V*wkhdY3lJcu2zUs|&L^AM)DXJUn$T zj%4*qgvlwqS9HaG(NA##+`LtUM>@8Xj=h)RYeg_BEl*?OpmMN3l81hOt_hXz=8@Y& zCWwF3*RXMx-VhROjhbFO)!{dQCao>NFb8$A$kP&L-yARXB3@L>2KW0t*mdihsrh#= z0444P;+}J3-PiEbDiQ~ZW7(xqWst1KeT+U;LibKxFdn3i6Xw;kekZ))3A4tXVr>?_ zp+CR<m|QH>uWvE3GGjwELjXQg0^BrVJWNh=>}6XS;_P` zjPY=CraGK08J#E(KeD(V=EOeyJTZg){OApz$J^jrxh&K5D{d3RTkhgnZ)@1l``5uw z$sR4-_Or%`$q>G@1@HZxL1Y~5Ao12ol>L#>O{5RsU z^FEwu4aOZ4)7fkOzEBxvgNNl82;2$|y}dN?x_k{gJWYdob>-pl4qs-YC_wap?NU!m zj%7Z$zG#;2Uf$2mfU6t%&U3Ck8QK3D7*qyhXJ8t8XRk=FziY?u=avYscbz0J`fLE2JXjp8MKQ1%gTjcy_zulq(GjVJCfriE>Z^9m0rE*rSF~S zIAf}y$$M>TW9u7!T=&t^ zpXViyWmQSHeE|umY31E>&1~@P3^*$0yaJayY-d3!oXyC^4#_Z5lDrtU#LU2W-cvts zkP;nztP216^mCcV^^Xhu^Jx&YTY|fvsWT3icf{4iyb&&ezHJM8N%`)ijwwf zwj-(lf(*(rQp1Re8VkXHL>9Ib5VBR%7OG~g!7D?HS+F&~k3?{P>;(f;uM>mlW}gyF zeE6FDr}-6f`-b4!x0!6y_Y|0Zq8;C=?jaZVa5jj4Fd8jLW&LGaq2HKp3>$D;*wMU? zeE(o09#S%&g{S<0S0NuzcFJeAy>biewVWd5D|Y5ir*};iBvT^_MXwaT!9o2Rte*Rx zB+tALk2k!-I~B34_(UscM|ESRR)=u2Yacn6W+Ps=SeZTg+zOjM<>8iJSJ=?pzI4~C z3e4Xzmz+~R3Z07lbX!fiU=Drt^x17xV|M$>1!*6g_ClAm6xz7$g zDuITmYQBRVMslY*6Ilye@oV39QO}QVo&_t#-Z5&dqP`E!++U6sYpjWTA3rd7wHwv< zB(UMDhtm4_6*#QwqHs2A9BevaCe`!X?MdMHpbXg_U||@P zrSL;^duB8oF%H2KoIT~SM2(vAD|KdYkzjS%9dts1aloEbc8He2;HGZuntWLZ;@w(W zeO<*f94%OlY$@ky{GJtPJu>O!`wI;}XF&---ZNJGUh z@Gx$|-R&+SSC>o(`do|Rsdgm$c>sJc2*H%jRJNmE1-KmJJ%cIN1$R9Y;`Mx@c>KIN zR><<<+ffl`SH`nzf&J;VodxLoLyb)Qya)1^PmpGXEW(^=|Ktmj8~b($0SR94X-E*x zsP!g?*S>-q>5&+4F_wj$D}&{|^U*ZAT5x(Y7KR>Dm+r|=@90G%Iyp}pg4n={f%KYY z3ASu8BiHpk;O1Q_Wo;eeyVh%Eb-4IJKQh|O9M~cYsctK_b%5$R8Of+f7PIV&Bh65@ zk_?>N8z#Iz!{2ev`092Bd$2^2&csT5d~vHFe7Z%fmYov+^RHp29InBvDm(5gaA7ah zlcB1n71utRNpuZt!BW{BEe_?gKbbN#G_|+n?NA*-ZNoX}s_{U*Gt!pHE^?1R&v6} zNR$zn3Vrpm@zNw)vS`6o$m7r6^toxQw5ku?9o>eDTFiy9`%jPul8sVdqO3_h2(=>A zwBygoqQTVGG)Jo2cH6dq*$sDe;5|OQj~t?VYR^g7!Lx$XKL+73A5bGTmc1L+n^vdP zW1Q^=Va|LbIC?-!s@n%0`qAohykGCcCDu7YleV5H#yeT7$vGzx@3rB~ZP};n)#q$@ z>ClJ|Mr)7?9sa$a)QJI3GSN4>l<3f<-S~WyBhj4t|MQg%-iSzI&!%cp>xw3f^z;y_ zD?gKY^8%%e+&_KepqcYDisDwXlBfJmv9}!W`OYAkrya?yL|3sWDP5Gp83kGv%~+u} zK}a9Xb4jO~k%#X|aBDxh%Q7Fg4oeiGZ5Bg&s0M!Vt75B*9cYZQuVjXjGI3g5K=$lz zlg{LqZl*&6@LX!~ZRYG*3b*?5+wQAjM7NIj04|=15!cFDm9rwX=v9TTL;A2!+^2nJ zbw0j4>PYmBLg46)op=KhS>nkY*g8;FqC753=)2Jn$`UAUR;Xc;_#)W!trDARjhSFr z0tYY$KlV^^gV;j)uQj;fXfgXr2T`T!W<2C=V4AGV@6k=Am~ie5xq9vk>~07~bF)l# zp*RIDD|TRi+dU*=jW=|NgRy3NDpQPXhFiiP^xb?*2xR-n&ieo9_PE7AICJ#_Dkptn zA7uK{BbUnYjoCmFUajQvq>Mwvp@G>DA(|$ z_*gc>s1-uKbff0qc41P|K4L9nE7kB{SuHSD;P2~oSJ;Re1?v626a!Lb5trFVLG*GF z2Abuus<;@E6_qcxscvS|n!bSPvOKg8z0VTA7r~JI)p%y-P@@0Qi8zPZh#zLOirA2D znBY`~OTVkJ`D6Oh$@?nt!)6U{V5yPITi*w*cXhg9903?IylZWx+(b z#bDH(i=&rZXA%$Ytx|2l5%b)`z!Y`T+%?3}5dedcr-uxuZFwpw~{az0Du~ zI}w6)&r+GO_#f{O@5DR4&xFGz^N7>KNz(hK@%TKDJ1oNLmvKyfWq&I6E5u!OYDDC? z2c|5UDD9*$56%Mhghq_W%Ok_AUV_T__q<)RCgTV${XV@0aJuo_pWSqRRjZ;_R9 zr^U{{Ygp<2s}QAckH^+Hv$x!1JZE8ViRh0RSzc)kuKV3_tY$t_`S1^lqI*ls4-XT3 z+r8lXF;A&)Tv_EFm==bhMOqp=Tcb&nhssF?MCJ+xmj!t6M+-fTYM9P@Rl2KJE(RR* zX4~sc;C$5%4AU)VYvrmzzDHJad$5t{&&yN@{>8HfW9>*na5(G_3&D52(%8ze$H|;Y zo1}Y^4b^qvr6k6kujAO%2vwS0l!H3nI%M3~&0zW09b=#5v7?dh^tsDLNq-k#LC1hW zC5gf(k78Lsf*dVrYrxfkAB4mY(|P}nwp5?>hjR}3-F(yvy2LIV7((ahm0;?z)x_H{ z21H6c0~`8;Ei*0xPtz`R8a0$W4DAM{%6;Qn-5=|i5?yrvFPgq}Bt!q5gGq*Vn9!NT zCi8E)XE_aMnsrJDU-p^&$_$j|?hTwj!_44v{MNLBx&6%HH!}YG4ssp*5>?R)g zCtWo8f-F5^+l}vHrwY?76=>+QR=l8hl^k(=4w}{>XqTMEw)yp=N}CHXd`O~@Id?Ib z`VT?H&MLOI(vD6#<0~2dYY^Gxl1FA6wTpjdG%>sDsjx39m;38(GY_9afJn~s`K?Wq zQaGd1W)}YRD`)qA^`Toh*Ltz80z0!=i3Ypm2@sja&(uPlL0nr#5*D&|Xf zCZ~GxVex;J`2MF6ds9{f=_B({EH|HQA7TSv&DLRKKruV9cMvVsZ^xXwhNk*F|Lc%k zgnFM}5G{xY^Yjp0o|VBqTjWETMQ@3hs|&e0;~Ye755ZWKR2DS45dJn*p|(n}uz!#f zxi-#LeBn1`8hyXR>Pt~5|K=0(*wTmYbpttDYcu@NF_30|hFTd?-wg_qL2vU# zsyDvC&MfZ5I`E#bH+SK|+(>k}70aS-RDfk>6Bhlb5xnL*kzM<2#fxqYVsmR6;qi_< z?7uyX)oLlwH>Txy;N>i`xau&p%vy}5v-8;1>BDI3qZ*t+qD>X`W5~qd0_lwX>U2DW z(LC;Bzt0YQ&4=yHJg1qjMTYEjB#y;4;=2o5MPtkUz^c4*9IUU-)ZZx3bJr?RHr$GA z|8xOVEB9c@%U`VjQXTs85#N;^^%wFN=s~vK0;z86txSXgDis*E8JMSgGSm#@+=ewX z$O&5q;?-a+PCoEmB*VE7ITJbC(DsgrQ@}t9hHaRt_k_I9je-e_Lh+?a2J0>yOf7d8 zpw_rzVbjnPu#9h=?+#97b8?FyFS;9L#s&!cA32f%c8A3I#oJkke-T`npNI0b*Vx7M zUeq+N0bM5cC38Yn!}vBM+?QX*j&0DQ`U^TRE4fXS(5XyKJF|I*=|S>)`xTh2`3_r` z#j#y;5}~rQ9BV6+gxF0EL__hQ_;9{Di+WZES$b7?Z-yTG(ke$4>YMP=1!M9{))|J+ zS&4}Q3)!|>E$TMA6TbvqG}U{rMmIeuM4gXukIS>D`8BU4KVT(tm z!rQDrICrZm@td~@0$R7B-sCdYF|P=Ad)DB9TABlLTpJGBI?(0_hVMoT6 zU4aE%Avo(>Dm!M#JsZ3WuVCsz;b_1y;%B^Bn%Or>sfEejVw}7=j(xhJO56B*u&h>x z6r^p0!J|&$0U?js$e*H%d#{SZ2@fn1%=BBu4MP3O9SEf#C&h zX~)oo6H2t-+yeAme~Gz0)}VW@mSAE1DzdfuBTUuF$Gc;nFr~m8Q2N-4ud{{_&x76Y z>ZynO|!T%n|>_ zKVGIJbGJ1-?z>*9?Rh^2(7L~^_-dqq=|0X2x^lzWkX?e|?Y5;@ta+Uow)*<@)3b_X!(~ zwiVxg+amI6=>)gy{G0258Z*41KvNZ}xc|_aXwJ9*M=x38b?0BK*G(PzE1?1PbpwR( zKwS{37T~k#)hujp0`%PB_gMnWsyG?e*Yo`8vYBLbl^wB^u@MKPeiLonE>HJNXve6d zcT9GuDN);g4S3AtK9O4z1sdt081pBc*>)d;cUMAiVrL4=UYG;Fl-g0l^`bD{z>!#A zIxN*&>{BJB~PC_yG~_ zE!a4Ezi8{2R2W-Ti+?8BkVR)M!I!?Fn4+A@o_zcV+b?uu`m5)H*m54}dwGhKTfWUM z8!{qAc+@hM{XNy6`YV>=<~DWm)n+&7HcyiF4K-vOrPWozlBQn{f_47_c)H*ZE}BwC zy1qOIgP!;3lm3~>J}8DcNd;J>TP=JFl%xJJC0O4Q!c0eN(XqEWF>L%gB9PONacBY3 zMBX!arVw<#C`ibRVWh`xA>q|DV9*S>J(?rA?1Qia2lOyQQyP^mA) znD_Vq$<*fK#CbaUd`P*jWL~>C)t2L?=-&;77N9I>JhcguO zZl|)fBju?p&lH!wTqt-QJ4$|h*evaF77}YP zACDOR6rz8c!+A?BX&!&DO)lxbqC@H@j5wAIqdjs_QwRq>l=cptwSzYTHyOd1@w|z2z$M zKs&e!dzcZ+^vZ!R@xL)`vnhGkZy@z*Xv6eS15;fiW$L3+jrqp!$c^!Fpu95_4R&X+ z&21?#$Ko&6FR&(AN4%gQF$BxYQrHS1177mq;5FS#Lc6*nS)pquowv`#e}!$GQTSW< z#MbrgLpQQ2yzViOlv{3wWd?>)CT;e7J?h`P2ZfEvB8lY>n6at_vr?nUpIZ@-<`Id` zGh>-sy91fj$4*>lGl=DXsfTofJWL1*WoLPQ&Dp*Vhx?k4dU6;RZv3AP*Y6%iD{45? zyMK(S>YI;bWLu&1E*aVJ8D1aE!_2Ao*r*4o@Y13X&zM)exAnbHjL)kV1YWsfj*|0?)=Xa-*GDr3)YsnSDH4cM{1R&>&4 zAl)%G8>b5O<viQO-IDUSz^e%ZcHw`A8Z$#VR9Fo<*e_vJ~@Z!)Nt^hxb9^(cfA;Xo4~8yIh8nn+3f0Jdgo@f5q~Sj8f0}q~Yf&cspaE zbf=xZI|-B%Jom`a6)< zFBHp${-D)r!+C|r(t_2q9B$MV9gw;;79FGOsmCD|-fL$mI_UdSm+Iy4chLcKJX1}* zEApXkR~O1U%o5$GWc!#wCAgh^-uK-I1+|YM=;)9|Pr1qS!HlQUt2W@;^^TME!*)wD zn|;QCFp^s1@-%yTuxSYI(!Us^8pjcZ)NNq-!j0vf3+Xf80yr|9an6A)x(cg50MU)Z z5%&}6N|ideVw;DPcRk=#Uu(eKfUy#MemPZ{|H}MVz8YEd`vUE3qgxzV~0hll6i@JaFgX1oOA!h9W*`6M{G0^+GNs+qRTnhJL4e!md~WO z_p0)CUwhDB%A0d66v*?YD-uq7q;CSGo7UqBzl}8CnI)YH7@m&?(l^?Uz>?$QDHn1@ zX*xZSncIypZw{wtr^rtT|BKpEH_4n6QLwHc1h?$^LC4f8@(v$MFs>k#E0Q&YiB+nS zyE^!`86Qdfgk|dnk;q8}BrTy^qD$^O`wjg67UGxRH)*6)J$y;1!-9Vdw@0~8abrP`OG$_;az88?Q4D zZVLM7J(*>Ty7E9_A>&)37SetS`H)kZhcD*n67@o7(th4TyxQTns7-DVzpSVmuO8RX zU8dv*D41fg{(Lf_JrVY73`NU<*>t#kCM-4mhvCf@q|MG7?w<<5W3Mx5#-n3=bFY^W zJ8nABWqA;TpSBWRvQ_yr40sracb*Bc+jX47k60pjl}Y%M>aPjl z`?3i4=H8Ey;i=93ui_*en`S5L>SYdKoXRM3@U#<8HTYT@5g9QQb@`4RciM&S_vTmX= zZcHoDDdsi?90Pa8t6X`NN&kJ#hm=0{J%T_kU~eDMU8sPIm$%SyXN%xvb`h?58$mVM zZFAv`j8HgTg#@#9;;v~+8Lv`BUrGBh|F#+K?q?#BZXL+`$*~M$vLn$}3V|hR(Wo4q zL=SyPgIu$D^C80HZi&|U$QH)B`ybE45p|*H<3Q?=LZ&AW;lA*WiGzY z1aRLxi6{K$!2|qgJzrr@o%!={GX>P{P}g# zg0iYTH+dRw&q38p&)sfKa%c#g=nO%#u1u=` zLyix-$KD_T2HcFv$4Jwy-4bqGU)c}t@@CknX+>p&hw!sUmf-8(2LDFHDoV)ufv`MIb>gS0(-v@2d%rr{0Jwj&EZ9 z)fvzALPj+&az05A_C7??_qRb$%_Lz9CCj?(t=Nf6RYgUe8TYy#yzHT-13KkTZ;;kF=NKIk_*q;i;H`{*F$bGD*cZrlxyx5YseD#8oA0c?n zCzE*zeuCHSO0-D};xhGY$@`yn;@L_o>CPpeAYkqXoarXerfnWDPSz5Gqy4zlWjjG3 zdJ(1#s-nXcC-XB^{^GgM>7r5LKOyOdj1YPKGx=t48*-1m$F%c_bi7Uuv<<1j1AB_O z+edB5VD*FIDEA@Mw7VY6dRfP^|5fU#=mEC^El@-6E!Q0A0s&I%aK+6c`h6bDvT==g zYEO*rV6|A*cTq06+l_Vzkit68-y7Vc3ZL@e{)Bq0y*HX@oU$b+j~^5(#&wETirYZ* zVHNr;QlYT}JixNr0)PHj!d>k0f#EERdf6tK?hj%4;<*gp)_QaAPEUrNcMT-`i3gVg z1&nWZ2_)2DaUT3~tHb0^9Eno3CaFVhCH@l|d0BpWXD4pZxUG{mz90Wo{TIr0+#x}B zzOW+K43~D^q_%Gc@ynBo*juuYdo%ke%=ZexzqXllwA444Mt-5r%yXPrzK@LWP{5G1 z7W(sd0la1%$f46CsMov(2wYDoCDC<^>#*!=#od~@T*!?jaDToYw!g2V8UE$a42sR|9d6lD_oMuu*fekeR&7&rw*dL zIaNS1WrcvuQzXwZ0ODjr5qD+MyGMV+Zr=|48uN(DS*lI`XfBXo`*e~Gn?_UId^myL zT;dD#lo|GqzQnl>H-Vk?^CTVP_Cw8i&pdzO;PC&rd-F1&kv5~LXC7%77zGP@VsJ}a z0zGF}4*PdjBDcShTc+nk$}}v*y-ka#zmqh-Ah!~m%db$m{=RT@kr|e_QSRghH(0UR zP_o@z!u*h5`~St%7S_A6cO_&tnBZ``D(X9`6slP+_4KTl@m=G8LF>e3JQ{b7jQ#3B z`lXtQGgf>SO<`SjuhgW4+AKRxZ^#WIf6Y_kOG#F}3Yt4?P-~hkEqIa!9lLvR-!d)Y z_jo@{*LBD78;WTC@MFAOj<@hYGlKi>?FDxCyd~M6q7%1aT6!pcx|~Io+K2Iu|H%po zNx7Wf&J}PoV;r9Msi)DNgZbh?CAe1a9F@MH4WrUb(Iustj(hqYtY%Uc)kR;U0F>wEskbB^J28T_lO=^_74`lkP@7Oq(59RvgdtI z?-w8_jYLg92l3s9@NP~fJu%A{7TTKOJ;Ns58PP~=mWD|5%?>|=5nCH@*X)gKk3NHK zCbpn%fi}6>b_j+wyRo-t5k08U35tf@tix>(L#PTw`HgM*>tKk0DvFPH+JmDt~@UK?+33eX`l7{~Iq^;ur@qDpC8lVd94gz=)m6f^0L%f%@?wFvRmkVJ!k(c7%oYf z0N}!XI9ZHze#*TLLdHHn=Z;fmj{8i^1@-46p}UVHax!i|9C$2aSrUx zt-+qoV(vhY9r+t*FUjMFJJ!Leyh4^I9R{!{^OHxWsTzx8*K9%J5w3V*`dSQzaAFTSGDUkl1`+x5!WC zH-viE;EQY(TD-y?>_%FmII@@<&GJ67&&)7#WHPv1SWC>YVv4Z{xq*D@ zIOgwSJj^h!EAXQ@8V$^oXueVnJpCarY&-vpQy#hmyxaA#yS$DDA1;UN&MJ(XtWNV& zn&5#)1^&H1oxFN~5O(-%#VK3L=$s-SILoppeWw3(n%I_Wx_UXfMkJ60+-KOW$MAfV zgDAkY5R8xhL;uCjB>(++$TbSZ!a?jEy`m51USYXN`xo5EBrP(cpN1sAIceWdSQ$xi zy>0^ClxUvrdl7F}mx zE3C#RtlMFwTRLdWXK&T{Dx~v~9)!HvkDPZEmFG%Wp1oCq=kG_eyFIuZS7^AA`|R%r zvA@6g*C)|VgCYEjJ}KeNBU{co{5lyj(@TQq29vMAaW5OpG_ax1wNfGOKrcGITSh$I zo4~be?&!<>RDmCk@EP`Af@pXcw_4Q;>ZYERWb+H7Z$ZkmFub}di_V-O&mS253%7+O za>jHyXdfOgxz(@FRpAF0R$}lpKkE8G8Ut5M7 z*4vO@&R5|?awxut%%rdLW%vQ+-T1IvpBw+lm2`XWm1v!ge|(@N)*M#|mNb0u5MJz4 zhIKHWw5D%{AGh2wBeIaH56uR%k!<(b{FiQib__Jee87yUiS*Fu8W=gd5MNz>zzrh{ zVD_c)7|(urk5~D?kuY=I`hGACV>^9aaz(h};3_hw`7IdGVw|M$h`yPb3NM&%A*KHi zGSRLNjH0B3ZDXWAsPx+NFXK#w?K$b>Ysp#Q=QyCMN)}CEIHu@qj$!+nbi*seWa*<2 zNjCpmi5T1#HKNqcjdY&xcNp-t1rsi76X)IbFs{c9_ox-o#^L4gDV%Xc`s29+Js$kQ z+sA}QbH+fO<`ale2}3*YEb8CJc9fo*qx1U>EStXywv8Ew85ip5g?tl!eT|=R9tRTc zXD%6ZxL2Zk_MAxp%dJIddjAHU>{bphhS%VzV`^meT?evhgQa-A@*p}uSBf{;U4^9E+*q!MBT3k@=CYcvaODWc!YGQdt+Mo7^7 zNXGWvgr?9K$=$wPEf?h1HDGyHDQC%aPvy45;!l}FY1HW&IPKia{NHH~YRORcRwc?e=INh}2F+^RrQaq*OHw`YM&`?{1(q3#U?Pne= zaQlTF*{Wpr7h5t)%|R?q>lW>6X@$y(Y;XOA3KiPi;K?E@v@Iy+3Re1n%`6Kn3reOX z4~FtrpI2eg?{i$#ph<8$=Kpa%{_Ix>W1h6B#|d2{Qv)dJ~yfv_t@PfZ`l98D#`+{)ZC;SLX~-KmRXK+$>*f^IYasH z5bXPrL0cEv^9j5C1fBlli1n^N>~pV(szY0-oFen)br#{B1>y9f8_U#8E5g&y+qr-x z>mlT!7Dn%?rgDdUV1ttd-mx2@}FI>;OJwqJHl&6=$ZR&fRte!;wOs$5UdQ3wP z`Nc(UUkvj8EAj4+I@-&$zw=jWaML?=`Y@~s#PyYUdFTwXe#1d1eYg#^?v*hgz7Ooo zvcQ-4Psi!XU|z+#oMpxZQZwTtjCE+o?-7SY2R#a5212-xZ5m~1vP?Z;po#6@8I;I&~81Ip-+{az@wI@+kX5#o8 z8gyplU(j1si5CA|rni!Opq9Nc|ALsClz0Zl_^-i}E`@ZXdn)U}`-_p5L&=M;JnUO@ zKytV5NT`6@o4WC%?c4Z2|K-4TQiw9vM@i!FLu9#~xwvEFC()t{L-`YfWQ8Pmdrn&U zIx)WOCGoUmsa}Q)jDH(zWKA1_zroGf|MPgSAdBOS;qY&FG?`ySL#8?L4QITBmybg^ z{imKVIP$C{*D1`q1#{p1KhDeB%k%H`n(@hvB(CG+a){eLLDIp}W;~Q9Y!_^4k}n

;$UVPzRp&rMPF#BTj|RhqcQmNPH|Op7;RGwm`?K!Bk#HnZM8OjS+YB$^PUwko$}A z`FRiN<#!pd>&tI^=`)-d$o+wPPyZpk_b=|d+F2;}bU=mknRGSVe|%hNiN&?ex=DM) zTy0=HQps}lFE8pj#S z{eom!0!!pj6>|S~inuc0p@1Qi=UY`ktRkFg;Be`6x$!rh}GnC-@bx|gC zRkK{A)qJ}7YZk~p&BI-0%gHp`!(`h}OR=6-tEedM5-88K#q}fZQcG!VUj3G(U_Bz8 zG*0t`^|Qm!)ismad}6x*YzHT*CWyPDYfC<5If#kcDtdfUqtr}i@KnBxrZmT$y>t;KX;3ftWGRrj_S;l}sxc}gXuchpsO2Ocr`{t99n}ISyK9(7 zPKEZdU4YTuV0wIp}1)bkO-l54Q4 zM29LcezIM!3QOI!NqD9;nUj22tUMxJv}si@WPEDF9?>;A7i}y*QcYD1`tuXLYH_`5si5q*3-yPke5EQMR4EI&0{oo2c;LLcK;E~`%`{yBDF zBHE5IwPn=@fqgK_L_?CV zXH+gP8hcnsxT(cmw#k5db2>2Au8>?m{TL>z#bE@WKp&Sj!tAc!7})-YGp=Wz*cx;3 z9n_%y@_o>3Rf+41F42gTetZ$@`}#gWmn>~R4L$!E;T99d{g!2e!$anYwNWM0m+&xD z(-dW%upKm|Vpx>?8@+;F#!nBfg^#R5K)868*reML&7WrC<0C(c@^>rpmsfV;d36&` zJL(##25-sjZ8_@_oDppByNeaAUi%d$?dz3fd}ch{2m3e=93)>vt1mh5z8AfO{d_2Q zSHTlho6h3rt6xaQ=9}zI6owOWGpU@K9B+K33FFr$a{s<)gJsbKN!I@O!lC@_8`ap; z<4YeWEQ7pL7WnUc4b5Qwx*nkwbw^JT@i8Uv;BE&hd^kles9gc2i(#0vDw77}%JZ2! zq=ktejkxJoT!=}qu_WX3t6G^~#&p2I$76_A%0>uW;en4G3h7AI_pswiJU)AsK*JX| z!{iAycrqx8v(T6isyY9U!&8qb@;_Oh-r)%ss5aY3`pmKqHMaU>NAPR#l`UcV>_Zwj zHU(xS|H2}dAtZ6d9}se+g#Y!WNO5&gy}JynMy(_H%g(|RGbenI&Y z{R4IHY8>AyMThz;@VOVNaQ{$SGQ8vhXpFT)(~qe%dPo**WI2MUvRv-Kw%IV-$q-+Y z2DJ4<(;_W)jD zTO+EOzb48Z!O&}OgAsf0(8e3ue0-Xf@c3^!acc5_xcOl?XImyco8AmbQ{{wV$#=PU z=I3cz?<7u{X+S&vB*3fv@i_euQhXrCd-*qG%gsR~-FZ9gwbaDSeJuC=cpQJMwj1?b zzKHCq(;+)bT4+>GBA>)J0ODfsU~dB5Sey;94GkFgx|DnDYD@5hqj=p66&lV}LC0yf ziRpTodinI@C$_iYDmxvrZL>49KiG)pLyIZ*Z4CdoopG(pMY{C?(d5dlDhY0zc*TR_ z+G0GNafeRxv?X7(kBFT%^@vUeG{eLZb@)VEg<8qV@fTHEaNlhUvTd9%NSE87f>IjI zTdu@!8_hh8Vs~y)+(bCpwp!v9w?3N$N8@Vnn4S(j$o9Fue031-)kzl}8`2B8%*)|A z^}0^>^H4tA+F#gRyd2WTzhybr2sGL9gC?2`;9J>UvF}qJcjKNT7#s@4yPGm-_+cAf zX}q7X^2Zo*EuxEb9q2FNOcpQB220i%QoK5hibgcR)DM*yt=r25DX)X3Wy|rHM>TDf zQR4fvP12s7<)Y%q0sMmfB@(Rm)w=|b6k-s%5^3PGN^serAY7Gi;-0Qs1aIf8!tI9j zbk~Jah_0>0v%cyy_&^yX7!_btu^LgSv4tq}9cUU?MkntWz~{gDh0AAp>ej>z=1uFX zP-$f%NnVr)8D1SYZPOuwzd1_L{Lar)OM+)c}6 zq{Ly7WZy?`T^20MLDX23KrbFq;FZ|spk3fFLdWd`S^I?&KjFp?#{99s^TM$AJGmEe zkDw?t4wWY-&>0H#usF62SLSqaZ?f6VaK>D`J9Pn#k?w_mqpQ$Dbcv?w_2Zjm*cN2I z4#~rvHi{+y!q*&sDs7Fl2tVLDl1ybk6f+u&DosYhty??K68} z?I{loPAa4)r@HXsem;WthY0T5a}Stt_MC(pfy*~w`^In-2WQgpHFCV>n^xRB`Xi@m zs11*U)FghDxt|B~n`EjnP~Mj&r!0jlO&0iYR}DQ}mI}?6ThaaGWRam_3AkSC#Ji2B zNbIr8aJwrE&rHaqnO#!6uXGO{m(}Mk{c$ETp(c{-ys29ylwMB6kEIDzey=jW+^ZB1 zyNw}7VmH7jHxJygs*r9kIK*FBA0UW>&vLG^(Qx-mJo+(z+IELJP@Y_Y7rP#D^Fro< zleLzAv5Ce@3Ng_QDOFi8%%d(i(uxw+6Q$1deaO9?&Q8GmwCh-VY;U^$5WCT17X)iQmJ6?33FdPqNVt(B^RmgwH-9BqJtgonEM;%r ziUZfFVq7a27xZHN-`QmL8avYQ$3pD2Ntw>O&RjSP75PEPoADVLj|H4AKmR%7wr25PAC9iC}2kMy~Dboa$fa6VRmmme=D ze|7B0Ygy(=zSAU97|@Tu*VB$pFK6jOkTS2_*MeRT-jcP^7h%g9Tbw1_rh2W~eByLF zVQR;BvM0|Sl)i=GY}HI^eXjzRD*eTni`Tf%>ukv#BWJO~H3RzHTYzFi5#F7Q)NGF| zuQjy=zxEqMT79;GZOKxceYuMMN*KdeF|Wmif1gArKBYp3oQ&|}aw7R)ejUu*V{s2A zP^-xAFuz|dj*l(i-e}vA2RmKFm#z+@#qt%EK*dUOTJ{lcYqt69z|k-P>)Xqyo;~YZlm3l+&Ux!99~;Pv8Y?g=4jD6$0I{*1l6zY| zFBz^?w4jl#IZ@Q}gS7H6$-TWWuNADB_e1@`6E4h2lcaxHD9O~zcV>XsALdC85$Hxv zk^eHd9-Rw^6T`!M;Wz6Fm>gL_NBr2w5B+yu_?f(u>uP-n?+1LqxqSjni2MyUr~aW| zpEN1Vw;^w)Scsh;FQC~YTj49y0=66oq$*bZ_)lfksB~MGv>2a;ru23AZd?&{d-4@V z>#$tFnxW)yH37wHGaM^hO)dTFV8S^Wp=sua_{*(XkYK_%%o(m^#V_XVSZ*#}FPkJf z&3Fj|=EEs^zlRHSi6ACp&q^>{ciKfrDzU-Pix%{@Cflez!S*N%SC9>p_Q3uK4_vUR zkVZT^!kf+Z5r$eva4Y3*fJ#m{Hu_~!vz|fxyrZ&$OY#qHS&SCTzfY9l_GNAe?`d0$ zo_W4>{lAIuB;E*>?NaEMzbPO~+HmBN$)cuhg%J2(2d>RIK{kKB1hHGfQMxLFj(^?< z8X;X+Ys+(IG@OZx(|!qVFFaTQW0jMz>^#eE+*0Q4gUZoado1~|OdWRgTZ_|Av+k)~ z@1WF9B*E&3QBu6;f?hneERJ(loClin6D3$J_p=}Ge5(eXb%Q83Uzs10Q--F?42aRz zmk?!Dg6~ozY1)-6xCy;D^6e-hUVRTADrTrw~0u{>2QhXWV>_>*s0ZF{w^aL%(&Ch8B&73_e!Gs(;C)I@<2!S zTjS;O4|bW#3$mvcaq-uxz^bPdhhFq0Me85JEevNOSSB4}Kbj9XB`Z8@ujSSnt%SVq z6C^jb=bE3yR(Bow1b%YGXgcXS-Py$aPO^=t^lT!zfi|RUq^0;<*#J6!P#-kJ zv+qc)6g~2xA7ABNi}F6UGNo=Lk3*PF2GIyEhjICEqV0NQoO>cNi;Z9o-bd|HuXAY>3(+X&wpG03w>w3 zBCDQXfIVw%(P!vwdMrwdAFgXBOmX>6jyk);i$md(yZYe6LTHigV!LLcoK%i28FR%| z{2;}U`Zyx=3liaoI59mlitU8%XvJw7gGgiVRxoJ@(%jIiuB|jGP*=J@+^*1<{$-3E-3%KoawxlP;MXbGV7v5WYC@Le=nUWzw**o)rp zZ|Th19>PylKhJbD=IuK68qDeD_Uj2wtdAo!!ndUcPN8Yr(&!QZ{yC?_T$Sf>+t54V$qxG z{(OSC1m!#rlapUBLPBN?HpV8>7jgEy-h)6v-s3pQ{h|S`1_rowd_C=*RRU2T>LtAN zxuL}{M2&UCU7JA0$qnR7W!iDIpSP}l*+Bj)(<$0>1oGZQfVbF*{TCh*y^PF&lcFA6 zI>esb3-twW?Qk4tl0om^VjRNkdd#_dgWJ#YsIj$+B)rEe=?suMB4E{4fu3+1&g;oY z3q_(y#I;}#Leaj|g`EtmNY8yCw9U)@HM zNO^|C$IbCqE$e11&w;oxZFoKES$xjxYz;E0{j_ni#DIk=~&g>KJr5Zo&`7!STh5qBuan81HVc%yF ze(w7Q)?^d04Hul9YZN%$KBfOGd5RqKkw>+i=CRp%e`gYPcnX>6vpSZQ9k-3xPBxn|u3`opgE$Q**%F|($TrD27n@2yT7eU~LI;59Z5t9#W zgZQSEICw#`sLWfIZ@SQix988$m3^$p&v9x*?+q`>jG`bod(;MB8{MK8zX9LX-&I&! zmPh6vbcg0A;S#Oz`kDebR?l>qt0CMlH#_p?%~5fG|J9V$uYkx}gbCJS8q4sDN%+Dlu2|F0Moj?5{Se0I8%&Y{ch8umxWNzdJ>jbO&~!mYw9`bm^eGBPvllu2U!Pd zv5^}>yNBuX%?V3|bs14)?>*MBIqDD|S)5J-BPM{)O(O|+p*tSow;kIF-MyUtc~uB= z$RBK(Wk|NPT9eV#RlIe1hR82WiZ{Rf4_l<~=-iJ{7s@VFxty* z`^pd+?p+Q^BbnB7t(~(fk>gLY&ffge0@3s5ihSMf5?nX*5Lr0oBH*@I3EnQ`i(r>n zUiiDPj;lysz`WuH693-%o-9-26^2Dw)@F;Fu%Fp z;IemVlAnu~NOtE>rGJBqZv?!Xht&CTKfd#JJ%ZwJqPl+%bQLbfllc`?)l`Q+IN3?C zs@CGJt3`tQ{SWxYT%g;0TcOrgO0fSXO@?vSMD~-Vz6g^}c|H-V?`Eb;Nl8X7r22SzEd+dk!4eBVYJ zvN+pH{QmVvQEjX|A7$2!fe-d^OYFl*M{!xKK!c^rVE&a7Y&w6RJG)wrKX$YlrHql^;dh0+~;{xffGJZrrTFBJ!dqLXxAovN9Uh8P;Q)ju9=Y$%TEB zn8sSRicBuIgz+UF=sdlUo~nER`)@|zx|z&p&i3LhgBiBGuHa57>cP7q6D6K%!&w9Q z*TXf1Onk?Uu*)LOc2cNh-bNQpN`mu##d!7HH9BTRJ(MyWSmZN<$XnQuH9c%4neoP( z8~?z>0rj}+krY*D-BW{DH}6R17hB#M0C!Yu5LTy9r9~_G|7M&LIy2UhDZbM|=l&YD zWm!+%+frfm&00LxK9~0OXBjB=KWx<3A!~P)xr?2 zkMVVnhn^7ItzJX-UZ=3pisG8(VyenEvur1n<0(BkvQuvh)Te1lG`{DeQT$u0Ke*{r zl1Mx>0v5cE!{tT^G)pcGlndFenQJ~562kP0ODpk-W-ZmXE`~kqtv$pkm<}%0=Qo|# z67r7)kSOX1n=fs{MJGzA=TKEX>sc>$JQC@a`oAGcuC?MHChc^^wfA8Au^7Ep-KNqD z^PzBdH@3%)C-MqgVa2!ucq6=$zPnxt(TSCK!fPPSqk4RC+ESrTGm7MHVx7sFhnep; zoo>zU&p#?EN8>^dZqk~uFgwi)cXUZr0odf@jUQF za{)E`D8=g)NC}X9N9Xt&MSk?}e`rzqh|Fkv2|1syq51SIy0u?_ekRM4X87lFm%JuG z&Y!iopva%Pj5XtXIX@wAzA6d4{F?;H4v^fs{K@aYSrp@RyAYcDtsMM2%hBme2lo`6 zNqmBZc%Pp#tyGcY%VTR0mlcRY&==xjO|kuU3uj|=0i3SJ;un`hI&EelXejj)s{7S( zL9DN4;1)xP?`~{r5qO3*BB@uW2bhoDRlNacw9gvQIhNIv344VG-2i&PH z$Mo1x?)Bg$AuA-ul`CoefgLiArhm_k}fikz+0KV2tf)1~e$c6%&GJTMN@Z z;w^BkT^x6yy3S-xL5hh1M;x;QBez=Cd{+%wOG~sqv**WIleBg8|&2eadb;KiS9Zl(fejJ_`+zm@iC=) z5503sn;)^&LHMT~MV^1y2|ssxO7K}xp#b_#_=B^p2681IBVb!;1b&Oopx40yeni{;=nqJr`EQGA@XV?Jx<1SoCLJ|JqMgJE#Zj>GX9-gA1A3R`(2HNn3K9Lrli=BGuZMZj zH*Bqs8+R%XwC?0#Rs>HD7daC#+e{q!gz-F6hx3tVWrQ)iytv7!@nlxnHE~X4BVAkf z4i=wl!0H4esxHI4N$PTf(su*WBv?TH3{OmNE1<75{(+N0UcSqO)iLk6sn0XXhzcqE zp9iCVcLMV(7UKf#YxL~TR;W{v5qfUTBd3~~W;DZAT%NB?uR3*tmQ5}5pZ^u*S$jZ0 zz6GuyR>dt~-@%4YW~|@%BfT$Z@g8;#!fDha&Nb5@eTxxhJgcWG6H}pp@o%xG=h2IY zav;Bj{Z{_uN!$xt;wN=b9B$PrlJQgEo0xavf46Z9+wGdH&$5#S;Z(i&49u*Fkle!? z7JY*Ojg2V%;{tb#41kq}Bd{Z}iJq(y!CeJ0KAkV7Hlz;LPAJ68HB!X*?PgH8tu67+ zB_8vIAIHs5?)4&($Lw$jY>C6;y#oEbp$7JTkrO7kba88DErUO2^l_noElqk;2%gMG zVVZrB>OWt}cf8jU9*+nhxY`j4o^EG~dkLLkjI~+v%|# z(V&!BjE1?l=>F$9&^f3Jll{jL%V}HS7#=_;k4ow`xDrl(ufh*c2GVN(L;Nt$1A^3( zEOKZv^Mzhp7h?d<+ft3#r(g8uo=_SyzD zVYHGi*)s76JRaeRIdX+`Xmbxp75AZj+D)B^1_fU8oRnbL^N6SqeF-|G z7b^cV!-b~*ad3G8oc3QY;fFsjGv#-`V)(41N-pHLk(pNpNc#bWGJ3ZX5^ zWzg?SIn&(Rx!Rvj#4y-Gyt#S+-StJ5|5d==kG2IOj&a=%{n;i(OEc$jB?#`w#^KHb ziS(fF8eWcf71k`@L0(792a)1xd>~a%HyY-G&5l}3J2QcP(PO%RTorc7Od;!6Ig#`I zEyOK%8bu#w4dQPa_Tru5bGi#;eBmM6qtW`TL(ZKQf$Q`xOuKtfq@w=~V&E@M*=tYo zKA(d$hX`CYB7?U1Wq}E)K*1%Hd!xIAB;3)IXne1d8K>%>fQlT_K}sI5Ai)BMX9aO# z>vx0g1x@@hxRM@>Q|4pVvb|UH0h}oEJ`~@L$Fo`j{W`D#2D|lP(xty#)KzP8alfs2 z%dCZTKl9E_y;Y8%4h7Nl7I&BtYJqtdV!6J6laQvf89kZbQonmKfAyWMaA|}WNxj6n zl^$AQ&!`%@>T@9^SM=d=@tgQ7vx-6XQ4=mZ>`5XLtjW(nTk(~fpG0cqb+B-35vpaZ zlH8(kyAN#Y$8s4%7(NeL&dc6)66$Q85xFrt;dzZGcD58ymGkGA-Vq@* z)j#9phDE?5y=yq!J%iRI*1+j81*oz91$X1&QmFVnNwPaB*UuLeCb8`gXF2Md&N}le ztt8!jM)(z$o$bVBR#QYrQu86?RuAT?oF>sjFM|8m2;|0P(A($!0b4>BJcCzp-=8=T zb8j<=FD^!^1ipzs;-?7$)$8zq6o&t44WZoUQENc+nkQDP7tl*K2l!Kq{e-8{?%bi5 zufVE`;*WU(%S)EQmc(-Gi+#X#c{-9Wo6N%%%60Kzei;CXDnUAx8IM=(=l|?vX(!ZTa53j+AG#t`JB%P7l{3leOey@|?qr-s0*H>V?_fp*&9?pygDOhU@asro zcix69+GQu^Ee6sfF&%JsEz3<${wq3h*aKRRT4LJ1DsB$P_V`#v?5@#AdS|f~e^<*v z=s2WDww;~^eqe;9=Jj-JTq->Fs+V{(_yKj`wxb8fHEw2JdpjcCeNfyywM`V$%zX0C z8ty>6fIAyTVCjt}dStc; zly6gXzCo$ex>i^|p%Np~<;eG}&CoYwIlA9w9T&sdHk`H@YHVC28uBv?Qd8qFm%W=r zb2DK%w%}Z)GH(B(Wf1sHAN>+)Y4^@T_%@&zm%hD78(o@VrQnBm-wvzdeQHQ6w-UhJFPPIpgw2Sx?O75=MSeJ5Kb=6V&3g@%zNyB8S?4$F!Rpw^=9Z{F2fD{ zrwT5Nlm8!9PqY$)&&dY#?WaSlnRZ}NE+_Oo-ArB{aDq`mo;ZARA)RjW2eP{RaLTTm zIb#hI;5ePg2SC2e7EPY z=(^Pk-Z$7%c;%5pR?a^M(^Dd_sqH)MyqyWQUn@}bUnsZq(IRqLS5wlndPAHF2lEmz zs6 z(BxYDZdJ=oEU_j-bPkH&_AI2MXElN>mf~k2fWBDk4o`b6&}cy{_qh55m`~V(p<|2b z1+~SznwFiAr|3m;@9Ds@QPz03l67&6%m%A6#)o%4kN3Xx4SY|QV&z2_lJUx#j2(PX zl0E#{Tno<6SvKnaO76Ep7^!{XBjGnrM)^SKXmeE2+C#M?mhx_24-0`UPl&<69Z+HF zg+9(&w;G$^~}PnKwT_Mtwo zzTFI`TFcS?Wg5_BXpPWXMem&X3U%dOIJ{_zNK1z8*jn}?Q9Dhhd0c=)TGw!lGV_q% zmFBzMWQBV(*Ko&b50mAa%_aD}REE7z7k%4eWXe>E>b#9Vt*U{x_7~WEtD1Z@AqL4wIcK=HkY;(^z&}h7a7z z-ohp4>F7!yNMpH@ZQGK#-B+G~T)$H0VS7MRXS2`Mayh~N>p0SA;l!I<^c1?)+&KS4O4 zU4o+`BIwh^Ur_%*T8QeLL#DD@`r&?iaeLN4s!4ytYQ;MAa_AE!Yxm>zE1K~cXHUG? z_hn|SIa)9HNKbcY^1>_!!OMpy_7+p&IMeP2d)CvXwaIXERs&`k%%d%=Z{KMw>oc^{ zCDBo~WQNZFk#yYwHNI`Qr9}45rbJeDq~7O#?LsoMBkhGm_KY-*GTQbmq@vP!-uu-q zX`oVR??KC|^gZAC{pSx(I_Essdq3BGjr~I4z&6R!76pF%^Cq1CH;mYCb%j@9W*GbD zHeLHR3?A;S!Z7bu#GvW~#F7A%PtT@#j|<@Useiac){i^AychgjHWa&aztbx}-a+^i z0ktntn#9$@-C4zW{+bL~-)02G7Z;;eMHT&P>k3CISm%!M9LcD_Fwopsg|D_eBlln2 zf@5*-q_}-H>m%G_S-9uqOSlc(0`Oa~0tXDQqunP8fK(LYi#=DV);(LkhRwj%c~42Z z=>d5D$rxv@D5bOQUBQH9dL&y+)w^FFPW%lUgljfG={J=~m^rotH%<$oV?1-9(6t>; z_EII=x{P2>z&@P!y^`)vEQg&e7kb>+J`{BA_%KUTaYk1TG1zg5>A@VC#_1!?zU&Hz znWof&%5iZW!=Z7gKJHYirh9VU!D7mAW9=e3eqAO+BsSxxfgEY(4uV(Fc_{~Sy1om> zvfkCA>34Nk_}9UmvJ&k3@H$Zld;yWa0$>`(;>Fp=?SD6cz z?|RYVqjLO`*gAadT_Ab9#}%F|G{>i_nz^IHz2HwoEbbe|R7&r1;mM^Q;_jK%+_uFt zz;mI#bjEhu{TXH%)Zp0kQS`vdJeb^6h|$MJkqOQAtW(EKXsxf4?74b@e|pMZOl$t9 zckZeyIJlW30Xas$$yC?ULC^i+JPt7UIY&xkU5!McAMnfcoX^c{Di(?vz$C zeeW%9JT z5AwbkrkC>N9@tNo;5&b$Sdj-C#x>x~`}N$?Bi2Obtb-BnBn`GrC3gDMQXE<;v4TMRcnt#HljYT9=9GaPFBCCyeX zjVXm*v>m56xsWX?R%Cf!dtt)9WXbx_8c<_dNiK_*a-}P8lkcUMg)-)${>$EzMegRf zCwvD5k1#lTy$XHjs}a2!n_gVi*;h#r{+ZcbT5>2(QH{zjq+7bIhcCh$!<7riLe>i#Jl0aK=-i zIW9PJn{gK_K|S;W?v5{{=?C`kHJ9DRPQ7!Swel;_ekWkb2c+tbtzZ!L8*gVvaK=v^ zNY8g>ECzZKeY#qf-xFAaeXHE5a-l15JuNVyFoFAg@hJo?VV-pH0j-Pr02?3u!=LU$ z2{$?ql*B?DbB-qlOAnClr4~}$b~-wMw=R$qttOx6o(z6RvS^Sn;&LNB9ux+i&)B_q z@-q72LmCvU>cpv2b&2oUeW34u0UgYW=sd&EV7;&g7cLsXovF%)Q7kjJd>%q@wdZa=_dm_6Prut{THiAGeqI)hHE$b_w~75Gep<*9nu z5L2eh{rRy?GSEhuU$md;&Fmvd$zE4DYhr;l&VF=iL@2zDs=^UQtH?qB<80OnK#e=u z^w_bl@Ui|M()8P$RyB8eBr*jaL=k?e~me(M`BHFb<6`igdvFVsJhnCl0M`=7w#a57j{{ zFeIy%W_0DliUyWlP;-TDD{Th7$+dWO!A#;pTXBYaDGk2j3d8f*|9|i_JwY@g zI$rKVh}u=k#lL1*4Xg(|CYU~+kOjva+ZgT*ClYlda4;~#apjeiKUD^EJ8DqNyAPc) ztsHb$72u3e1JdWp6{u}Jhw}r!(R&B`@sY)?xGCW>S7bR7tWwuvzvOy4*zg@3NMgB& zev7DoR|Z5jGk@+~JyN>z0C+69fc{m5w8!ZVc(PSi{5|)Mu7iF992#1Ij`MuUvgR=O z;T(kPG;*lh4l5`Ff9!gaMa%v6@~fA4ic6DJ$*PPWMD?8tYD{XT)0NX9lli&6h5J&j z*H5@Sv6LTKvKo9^ai`7txXHlAiTSe851arJr$tXsz;uP2I6r zQu3Y_=H^1ar=s|GO%2y}bvmpq)n}fjdaBC!ii7gCsFFO2s>M}Y3QwAcXKl4V6T$uln1eKr~QWPy~gc8yAd!T00Qj1%ar00o{SKcqXv z-T_--)n9F#zO<57J`07R!>UnncbMLTQTL$Ykpw@uB0byV3z*%jlg`_A9acpD#eN~w zcrHB-)j$>%BRAQd=6Lqt<$pF~;zb~CLC3&Hc@s9QD5i76LSeFMHKw1GAx~p<-~rp$ zxOrC7!UD$UjB7(f{(0QFyCpDg`A?k1mW+$CtVr4U{X%0xiX<|yLFz}#ShSK09dev3 zJZLIZ<}l4kNGMb)RU=hZBlmW1Vjb=-QV!&Ty&b>my_yA1=(0x`TIix%~+ zhnBK3+?4v7li4~SX3bE?-i{5_PEm<(_hkE&C+BH?)J*u1Va0L)s%YQs$#8__4_97R zlQ>RGhlGbsDF4NtIB9#sc7;GZ`aX-U-`WmtCY|W@jBpX-9mugy=F%PF`;tP~FeDk} zwUAa?_2l*Is?q4)2;%f+1-KSpz`f@SX_-6WTl?)74G-?-BKy6BV?7Xi9!1)_Z##?{ z)QQ(^GGRy0rg8$E$%2CR?L_yK)A zBpqHIWSJ^5Ly6(J0=W3-2j&#i#0L0(hW;@H*teOGpAPoSgK91)FA^omEVEih^*dHa z+jGA+#gaXG!P0%=0fwak$E#VVz%shOAqA?04y;(bm{hMag}BcbaQx^Z>IaUzwy}#i z-SP$Zgi(;E|{%tx>P zgG;|flHtRT!@)}d_{J`q#vT3&+1t92Z@JBxTvvvHpN2~LYDq>cbkF<`pCigzVUZ2{ zSu#o_*~ti8<8;v-s#%|1Z{Fr)1FE~fksN5Q!;rTcG``ep_73_!b8QU=LPAQ$VydOWXkI?h`Y(yl%9)fZ4Rr=?C zIP74V8&m9psaDJ<_+j-ILo`Q`M+?@$t5P#5?{Uq&6iV;ZV&YMT!*j|Yw4?x&P8tyH z7;i`#bslAVexpvkhw?)lWyH;wuW+m1t3p2qL#amY<--_&y>%Fwu#m>|FNSCO@?!s$ zYYAxWhaWdC;A#oGKkoYjuQg>wBZm;(!Adny;#P`V z*sV{MA#2{)5%Yl-!sWTWsPS4EK6_{#o?4MF`Nz2N$I&(Ts`daWdf)+H&%eW$)$i%* z`fSLwQxG3_mvbkYr$K{{fz&g2V{8s64XZ`v&7)|*k?#=I=Qlc@nL!RPJ^YA!Y<~V+ zD_J%{g&))O9ary-ClC4wa6U>#{D0qi_!=Gl&m0?Ze7~<`@D3L+=nTN#?D?XtUI3e0 zno-Utm^1g7O^jN#rCN^6v{XnKmw-7+0u7q3z;D-R#$tuRWLm$i@HlHB8tl($g~jS_uhpElPDHDA$@C50zK~jLgLlVjjXmNh8rA(2a)rr_2w#ATgAHb2D;Ob zOy-Z9*oK>3cyeR@F}N^iGoJP>rb%9lKxe5nE+17*ih;+JnLG128>~lSf zs-9$7BA070w?T^wdS*|`yDg+1Kz;c_NP3-&#l4U&-`$g6f3g+>R8-0AB9=9@%mr0$ z7gC*HCcF>lDfSt8p6h}aF!mH;=tiVlTHB#D{vS^1e!~?f*^(zy%!R6#>Qt6#^NjMV z*}cP!KD@8UAHP(EL$j8UnAMM=;(95Tk9j~{{jy-UpS)NSt4j85VtNCO7TkHYHa7k7 zXOLZAglk>^@qJ@Uaz>a7XO5wyn>|`6{|3 zAOrYlS#hx=5Q77I!F7d;R7ZEd?GW#weMx+8_=@{t+YGgX|6$k|Lraaj!qcGT07y*r4nW%HVG-Hi}Ey-(jgIh8VEDtb^PB}aQ z5_+z|wY%%+%FPL|*Rd9V$7#}?k3NE#X%)7f&?BC8)?|t6At}a2J(A@YukOO0{WbN* z=l0|ml{0-sb|kSs8VzHw2BYtW92%o=6f9=3ncpCrE?i>GzY25{m6lB+ldkpz%WK1= z^YGq1G4N%Oh?yM{YJ8_02C=Ty!DqX;UUS!hMw1?vOsb|+1A6i0K25kc|BWPV$qi6S zibH2jk^0qDLg=ubqD#eJPDXJa(2kXu(O660?#YGRZ6z2p?+Wb-t%t=X%m-aIl{|gp z09rNM@!Z!^nl96iuUPaG3ztReMI1CDX8Sw^W&LaP^O;xB_e=>c9vMuVhO^9PJq0oT zkQ#|OZ3s_Zo3k8%O1kZKF`Ut5*!y0EewtqdiI?+m!;2LpW}G+Vvfd??%p!WPYap+A zs0#=8@ZtuHR)txE)}f_*1HI7|4TBfg*8&Il({TZ{BMRy9 z+6q{a+=MUEuIt`jP!9dAzhTm$E9A)LP_S4W%)0!tX{C8@e&a6IVYIlEQ`uqx(NhC( z)rTzF^LZ0_d9;sIFPCkT0twB`x7grAmt@t$%1)-IIwD72v1jG8ofd*Zxia;S{0F(6 zwV1p;PqMwZFTaX;3KsM_O?;Z%!KLvX>mX*i2fwmml2s2ercWi8;xG+N?N;Mf$9no} zZ8mIRn(+VQ?dI4r7C2cP*K=c~Ms~^dtDwbbi(We$vd>qV;P0}I< z&9$Zek(xItumpoYR7ppDQ0DvhStRN_?#+Gm zxC1sWET(D+(%Ej=FoStEZaH9u@$n)u6e&C2H z9Qh+0g}C)wuq(Hi?x{24wIV&m1!4eMx_&%__FRolG09ZRC~w2yr=>;37#Bg-PWW6XQ(#4uCr zqfQTw{Rfo?YcVC&jc#Nf3a|AwIKyozX`K5Ao(rYeJNrKMV7{<_J__R0LnBFPQa-3p zXu*-0HL>vqIWXF?5QpdzQX0cDlc~8dYa>eHI~92K&8(|y*gqrxyZr(vFaFASWkbf%pfoN$xC$_S;9L={J`ek zDSmWkVFhFdc4Pk?lgW@f)*@DG7h3gtj6b0YUq8Pc(|Nai}fcpY1`Ngc(R7^d)X|9|A#gCzKnI&*x^2&+wkjGpqJ{(-o=T zz+p`R%JiN{5?kz{uVjZ5hx5<$;|+3Is^Fn0y)U2Fll8m3h3vNL^vn8};2Kzh^MoLp z_c;f?u`IZv52MKLhilng+XCBCE2;AA61abcb=*JhLl>SY1|7pfR6n3kdT#N8uc7Dh zpt>@pVTt z=Q6<@hMf+;%os8XLR$q7{CABeShQ0V|!Gu<7GR>k4;SMTY9m03`-x`()GaRs+GY$}8@ z&7M5l3p=pf5?6Mg(tJIVTIH0$WVVBNq@+#)+^k65TyrT7zt-=;_Xzrlksr_MO+VM0 z-wG`_;$=LU`Y0M|PIcmqKK2rW7>-xcJtUseDkXN4FMv^MAUd4Rq8f(^z%!~Hm#W<1 zN)oilyq625Sw^3~C&T&yi8$^$r7N3z^Mek{ip6h7ljYr8pyaX+CIwg0P2J0Q`}-Hg zD}k%HnMolq<|oB$<{QmpI^l;}zp$5YEBA7sHOVP)62|YF&vd7i;89r0wD<1x?przD zsjwM)a~wIPauoCz8{>fTVw%6wh~H`CCF&~$lBD6|Kxj6=yrIc-|#AABCC ztNRg-Dc2yx9VN3?Sd+iQ4h!@4rc3VbSws|VrwO9`HG0aR9%dV)qp5{JM+dIuEzfv} zXZj=(y)on9&2Iw?m3d5qN80oK)mf*NRUmh~;s!iB6NIN3BMMt;!GL+g&lyE)qak?{4fm$_pm{i`<3+3@f4W3Nk)A5L_=btSO(5bisFzw7s3tpgfH!ZSg4#u zZ=KD92HSGH;!cyq_@jvW! z58K5s*;8z5ILG-P3WZW`fs?)omyf|CfEOmz3T>cf!vrn%zNTS zGeD6qm{5zu9hjd^<{{jVFGUl}`}B%qCfFw^i08SHq^4g!^j2;~uC*rCKdlXhU6T=~ zxb7xat8B>TMhhV$1SNYs6!>}NNY zlq%VfJ!OZ5sX~7``u-1ap4*7$D>@~QecYhp{(hXBnnoWo4^FtkYK%3hp|cOYhx{FE z?p4&J`<8wH?N60hOLR$1pe-r)a27U~{+9H4ugtG0|A&g1Z^%-`x3D597=un{Qx|n3 ze)B>vanYEcExWjxyZ@yllYg?4y`TXImhx9w$su&I0+eMszSVHxuRDyqbDRxYf zA+P!=^G9Tx(BycOqQ6i6{l?_Y?cPE8~Yr;iZFpZkREL+d1)UiRUAdi}(ytRb;8F_gR?+$8mbEYf@d zeV89D)+&gOWIE@5>lH<@|0HrWeGNQPv6ONPy$g!rYFYz6|JjF*Sy==J9~PkUxK(8L zcqgK1}0YokN3c5F7?czFo_ zM357;2DfsvJoiDKcL0uL=WfB*2GVNYSIY5f2Pc9`dohN|`cQ+a7Fg%Za@ck&5od2} z^6rzRke8%PzrX4P-l`r`mGdOLsUm+^z8rjcx@#0O)rIS`7B$Hb+TMq!MbL=Erd4xT1kwaJiqL68wTl| z(fh}`=Q7(`u=Yqi*){hq)a_(`|Mhl~TkAMJ-q}eEi7X{xUi*_Hl+k+qR;&dI_E8xQ>ra^%7@I3M9H~$3lWR^QLtr(U3zQ;mx5x zsMa1DSDWwwphpc_w>Xomn^weO_z~g4<#fqXR~g=DYBzRY+`;uU*CF9PGlaNR*XdHz zI_S}oj;(qE>oi=;?{M%GI|>qs)A+GqG<`J&MLnV+?@f8NAFg8c+?!l2>z?*64?^Do zS@c;=DJ*3@I62c_aQ3|qler7bgkL`6snI)mUY*_P{N>Kkwog;xptTK7JHXzP$W*BB zEhlpOr$|M))fdX}@?#ge;kz<_ctJBN+Ut|kzwR^c zs|>$SxlcFDD1vn6wYj^dDR%g_9Js|aoChL+{9-=1ovW;bm_edsIPJk(%>IK8eVn)f zE2GH|*}Kwx+(C!OOb=Ow%Hcfqy|sYfchyD=pA$xGx9tX*05ka z*M5olBbLjED{O9%+MOY=U}i9S4rBA}?gp@(TZm7hW4Y%G_2BBpNz$IILl2Glonw4O z`MCp0xL-PXULr5u$0_ZM0lV?cCwuZX9am5Yqo@8wM`0rQG|h%|R~;2}qX*D;_ACos zXv9$2PDuyzq7IEcfa`XqQTV---w}LCbh6n(>W7a7cg;08#J`3v*^MwItQM_prqK9H zUqOXwRE$3BGaaBcdH(*W(EaMSq?PZ6rl5a#TYZY2{?s=R*&2eS{@HZ<>NWfeOHXlL zP%BY;JO;X-t;TC9m#CZhKEAAvoA`H<8ma!R2z&qiH|rMOd;@(Ky+@<@5;~}(9BNLK zqv28+;ymgw`F`A7aBo$nHWw86txOx{*C#>}9Csaj9!qdJmNp z*?MF#W@9Cv}ox=tS}|%>?B=wUP#FHa|!FM!V_= zJdYGb^e)Lm~Dn>x1YULWhS27&zZv^T$%N-+ceOeM^Uh= zFUy|lyO7Q_&V&bsod`8ch}CmjxV-zKR4)<6IOH#FKQQj;b=~JTnNRR^5f&PIk+!kV zK+P=#_f%%l*>e>6<}D4lFN^u3*O~%Xz-HZ1S(I$-!>2r$FG@@kxT}HnWYV*~QoV%j zl>}J3xdi)sxK1Nyx4_A68Bykh5^-a5?_LjUAdkLzYD3c%31s!PC`e^p6^h$zC3-g( z@<;L=#2w8AB$;_Y)&&INq+RS>Xfl4|K@+ZW^yk|D%^(A;773n?P4rw{BFy}ph%Ub* z)bZ+f$fPAWy-bN{{@x5G2D-SqsggdwyN(xsdy6|xZsx|Q1jF6{0jr-0bh>T^$ZFN$ zM&n9uW8yG)`FuQN54%@Es&BC0IL8i^#}3L!;?7EHf&h7Sq=8 z>W{p|$>D)yampAloVN!37bjDT_37Zryq~xGJdf*qPz*_JUAQ~@60!Sn6#kBJ!COxX zX!ZHO(3|ZM3?FadZma8%f!AgVGq171eN!#i9{GS;zbTD;IR*lTtdY*Wqpz9rW798- z25)Y1Z|!~I_w-;id!I>7PSt|3SuM7|jO4_=PGoi!)Au@!r*dlY{Qb5nY|1)Ir+?Rk zg|#+#c1tB4q>~2m>*d9Z_cSGU+3e@PUs1g6dx7ZWxPx-yf0!IwmQB^f`F1ZH^n9eYq@e9=!RB==-yPF4kjb>hgTC%SVG7 z{N@?V>lAULr9d+hOQGn@541Ob#w|WzO;nAoh29${(OnfSFoOB24BA}ig6HSp`FL~W zb_iTf(>?Iyn9sWY9_{4k^C})T;-{akWWk?Y5ZHV>B(OGiUuhATZfn4nk*i765gX#X z%SI?3`(Cm}Y=m`vm>=QdHg49Xw`9u6yV4o>N7-YD9K!VW8cS*Nk%j!nmk#2lgqNg5 ze-|{~zKEw%3+bZZLQrDdQNjEPTtNO0c(H=*Ynpt?f(yYg+A$cXMrP7eqZ{Dzxgy*! z;T^XpMHjA)(U9^F5&G-+^|n_;8NEJ4!9R_RnW-Sz9(G8hPO(e*bxy9L@f>4vF>eek z*svBS>eo{DZ~-bV*5Q8lDb$InbSv&OBCA0n4Rehlc)ta%4zHwdrgcH<+J9KHb+X>G zdktXBG=UqJ29sWMqTuhMI~YGPn`U+x@ZjbtK3vpFLU)aUUrB4Eyu{Ao`*`=SZenGK z8u{y>2;$)pQeMJ8DT?{)-{X-%653$h3OP61(8*qzEct$j^!#To%$6uq_4$fCAJ~Xb zW=BYRD_@6AV<}FuMf%)g74Ng!N&IrI~zZGg9i zjp*$=gWUOYkQ^FrCiG9KmROGN$D17KVxEOJdP~BelliJYgn3o%w50Jlw5yil-;6+- zW|RT$_d786i7K(*vKl5nw~}hx-1YKdNUvJ-OYcP=tjmY*lCP*)y__6s+D|qInhNz3 z;v}Pc4d9mt$%x|$JQ+R=hm3t2FwD4-X%eD7Jx(@l(+J6oM_MvgqNSJ$T*bdi>&>&;6RW z7raTJ6stq~s_-%E=8H?t#B&RS>d5TD{iIl}yC)t@ua@BWGuP>CmwKqa--&6u3S^5r zd;Si!m1^5Q{^u}xzlWfz?Joq2Mc=hqiPu^ zKQxid?;8m=(H(gBqK(9R`8mj|2*T=#S#-+d3}`WGz#oTibE5-hk~b!crCs5*LlPmy zGzq7Dkx;MuO_1YQip3w4$TRoNz=Iyf&a9#(Q-h$fPQVmffksEMzLh$8F@x~q`E#HWM~+cO3>X|BapcarI? zeQe%t?ZogsFXCQmrNigbwRoo6nb@Q{!W<`1gqffkGma)MRp6)HsKYH=&Qsk`gu+ps_-Wfj$;5&zNNDTEA+L{< zTs3$2Fgh4pLNaNgc_-{MQ4;3|>2n)n^hibrCp5SU^x3*Epy`~-y1FR+Q*;)RH?Tg7 z79Z~2k3Rh3cx};Y+7xbh-czXE`JU~t1iI6@6#ji^My2>?oI|)ZQPi^)GKXoDOWI(lyu4`awue|o z+mM*$c0yE-c*)v3b+G+O5!P%s=H}|YC3E)NlX~%X6)og%HXjgMT3?YR%XWh0kBj&@ zvXHI~IK=NNbQd37jo=iMn_$5}8L@u0FPZQm2-5R{arT)^>anaAvP=rG=~xUmVzn-u zEYgtf)ZABGA^mP83k5Pu^$b>~k*2l(Vd>J7Z(*B4DH>$mqSfjn2ghb zO|dIcZ(uF0xBCvqWt;IA{F8j(_VZhQ?-iX5zY^bBtXF8gqg2mu%>D|Qm60rXwFT)7 zyEhh2d@w|tggQDwOMq#Xb@q5yJBS!_~ptx4;p33k*@Iq<^M#f=o^q4k^&k zTgEg|pO{w1Mk|;&$47#y)*V#&l0}bw^(Hnl$-f5CwHU@3A#0j^3PI247#4GtR1;TNUg`Mlfy3zGda$~iVQfu6KmJq1KlI=CR!{qb7nvrPENt75 zPE|6Wf%EcG^gA0!Q|4yC`88d5S$8CXW&`jnvc^8lY_y|a9z11p$an8v^n+nOyVn#V z@moQP=Q$9W>!yN*Mq++Cd?C4_Pysi5^G7hZ$GJT`n&9Vu)bb`iG8or^Cr2F@|b1) zCA4r?Uf7WJRrXR}UI**7?>F-Y=Kjr>-0MCI*)uJ%{$4$IM)V?6T9bsRyXlg&1KRwd zF9*aIA6Ju0?HcgcXe~A@sH3Wt>9G4}J^F4PNr&Cegi)JIF~n*ldC+A^x;1Tu*2DD@ zx}XELv*CG z?)>6-IOdgv+c!(7KWT)qQKeYsq(oACYz8u(!_LiBRD9`8zL69mWs0wE&89$@w+wOh zB7vSbZN`_XUl1ch&Jg4CLt*C43FtPciH@391ar06tZVE_v+p#)WW{oPRj5Vk+E`DS z+YXEnN@z;BH;Gu1B4~Xs(7UTT7cQ&Y;{I8cbTQL1UFh{2AD?&@r)iu8>O-5+R^tqb zHgN_=jf-g7R6uJI96k z>{YmSt+nub+9iCkvXEZwZOZR*bQjwnvpnR!KA`j?7_XRR(q6M`AaF-Ly0t}esW!|j z7iuOXjvhy=%e$fWLIpOLouVC9US!6RBq8Jnp`vjHL>%qHVh?8$>Fx#|p27IxN+#8a z{|uX1_Gv70d^z`J`E(D66nodM{S1mtsp!b|FY3(mqQ|m2Gtq~OW#570>^m^^&jfni zK!xAhx`Bu4SpJQqI)YChBM9H zoJ;h<7KY~xPyCr2a&NL1G4Dtc{!Y0f`IR?^d8TZ{C3{_o#>8CcW?51y*Xv?Gnty_y z2P!eTU@5WtZ9`^gIS5|$@sifiMwm3F3?-G@xw@w;Be%zWDJGxy@FMPyk_7!38j^M9 zI=o4glQ>c@f}GLZ0Wk|N;RTOEYVBACQ-j;EQPGPO{R;%ENo-b`mPw2BYe4-U<1p97 za4vzYhjIU8>3plE<4w3TDMGI5QoRtRRI*sH2d-#or6ws+u;z3rzB+h|+K#D#^$XdZ zLTv^~pSB48F>lw6Rkd`mRTbE})*%e|DQUiE$LA`UiZ6%e6E!m*Xdmo?nwyL0nN&}5 z+9OGj7zXOe{1^j1CPq>p$J&rMh*hY=!@85H_@14w$_6}UNJ!GG%^<(u65Dht>4P7g zFg!^{wAemHkB+N@4?;1jvM%DYuOi^F>RmR6XHh=FlMFhOB&hppa-r|`gJwt&>SSlq zJqauM9fe24QDX;^pUyqtp0lbHlgIRogvtx?sQMs|YGjncDcLGC*(E~^$_|j;oQ3eQ zrYGI=T!H^Qz6p;ncrDTH@+5EnBnh(nu5#O$2Y;i2fR#o_=X_hjmsA`Ok4)Q6Mts!* zbGll}QAF2g!rkIBoF?Z@tuu4sb9DiJeKn341v-$?lg)(Tv#KNx>Z|xYK6AyrUt~G? z*`B0)Qj&1%cPj1lc?yMdOEIfoAT>Ri0fr{sIBVD_@^{W^m_u!G$_=KAd;0}C*!-h0 zrxzV_?F&RVf5lnCGSV=_o~)POC!~*lCs`O`!1wIGK>WHZncL*zNvr~r1VL#x-JcQ$ zJ;W-kK0b%)?ahS01u|k0>&Myh!V(P1E}~U>0iCZ`2r6g41Yqm52w@Qd{~3BzQ_YCATEEZi^TX{*pRJ^z5(=_Zyvo-66xrpV8@ z-i(?{4iSyBp5(%fB;j##n#7NJ4PGB$=lYq**=cCNs+hG{t5Qc{K{|Ac4cKfqlGdIs zhxul|utimqNV=>@m}oD}wfOk<25)J6MLafZ2xomunZIEE3w{5@6B#8>val{u(4N0A zZlZq}lwYXAAu&dzrREIO*af5ci%fbfvH*;t|6$?&`*SlTD`M>Zbb$|R$) znuLz>se}hb1sHrvp6Hlvg3vGj;r6zEUW_YA7V;+h=xVJDgFVBlaN+g@QgJf?UOq*P zQx#~Ib|%PLHsj7UbzFa~p>T5jMCqLD=UWIj2A87o0arS1Tm#^QG92$clT6D!49T@S zF@9Ys?Um?B!hR(Q@2m3l4mr#L)k<5O!#IJA>=dZ=V?86P&*S9#9$~t&i#Xb&fc^b; za7zA*zA2ly5r=h1>ZLit=cT@M*}N(!YR|x$iIjGn@FaJyBne|`dvR|ku7Rc2mvHBp zLYjSQ51+N)UDVXQ#eLa$9gG%)pw`$-`sGYDq-i(cRmCXoyq5#%urU*+?;T5B>gD)S zvwAd3J4dfh@gyCpNdlQj=;m`_Flk>EmYp3e`Q7jV!bAU|YQLjoSM6o!EDy#*mYKBl z!e^L1s|Gheo5l@CT{1ryge2yF3}%=)*E$W&?n!7s)){ymWP$G<_;5W}d6FF~l7#YJ z6KMa0FwlKhg)^pR>m8i%1nP#yV^ln)JMNT#?eaF9ZU3B;e_>6o9C46lTo|XeLi^EL zjETQQM--ib?XNBH)B(z=>v)ocIZ1-U5^ss4br=LLt-{<~1@fBtFD|hR$>yWAu?M3w z!QyWjUQy>s3d_H}R=QuBalsqafwM&k?mfDdJKNwvzQ!jCeN`q&a@g;l%6|8AK9gCF z*EVoidI@zD3#nqQ3%`%}i*kGtmk?10RyyoX@$NbaTpI|s=R@$%ua7jkv>Mh8{DyC? z#c)?=F9w}iQ;_s(pt1~O`L<-?-_Rv`S4N}|1C#$Se8#;5=ws=ECs~$)bGip9 z3QiJyI|B5+#Ek)?`|EL)VFMjt`VP`H>d>@EgO({5!P$5jQDOf&BC*{B!*r}Lbwwqe zGoTATNMyxXDw=vSPz$4vm*BL^LFB{t*U;^K7biF}&yzx?a6AUaozu=QgZ#DI~m@XD3s`? z(xrY+;H-Not|<$kR~+&o-bP6rGgzI>?ri|m2ioDudDWCF`wWf?>(F;*FRJhO1wL&n z#1`Y_L{8D3=z5w7a0&C=X-@GQgI`148tl&Xjv?mHixRcI#9txw|tMHNL92zzt z6|7%(pd|tF_^}1t*S&=Bwt)8bDS$F3);)Uas&2>HTIQMkj>kK05<2-Ycuu>ETnC%4 zJ`Ln&H7SV2yIVM0Ll5$2cam`NmORb#3kBtGRj5*Nm~*JCCL8SfOLu=CtOST+y2sVz z8dVA|g|0!ruvArsTs>+-R<|Dz-UuqxqTg?rsq-DbU(c1K&hN>uy8ja=+d7lM5$;G^118gTY2{2JSh*>mr6Ej_1`2Pbub=#2nAj%?$b8d9Wd?Be>LrX$VY7M=;oX}Y z#BcuRxZ)?*z%?KQNBsUs#Z%2tul5@Yy(L`B7d!HGx0#TaFoq5~Da)rEu0vKpMcV^B zhUd57J*fNvL%lPy6SGLZVhR zo>I!zd%5N@=$(saIkA*F$(O(iqjvlk@SL-bwI;Q*4hR7ylj*JOW|+5tX(Pv7qL1u) z@N&1C(KmlN3Dfi-@l%rolX5S~#46^g;j0n)_aOf4IU6~;6;(f1#2#Az4Tc|S#Z$h9 zB=4au`KIY8xD_QzqMy}5;I>jU^4rRtzI2Ry$=oXh4!%cSQ`|}PokT(PqPnDaZYT_! zQH|dsCzD6sTR}L@&R}u@4ZLN?cSN{}ZYN)H%_nQYCA=FIU9S_J=m02JzJr!OKGN{Q zO3)80!tATj+~zbL_@tnTKbJSqP5V8_JFg@``zq)i%}*w`J$hiKavSyR6$!)6mEx(A zoAfyIf*A)Zh<3ZClI!~x!bC*_{Bfq1&Z;Ye8&hg=>Dg9ES$Y|m#C*k}8J-km1Vj6%2t0G(Cz+d&}V-)+QCS2vTPN5O*_o|R7LOY{0x)V)T8^J zUi7{J>t@O*#*>LFiTYSuvSFQ>Fe@ik;#(olUp@T;9obp?&AF2gTatwP_jb~a&qBff zUJd@}oEje}?MM_4q!ql^gWUhV1WmNN76Mhnik&hbae}FmCu4NxZoN z-(uU0M;0F>N9Ei}eD{AC9vGqye5xVp{HUc8zZ7up*NFGSRcXr`TfWz&bK=JB;iRXM z6;We-i2uj!PEL-W*VTzh>1XxMs<@MJeUpTd4%%_*EvF&ZBLofpGLEz%A7+n}5&u6| z@66O>&!fe{Y>h@5W+1|z-YMwzC61cDtpbMuOxM?|2T`B65i%_SH4ju#ZlDLrx$qx8 z>reEDt#?G6(Lrg%o6nH8rUSPhYT;5-21C>kH5?|_L|?JbOW|WNeiSa!B|XYO=4=7l z&6q+=mLGQ2_2ND^)s=INQ4&4Q3ScDNgxT2h7 z2vBdp#d*%8VA&zCe034u#eJnWo_4_~U3u}d?k+BWo;8`^WGWO2v2<8rIoL@);ulj1 zweoQ%FEW#a*%rOH87ca(Ao~)U2N%%s{jR~nL3hxp<|ExH+YHtwf6$4=M_q1aJ;G{c z0@rH{{o^IW_qVCTD();z-{?+)*jZk1nWIlG#(+!VA1s(+!f7TI4&DP|s9UsBrs(8$>qSRLQ6R3Tt#hzXFIOR1qWXDlQ z;a=qw`ckPG?hR(U*NKRWl z>)}qE<&%U&2X)B-1!HJCa|w;67f`n7DT@(`6lRNMcX3 z&ZcP>@%GI^`sSw_`Tjde*nBcT&-uYVInX0G7vhRitD`H*V{={=@I9#{5hZPN(^k=Lav3-*y z47@Oft3P22BbEf?X@yMsXFuUpV-JdARUdNizC4%*jl}n6->KECaCq*KfSoz-Xg$j< z*~)b3yH~0ZZRWulI>JJTG*+U@IWqhtwFbNy`aD6}? zd>dvj#pJnZIbb!v9`9Eu(>}~2;GtEB5k*VM_=z@zZ#NSvLSrTKEfn};<63dL>v_(_ zlD$7cj6<{BN!wjsL5LgUItsOEn?)+fh~1dKdLj60jU4svH01Nw zdx+*Mhmf4sO0r?)0I5fB$%{BB3Ms)GJFn8$_E|81`Bld~{muoj_vB0If0*p`r3IFp zY{ammpCtLq6!-<@Eohy1kVHGVk;AW&gpKB@lH-NrA>`s})D5YmaCkn6{))6DENhZmrSdYq^ z+5Aj;St*}sJpRMvw`Nm`!&W`1CpvN#g8AAMJbN&X>P#vJ3w74FWhYNsmTiE)e*m)< zSJCOK-3eAD3+;!m>yDn|2TSuroWT4eLwZ>AiC5f2Z+#cCZ|`6TOI4HVF_x(p{EwvT z@T>9r<830@I~qoa%p`Q5^SR1QB73iBX;PUf?IlSfL<3(m$!I+1IZxDWM@D;3?G!TV zcYfDDa9{P@`@GNRyg%;&t-I@Kd4e}SxS$hWH@A=%kxP-&n=^1a>lcHYq6Dw)>w#7dwTF^#9;Dl;6!%em zZ_=Gw(!P>m1|&_P4ljEUhlz(r**qU%$J zZ7oBHxqQw#;rfFfw9e6viNF33 z+}FG#dP^}D-1z{#4J|~&Cz8?GZh<~&o#8UQ=Ha0(%^-cWj%?0z#rU9%uyfQmvdwEP zTJqcnDGw8I^9lplnvE-j-<~<~$9Dyw1g;F`Oqb&2oWG@XC+0(^e*^h-L5N0wvOp73 z&v0Y!X0mbH2jSa`elp>>HB%mW2Ho*I!ZEG)@iP-2WOO@IJSVr`-6otpIe@>pEgzLx zsDcsId;hu|g}e7z3#TUg^HS?yF!3A8V5m3kBe?I2T-Jnvljs4dyHtSFuhhfp^HsE` z=?$~x_DVQztRbG0@6Pr?yR=2zmOdm{5SoF?!sUpyQ7=xKln8Gp){;>5o48B966D6o z@E^C&MWSMD7??`6Or10*&AA5B<=e>1t-b85jn&Y&yPS4&Y(aisuED`89%Rt49RH#C zkn}{vSv?5OZ=%JG)#&DtCf~eA*GzZiG zcNDq^c{5d@y15Fv?aRnQ<6CIX%>>w58c7bmD8%dJ>F;@|NQ}?-hFZWT+iW{Hvlh6W-b*as$)Sq<7D$Z>>EnkE!FR3?f?plYkuHj5 zEzfwP*VdWbmyoNBac}@wxDgVS&tVaxD-3qE;itIlLf;A&fSbe?abBF}v^@AQwt+3A6wDKWb z=&m7SyTkCckUU_Dr1&iL>F9pxI*8h9CEgnz9{T}`d%lu%LwPLs<^yb1svw_-=%ew8 zrf4b6ZJ2j3nf-dfS$K4XCI2~mfbqNJjkafHa%)B&!2bO);B>Z)w8}2W6BF`4xn7D- zGhT-ph8~AqzdcF%&r&>WLn-W0?Ip3>f^=J-eS&jZ)#TSpKVBJo7u)o})btKAtn4GJd0$%CZSsu-9k4?ue7%um zc_w#tTsHgc?ONfH37))E+xl|cOd(lYI|%Z;c55Hkj>09T*sa+ z_Kau%GQR#IrcusUJHDEAzx+jt|h7nz*R%oS|zWEmXnUYSDj$wT1)L0l_JCl?=X~$g_AU$no`oN157RYtTJO;8HbdfBhG#ZOAVqo?p}O=kMNVx|4`=TR4nSNL&vI zCSJtZybLQOy9&P_ddOdjc+PY`3k0Qnx+C@}z*9WwK0TqGM7(&x6!n{-AC@P$S2@%0 zv9p7qtkou-lh0*)qsJ60s&_DW`1UmT^HhQ#H+Lpmv598x?SDWPeJQ{bo>qcjXg|&H zS$jH#(>(;`ElN;#i}#LjOz; ze%~KE=2m(%SSP+CO^O(sdA|q0-CxP{U6IW2J+vq2n*-OXp@BzBwZKoO1~S6?3T}EJ zB}}{8O%en2(Dx*7R5Dq_ZM_n}zGjVt^DF)N^1lzzk^P_H!=pj6%e5nAb5RLAz59&> zlg%io)B?$zcjUtMi`cC}18^qk7x8wsW)!>Zk-N_k&TH#^{P-RH-xrCvQ+H;ubxXGh zKfU+k!@6>42eAq`s~V79no;nhaFS{=;5bmjp0xt|2+KA=pu?2pk%I6E8zm zwCSieBv0B*PCudd@mV!sFK8oMnO=7GoGRG*u8e%GF+{@^ebAR%BJn(Im7@f^ly{JJ zg?8+C47+}c%v7bG<;r?EJ-dq}MoblauC0Rk z7t4uv?JYD95@2XuBx!Li#8-m6(XPf!PGRm`rr6#bN_U2nbh`q4CP-JfRnM09xT=8u zER%-Y=as~~#PX(i&?r_bu)N>3-*DkX!iys$u>G|ck<^Y9%{NnxscC;7A| zfz8?aQs2zsg_~9h{~oa7{Tz3o3-=em__15a>7*9QN#=sy>w03W z7l7y1*8@Ahizv!3Kysnx=vCtglNYJE@XP4KwS~{>24NIREviC zskMZ89EMf-0@~Rv%MW_1plfAo;Z>;>d8OTmH(xA-`1fDQ#{8jpJJq@u8&`>WX6Zar z)LnIgiZ`G{-VCU^7vg7??JaRbAFxl%x;yUQv z_DwnX+@hXMpJ3hCYoB1((;9M*?sM*skA`2bBFVhp1z20Y6%KtaCH9xzGWM^%kiWW! zGyN=uU+WALu3w|eKQ$6D_DAcH*^x2C=S??0?VJMfS~WziJ`lHbm%_Ht?KS(L|ZMsbKp5Tw#y6I-=aIO9a-#6wY5UGXivU( z#ZlyDuMBrh3`nj{J-)L!9nx-mCF{~A;=44NDDUEB24+?&#xLXh$c@|0Yh!dFP(A2 zp6aH;tCqgJ+M&hB_|QCbqK*-B%TC8ISggt>=M>X$@s36qJXKEy7s;WzC64Gc%}MAE z9D+|6d80vDx^piM(%pGJ6s|a=6Hjf7|9<`gYwuGmZU4cz8I6S*t+T{?z)@$uz_cfI z#5TzjkIbxs$?X*+bk$t+=dJ@Pr04aj)OvPGj2G&fAmZ9id=WsoCd67=i|1r~B^#dP zO7g!vTJr4iQ)c!{Gc=oaskqIZj<=rZgYXOW6tCxemccyAOLC*nLq0$Aq@pK#PisAyu2^CkuO0 z1RESA|b3;J3ziD*fDV14z<)A;Wqb$D(MygedjHEu(nNirg{;2Tw8ZUnAwr6yQUIEs)pX@XUKyRXN zf!^K-a=bVnzjCXA(T}P~N8oE_kqD9ZvS96%Axu#G@HJNv26=0={Hp0dIxA}K3mm)(gDezl0O|0cuemM?aBxMjU zjZ}Q+Vj~28>=kp!Vm|9vxPCxg>+><7_H19i!H&}$?oz2jk z3R5wM%oa-v>l?n4&#p0oJsZ8y%pqCa|M}#W$x+a?yOxYQ6^2JFUoQM4wBUoS{L#oX zeUMvbE%uw7zfk}q>|2QpHx#cfFNZd%R#GZ&geu3Hq4c+=ob%5V_HR-vaFP{dnVlum zG|vmA(|53I{sEl*@-eVU&7@&D&023i0$C5e$ia+Kd~O=mDtP`R&GNyzZIWfMf@-Ao zH(f(ZHbjBV=qNInP=G5ZwnMNx{7KfD$^tzYghS z{=@18e#vnBNeyAs1M$}fd0@G^g-oB^!DOW~uxf+>S#q`o&mYze2VZv)uSuWSp0Rqu zh+=KNA~A{PMR=jls##*b!bVkJSoh77H=lD9U9O)F`s$m-v$1~*0p;soiQcA(*aeq^ z!;xP^wtEgzjNT8+Xm_(yOg;Wx@(W7be$nS}QBeA%2i!dC$f?l@=uU$t^0yOl|Mh66 zd0tb7SUE$oE!+)%NIN0a3H0U1$S+1WpU*|R&Lc5C-*I8V{AD(gsZGUET3s-$zLV^- zQb0+sPotpICfw0zIlNNS3q7e2ap-7}?*9L7g68{lvS&EP(Qc*Sry;|y8uf?aGsZx| zx!Gjpg${hY>JvC#uOs<>RLbkZzK%q`dU zETFlg)+FS4J(hFLfssd~`5{XZ(=69*#AbB?{<)zWst!r;-5fF zywKxySz;a|=JZRDdGectyjEuC%Xz>jl?ak}uK;ggsJEi9pKRK^oay_cgB~^Mi}!so zqRZ}5&oJ(!WxAJHd8lH8GdfLgh!i(1*EM zVyxcX`2_;Qr1;47Jt-%*mB77A-^tTPL)6mm3w%iDGkfVQLFpFtfiL>oXBDpo~ zHk(5SKyc=BI$D)9g#0?$i|0|@k@@9Xa%o8jmYz}xe4iZe=b?cP?9~E^C_^!~toW`1 z21m5hUgIA2TTnR!udg7^hYit~NvBb7Gu5ciPiEyqJkiDBS)BBzFu^_1RCxP)7s(0f zz%wtrq~ApwS^jr6-lJFo^gtYoS{@2Ze9=x zFH>vDip^p8lAV^2`)R=o&iSKtAM`*a$6B0yk#&{s5GS;g`|ITKYnKnO@LCOdE4L0Q z>^4IMPt3V3#i^_t)t|7lDu~5v3#J8oqWNr=c;ENT`7zY0d?hDJmf+u?mJ3H^p5hyW zpVRr}Fhn+Z(Y(Y`?E0w~-p2eO&&FNXl|EDp^4EHZU0Mjbcqg3S(4ty!|Gic3fB=mg7A@{$+^1fEm7PADc z@UTZ0J59Jdd+OMC#hz$d-9LOz)DXe!xl;VG(eY_%k3>-E&`Sh07tv&zsgmvJMP@If z+;Y@sSSCSpZhaW$Xaa*`G7(p?>kdvat%L`I?@3f;D#lTsDDOrV_xXoBlRs5aSW>Wp zH*eEtQepzYr$2(somPMunNH}U-1WpUNA8a+E6}m_D#j%ebg^`jn3Y;Mj+S!JWYc@%*!V&>W=SN?eaavX7g;>Q^)rOY(%$W5|1qAo)gWrMCYh(vNqe2@ zVRT3X8K>ilkB#qyNo)KRl7*sBE#mB2DQUQjEx={m%6Q+e@Fp<3B0>P<(gF ze!8#mq&n3D$Jd||U1!+Fd6D<@JUaGv5K6-&_@bHijO8>NWb*1LcXMAjUeW7`nulj| zDSflpPX`0h!rLNFeafutBcCeaPDTegXw%DH;7VcCKp8P< zGeGjT_UJ;H3Flh(hCOcQiGFO%;zoQ86VzWxf+Hi_NQd!kTz#MbRH)A@Aay+&tFaXp zv{{iE293DMrW%5&PGINuDT3V25?DOHjMyExiO$Ky!2uLa&Nda`gK?fHBsz=RdTK7S zoBFnD6twtV%zI{^yCmGn{fDtZn`plGgiI2epMncIyTKt`lE17o0=b9M4%ZG#&f)n` zEO+BC+_Rz>YZ%8iwR<9WscddwXCM=D_$q2%k;y67zGZXX2!&p{7x`yBhf&Ki4HzF{ zL^=*rjaEz+j5$a%k$(E)l-J(<*jw#xUr8M>$-^$iGYbkQRJRh0j_eV zUV{l0F)ePz#shk1Sb;#!Bpi zv0E+0Gw_vdzahqLfc#2w79@`8hFt9i@eKU3)dR&)JRkI2k>;R#6)C!ixEo1JnAsXGy^+Ns#U4n$HH(vR2-5v@`zj*RSzJ%^V01wz^KvcgZ-?BR{ZC7w6Y^?7k`nN73|DjfJx%uC0yldQN zNR@0NL4;ufXrB1ZAjG9dgyB7o6|nyL2cn*kicfZVpy!I&VjL!asMlk*h%-B&jNQhM z5Z<7eTyUJu#=`?Z??fbdLAz{9cb37c*fuilW&*<+nj^Ojr#N|C6YOBvFygU6)7r#?Am#qnpV=#P8IWb~lhyiX@+73-Av&d!ha)KR$jz4%2=^2l)xt zbJ~dZH+AR0GVgp6H#-$O%x{KUq?|lIBaixyc%szT*_`eRReb0veK)6MaqCY%*A3bq z0lRfF$uMIUyIYq+hW>9-Jn)Q3QC0(+ZcU=JzY`ytR10Q5>q)t#3zoXj4jb}o#Iv#G zc2DFKmCc2G4`4^HxQblQinzI9wE|nS9GDT>Pws0rrl5B@pmy>rarR$>YV$9`sxB{b z?n^1|8a)W=b7-#SPJ1TevNdvjb4)xZulAz&-;>P^-7=fqOaIPV`gi^xt6#m`3d8q# zlfyx!*qIy?2Bi4%_KV_}MbB?SW5PdtF5TV?i#N2Ax>+34{?-=h)zH3`;Hh}c1y3}m zI)_tTAQY@t3qUVgGP%y_&vEd%XW%YTMkqwynMbxYH(d_UoP$X?bBIY#WZ4o7~=6nT-7!``T<6_`V zZ#21hu>c>n_do?s6pJW6@BfebEKI1+0!d&zWSH=NjuyXN^*ysNR00Mgri-~{x8i5O z)Mk?B0V((t&8f?hk>VxGXwH(h1!_5M&AAxMV?OgQ_|rLXpJP0$mg|Ak$K-I97Xz6O zo|HS-kjYIO^_C5r8V8Ov4?nIqhuK&<7x=KPq5tBJWOBhmFP1Heg}pJ2 z#Qd5(niwtwPd6JNgn@PR|KteHfYw{fP%i6qAAx-aaI*+tbSw* zlv3@q$_q=z+0+9)&Hjhg6X*M*Rbw-`e4~l%sTZ*z??$`rG!`HO>eC-de>2r`rTCX4 z&EGcoK^FYDrpsM<4_BVn5s4r_l+^J6hR%#8Y7P0c>(B$Gd*yJBdD7TOiQ>NrET`PEdjaH7-s$+FZ;U3^1>WpdmiVN4_Be@1s*8#L=JZt<*<|G15n*Y%6aaN7WC~_p?Rvtr0!)4=Jv5r z#I%xQ))VkE-7;wZ{g*fv&P9)fd%2=4|SabqzpL=a=*92=*}8aP#=R1 zI(s0^_H40kxsmcgwziqvwQY-;g5{2&F)5PxZYsoYX0I1Y>~-Wf`%XnS4ymKZ4ItKF z?DI?klgu2lK|U47zWojxAO9xCxucQ)err^`(1g1$C5yQi9_Wp34yQ)%6o0PxqXkzp zx!wA-*WUC7WY2g(;MN}{eEa^ZU(o={#R}cE`_Q8W zZm@4pBw2Q%0FTzO75cyNBG^}LJw4YGKUMSQpG9tRQnp6!KszT>werE3;+FTAjcBcd`2UXy5k0#j}+JSkGT6iJdL}b-mvEHXP82h%CxTt8M3r!wK-zP`xJy9PU zfJW~TaSs}61g|D#!zt2FvSS)jmcPk^iN8hBw*ZQi>1KoUZ*Ze~>&s zQ|9sgQ|N=oF`7np509MciN+V_a62E*W{ofUBau7RT|ZG|o| zJN$SRyErCuLLuB6)lH&eJ<&)}2(%VQl93Aen5}7q%+swT?mlK(cq^24=Q!s+X9{ll z;(>&xbGd2jgo248szpDa$&K5Th+Ee^1zCzkIfriGQEA0+%ukM&@Ta?&;w4}{(@5;^ zp0=+X7WsCO+}XWs%GGi>)LTP#Tr)zhEmlaFOMlzLU$e&-c%Vz}Isdd7w2O4|AG&kb z--qi*#)9$ZMl$JwD)x@Zf{E6@NWOzUYQJa*J5Jb;oKFonFs~fgY28Ho=w!iV`4Z^0 zs3eybg(AtH&mij5Lo&s<08f&mcy%C0tYLOt>4(l1XK=UY4YFru#{!mbA}QW(jG}}D z43$?F^UqPT&tT>*5h=Dv!3tyAz^O}u*U%k~(k56S6G>ZfZbrnFAMk5+2T6!~#%`M9 zf%Zq|aFKz5Oz$K=l$Jt2Up}2pZHNKmtVZ(Wd=4`tZw@5nZ6&j6n{nCR4EQ~viLlH4 z@w~ZB5PJI$5d|+nJ7$`rJ=1MCg_34=%4lg}iOC;gkrgYL7T|z(o2PK9uE{tx&<~xU zIaq=a=2njn+vY-(8}*x%55<9NKf(8-E#z_cCiG2; zX8UZi=6Y_jY>;8F@Wx;OFF||lug1{t7w2*rhY#WYK40YXDTBMqPhjP!KjJy%VTAAI zBS}hbStWRr*F7cp?yyfV%>SoY&n#H*07BiP$?YfkID3Bsj8d;4Z+mz~&&dPnTIGuU zgPI@w&>=;tADgmO@Z?<;+Wlf2X*cM>4>OXW4%Lzh=c~At)PNK18kT=AgQB`tLkKYx z^BYn{jWAS!W)J?%XVpTRAzQDS^qTKQJzG3b_o7^GR!|N*6Z@fU)aQHSag?A_Ru#&m zc9KI`t@ws@8a&8qB}4X2zy?bzpkt^czi-HVbjOAE>nT|i?ZyUda%>R#)uefiQddEg z@>keE@524lVo=>44>SVha!(U=(#R(I%(u|rYXEz&0#B~RBXc8H_PBZ0UjtL zFqebG>$+n+{m|3MOirr(A*1gZ3}GkVk?H;{&fE48&v?U_qF>a9ym(*Gn{NFBf14Mk#L?Bs*E(@XwC+^aw(k;ee$?HiKT+WHPnYSL&WW` zS&cVz$3P(UI9N{)OG`YE3%v&ih{g|Bq;$^$+HJkba8U_9JmC|p)@&gQw;{&4XB7&Q z2JUhDZM?*$3`}nnkz(ys{3Y50c|6bMa#e;i`-c0WuirAbVGpL^dv!5jqSQp@`1T31 zZT-NV>Z9WK)T5*-VG0q<)S&F!|RyBfEv$ElM*l(hl(wH)GQ3VVeBFXcAcc9Zt&qFMI&WxZG zzbNU0Q|JDWU~Nlg`XfseqIsNCi=+jjhdt4=f;_IFTAd}9erWwAst??x$n3tg1$ukE zN%Fx`Y|J8IK$A6J<8y;4-<=BvrX2)}+|h335J2mqNOpT3K0dhtT-UY|<&P|5l6eaG z=$UYHhfTphu6rV%Y581J;u^te#t*g8J5Fm`0ye+*1QOG!7FzxWcAJ$0$4dW@k~zxg zm*Wyxq-{i!o13WyrW_{j=q52Sy)5be1nXXw5!1kp$dh{L{8~&n8MIZe#IJ*Y}Y->C1 z?wQv_{{zp9|QhaPFXp73N5Bi7l6y(!$0IC4{1#Kgh>9PX+l7_Nf0{ zGIvP*4PK+=i>A=$zh2ps^*TU(Qj?mAYrH)2pNSx&%7$pHuE%e0Wg3|9pj@xm0r-W6cmZ4`ebrpIcyf7-tRlMX8dR+%xwH z>#j=nOxjTEvix`?$th$=!Z)_oVELw0?P$MYVcM$es0eceHz=_3WxvK&v&$?QXy>O1~i8SdwS%To!2UXa-?O4aqw641K-pfx5KwIpvY7()JzkMOsvs ze)Zxarq<~+I7Cytq8!~?8`{J2*P7ooW&(1pn1y!L3dNnRf5{s#c#%sE#;0HnsWzw_ z-AmrsDj=UPmT1fm6OMP5!Q-f2dHhuRemMr~o|)>4G$v(o^F}>n6wU>e?a{5dztj5nzq<|Lfk9gYnDDB?I_n_h-&5u*`MA_@jK_b$d+_Wyi4-`K_ zWLyi`rh*t3+f~T77`U3zVR)NvDX26R5&lC8ZZ`2mo6QTjfQJgq$=&hSP^pEW?XRHZVzrkW$ODR!K5ktz;UpgZV!jl}-! z8Jv1&8noEj674^=c)=K7R7c+4HQr~+6 zLTNv*r@?(Z=ejStkeq){Zzi|0WCZgH8N!%R zKE&on3I6)~h;aTxf8JnnJTq!{EqwSX!{=rPqfaI`fQyJCg|G8)QDPmGpKT@9yIH2I z#sb|QYQo8GpN!Y{`k*fAXZezrfWHl+dC^n{9-0@7gXMEz!|Op3r=xc(GYa`sJo@Q-;(v_tJ1 zse3pVC(RJS$hm)r>}!3rz})~|U$PbZ2PgTLgO;F|YE7pI{CvN_Fo|lqgAPTLjz5K_ zm5)eUQ9d?0;e%4?y{~-#0IO^~fD-jp$f}K9SaTlD!WtBj5pBsBrqQ0$Dw@07_ltR@ zV~M_8Kg0br9gZv6AHWxO69?H?R>$0jX1Zo_x9;<7xTiW)>KK#jb6W7DV>E-}N~Z_QVC(dQ%$W5=Aj+{v*XN~jr%xv1*Gb-J z!Ljt3LJaE zMnWjB@tZ8QzrvVe1+ZANhXnPu;-i1ODGp?CN-7iBhT6SQve1W=T`9qDLW)6hmISZZ zena3e zMcl8IMgqMr73jc?@kHLS2VdR!9Cq2%lFau3_(SPOsIUA@{;#!*y+^YOmm3k^xE4I| zW*yv+ZYK$Td2BeHu?thn$y%EoXwuwEU_b9I(T(Nt21Q>a?JD9<7)1%}*Q-F+?A=7A zxefm*Nv6H7t>j_YczmL$0+tJ;`S8vK$i{0o*cjLlwHpoi>-fL0LnO_|+;J5&46T91 zLur|od5@j($4G&jj)5i_sK4kFSc$;T@NcpyYy*mnLbzvcQ= z#NC*QvN<7lIIkTa>wFDCtMbT=;1p~#*Z}ralc{w;9>vI8qP^KPkDX%d+(k4iDXNG3 zJQgcRJ5RO!u{48X_Cv-}`Z^Rr2I)G?;yu0;W6S1>cZGXsSMS;Tjby&52Tp1F4C#4Q zWc;1kXcq0|(M~YotYxd%U9mps*^f-_T<$8|e>E9wZvG~xJ0GR(%QA(1$=>91XE7ck za29^N@6U(MYG&?ru0-==gxuuiVfeUC3CuM4NT!CQ;1h%1$l`Yf7h0=?h0uGd>r$0hB<2dWX}~@tKo8!R?wvQxh?cG-d?2y z*6McTwOSoMIo=1&no2!!68)*#a;|V}eiS_`^Re^~E8)ze{=DX+Y{vWILDbg#4?kTx zGNDkbkeEzMp_zv*;NVzKG_@7bl6Ol%hVvoQwwGb$5Fdm;QoUtRyzX|Iv)cMzM9w9p zVduu_Fn`w~F=oa@P_1|&?G=4-89(x%*|xWeY3_suvR@Vq8#3yNV_P`BZsUW(sQ2ov zRh3|Zkj{0*QvA8-j+9eA1u)}AAJMSgi1wvBfzwbQvLmMiKc~Gvw+=Ou{_#5*k3VLp zT6A2DnHS&Qf{XjxNm2^Jd+mIX#sfNcJs-h1%-;+qx`-V0_?E9t7c6gejaqCWSJ1@Lsi!SO2x7A$br%LZf&XPW8{CApn5wi!6m45-E?r&uJp1F9> z$~?HBA;tHGZbJL7Y=Ud;w&Dy8i3g=1k@}64hfNkt_4@*Tmukqz^iWil_yjWldqlkc z%g6UNdm~2~y34ytJGEzQ5q2E)c@JcXnNnIU8rpL7ZoVdG$8A9s`1}? z9I{49M+x4zuPNpmV5=EU}lvXWa9l^fkSI zVd??dOZzS(PIK999J@7Q5cb^tP1fjMVKh}0;7Q#cGC{Qs_YS4nTIyLY&mYfznZ8Yk zp9Jv3=X^xg8&zOT#wId?>M$?8EPw|in#r?E{wTQR9_WWYByr#JaJfPq^qi|Aq@8E> z$#12(;t|9lv=INOp_dOCz-J!9D5k zB+WWrfW5rY^*5A1%!_8?RDxigbp}~Bp2bGStA*ue*8K0vLnuUNBp8LyBO?!WVrz%@ zFjDF($^YqzKe&H_1I1Nzk1!iGUNJ{qMJG7gRm~om>w}6TMBImgRe0JYd133kmAq!# zkF@RVYGHG?HD5Zi56wwB3Ek2@#6wh!mrGT_vYGwFBX|?@G*bsv@j}iv>o&HODTda2 zA4&7<6ugS+mM^T#VUy=wUwju!%ty_<%YH5Nn7VoAPZLmU%iG#x%v z{KMYySE}K`0lHHwa>XP5mV@_|5@NbR139d?4tihf$&lD^Jky+hrhg`9TwE!TT%QNS zE=ck22ijAziax-g`fuWQ#t;=Pbb@OUKH_=R!{#r=XBoa-*@4luutayCn{o={?&H+E zp)ka-oj9*Wc;-uQJKWnp`uDC(CA9$qcfes3Qll`?IvSehdVHL1Dz-BOqjKOM^R;V z6bDK{xY*(mB<-P@((8lq_h@ZlqN5qVlfQ=0;ze-0VJlgIo3Y0znhiy>G)MQhvutq@ z_)e%K{wW)gVh-)5nS7F4-SU!kAAS$yXxI6s^b}^Dv=6#sA>!`K?8SCdW8wFyHnKo+ zCJs872Sw4Vy^F z-fG;oEe)po)Q}fGUf8j;67qihB>sAu=((0!sVcHo-332T7^h1;C2^1sx^BgZAfp=;`1((t(zSKRkPJE-sG z|MM-IvRPR9(vN@gst{FKD8ohSKT6FF$0LUngY8X8eh&%Jm3;Z0=0LU*ck`=g;(~i% z_vayT;_~pH6?NdMT|<<)bmn^F7O<`Phsim{)GyX1;{He(3I0whNB!Oth%l!I-=3KO zULR_Sra=I1Q(p=1t+$Hzea~AeL1}v{IrTQ1olsE)OY16#|v)s2sOe}Jue>V<6Rx$pmYA=5b31}b!- z$o7#1*zNRc;Vna3UjNy6l)qyZT6kbBSM#w8-x^LaxigRO<5KVdsRf;5G&ASKP^3up z?E~$m+`4=j+s7t}xoez{@c^;TG(_>=7H)+Z`?H6@zlz0JqbOOFX1Hc_7i!!xyW_oIMB zM{Z7LD}EwJXAi~qyEt`srfuT;fYq$ClyI2ffkk-y$(TT(SQy z#9YcEZrjsvj3Vt{(~{*EYrSB`q)h`2$HgRlZ3kA5t^$cEZDRlR54!j4vMD7}W*X>= zK@iN|o_Poh1uUP$0 zT0+N_S9!Hzd#Ojj3oYH1#pS8)#g(U@fq`;6dH!w&zErtfcxor@VHx%c9h2MuH}~6- zY5VH&l2K*w{n-yPL}jXA4Bcf9EUgmb^RP+(fvV+WvT;T}w*T#k9*(8@ABxX1MutKc z>Z@J+Mg?Vc{6g*Ss^U5MS>_{vL)oM~I2r4%tbj(XUxbyGMSZs|&>Z=5+>rnU>}=Ho zq5j>ZQtlZ$xVlJK|;M&&=Z!ZDJVIbX0`t_60=L=|dwHZ3H+=(+}+t~fPe}S1tKY5YypCFmBMJJqC zZi!tA&Pt}**Ks0F$IOGh^xjZt;~c<`KJWi|aZ=D~dw?O^JV!Aev& zE}{3Eyjr*$o&9QtPR2NKuix`*CC#e|Ui6o2RJ+1No)`wJeD;!&qE>7w;e}S77jc%$ zCa`(ZhQim~{(QdV2c(0igI}rvdH*?_=0lc1zKJy7X%?#6CXo+=Ct66YwLcm>a~HBr z9+7LodHBrJYM9Mb6I&gg>2Nm$c0?pepm|W9zdX@Z>erAOvPE$3St*KqGJ*U$(t{ga zsLp&Z&8xrXkDpQwYFshpV@FD&VXiu`R&$$JUw39^73|V!C&!a>*aiNyTYN?-F-|i= zHiC0t74(icXYsg6!3#zCi@2P{k%GiC)4_e;Uh>7g9ji*bhJAEynYng67I@`C$BZAO zdA}MOZoUI-a&5_xrh4om*Fg6y-^lDAR)SylRRBY)i0+8T$UplIED5H%l+c6h{CF?4 zjcU|a-dM!k47Y;aW>Lh3;z^CJqfo;-oDUc1quX<5pyBHJ;<7|@lte{)X3#rD6#B+7?e}V97cP8omorW*+ zAatoe%P&1)iX4>`LGVh0^tp865}XHm(^|;hyB=8H<0BlRI+L#fv(e^Sb2P@*T&&qh z7ikGY-LLXbq;I0?pI+!vOBT0d<7yl~kOnlTgg;~(lh$XtTDW|`j^AGN9c>9RfoF+6 zVT@4p;c53~pQ!~1R59?>8cT|SKqYal~ zz&@I|Mdjm(x<`eJ;=K6Jt9j;K#y*rKd6w(h*oL1?e+P4}z9-t3lCgGeAH-VFT$GVC zk0o&tB)a^=^Rk;>=-l2cF+Xf~`3_LS7#TJ*4eL&y1|`x<#29{5vkdg5TZsFU%lJu8 z3)H%_kYzWQqaViC;PANya%6uvK6{vYorY$K`Hc~pxnTW-`Ye`rq%5Lb$6BgMXnksc z!kisoRn$KW#~%lw{Lc`+fBiY;s=hvQXw>71ojve!+Ym_hZzqc33^pwELh&(K+}T-* z%qF9aPTb7XB{&KYu3 zuwdW@+^4%CBh5ohDb;f}aCDv=h{HZ+Q7|r=@*8Kb<3hY#n3-$I&&Uiy7l&zroxU*{ zdafCdswxEk)OIny@#OLcu*$C{S59q0!4u3;dXl+Vo3V259mv!9Nm|`gnGm5D(rU}% zehK#Cuewj*c3vy>d8y%{t5ykLC)n|0AQcI}t^@Sejwp?*$5yn9{HY7=_BB@$cu0JN zM;B^IZre>X-~2J;v_2+7hUEW`r0b5W=?&u=DoWXuJ(4XX4c+rThlEr}D6(fpMI{Lt z?QK-36qSauqjlf&p3ojNRA{TTmlEOk{;vP&bGzO9JEH}BbF5p&XKp7{noR<0=S6V2@1%nO$f)n(^< zx$!pBPa-yTD#$e%klp3gc-G%EXsK-=RkX`E(Wn_7I}YV7SWUE|W-o*vvm)8v_4voK z-vG1zkanX-0`tvQXx|FVt>ja%`9kXBNT-=I-Y&vvxpa?PXGkiFIb89OfOuRBxmqVl z^#-}1vEm!~BC`&a?z{q@d_0M3PdQ$EkZQRf{}J)YW#+@cFwl(b+T4OUEmyRrJX17p z->0~Dw#U$iYcnCb=}k|X+gbSCVBTKcS<{kDWT#u&hO!w2N> z%0irV+!ZO#%;LltBSG(}3S<>LfdsDa!N;5v;N#0$5@Jic23F9{=y#H|lvV=SJ<)&_ zDO*G{c9q2!=osEcHa2AoAH1f00VNgW-J?y2DYgf(UvJ4{p2xBmUC~ONEUwP{fgpJO z6tLKCCgPBbdK2mI-bTz6$KmbDUm(<1is$rIQC5X9Oi#8Z_A~48v8~lGeqJZB>a-99 zCVU1#!58A`6@@CT@4&@3-${wXE@8kjH_HEKbK0L(nTuX0p}#tUj4R2<%jD$Pt8FXz z!)L3RnU`mw^ntaaP7~+FFCjWPpM*vx<6FCF$Ha^we1ZHZgmf)X!r9~8?9EhDmvkGP zXr}s>wFv^}Na}$)n{n6oU6vlSNQS~sG#d*Or!?=_>EsUNM0_RU<&skPk2C&!k+tOcb+(<2#wnXJJs zy>OkM?f3?L3vxwM57Av_;}mQi=>}FCqD0s`n`VY+c2KW9&COVUbuI)RQ6p;wZ8$Q$ z7NE6`bbdL7g_{)N$d5DRMM*7Q=t2DzMp<0$p@CE#e?KJsIFs`qw~ASBa0xm-L=q#f zd>kizfL%1(gFh}zXIdJ~Q1;t@*z5i$9gK?JlfB#W$d#e(_|M8} zh#B5V)=s&Gzh;(!O?^3elr;|>+u{c=qrVd2%zJnY)hAEhNWDDEssvH*vLI7lf}eh_ zH6?9w0qDpM66r$*$n=mcy!z`&9#JokRB$OwB-GcCwuO0Xwi<0TTf;@sKEaRYZo#I{ zZK7Ga_MjUYbu*hwvX*ByrO30BEj0OKM-MQqXR=`O-0$SsQdji5(;r4SN0H|GT)e>j z6X;0O9_qSeX8qLTsA%&E?u^|e>`@X7AN>c&s={MTedBpFX>Tv`<+O5u3K0L`= zFStQK#a9 zzLT_B$&3}9e_l{;&i~ju`P@qO)3#Im;+AEJZgYZderSeyCPxG01^(6p zs8n*M2yY*|MuBN`HZfnAjE_%z4=Oj?iTjg5CRdE5vxE`p_i4ft7j}U+%@-}Gi4#6K z?t@hC*K(8NLzz7kyIxXX^Z)#YVYnaK`ZkmE&`A)OT$~Oyj+;n~XB~cPi(&9j6A3Hv z#IYkQ;l|$I#QqiaN9gT?s)g2M%8al0*K{$qHcO1ptbQ!GZWe-m?-=CzQ9m|$?1D!7 zWO4AuMQGpWi>`0U;&!ZQ5x53v!4(x7GWuQ}c8%j`7H%u)eqi*LlPTn`l% zT?UnYPf}e??-52c^GZ#OfAj4cqgEvY8csV!GjkQy45w4ypSksT;rUo!WYm<&=~s_o zoK3gEm{nfnNOn0kEXswC!|6Vi?x(XLAqU3G(vINoUg%igT~MDLP2SJR!#~1$q4Rb> z$?Pv?wl?ZR>!k<8R=f~D7~+bA)Zg(Z!ANjvk{>d4$>Pqe564$LoZ+J^ba@e+#l}pIavj3FH~|~vc#c=kIE;F`ycwioyOu0wj9VfY;=WB(h4VJS%-}>@ZApz*5u#lqNE0jNO__Vki$uEui;9`?%@_3p^x3Y96;+^X-@l z&}Dy-3r4S)npPF~Fl+^BGHAoeY&~SiG!p*})>!AzL@+;OLx!c+;`2XUkn5i;PB~^E zRicr0Nzz;YxFRh^Ip+eb9Uesc#s2F7UAlaEou(EXalV5#LL!sq|-->)Q_yE5ac&W1<6sI-~-<}T+kYPok{ zzE?Jxm6eJ&DI8#LD|_-L_q338@g!KQuv~N#>~biE>!ZJtN!!k2hu!56CH|RsmCZ*{ z8+~aO>sMk}ABwLGcSYC6XLA)^RRXK$a;%1u244}WoLYD)AC^n}Ce}d)=;j6+cxdJ& z;-wQ+K0;w{BWW46mGPEbjg}qIW*noW$ZJ;fRYtpjP*t%T4^xW5w@%kVJi)x*%?GhTPd-hjTZULZcnsNpC6&=16~l zTOM^}T4W%4)ENa0IWZy(S9My=N+pEwCym8`7`ULU>Diphr9Z+Ag+6FXQ6`u8Zl6G6 ze?MB5Jd;cr)rpUekAyWRa>%;wBrFqO0J|GH$n~^AWdg8^674vlh8*t ze2y1BG4?{YPuFtaTSJ%yn_bW~&1|kbnHS19_@E4`Z)~0$FL+);c?q*E^mnHjXq`fc z+SNkFxp`r$_ImiOE6LBZQ%9aQdqA2!O|stCW9MnVLHYd1>Xd+=QN@5v<-3CP={Ah*VwF%HsXC`DE^|I4Y#G5 z$r5Kh)UJCOns<1ShBxJSrLF{9oimibI?tUM+9?eKFLsj33oSVR0M+tQpVa?)=JFvv zXkbJp*H<%|*;>36+>sYC)G5bvb#uX3Wst1<!%n*ACV%k8?z9tmrSnie z^ri$FEw>V)J{XHMZzeClfYtL(dS}lSDpynAob+enyk`^oJl78Xw7w(LKl0chit6`d zayV8#LSVVV2g&cqx=6%zya>yN4d4(B?d{TVGb;^Lzyuy8*V|Mn!$g=P57_fssp+Jld} zTFJyc)<9L4*HP_aFdpCj0p|ZMC6WC}xF%ndy`vJqe{spAyO9fW9?0f)(cHOX^L>!( zx=haRTA|J~HUTEa(R{^AN}y=%3QejHiD4RjzSBI4zmC7iuGT~*PfZ2lTvw2Y#ckNF zz7`moQE&6i3RhW80RMCw;&Q7NpL|Arok}?(ZS%YkZ{&74gA13_Vmh`sf{|VnnIe&o z3ohslGSN@sB%@RQo?{@14v;ecA`okd%an1onZ@G;z3Cz`%LNwT?2l-eEGsFOo3wWZ?a_WRkj8MO1IQw!Owp9JO4 zmXopD+p)=nVsK|0$l9XwxGKDqc4Sx3{FZrWpS}+)`1O^<#fD<*A1;Wwmcu=~TP=`$ zod6DN8;DgzeoE`sA~(_8Vk!%Xdt|#@`aa-nD@&2$f@eYO-Os z)lYJp-p$1P{h)8dL$d02E>0Z$1`}oekd@CenT2&0NcX5EXLxKf&N8_UOJ22+v8T+L z33tw-`k)lHkk+zOl|{7yCecp!(9X*a`xL%h-S_zcd(T}J38o&bxl zG*AuFQnWQ<4NUGmLzI|0Joj%g+<4wk>{lxaE*ezA5w~u#Y-%`qBohTy^08#~x;#9< ztznmS+~Y6Ti$l8>^$GgqaOuzg3ir2rA>Amdb!^xpSht`LxlfuUx;f5U76Fsr|kmUR;zakmTBc=eMb)$zh@RUXLsQw^8DFoZGRnY{4Hb`jlBy4O{+braZ+MNE=xOD6cJW>|ocHAA z^`;Aowr0ch+!j&B-3qTeaHT(*Y%9&hg|xfDrmclM_sC*Az1G8Gl?YNmI~_8`T~OQI z9Pa0~O#8v=$Q8yV6@$;V3Nmh#Au_YHfu6A$WbitVV>Y;;8N+h93yu+joA11kUv36B zbJ2D@UOEB3(V1{pmIBuL@d0KjOYn2e=c6@+n?Tm=46zTa!&*J|Y{YmszNJipS$epP z<_A`i1tTNTkitNiv7w(VIJ!%Ca5VMCKBu!ff5^WLnt+y`l^;Rl2S)+ z#d>kJeP&0gnu~i`7IN8nxlUD zhBMARR1f_$yYF4%3Up?y1-c1V+?r=~!v1j@?D+Ou{IdhWs7B5eX{hFLKK?p*d7l?j z8JWpRYFtfKNR0=B$Oh7ra|9W`+6NUzUZT6?y-z3E;M*R&_JK+!U0D;g9^b%?=4sb( z`+InA|B=XYNqGGWE!v?L#GibSjhv`=Sg4=NMc7QmyYjq{DxI-ccogWk7{){0m>)PUTBM$)#%3YT9S53d&6 zl8W=S_&xQ>_NeD_+B&~dPyhBpmP(nNm9iG|c-(nNij5)z-Ff)-P+gwpfGb-3JdeY9&ve#u zUMQ66mTNZUFfUf$hVAw_BqJgfo8klPlpEgs+x%6i%1sHjOjIMY=Cot|*_7|aU&#zR z2i)RHJ@tF*2)m1R*=+HKrD_f2fkP;U4=zagV=iazRU-(dnARuWNM4it6k$s~6o(Dr z&wnvO!9CWncF>D(q#VD9ErvN)nuxKwF|+m!LOUvSx#Jt1@ggOE=%)9<^1%#{UxDeQf7503rWTl?gjGi+z!vJQP!Et}Bo}1CBc-3Dm~%txfB8aP&Oe;L_@)?k zgf@`|)mMz3{c)6&V9m|nH3j?qXo01wh*zn5#uR+9L$BRaxR&k**!`LpDmj(G8BKQ* zw)Dh<9rYQluNr~m`30ciVItyThR@4`=@UE1!kiZ2@}&h(>s(8=z1x7w7FnQ(omNyc zkSq*5e;XpiDbG(i@C~xAD1T9&$YUPVOJ{OKQkdqk>;8;^xxZ% z+mq^W5YsaLz-M*~QCynIl$fjoi8B#oUR43sKJJ3%Wan`mC@?&0X~G4N53?qXZK@Ju>4mMTc{iWXvM#1on)qhmsL-~5Kht*8Odo_=EC z_Fi~|l!8#%OQ%Z7Rna*D_Yl|}SCPtuKdWLwL*Ws5fPHax6H}5@m7-N}M4yq$)Zpq^)6fGA3 zq1*e&{E0h-GebO)Sy%@5u%}=6R%1AuQmVlRKdhlT+i7U7$vQ4Yu>;RK`V_2I783Q; zB>e1mDM-I)B^%aCq79!c&|=|fQI=`r)f?ctxSPxx5hrLgpm!PN0&dxY7{>3aC(5S& z-?sD=;ok+a@M+Cr@+qPNzm3lTc4ss3px^iNVqZad<{%0Fs!ngt7O39rH0RS)FU**s z%6_`($E#cjKyKIQ_sG70v(sTP#-8Zo`wUJd?MiB~&0ffN^&-c2mEj?#maKv;&Gdd& z&77Lyj^6zY;J)2z#!r40!i>KkiO=;U9BSx-wuk0%ZBwRUn*!SN(v-n=_CsyFXY@RkW0w;lblbQEzf zu1h$8pdz}rCgHGoy>NBcAW4WBkIG9H!1oc}A|2rUhI^ov*Gu*o77GrPdZLxx8C=1T z9A>yf5WH!~A?{wOxX+Yfo$gxluZ*Xmr;Um*MlKlcx?dyr% z-6cqRn-^#tY9Ix=q4?S5;Vi46$>(fSPIa452+ixn`BlA}(P=qr2(s}eO~vInVA%)w zeWH;B`EF+H8HC2YSj){n?u@Z-gLlcLyS{F6>EtB>! z<`XmFu+L92Ez}L|UEvGt*l04%Bo|LOUjloFw~&}CubHzyEzpt5(_C%P6g+ls0JzgW zvW&Thnb;UxG;J`Idm0#l>&-pUBC3t~AD=5)=7W;dc2WPVWOoh(ob9BVpB7<+ZX*__{8=pf=t~)IAqyCZcPqC>)awhu0EESe$B;;brEZn9?D1U z6NC3hw}H*5NFsSGpJoJkpgQU=urJ#!m}}9CJU7o4;jm`#eUN&UOWb^ua8^bx?7P=R z)~p+3RAU7&QQDaNNNmE@AM0VxTbe^s6Dd4Rb%`bt_1wZCq0CatD-iiDlZeme@W>gS zXkcn4H!M6(@Hl8D*t{?!x1Y3Nu>-FmP`!z~yx@+$^a@iMehd>7~io+0^l zb=Ym}0JvC-@wGmW1gq5UpvrlFIq{l)yf5Y^lyCb=es>1qcUL`7Ce5<`S>GT46LnAx zwk0d+9{SKWmF{S5WZxV~tS+Aq?|gd5>l_1Ae)$sYiu5MTvvS(cLObJV_FB|aH|CA` zP$*B>MHWc6;3CC4(3jjs@*Xb1T~eMXMK_aM+CPd>3)u|qi@XWxE5nwX-$BuopX70< zk51&PPq3##j8F5vgF=VihVwBoM0Z~yb*e^{z(L>Oew&#jz54m zN`s{FpcC_vdKj}P51g7Bif`z}K!H>}v9R#M26sMyT)refE>jFWYfyvLMJ6K8xL0K@ zEcN(By@y4@*1#e#*8WV6+881|6>FI6oI&0#9GEy}2(NQS8ELOK1h-=PoZwJG0#E}I;R|zBx{Lu zX%yNm=L=dCOXJ6E5#D;{fz;_dpX1vvBvG5#PFF8pX6gd8di^w1Q1=gq_uO~_M-vOl z$uNpzFA5>}a3k5$I0U^;v_QPR4HrHjjpus$!>W=_GBYhkF#f#j4 z_F4+xLR!iv>6!()Fu{gXefL$kp=KHwN7|9?^!C?O?17?x zQ_Zm3mDIn5Gaz~FM&cM7jMK+kvg!uj{PVpvOl-Rwy7wWF%bC-H_36)iak`8&m?Yt? zj!RjEvg^D@1&_}BSP2P@-o%pj7?OP+=-qbePm#>m(Y@>pKlenFcDp=`E`Nlv$$v;- z*ej+$Um47GSBhq4nL}0Z_G%M3=wpd3UW^5kk#@w?q!y1>xeq0CeiFk)io&F^p6He- z<#^9(GKWvwgR99ya`agqzBgnqy9B)XCbPFpTb&7VeecL=-EF}I2t%J-F-cZR!d(ds z@L92w-25z$ZfDL1kB#0$U*;43p&SB^r@G1LckcyKnI33jO9p3pKASn|5D2s7a>@Or zso29D*teBu_~nT+kO#e)X0Kc!;=PA&EQHwZ1`@N#0jsekAWom})iU#u!eLKX5!*oa zPYcBhn})HA-)Qodhm=#dHRi)tdvTt5v>9Ehu!MTfn@B~LV}l+?_L7zte{b$@M(&FM zsdiq&+tPhuu(pku9M{3-i&wGJRs8uS*;(k^FZx-c`N>;mD&a9dhq3yfHF>B0 zz09!_I_#*1Q~bdOG5B@P2UZ`ACUd6e;Gh^jz-`Z1L}KPmdSJ5FYpwD95N8L)8WM)D~#6>IdLVCM?Gc*A>i{(PGU!{~EOvN8Zo z;2*$My*N_zC>LLqX4v0@p?v)YG1w|+0&n#q$;}n{*h$6%rT1oVr-OG3KGb!i4HssM z?v+n-!l70rk6bvNgqx@@epyjBxsyG}G$iW41sh`#A99&`;<)MUB<@C}Fe&CT>}9hE z8OGtYRG)u}?ogpkv4TipTc7h8ZEvcpPS|$yUnw@#XP{k-`BF^o8DWP9<-{`;R||FE%~o`?m2| z{AeEhvK8lVj+%>PR1LrxY>1&nEuM6|0t~Brh^(B2AY@e$3?BYMZq(jKV@oKP=-Wpw zn41X`E8Ni_-77T>`i1%?n^?mg-u#T%1?b|fsi@R?y=VsBT=W?37`!K6?j&LD!B4Ox z?7K*VJ$KD<!wb+NcEH{GOSbw?Ku6N&L72ZcIs3Z; z51Dii0=D&&JMJX{?@D*%J%Q$9EXZaop9DaeeJ(kqn2Oh?PlTi8D@6SB$dLtLxvY_V zi#dmXDb|AHuU7K0T@4*Q<^ihZ4aA#ztFw-+VSj@&UlM;Jwdke>+kDo7*RM%Ii6N)J zK+1>s9WSSOL1)-8l5Tu{W-p_@U4Z5|>2V$M&iL3HA1IyNPMnwP;Gwg%*Q|Aqv8~pj#;MS5thVFS2VMVf)*X7^fHl18$yh6E55Dcj`|i+{&|wLaH-Qa_L{3dZ!2GkWId-tSGztj)lS71 zE}mpfcY5=~G~)$$SUz};XrK;_K%{&60n`}9kyBT4X)e}%s8p8byPxhvF8x~}-|gQF ztexeKg6ZsGb#b?#Fu4cK*`-WUp$mW891gxMxn$?0B+MKxrW(sZvg)b?f@mGkOE)GP zgPU*zUj_cI&BVO(KK)*JAdT=wPE9F{Ict9z8rNiz(S5XA$B%07DZhO!IaV;aat72r z*hz->x8T`zuRuNE8!0Vw$Mdcfz&pu)Vgqy0T0=9K!kru_*r19|^45X*+Rq49hMw?(!=u={`-IQ!d?mm6!bLqQT;raHRr zGZJ`7|7$8c{n~_wYBiM`kka1tja4GfZHTpD*vidK!NI=e8bCR&U1(V%@P(Hnl z^qg3XcToNCCd#FJ{xOoN$TETy`hWlDpM5}^{d?1r*Zv|cc#Z?XCOno5S(A&0U04I1 zb0dkKZ2?v<2#0;=f0M)4oEQfucN8U`#f4oD#aS~Sf}Tx15&!Oqon~mWzm8k-2cH~8 z7DtxDs&U&zv#u7+aQ>v;E%LwksTaY*_DWJ2WQ67io`RdS3;WzI9?P#@$r^h4@^xm1 z(63;3WUP@TnspWI6JVVK%^9m3joma?vH>S7c>90=blQY^zJC0}+vK#WDP3*a9gJHNz zFB~fTqqco@i!QYC+;cH)w=JlvU0aoGAQ zmibfyQ|SKal)Dhc(abKh8TOpDRFjZj5)QWFDluyWcc!e^`GgKWwqcYf-zaz>W+9RwNQ=B5s5#TNB>V7sZDcz%41A4`Wr zgPAn{`qMHbF;^Y##QTW)Q*Ix3M^id!Mn_z}j^T=HP&FrpNYeXG{OL;gxqT=6)PdQ-QeTG>k?4*BtoG&nN9gbXyl#t|w#V7+As z-|}Pv%1E0FI;Gy^es={{dKm)S(^bu+Wv(O6rTg8|rbZHPuZpJca)*KD26Fj+2ril} zU{S|Se(%-$i0NI;E^c+^b(~#*7y+Dx#f7NDeZ-+`$1w> z?_m_@3Q+8ebs}Eke1$hu*te752|74@mGqEc}fd+xBd z2)8#LaAl1(;`wLWwV`FHH=JG@LyUgr;4vYe;l#)vq@#&rPSUL7Uu*2S+ZU(dGcIAU zHC&oEmUdv=imcIhbD>DTw|=TSDms_Nz5jJdsN8MH>P+_Gw>m#U^5dt`9E^>`PWCh2 zeC!=K{b(mc&Nc~eu$5q~KzGmc=BW6L1yTsG=lox#39s6P!4vxPcerOWhB_nQl+A7t zZcnA%C0~zaa&8Bug~eJXY=XmeewTYCa@jf!8f!L+aQiU251A7lk#FmBvDut35FVH2 zTes~*Ki_PDp>k0~MUankM$)c8uPpBJragkB@13Y3Kv~35oTs@c&mZNHv5l{>xcnE; zUpbV&Ts;i^4PFIGY9?e$YZG3-p$cNDztS`Ef$-)|cjS7YiTf=T#)Qi`L2pSG5lg{1 z*O~5vR9h1FH&&n#Lw8B%og%Jy_vS=!2yP}7Z{4x;pIn+j)K5mAQ$fRgcR+Qu4f*iB z7VjDP6ArwTZ3pZpmKr=2VM-jDpIkcD9 zk*Pmw@Y$r-AUC3&_~=StkLdTHq5PX9N^eE_?0J~P`VfaZWq5y1F?1}fC9Q%3jHILl zuoAn8$&Y4Svn~Mom^P9*eKD?8a6?PZ(B3pU8z<)&g6W=r_^eu^#mW|2@q*>p^u=A@^TlYN8|9bz;4}q zjyHdO5B)XMhre#N#8ArQ(fa+@VT}9_qMKnRTt8lq zwN(z`Wxh#))NMDUNj2O5a}*11t!49Hx$%FODWlUhQ_&>6k+Xf)g(J)3p{waV=}<_* zXP7Tw?e>$HtR9X^SFHv47hA{@?Ix_b&JPSP_7X2aoIw8T2iEHBoOJ6HDR%BoH#D|3 zlY6F{B5d8hhMm30m1q5J(a{zem~dK^OdRaMT1p(e=x!up2e05_W7<)8fp(9kEJJl( zhheRpExCT69vf{71DA4X{)L7ds`xe;S`yEah7GkiSDZc<_GEJR%PyyG>z@i+K5Zlc z19!1U{C;+z%#AnRUB(QgxuV-IZ*yNiwcw%ObKz)NIhpkMHNK`F2Kx%7`Qa0nBZFQw z*jM61K8^c?)knLb5IZ^tKF!k+e{~h)(_+XJ%RHRh^%-jS59MpZh0Lonvp|2mrbxf1 zX8r|Uu4^Gf#I5k^C8Htu)j!2fzl4i=Y0bG1)QDjc|9LR`4lxTCTI%zOV3(`Dn)mP{3}p6er; ztNEro(CpPqW-k38m=^4YvLK6#-kZ$~oqr479LOURf2H7v-CAtH0xLeXcM5vuIspp5 ztBbPiRKoKi|K~UILFqiUo74b_H+qSplP0=t;|2=ajpT`Q2;O{h1>30R%SSZdMKtV= z?WuO*k8eAbdV=0h&8Ti|62?eJ@&vGsKBW0m8BX;044EkdWX9G#%&~qQ_caLXP#(N+{6?4^2B=Kn3?p=X$Y<*^ zeD92&85;X`D%^iyK%Q8n;yGGJ*lioU z_!rk>1sRDsp!dF!B+dv#OYVk)U+^Q6p`DBC?@})G*gt&EJLQIkQC;q}Q+ouf4|Sq_ z$LEmfNnO}#!adkABcGHPyvCy*SHe>jX@2Z^S+uB98;m~x!{@r>DtIN=LH68?5N=-O zi8k1@ang$)Fp@sUZSaG5mj<$JPaxK$p21^PS)AFv zMge2K46YnKOJrJWuubYKD7ny1#O6uhhYF=IOGTV_JZy>-7dyb`NFP$%aVe;vWTM)6novgXM7<=w=MYgT~F!^x00W`kwA%Dh}<0mRw?459H ze#LqjLBr5Ih}|?mZ9mu1Gra(KxF?R()#ufNs*8%`IXcMdSYv1U{7^A@F9Muk)gsesB+mM@*#=~ z-a}Y$JDK3}PI&Fudw4jznk?95g#5VUU~ig5qD^@GWAPn0qyL?JS4?LVkGmoHi~sO> zM|>P~%xEVH9i#Bg@fvJl_bFaAHVECBumSWqTasKTkSl#U-o6cJZ_6#qC{701} ze#L#1r+gijM+}h8q@BXCfx4{Nq7eS_11ZRvp#WC#6_@ z>f@86zB5bz6k(0B47_@+N(>S^@Z($z(^q|?z06ne0<}Dd7i%WmG!^vW+#y&KYD?xX ztjA^5li=0wv*d?tEiR>*_C~##oLckc)Ogx2vrE#DI9mqexxebKyEIk~`Itss9RUgO4B%OUi;56Q`?z&;yYQBrXxcllPH&YY1HZ>PnQ=d3^gq1)X!!-MNwg9BUskxubQHAe*^79L!*6bab9^i5exM-K z9;AIq<@CESR+DMO^6dT%n!MOBCnmp#2AZyR63xcF^(k;+O(|KK@){qW)&Lic`iN=x zNOZAc4(MI>5&6M$zXw7m=_0-+1%i=HuE;CpAI9!@;)gCiqgoWrS3>V;vh3blYP@}Y zD`QkJ9zGmcDe@I|Rpo*2+h%fW@p=5)(iO6HG!jNH1nWqwV3+*%R0*U)=k zP=|=eu#wSV(ZTDy@I@Aic6CG6(Nyp1u7p>N@J9yAsfJvkOQ%833(O5;$?0LaxM+0~ zd^#n`XT8j&F{Fz?Vw@IvMZL5Q_iljP{6XT8d4%zPYmLTi;W(xy63f`o-PSXkd&xQp z9nEPG!_XWqKJ2@o#bFv`i5Zc%9ba&<hx9CNSB1 z1Q0OkEFoI8_=w42c2L%fX79%eV$*ZrjCm8WGYv#Gbf=r_@`xz3=isecYuNO_hy0qo z(jY!(GbHbhA{)l!W9`FksK_pxbC2C4*iCbRKCk(Qw-%pE;Fq*G|9YYnI&@W=-dRjU zH@jZNN(f47Bd^^a2tyxxpsin9xwPc_%-e{IVCb7ox|=YbmEel}sSoS_d01-a6WIE# zo`nB)#;1Okfohuszij?8^j>N^tY2YEN>0{dn;Kg-Cg3VB^>-m-QE>|`k`yCm<9}d- zdS9At-awM(2I9F_T+#B_Y>{4KN6Aabqr61QL2(=}oe!tC4w9*}wjiYed#Zo)A~;QOsZ>^(MT} z;EOF~2>9_sRYqwi)DLIbBJ)l6j6uLN<-_lD&zq|Mf-tR??ob1RG&mz6QJIo;5Gq zaTIB-UJ6o*rXt^pcuXPe3GX1c(%%Ui!V1B<>L127>RG_{7g3 zzg@Gn;LP8tD5ctn%N)~-4-b0;zRx}o+o!Mbo-s9$sw2j`W{f~;T)WmQ#)@Y7zB!vM(#19B`=P0(*<3?aqF{8AGz6YrN<2q& z;x$Da?48?6bpKw(Uq_Ze?2}%St+5!*)jbF+WbMe+qB=a&k6{_5?#S1% zV13cZC6pg%kwEt&uE6g6SRx&ohZp{yL397KL_9`bS{2-y*F~a^*x;};BVkL5y@3}MEDqlAWN9=-$TLnz9`#)=6dNoNglOhC2R50k~a|-qIWjO zAf7(gKAM!_i4#t-<%w>5xKt1GSW5?a_UUuGSQi|S;05<|x=Ce&0JoQ_u^)f<@q0IA zph6ip6nG{_q=i$O>x=Y<)6e;+4xKHQp3wXzRx}%jUN34=p5 zhr_LXdx*l-7OYe4f~L|QkX6HEgoVd^&}JFhWspCf$tqd}FK5`33A5;IDVGhQOTH0K zF%X$ahrx_(@gy!i2Y0_>S+D45{ud_=d#Vkgq%ewhH0R+5S82{|Q4V(t?G@zSq5TMZ zslMx^9}chx0nPS>Y-dKIi=rmc5YVzbueJ*#a%d9J*cPVY%EuZ_0PN$=>cr;bYpH z;Qug(?nfNfDy13Vwb|S+_c#H+*9Y0o$mH%G+luunwNzs^x z>_?iw)zNn3@?Z^qCOpGlQ@qC8MK5H+ByOS7tztxG=?|PB=?m{CHj-=O1M$!<7j(fi zhx;(tD3EpYLEaIWoV1}jUg!4`CQa%P-SuWJ%!e4GKZGnXMt1pUp>d-x`MSIeC%yRy zKbAL>mD0zUeJ(?wWa1t&JE0k$`*Q=v&FUbp%opRGDK6+9^@D`hjbdU5)oFXvEZLzG z@WUl??4b}19+V4oJ{cB+f2TN~H2*g0$iE56N{`4}=N$ajssikksLvGMGL`NO&AyHj z&B<-=Zo==won&EzHFLD%46@FB#rfXx#lOJ^bxscr$)AJ2y0hhf`9pPR3L+>i~H0>|EIXm->V z?#iP+96BowCMgz?A`LT~Ta@D0BJ-@}# z;gZX+;#aJQi?#~b&rZXhyqx4(^kmx%hz|OP;Stx0pe^7lVcL%1wIK>HXTv$sjD4al z5awU}PO`U;6~0PzL1AJ!+@iIbOvVA~eHfO(Ney%gr>Q=MM=u-5xa(7ySz?>fK!Xz} zIjt23WhKGks#0P$<25ecO}nZ+dWiE_dF0+Z8xrUHl6%WP(LP5%Sl#uF+~zX`Tc^6B z^pG5po;mNbH#)F9gF`(pggUa1LCLv+$Q=q`f?dXenw5rV-qxR<3ku^}N#uz0c)D2u zY#3ETM#;@X5n;}tM}37MBSLW9d<}Me&P~3vGmQ4)((h?U1~<|8adK*H0;C&JZSWX% zWCuq2U=nXRd{}r zZ~T*kCet0fo%W>EE}n!n=lP(~)2Ltgdb`ekoB(Pw8c4X79lBiV0SMwmc&-@x5!Rg? zAnkWC^OAZDtsJz;DZUN6=pa@q`62&&ha!4e`2Uv-GeK^@uc=t4sII0k(FNXjBlK(0B<7dfF;i7)=)9t@k;7Ld4|uW?M%N0?MSls`HsgKT$eLXOLJ(cN&& zv(K=!u#RFf|mQ|aN}Ob3FglCMiXcr-Tnw;oUN7sc3cC^ z-gm*Tw&uZ(q(5ZZgZapz*cfK)qjOY14G!#bVpn1>zGwGJCOY>9?FSSi|Lc}Zn!F)i zsgVS}3BY0Pz~nK4QJ>Vo(WcB8`s^GaVs+(Vd5TNMTMhp0wN_w%fH5KiP%Y%bI@osc%BU zbTspEix-L*lEFo5kH9a>i4A14_GqN2ss~?f z&WiB7uBQyrp3+W)iKhhGnm(Xg^MhvmnhHmL0M_V32p_je3g(5<{;Z?9oaVFv;dd7= zoFoV?Fxu-&wIxw7ZD#t6t;u);!7ycaRHj#8H~$YFN6!gv7Qs zV(oL@u-?C)z~4B5ijF5*M{2paj+YEEazWF&a=61gQ-wNZ-l%$R7Wbs#g`iVH8g42s zCq-giSWuY;wbd=;!^Erj@}WvNcTJ4nX1tPiLeVUOVmmTzLLH78tq4i$&Ji1~1_vB+ zL2F0naz+wYQzN!gFM|Z_adTMBNDXd-5rIBrb5SX_kO6jofhGSRN!Q_5zzQ#AzCyi3I1TgI=lGt9ld&JW2y?& zsIMmC(_3+^>U*$>r@7@D4r7VPkq{n!UZk&E8-5EKoBPO%nsLHw_uWwS$$XI~rFpUs zGJ2lLW%acSbH~KN%0}A1yoqA?@-65~f+J@$p&9poPl3C}rDWCbWc=O#8yq$5Azo8P zqP&cm@MNREXrHJk82~HkuHWWkmLQDY9h7GjaQS=lnWvgQ)OVK2?Oc{9?Ee`H5pV0s zrTI4*k8w&+p{^zB%rdy23+tq)-b4EWo;0QwhU@>LJ1K2sX5k9z$7x1WY8alrT9Y-B zyvZ+Yj6lQXeUZFmHg~W$E>&ky9BdrXK>n(&LMrWt;OS|9vZuThOZJ{%*ZuY6oj!Im zb5bIaiB1w{VAh5WOub=6O*i>)g2Adew8y#RIv*&^Lv^>@k@@!muK33kTq8v>km@9L zKD6qZ_Qir@Mm@O(_Na1^7qmZ#CTh)epSbi3ELlyxjVInPo$U*0SJY}!OEZ20w(77q z-aO<5p5u|u_ITtOG>SYM)rWV}xtVtW?JimCBn%JtLGD&rT*bw9L5190Xbk#?;S0NMh)-XDrM*_ zz%>Nfgxv){vsjYZmx~9MuVX{JV)&^Z!(d=gpZ1fcUWlLPv$ItB3zIu zWY09u$&l>$4qEXSz)dAzq=mjnGf5uB7jR=v#tJH{e9-7z>I*or1J`N9ffdE)oaJtK z&8mDzdoe_WpXa0dM|MDrjy-YNUX7i7o!AwjzI?QqCiBhW8d8vyAS0dnu}r@YtT1mN zi|*aTPn+D3m{lS7{8*EqMb-z6qB^lF-_^0{R@!rMy@8m^{T7Z`Pzcio#dsenBXr*2 z41BEgCqo&f_*L`{gqG%N4AOc<4@eALFd@7!+UCD{QUz_QcJ;(nfZ{pqJz8+ zlt5kUSeRb^59c=)c|l`M59!T&BB*TkM9<7>xIcoI%w5_YGhkH6eNYt&*Us`qTciHr zd|s3c^tP-ZKQDG-^M*7y{9g+Z7jwoNdn@3wxH#`Sauv$^Y6g?t&XQiS?|8-JiLfW? zJV^+t#`h)Nk@_{-7qiVJZRda&s`1a{{QX#F8gB%VMSjHib_s4@h1hy0YyOJuYi87T z7j$sd9g$b%X<9Y}_I)8LJ5z9T*?P9|&@8&`|=k1+2Ym{2Y5#)*gV z_j(1e-hF|@d(_|@XUaE9+el90D52^!ZzP|Q$wi)N7nUuEgRqnzL~-hL=1-j=O0aek z<)iZb$?zno_?PJlFul&q50LtJA)xDdXU^1_#{|m?v1Ku z&@);rQMfF07@NFOi=TF=gXuaq4lZPBk;unwc%>Be_5W-k$qpBA+ODrK@?kg4>{^LT zce+BIMl%^5aTk}L*vKjxKH>-DUZA7yw9myji%aT`O|3E8!QR#M<)fxnqCe%9P?7IX zmS&dXdlyf#-z&X&{lk4s*ONzR-rgkcW@al!LQl}5J~E@d0&J4Bl66zL!OOqQL!<0; zK!0I?C|j@cu{Q!w>WxZl(S3En6IMva5TmzwSlPWC)aL&s@ufWTW6nZ|v(zE`4!7bv zMVf4F%>%w&R|%~<9EY;Mj3VyOdvV?R8*tpCj;zS{$D0m$qa}2nK=!r^Tta5U&<<0g zWZR5o`!S5)-bu=G>VxCHJiNp%1nh6NQeHO=d!C~GO7uSde++kfrUmNe=gIL))i}E71UtR{I^TNbg&aYg6!=Q}5y0J}EvlP6qv$tx4x;#^mv@AK1|8J5=F8GB4n%@C&4|cV^Gc za6a`N8oSTJ)XaRcOp?R5&U>Q;bZ7c(#SZL4=cQ#D4aD)jE7l9lgMjg3yhYRkG}3(= zR4zPADt^+e)TvIae5)T{C#%J5xEO>I*Z#xmi4%Pwn{Ob$d~f3Bo!+R1W`6!3pF=HQ zg4Wy~GT&JWJ0%psu__7v|C!b0tL$h-Rsh-cycBCI{6+?I%|w`dO6U(4@>_}H1~oh- z&B@D;p*`OXxzPP?X_fs>?1dbmd^DG0AI?Y0D-Q5YD3gEZfRxH%)}Ka9ZeM_&j1C zIjYfwd7pexeMq$;!!w0Zw@TsS?>53+Ge&x42cgCJANGFw83etm-K1p;Wil}@14Z7bmlHUt1<&VjQ@_hURyigqN0=v<8LJ(l8fu0T>{G+F;TA1iGTu;24f@v7(NAziQOpm9z| zgs}>N#gI%j$uo=&d0Px%)j(ukOQVqcs_;nYPqt=##%9%l zpl{Sk_K|#nmA6Bs&$J+B_sekCQa4hXg() z_`hGiAy>H>V6j4k((DXpdE0xdz*C?=Jv6TQL{7VRZxxRI}Zpv5kv0B<>Bs=-{8zIN&a0= zHZyd00o<6OE8@vU(gK$M{)BHjJQ=0libc&kMvG?GYZIP3O-)gy5ajNshYJ3)#YAxLWv=*bLu=f?hd++HW_)mhVv_ zp8R`NC@8M(BFl!kFdW67?bouo(E0w@VPOae9u7UsOdXLYNWw;8zx#Gx138=>Gizc(L zDiHn6lOV@se&Ja<-r%#~2ifL$6ZiSi_pY7p3-Z))+K5E(p4ubw34W?7fJ;v#c-4?y zXk_zgD0K`VqpVA@!j3BFJ2pVfrR^E#eFJF5MKhwep3bpV{GlqUjktKJ;TEd19d$H| z8-H2}r%aP)hc#;Pf|G^1GVEI@Gan#2?*foab0BOBi6xi5=HieoAK>rzW+KQW%*bGE zP}~wF;=}K*Ux($~PcppOo+&N;k-YdXg2jxelW8ZT2!mRl9l>o6Dh-r zu6ZzNMi=?><*o2kWFSpdP4Ytd>rQQiJBb#;qaxks_1y63HQQ$2#bYBfqTYB zV%eCCjeS3YQuS|QA1Q}oUL*K2XE(Y2tpV4zOkiy_J$R4#I!wqGPqePLmSeq=n9YMO zkPuu*2^C{k+HuBhtF=b zVNc8m=H)C}nX@u3Xkbj3NFyConF$VJm1K)t3Z9Y+Y$1uI9XHiTIB5|WZVMpB3ZHQ( z69x+mddP;yeF8@-Ph_(>i*tW1j?T(m2CY>wIl6loTYgZ7|1r~%ksoh>vgchDap1L(1a_awNJ3~b-Vyl)injKV1K$;pZG;Lu zkO>gs^F~R3Sb4UML@q?qE;I2*^DT`Z*&b)F3Z7DSkxk7SXvawEU2zW}9}bn{CDXjnQ~GT8+qLLEJm14!emy%Q>EbgO zGtUDye~2M%xAO3_^=0sgc8i$p$Y4$mUjSksbO|K1V$U%XS#=W+-YV`VGh`5pzB-H+ z%`_?m*WvP3iq+-*G)Kh~+0h)8Z`y5wd532~e7z}oy_(Lu7GN-oq`u4L4Z{8I?_kY_ zUu4{*-DuiMCy3MuAXPG@cwpZuR>AoJKP=oD?J1N2@oY09{*m5c7Y0LEUn^NNhIYq) z^F+;bhRn=YVl;MWf_>w8a%@#K-rBFr#;8)gfmDEC{N}Il{DCB&Vf7fzRttsuyW&XI z{9OF;&PMpA^q8o672tE)pjdmt zXB&QNy&c-ST?6(`HX+ffjaWdt-dbPk+oS3rUmaJX#L zU5E|nB|jb(Fvcsq(7t0-r|PvGw?{pO>Zi426X%R&Hf{x%f`6FYe9w_xdCQ+)xlD^$ zlM;YFe3T%mclvS8dN0^`_y;lBeG|v;*J5j@1oFW#4^T$7C(7HB!_7-j$J65zp!O*B zuTgG1txc1)wmQL2x<}BX>o(M*9YAbnm*V`pUmIcVO4#=0TGn}|8-FBooZxNvdpPhwhELyi2X!!k5G)@@JhO7~ zsU?3WnEcZwT#nxlA+U zk+twx+jO{lR-e2%Rfdl&&V?w{MI;Wq6&3`4f+Cd;GJuTH;lJiEXG^|lMzMQr1f1F@ z%ZICeWK{W4kTKev?3_yX9eX^HeKhqXW^|_CjM>IcUEt1UOMZj&7OkK!w+{$(1dWa<)YpH{p(vJm!e{UO5YTHWC=hQBD< zC)U={T-j^=#5jDM&|u~U*6V2~|KdLdxO&?IvDdP=p9yWkms;|y(ec&1n!#m8b%#E3 z54|eVNIRLlgg=|hiT~MTJZ!{gIHJ-^f-**+LI3GcOYeh`&p+d8lL+v;Ez5hT)Csy3 zJ<*G`*&;4IY|93=B8Q%#iz(uOx|XWaFZezJo$Jxa9KKzFIUM55M040q}5zQ;2KYKzU^NZ}B!s2YD2yif!gCcJI#EfBP{l9{Kc;zUaibjpZ!IhBoL_EfC`4~2_#idBs*3$@ub za@Kswb3ehNpln#?+DUU7gHdmN2+i(}BXhsx;3al?a69ZVIci;iUv$%M4y_#Sa)%#o zGQABJ=pB)Lm5c-QwON<5r}zg?ZP04PRiLzOFWIfrh&Rw2>}|C@q}24G@V|^?)=ztG zMzmH9thj3nzH)^m;y1?a^clW-DTf>6w`1GoQE=cz9l4a|j9>O>vS&V6@fTIY5bJ6P z7r&e%9&S~5YQh&#zDo1G#qJ3nef39sW=fJnN&R?>x+m>(|3N%P-o!(5JkjmC91&+m zA7kKfb}PvoErx$JX|N+co#02FBxvV+Yv3CK$nxwGT(sv46r7=c!vI^R{Z}6{RWTSjgpE8Xk!E8I~+ipg?RPu=i@Oa{m zd*Dzg%V$`8WXS80w0Fjw^rkf7g|vfg5ao#Y^O+PwHcs7-ujzh{GCHThxfp#C-11n@Hp0By*r;ULz|ha=8e{7HFJf_Uo%g3I>W3LMZ`ce9XCDpKw@e+oN4+C z!P7gEP_4L<#JhK3)-)N)r?-&(r<|~Uz$Z9fA;w3(T7m2~?E@dn^W;-iH69%@4ye;x z#Gel+g@P~YBemN?(*y6iqvi)$+~Ra#?1Q&K%#r{y+@=KooIi>^WI{b4%6^P@=v8_@ z593y!YQ{c?-$0T{CHb{D8EZ%_1nI8+9i0+=63UPzFqMhIlvwTpYdyuL7EOFw#VK7i2vXG{p2OO)l5Pg%1veARnf6#)k9LI7%*Jyx=N5Wgp;Env zygT{;5AM7NO4PrzML`k8D0v_nG{)7a#HMaJV!&F{43qOeE07)SW^$A@Ae(00#xK+k zvP_I8|2(0c`S0Wdq$~4^^M^KE^wSd-x(yO<$2Hh$(+<{+`rOBy?m}N*X@GZI0I85K z$6XIS(7ZW0oQhG4?ls9ywmWZjhS=jc&@OTVqua5h`#>K4u2e~}OPc=()Pv(Q588?a z#M8bNTPZ2AZTCEQ&*na6-;8MVBw3OC&FjMpX{SKu;RZ4(&L7|Fa!0o&=ZHA7rt%Ef zH`$E5{LzGsOJ70N$qwRk>bvlKFwJd_9VA{?cB5?VD_}7*kPHNu;L)AxY)S1S{?M1x z=uemwgtnQJ4@pgUt>#TIr#_4LT~qP77w$;1=pPR2$*-cjxr?It#;G_3R>D++KWt?z zn5Fa%QUZp^!LEBKo#w=DvUx`8a1LH@ZavM)ctXk^6kuDGaMbQ=)zWRj^x+ zzAnVi^-d!y6W~Hr{_k7ypc#ER+z_!A-Y%L3M+Xgv{g*O)D7e+AfmnvZzpHb-=~NC6(6Gbf=}ny{I^2XdU7%cUIZN}pV{ zg&i?6fKM+Ho1!Q<-&+@s+-J8_i8Vl7U9LU}y)wt~HT@aJ`O+q5V)BpIpqe-K4xYv(arc`4qly3?k z86!)uxXnm*GN;Mc%K0&;qn%LctuRhCwFz6!%77gXl_WVe3Fr0Chxs!CNoZ?1z8x9{ zjkgBKk)4AArBHVyM>}`^zsoyYd>+)N#gf`-`FJHeoZTF*&PU1*GV4Ao!}17$D39)R zS{_7h_(5`fEV1Kpc}NU(5Y05kpQ4;?%mDdOKTbIE;!f6~=`lYUPk>I^FOw}!_2g$e zgmns=P?wxDXF$)6;+F~V@yKVAx;q&^V~b(2O)D{UmPJ_?r_$#yfDGOFjE^Y=!i$Wb zqG3{|j{SR}v@skpT@rr?{bW{!}{lQV-;HL;@a&^ds)$Mq^ zBY|xTn@QJz9qzNw2Lswu_Wxem*6D5_;nzp*MnA-|FMzGLc*MKu#UmwmcT_Dwf7>mw zscCJ~pkSsUiSWIRufD%!A~j1Qh`8XL6OSPI5U9T4%}tB-EL_tsXD@mCqo zj&Mhw^Qq@TT!~3CT+Nzyp5{k2`wJlUExZzRkj?vUBVkc6O#bf~(LJAoP1mglMg1ql zpJs_48KAub_JMqh^;FcDb_wY$r2X3KT(JfOpdW2nT-@(CVcQ~Y_WcDLUcKrx+V(*m ziZk|#daowOet_w_I?2a<5yFI&m#mS@+>FGN)$ky~2DG;q64h*s4-aUv`xUP7YLD&E zF^ad79dboGyLbC_*gHGy_&E*tsP5GOymwNJU08)b+$saj&OVa(HcY@Q_d~POBnfWr z$G66~L*mIFB+K>&eyg*Bt@85c?^fJHqwl+;d0{jgKSUkNrud_ro7vm~iPH47g{#WLQrNl^X^E6_X%!OG?pa5#UEd@;9Urg?WG_MSPZd)|m|IQsy}>m)S?7vYz? zSF#S;fwYgK09nbpqq)@2@_&pyTj-A_CuMVv5BKT3DY(jx|L~OWys`$$M*Bm)!ZYHk zlZ)r7l)+x=_rGnJ!;B{@q1XH|sq`$x0xhujzm`u_<-|B30~-ICXD{ZvJf4` zTRj{BLk_#3{cSXnm{y4QTy;lpt#U=!d*kN}w9L+e)43qQne2WDuHhx5)hii$#+Si| zKq>y&BL(y|Q5Qnf|6%W#d4{aXkdUuvyvj^j;)&jmZsGLfQkjKRGd!}VhzKX9W9Tjkn;|wr--6ADli&bA}5K=ZG{FQVISj&p(^24%$?9@!@Ht9y1-@vDc35=+4V_yYWX}USRY7Urj+9~<+tFFMmI@4(Jkno?T)g( z=WuJ5OQ6Q{{%AbP=3e?O9mBSSg|`Qsm|s8uX#=~3_z2P(#)27vH~2w z5siNAESgamXTN|1@|i@>NX9m{MR0yf8_ByOi}GESp-MbZgu{^ue&FKYOB6K=1>dZw zp3S|6Q(9Wd9J6vqPKLQ$;KoFu*%8RGuM^AljSYn#=vxic9sQm|49b zm(#qd%se}23e6gUq{5;EcW*erMp}FE-SO>A?Rq`*{MA9u+#(2v4|&6==i>aeuN&}$ zu$3_4bRhArD#KGpdZ0i-9%q@*s%vQDkH)HJb4=wnMmo?H(oV(^q@RcLB}>80Tar(- zdCQpnnFCeP3^_Zc72k?{g4|z^A=^BD;>3P`NPE*jmT&gQ?vLEiRn=VXmr0u-KHLwv zNM&;c54K{Xk;za;eFvYUX{Qg()tR^S5Px0l4a#e}1aTHYL~UUyzEG3EDo4!CsJqgG zG$kcrUdjOy72Je{b8f&ssv~;ZIu(c4x}lHPX!i}>_sP8WLvLsXY16Ld*#1Zc+}zwj zlwxlogV5XHDjQFtv~uwD0?OM=o)Y~ng;+*D7}R|Gh*Y}^W0ijaEk2mWt*Ljx-|qUM zCG)9Q#U@VZHb#rpkhJCh7}}z<%`4#dj{k`9!A7j(SPZ$>JIE;6d&1B|32eZ&xfvx& z)gUqU6pWWGB7p?sPoLD;!B>I&RCgQ1UUo-+B4~Gv#}4f9)DNAc893h*4hr`w>aa5M zXL;jR%4zL4gR}Vs;{E3v7XB^+HTwaQu`pb4#l;VupCwJ|rVQfMi{0Q_#t$O>-wk}2 zUC#D=^XE@j-$VNJ?0YyYU!-l0Ug3w9b<$mP_NVm4Dy!JIYp3|xsyuR!I|0i}{$cfT zdn@*>t|woRCxzmkcA}qe%t_MWMtnci2SS>=$(4Y`*u{MXYf>M;Uz(hcY_J>3ewQoK zHV0IO-{T2m!O($FS_TXt$PwuOn$IYE-Bh{xNIQ1W$?CY8ueYJfN&8@X_&j}va{PS?=(LzV+H!}CzTz;`d5>!$p}=cXwK*fZO``NM0)m<`575D?Q& zE3erFk88|1DR}#G1{#xfkdtnd;3Nzl zz}Dgt5}=Wc^($yzw1pIJsi1&%Ht5i99TRfoZ3BL`&yc-J3?6e#t ztIHOl&nt}~Y0O0tCdZU2g7qH0$5H|@-+j?k$1LuMQj<`6{WDMts3-FehBFJ2ra?FM2ssKLQQjcx23|g>r3LH`n zBw~9%<6CmRDDm-kPN%q%iTvV*(uZ<6g$s$ooKt=%WnDIBZ*fIXq&*tsQgz9Kh3)v= zZXwtPHjx*9Pvdl>k05Q`OD?RZGw^+G&@^n2+){|bq2lf|D>;uVJrb9?d$S+9FeaOm zyFQu8m;Dc1%>v02g%bS4%$yzj&5J)q+L_=@dT7hOL)?U+Andx`2hP&sX%w{yN4l$n z68&wf^UAQ7gF8CXMmyPp;S=OyL% zDN>otaZL%RR-AJ@>q)b_so&)P+O{z^RFmJ3#RUZ~!`#O>cs-|q zjO~{d#AW0|Y{(F43J*sz*KfgtvGHV2Og1*V8vxIHW%(b^cOiq_YeC*9nw%Y1guev@ z1KRV8n9gxy_P3lv_;4CGCBy~e#lC1%81QrU6!Pz@ms)Ct_UYdlL$1?n;MdF7thqJ92c- z=YI6>!0YGwqGOM;I3YeD^f?p)TNEjGc4(hH>e?Khk-yac`%_Y>{NFv0el zzNpLMA3pCn?Fx@g8%12&c$Nn1@{4NGwIY$|rw0L#0`Wq)3{Dj*le7c>*`S=&*Z zvk9#FT0mw`=dqb8%Z|cN_>vfB6u)&i$VDC?Ep&I;S?Y##sJE!ryF2}*p)Zo7=dXig zzhKJ+0W7j`5OL`-SIpVi4sTxhycmsq$pKxXCZcQo5T$JnfK{Ecd~E(vq0o?JQ|q7b zs8a#7ZtQ@O$}wbVL;;>iwe$=4d~SU1DZzbaCfcogm>U|Bz3@}YP*U{L;1Nfw`eiS>2_!1jJw{%`SOG-~-=C|wprVl+PErn@2F z#HtFzGwVCX$JB^2he1PlQ`$(Yq3e>*D4eUyO6QlMhyhM!lGUI%ae{hDjFRC3* z^UoJeW>STF;qZ+>axeE2&RGU*YR)PC+L1!$(hNPctLQK{>fALvXBM4r$V&0Tl+D=1 zdj*^y5kyv&lwsQo)Vp!6fV;Y^U3bfPUo@L)?>C>>%1lyofe_VaWR@J&DmRzF95ZSD z#;7djaQ$ppF&#v6=Bl*;K$>Vq)>J!2N&PXh9XnQp=XXZ>LI0Ena^;*K-b?vd=e~UI zv`&Y>nfi&&HfM6X3JmdnHL3~Et|xkyWx^{K@8ChFIREkVJ~T$&0pwom%L8ae zt1KV?^er>~gE%P3Tacu!P1tk%HCVfu_GHy6V_fWpww=xA433Rw{z&+uoOH@VwlBjT zd*fiTYy;`Zkrm|YX2NcTKH{4mf>e*)0$Vno98Ji^dWr!sD^-@a*4~A}B-X-bi)d0i zya;ph%h}lX0sLb;1*zRWhuoe2;rZYtA7mz;#p%_@2rn&;gX4LWlWeVLMwzUDJ$Fn= zN@F7qQYeC9vYq5ZO1RM3@;PgzGB-ny>eL*RtYFZfh>Z57$Aa?;_Jwp1?|IOM=I7D# z^m+kzv2Q0fx#EMiQ9qY*v$@c@jr!W`>q*az@#xk5O>lJaMY6J+;(3%0`g{K$hR=HJ z3RVxBNyMF-*v!HmO=u|OeCBFk%LH!}yf=%hoANO|WpgaVY;GWGr?k;Q{us2r4kByp zN^sfyQ*6dkA3mW(21(ksp~=1nNaY^-{pG#D=f7^U;`}0fRd*%pc=I~{^H4D|9_xRoPVXN5#)ereSQZvvs**EBHk_suB*o!v=QH~u|!1c@73QbadP}zH` zZ_j)!=v0~yYO&_z;IwA^_zn-j>$}OtYF@bITn_wR+CtWT*@m9i?E$5+g@o-RxXo9< zG6PZkuHjeFnM=c9-8c(!lll!0esn|EM-*}o-}R*XZuLQ5X)oBAD?bG<{B)t?uLBuv zUWIFo5WDA;HSaz3i=g;IE(|kkB`#wlk@YEm(A1OTCAy9Z#hh5y?MyU(yLTk4TD%=j zZ;c@=&1#!I!yWB+F62x$*$9NzGtig9f4H4y8v!j2rNsS1627+J1LXgf|ljEnByb_qaxD2O@ipk8VG+a|lcPOz%T!JEI{=z2EI*;aJM z-DhLrrCS5p=5zs@9L$Fpr@ut^#S)~@vIVZEWyP>bv^a6omk4W=NO>f_Z+#aw&}P+TL=-7 z-$>g~BDO#757uks_~y#RXj;!~2;LMVnm@~4xB^b)OC-GZsK=ke3hLT-hE6q-kU zC6}*ca`Q48gkK-W!cbO&h;J+HoDBLch^Se$;=xaEVS8Hxsk(RoPwSBeS+C0?owH7w zAJjb>ByXa|3E337(cJ%o`#fOCWaraMIsnZ^B`EG>|$SdY#nx`<{V zRdLTi=WYc#WtfE5$rQqO_fBHCN)Bzem<0W=1Igu!pK;0>9}v>cvfEaLf)=3u$qk@I?fZwLdSMr z0FC3CS%cIBW%*>lG=6gJex6HIBiFN5B{@kPB zjr_f{xNG-fgl3A%fz97fETrh3QM~||@=o&dWVp~>`WgHF_}q-61K(h;%`vzrRZJY+ zFuo*z4Q#@?$lEtrOql*yNWXZ1m_{|?YM>Ngy`-y0eF zNK>9LfS07Yg2szhGCKSgHn*J(3fY&5l}t7MLAx7HxzkL5%n#|h`Pmc8&BImf#J4t=J7$eE8R|WzaUe7PKbl01@x}feWX2!pFpJQn-H+w!JHW&No3M zxuX<&+j*m9RG)T3*FF2l1r{!XRWI&2a|15Tt0&FR+;M0j{ZIeW9sR}Ef|AAaAYS@V(<)YzFcY{r2AlU3fRKZ8yz{4&1FpaDY$W82TJZ-A{ULS@P3#5?4%?geu=#pa~ZM$ zooXSsS|1`yH9dB|^K`&H2zzJ+1lXOHt7WBVf)r5VPx5*kbo6Xs7@0 z|2=oRLj1rYx|!UHzm{Hd!3!;)KzmQB6ft9LfJU!(;ucn=<6V=|VZxekMEr3gKJjN3 zko!R*tyki+0V+$$@VXC*gk@v#g4F!^sM!L(2yV?tYTIF}1$ z=Iz8#@hG+%Ee%HES46lc{@NEhng?kf;5cF5pf_^b-N5;W8!+#enZtsEv4kI)k8ebH zp?d1kSXL(``21iU3at3YQP+AZ7)7~P%xBuwe=3XPWY1wzC^R6fSZ23UiR9<5T`b44zeWZxLtwUU z8~HpY@3n5V7drMdiz`;0#0Z7PaBP1NQUCY}SL^8^uMNk!)w$R4dENEw`^E9R&%0)% zwr&|rxEMqle9N$AK`@Zg7GkF@&k#c|^sY3M<17uC>hi15()^4V)a2r%MFQ6G^eLW; zUxqY&X2E3|AN_wVgik2}!EIg?E??4{2(tp{cy8Dlg)GX z;~#iMqPOS0&}ce;8@geL&-T28eF?opz5z+BK0DV(`je zq_g25G2GvTFSPp8j{A1v@ofs;?Bs=HCuVd0mzLsTvNQwAR-3PTYApD5DF;o==F6tGw&y{o#n#3kUfL+V*lacki8cYC}(p; z$uYtRJ5{hS)F;Eoe!?y7`S5FgH+fSYE<70!%i5aF&DiGg4GQNT1=UN%WLXHt`->N| z!?pzSvBf7*@BT3$pLl?@nKfc-DQ{FUNPR952ZW!Kwz6hpe0fGb86}vhLWiC{i4i7Z zWm7A5&Nm-^WzSM(9`&u{Je4L_*AL)fny#SquuatWq`!F<2+J;$=-?_WJnM;!hS3hh zx9`)JoZreGo9fHY*j4N-eI1wFImu2d^5xHk$|7yWX0&>&1$j1-exENM zuxmjt2_L^0&j{6p?2*^VgZfh3GK%)a(9DfD6ODDwXnVu(EAgaaLJpQQs)o7E()`x> zB}|m^GMG3an%w_Ygy)`|$c}RN;Ike|qqd1W;&1)K$-Bna;qX-2<7w)S)pmQK659Fu z?Qp8Vmv$&S?mIxHJZ!?bUIa9Zd&#Pc8N!4gh-LLHd5eHtq&0pQlotNunHAwH*%7h# z`Shj>D5q2oOg>wXz(0+6&y*0b7~W1?4k+MzZJw0h(w^mKy#kMr)iC($5($`6h38lZ z*n`G4{9C?4@N!rdSlw(P?}Hv96w85ziZ<0_hYQ#qriQFdhnCnw<$-(uLgREjs)JRC{%YQa~z z|3veFN|%f9)AAjWIg*CohiS3(z5cwy+l#1*>i>K8Q!mxxt5{|7Q?S`kPqORJVkff# z=uwm4n@252D#D#`=9>el*;a*1-A01r)+-`D*Zpaxai8>sIJ@*UB&`2N9?nn1yJ;5vvJXK-?t3{d^S%y$X=lg$ zt{y=}v?t0n%HnDsGzd*sPJ#{%md@^4aZC3b;3qc`vdIF!SuaKV5w3`Q$4^{*LGtPl zIkQ+v7(d$#rkBN%pL6o@PRftK>;vl$_qyVqV8PSd`WGDrOU2P(V)>-3$6Q5y!u{gi@#A+l({TIrM#QA`j zr#L$?l|@t|8a8JsELXV&;m4cEfJN5pWZEP1Aei>1rA}o2&M^j)p&-(~q6GKc)kF8! zTX82NZr}@ADIn3ej9=#Of&ZJyvU_S`d9>vRDz{n+Gi!o~R&p8MBMgQa7u!fgwLJ5T z=BvM?yfMDdfRP_|72eT1nuB{THoVNTO}_U0bca>w=9igZ_m&m$#?Et(klV^}*^(I%4>x_e>7Pg=VQFK z{#%sXdk%j0UK43|6^_NSu`Y8n(5Wu8CGroNt8|cL$u?nJ;San=JNcrhjBUlePzvp2 z{61|dUP#Z);X(9Wcwj8BoRR}8I{uKmQsHPx&vlrq@SGed%fg-;5GZKHkTYe4xc%OJ z_&NG9^hE|@s_=Cp^;Nz6 zh~JIQhnfCe@iUE;s7CQDMmSap?2yK zz9fG@SXpVnT9|nAj!B8gIz$E1Zfzze@`>2?1% zNT*S~L})P1v5$ZQmu2~-txCwnbS518?+Ur;TZIKfRIm6ci|d{IA^qd!>0tF}GkJ99 z8eXmH!j><*%MTWhN7tD~)DITK=)(_uZoMbGZ~sY#B`?8IOax5ZD$Cd1(Ls_obYPvu zKm1I3<%z!i$mZ0djdff@y#rX9~1+tSVapD zeiI{&7VIVH2FxJ)ntSo$ifh16Z6NQX+_BhLFQjrjheLl-1(L_+fM4f7{JeY@gZq;n z;&h0{!+v4d>9LmlBEwu{a$_fiO)nz%e-Iq~-zzrRa&CrAxftjV%7UThK~h)Uh`;=~ z4cq3llmAo|u(hElIzac2X~n&Qjmg@e6>(XFpTqQZS=Sf;W9ho%YW)6qk+NrGX3NM3 z?YhtTJVI8ozabeVAtZaWw09bm?9$Ryncef86YWxIlR_GVM3eX(x8HyL)vNA3=Y2lo zJ*=qT+1H{AJ{j;f@e5h^CJf0e5a6gtn{Iq_Q{3aO$KSu0NJmW{1t+x(plWC=F(1UV z6;?XD_DX*$-NLlt^QWNCkrqP2I2qya-y2|7Qb8(xQ*pr3BKYdvj}F*A7zr~pVZj|^ zNuTbt4TF`X7S+uCEwb%73+G>2YRhkIkJ$U`5zL3z+TbJ^uJXsypL*_`07H4koK&Hh_l74(?$u8Kc6ep=mFCBD4 zTTf;Q!v^#dMZH>vx}1CQcC>mde3?^COva_+|6Ge9i}By?*AGT_yvDFT`Z789tO|3J zTtTY5jr{7LCn|~YMDrDzg|2&bT)!Ev@Fc&46v{uvTeRI#TX?oGd6)g=( z)mg&Cy0M%=*EYyr<}cZWwQF5RvKr5XhQwxEx$hwijay8&RJ-D&48&KBiKE?98_|)Y z3xTNn6ECLmJXwAn93Qt6>CHpA)nna|Sr5}STsPn<_u7N^@dRRYCI_E7&oPb02^x5E zDf1ki4%bA>B)hPpMhZhaMKpCpH0PEZhU#vNCgG>L@Ld^qI9Aq3@@9Es*TL%ir%WHJ zwmbsOl6FJ;O0xvRa|SrH^8xG)X(wwh)`?TA8PC7^5arxopsnaMe7qkZ!P}*ZF}(a! zrSu%BR(n+#bH1 zH$3G+e{H@llHHdLhU(I^t|j3#fK zMn*fdVWl^h!DdSXS$*CGe_|T34CW{H(tu&_Q8uH{+ehZ_{)7uW(!e_X2g#dF#Mvh} z{z>tEn)x^fZED{LE*oDmwg~$?(u_cxqYi0SoPt^I5$-eZUzY==Up@?>cSxD;Djs-VhjX@<*woAoZKB)6i z7Y@^(Wv9_VR}DCOc9%pqaa#*R&lhcKzWa};BZ6sT_5jv3#d8}QFQ=A8bUz06awEi7d z3H68i)GkuxaxHE3e=GT+(%0!P{n1d_gYd-7i~BJ498xQ~ zC7fCJ39q+$49S;kh{g5?IQQjLu-@uVYVs>_|NFO~n(fQR^_S&5nOA?D9n-nIZxFBi zq5ztEmywXFFL)Q5U1W7K&&l#VSp8xjc&%e6sbdYRJm6;hAM$0*XtAn0%cmaJEKnCi zZoR@T(EA)m#I`KofxR!vJF|s6!+xTNbv)90+l#T&%A3fA4 zk8WCwhWOIUWVT-wc8QYb*BHCd^Zag3?w|{_uPY@raP;~|&?WbUEOxcR6Pj}2RvF98I=Tq$5IckFAsISzOB}w&dwUdal!l!hv zE27p}!hw5ZIkR6|Av)Th=qi-qOIt!w{JCes{VmNn^@t}N?K6;$9lQy5+p#l$&0oUl z3SAupx@j!Oc3FSU*o7VB>OA9aGHrLI?s5O|N46WnGZlgpY1N) z>cm%%sPhy0SkiIrFOXUv=5_EZfRwtF;aN0_&n;IxpT}&@TVsHP~IEb zl9|5>n|YSJSLKuC7=CIOp~Mnbbf0nCd2~M`} z$bs9;hdI3Trg+AtC|=!1Dcw2XElmHh4{}=mkD0~8VAs!mmx$ zzn1@I=S5ppQqjP8MQB9ph|H8^{K#T2KYp1TE&n{1vt~Y`a<;OP`KMQq69lenBhmWT z@TTKaVa*IX!Wq|M?cFYD_!*Wb$ohIUgRQ*XssK8$e>2M2rU>a1){*8n{&-Z`K7Qjy zcbYq;FM9RyBii?|7bg!~af1sHzlpQSVtm#}3k)0mi72@oA7LKU)2*_FL25=iChBg` zN1RADR%hW5wm%xlJRel1zvRpw&4>A__sM?sLOgsWMoSf@6X&_@SaJ7d__L#tsAjof zUdI)EU^FA@e0vtols?T6UsL%?)tK{3QuJ zPw?rZsr*k{rS$)fO2G^jS-8R8%C{a(_?ul2gfx96pN$9O{Y*VGt--5B+PtyHajH4wwMeV_1x!ILBr_%)t!#J-R(e|0?bHqNCX~v@ZdOX~yU-n! z9M`~A=UCz(4654meLa?{)E6mz;9rkBd61$_RID++44{sl( zvM0}>H={Hl$$@$99c{#m<7D|i_D(dxbSZbl>NE)5#gd&-Y^^#!wAGK!@VJOpySkvg z53+=rlN@mPse6!NTu*Apox%-7hd*h5g3hT9N8M!`;ChY?F&$Qm3vLerlO=W%Z0uP& zivLgUJk^q$C?2lAf`765I(1$@8a~*&p!z8GK8BCLE`!$dX3Ko&HLY@Ps>vDD^X8Ti z^sEV|sXc-ru{A{Pa}u7*d<>$``IFA8m3aL%Bl=`SRmVj1?P~uH`4) zi=$rc<3Q#4PB^0(Ph8CNu=tWI5;MI?h;u*DMO_{(Fn5;hh7uHG;6Y?HdFhyf6H7{9 zftoZ83mb;&*UH1TKCBKr#`5XRM)6&nTxh@x6D~d28NNrCk~@8#;+G#>P@@*(?Qgyy z%848V!g3%vYrf%Q-%=sBy_uxFJcf5YErEhr(sX#G2AbyV4Eo#q(TgY^?~S+$W}8}x zu{iIkN2d!4HDbS~b1e7%?O?v>tQt*l3gO0%3`PCz(}aEBnz4bDCvaH<>9wj&7;&k5 z!X~Bk;mdY`;_mry?Nx96SuywuJjnb;DpCe;kt*!I$FXc9ll7d%3oSnDs}(i6rh=Zj zOob8C^vJ}XW~|j9h7?_0Dolyw7gbYEHNFt`L~kNFF44;YYWY@{f&usMYFw z=;0JsG%m0gGoRY2^M8^oX|+)Xs+)8Yh8G5~p1lm;oe;%8xTBN~>%XIEv0Z47jv49u zrU}o#;|1Ez--)W}L~Pim#Y>w8(0zx?(VS(jXhK%DpcS|Xr`k~6!EMe6;X|8AVWSBnE zKr$C~`Lu_xS8}6833EBeIA=5_R#wvE$KG;+E0!H(>6TDD{lzjqc3C8yHs~>0^Joeb zdfQ26q(e8jp!-a>E7>L8_d%)5AEQ)yGPi7%A{=)zAg9g;VC=h>-|p&8D}VGs&7+uq z-w0E3<`B!yd*uO1*3#7Hm>QmOK@+--10*xjPp@21Gs|J=*LS;)ILZfUF}=K0hY7d& zsw)_2BuQ{J{Y^RiWjp9MVTIhYlgiLweV>q-g;?}H4cRT7PS%yR;rriw!K1o?99ryx z{{%C>*~T2p};c3S-Kt=9C&{MRCxlozlz<2wb2(j}YO@7(^4fI@7K1CfPxa_^!bth+C^c2LyGBRK1e< z>9dv6BkQF3k7G}Pp3^I`S9pefma6dEFhfoI?8KR<*Mr$_Q}8Rw~w@{{7KiFDtx=a2~yO{Bz^ijb`ERU zIsD~(QDnK#2Q6iD`vvb#Vb{(S*njv7xpn&(o7)$_>5ae1q#;XDnu0SJj*+ET8sqVM zw`&mns*})+qNiJLx}bC0S$>(xIPPPJ4{}|SC44p;j_Tg%e(LOc`X<0wlF%bpB<~sQN_m0%f_;hg^`u;2fcL*?KN$w+|A% zXI=`oK8WRCsq^0DN2yQnLbQ3xR9H1|xnvgVZ}bcd59-o&c@bRSgSXLpG=^Lp+l5D@ zID<__BMBCH;mE&>`3r0&f6DM48a2TM&0{?Oe;lX0WN+le_@x(LJxp`_c^nRj0?B~5 zQvCb%J^oOwQo4Uj3wr3%j{F16Nd3tsyuii-jAnc%jUf}T;nk)51(6^9IIw~PvFr9dAgHD>SA0*Z%k$0+@_{s?_uuh33Y2pH$?f|^X<_Nk@K?VI> z_!{LJEh1yy{J=~*jIQeE2;1E5i#MtHpgN{s%dvbeA_>eNiR~{&AN_z^T)wB>7q+)?hrt zy%!jdo$*ooH+ZA_`&q{5E-7y22Ob;+Tk=7-2LD{Tmroq;L04-jbGzc5m}iQtWS8`< z$O&FncafL=*YR0Xmi@OTik``Tj4paHe}Efyq(`F`Pe0>~9%E|!A3%!CO0lcq9{#o9PV2J!pqM4^(Ub+IWaZRGEV|ZsNrfjwsQ?% z{v?5(+x!#BaT?I+96;tqmt(_jXLRs$j&LH&NJq!X8_k}>`pV@d+~AKcF!pK^87gGq z{Ll*MGG$yiy<(1sd5|dd;%D6lFfXiRg#w>XwF#V+N)8EMf= zZ`9z&v}3E+Ve^ouAb7SDW@RZpecAw?EiWXo*9q>ndB9uxE2UrTBL!Qp$bigqGf6Ev zV@MzbtZyMzmj~m+DbA?!QZJT%8s?4mI%W!Y%jRRZ^5?MXSSvZCbq^^oli}ALa-s(6 z@5QNGAMjQjYoBw$H6!jl(hfbBMfy=@@M5Ce+H+!Z+_)HDj-P$3#(*FV9FheOl>#j5} zEori$9YO z@_TU7xxZ-pYdgulKK+6p?0F?e`)pGbYi{8A)5ekXXz?gm-)#i*9>tTAF|5wt>%y`^ za)qr0{Y1YVIn?i>vvBG2C!BR83cO<8k{FW|tk_rxO82Dbgr!5#3g!=Upv<2XG*sa; z*Ztr#;|woqtq~OrVE$b;WyJK;6Z~)y^9R<=6=b3=idGbOp~bT^g)pO&Sb9MU#4ycQ ze%vv4eOz6pd`a;hI z8STgwwr7mv*2{P!1?FEWZ#N7dVqRTYH|j|?$8$rrGY;hhv80#p{CFQmTP&c8k&c)I z`@!+Aa#Z=<64bqG9+2|^5`L-C&}-1y(?v9X4CNA6xFFH4TtRA@A@_5%H+t)tDIAS^ zFYbflA;qws44NOw@#m(%)qBe&yZc1>>+&*TdIb=Kp@ou0_LB}15dAvJA&VjOrzGkwPt4%sp-s;*5SaXeCrkDU$Y z!+tPtmfJ1p)}S^taq@mL(!U9tF?_fb{GDtLnt**QmhcM?`_ZShMW|}13wo-UCp6fr zVCPUTM7s70(KX84zXlao$%->;3ESM&!R4xP5 z)Y`~_qc_AehJ^E%VwBPq{i-3RXBW&4Dq^1AV(jvl=c@-t(-(5?=xf_x2u?61dMp>r zXSoZS7Mv&iIk`{V_}CMzEX)u-jr=1Tk`Hi|38}UE)!^USdw5UVUL4+k+7W3K$dc)# z3&+1QZ>C3+rIIJ3Z@U8@WL6lFb%JXN1l)v z`&1+~+6#q*W(va#*5HBb;$X(JdUEeWvUp(qT3G8?NDey?e1DHG9AfAB(yEu-jmON7 zWzv4K_-GT3u?T>PvzZPzeK6j~vJBi=zC)*Rhv?z~rj>}y5Y9#^W6iyBu%M!z$hpxR0o&@_JhucI*s>af`ai#Kv-Nz2JGCyPWAP)42s1TSM}Af^V(%^CnRC)@Y#{mUkwlW4Bz9Z9YG_j)qi9$ZVx z5)-kD-6TlR4r25R96{#@E?hB^-9x)oM zwk(%mGIuu(lyyIoj0?N*$Y(vsbAr8OKJZP)7fN#F=&L@8;;fl^yv61idS&t$NRRsu zjM?rxUN#S#jb%M!Sf21*Q&vH@Tqro;<-4Y(V~U|D{XVdumZWWj%5aN@Kt5Vz5a=IEDlvxeS6Lledj*+pHreVjAg)cZv0 z)4lN2JT3l8`W3qHLmaZQa6uy{=L_esA(md{i8{|`2y#s+X}2K`2FBKter+NY+;9xi z4hE9)iKY1C`!Ie*o>IEcsut92_Y--k>?ao-o3N{~JGejmPN?4m%xh@!r_Kja(ZEV1 zJH-W6#penBwJJD~?UN!VX9|yV>U3mShDe_y^`zmj7h2%u3t{UY5Y2BH*sMqcR!PN? z>*B~#e3nu-QnDuWoA zlE))H;ZG(nU~(Dr0+PQW7S4q6z<5>~6^6HC+f zn|q*mh84t(>8#sKVDYj*(%4pleODp=;jClSYsx$BO7~k7SYk>-`Zi+x&>dp#^`#k3 z8u%4bgP{3=lG*I!5iY1zzCbWpxKl^xxd&>S$-G!c8FN!2ong(z2PExL7B){Tfult- zG)AqE+jnvfylP;WTvmvmF|PQgN&V?&+e@6|;%7)Tawf?g+KJD<_JVfJMq=sdj4jw_ zuC}5;u&#P0TDZg$4SAj^xL;U<$J)k1EYI|SmC52$j|-vSwmx(s-ot!u)VdhvN@wjUhW#ImCJ8)=7bxg*(@_k!J-E!ce-$@Kv;TF9#6AjIty0oKB|`& z84Nptf+Oz;FKe6dpCb=o__$gU#wTJA$B8Txsu!O<5XpO^jW8qX?{I~%$rZov` z-SvSUrqS?tI0Tuf_`p4jPo!nn^QVoCE@#BOYWvne zba(Jv*3@8B!eQaiiDqnZAR4sZEugu6jyUO-4+O36Plr5Rf({zaVfv;(iN?0V_6lV5 z=_KZwL%2cH*}aI(6qY@EC$1kB2Z?(76EE#1Y-;5O zXaD;_`b?OJ&t$LVe|tnybKO=HoIM*XPuLUPS+#iaC=aB&I8(6y@j+*=w+|F7N+vsc zGH~R1HAr3^C-FCUCus7o?U^QM^nA3ar5qj0RUsPz(pk-P zi)?L__joRhEHoua!A-d5V>(!Ow~+_KZ-_5&cX-c4rSz^hZ$SIw4p=&=nB=RAv0Jw) zU#)eUo;7wr30nq1KQ}W8CO=;g1X7;$Byp}SR@3xA3Er7PazT%1Nj3*{zILQOmGi>L~pvPQU+Nbtwxtt zm=UXyjX3j+2i&mfM{lHS;hGnE{IZ*IG+L^K@d#8Q|8$^aUZGLtj`p*9;Leks-0Bg| zaH>zTq)rYNzk(t2`_U+sLe4)=3GCBi$)Ht*II^6AjExqZTlRoc8u%0q{N0PmsS~}x zgn5wO40XmTJ3Nrvpe$kWiZytX#S<`J-A%4)q>DfOT?J*cib(DWf-BVffTg0jWGbSq|pD@nrDCd>pmy3b?0qk)dhcT%r7Ubi3}bWEMdR-BBUCQ>q`s#8ppKK`z9U z)LVYSai*U@Bk?#r<2Q}loe{@3=qsh`4U*==6|G=!cQ2N@E?&gT?DV6xBobv9oIM{T*@;=4~(01@vPY z)pw($=(w=!X=4*vu18s&fb+I;CcD`L=y0IKQ&G{*19>pNm#;zcBHtg31Cw!A*#7nt z9=JUTzW!HBUbQFSVZjri`%8etH)cb^IDS3j*V#2Va_{b&gUQ$=5-OXd$@>oQRDspkTUno&KvW8HaauqKtdIIa$f60{%~~DQ?&~7_%U0WG69FGT)RObhQ?N~V z5r|&*rK>%Mqn|Fr;B#nzBwH;oA`RX+tJ0In^4!ie2blS=oG9cy!DGgHAk~;mNqyU@ zod9aLn#umHmiXt;LhyRshaOGPK&@9C;RO?&=+z}*HMUC~y0MdZ1-yJZW|=1MaL}7> z{aT79DgFD@dNFfi(p989N)W;en{h#1Bt+IMpo_LS;63ocXU5$7T(|{D@DoYXr@DD;jiI84XZuK{u9|6GP@n(wA|!78$ood}OVZ!Gce2;P1{$pC{zNsH{G&~zui642m(4ehov^`I=eVO?j+w&T89gGY3=yOh+mQzUx0pol;=i%X4$)a< z?w7O!$}f_W?7#R9CkWaoO`E^o#*4gG@VViM)bcn%-cb`6U&x-!5^AtQRS0}(_(sm; zb&A`VAN3QPOd;XKM6PzBF-!|!cgmmy>+Eyn_p?mW|BNRh$b5|shL}m}Rp}K^m?mfm zJv`|=zHn8KFZdWwjrG5y-DXR{Q7TBnx!TNjqZ|8vA_^bR=w?51Ll@^~3R4E`acZG?Iul&iL9fceIspyzl>9 zjZd#jg$mzxa<&MId*t)scatn=qcmSU>!@LKDw_^HOL*^WL^;61!3aQ z&M7eE`x>I|TZpeUG{SE~YwDajjZVsVb{+M;?tKl@zw);=X?Gu`oGlu1xgnty4P1wfCYyrrjy*RmSraLmp$rLO;j1nbl97o~# zcO^4{*L7wm!_f$Xs+qTIR@FE;8#k&k<^(eK3zz@J34;Kxq!hYc(EXU7uh4FB<9@o+QP z)h3YNDY1knpLx+tT3FZgm>fI+|P8U=IQPD@ac46KvbgJae2g1@&XrxMEy1C=RbDmb3Tc zCHgPnxj|n#piqNxZ7#uklL1sGIf?mu_(Hi^3(0fMdg@oJ!yB)^Oz-KxMn!wvQR`He zQy(%Ee_Aqt-{+@ELlZ+dE!nGR3-jvyhm&?F5_(=Nq-J@J_>Fxmztu)5J!9ZbNSUhy zi~Ry6S^&h(;VpI!$&&uuT(prdslG$sESL$g>)cT>^SSzmpX2FDe#aOWYJ`>{)vihK zc80#Bw)}Rs0XmDV=$)t%uI5!JGBQ;lKcu>_@porW4yy*HdjVR;i6wqs4L$Y*yap~iFSUJ#&rahjA zhWLL&8<(4t$4rNwW#kU8S*GeD3q?HU(j5q%Do5|c0n#^D0;yPgqEl0YFa2;smJXSM z-jxqJOFDk?sgX0&*JfwK)BwhDy_-x*pJ(98wxzH*p%+Wv>=?_R+~7*zj2wn4^m_KxV|jQsmBI8 zk99{s9%c$FR`iHcj76~fnH_0d{}#`P*~R}F;zh6AQs(kM+M&g@a%A?1ZhU$d+pAVd zQ+wtE-+f^@zg;PbPQFPPZ=Ly0+_Wck*J^O;>tHBnK4V&*o#H?9+>rQfrf|b#BIl{T z6YBd0F%Rt${Qc1-{@$2KYO;JHqCYFqA!0^QRs(if{s@c@E}=)qpTnN&OW@VgAacIA z9FO)7gxpI_`#UC1oY^QE7Cp0_8`&o@W71&_@866>F>sH(Gt1mP&~7nIL(bhwr?At`_Ks* zaXw#cIdvI)kWG-}l;zyL4X4h^(UICAoXOy^==^R=2^Z^xmn%x^$Pi9e-4#F3*ud{` z_NJ%xE~Bj}li_dP8X{f!5hbdCOWF1sOyAH?QDh2c`XgP$dAUtdOS|31V0 zV{e11y&V1YrGZ?%vd}E)C63o6Pv|YsjM9 zc>MKH9o)%2M*BA$M&%d!fqtjGgm2)x(F-)X{t)|hp=l?su-q=gM&aQsBkscn1cj4> z$lG&exM3c97dB-J@1o^JhF^~{ProphWAX_r4M~9a5w)aHI{}B>9tX1m10_1F;L0)l z8+lh+JI0ZddSMC?{z;@NBL}B3E!DY)z1Zt}hvgS!t|ZTAf5r36AHiJ1&t${IU3k{{ zcI4M&FX0>f7m2~>nik#XzfFva^!THmtOnRM9<0dIS;Hy}zI z&3)u5;b@urgu`jycapu>p3sI2SR8I^J?#FrTynSZpt@dm< zs=4g|2FU~H>(V6r%#r1Nn8?xG-S3{hGt%TW<9(^!&I**_=7vnoS#57U6sP|hz%Tlv zO~)ICa;pYiL4jgHvJ2}dxd#f>3+d)?N9OZ?pO^MjO5gKv2dp193wE)(@t>AI<2>_% z*d|BU&1IedQX6>nnRn^Bu`^lrmmBI+lqFd2c_+3Rsn3_LcBRP|^w6XglOQ#*7l$FT z5sa9JWXbjlF8^5wT5PXCQms4jCMg$I5Bwy#RhRL(r?)`gLXK*>jYo4|j)WKg?I*T9 z4cL+84h&9Z^BFdST@`4+FWB!zl{Yt_!S>9n+-5CV*5iXsS9|~%XT{!~d8lS*Gtzc8 zC$e>oc!;+vEX(U469*{bjL=)K*jSEk*$k+neI}?O2lA{>EnZ#5yvmPcNordAGp)RW z?5y;BBj(Rx#Ju8F)$VV(?duCy!SY;48uyUcbzhR!<#p<~ldkOZc zTN(2&$9vQCq4T+~akj|)cW;lM&AimQe)OgIP8jY>#z9(LFW#!1xeB=E8!3v6HJ{-aFgOQzX57!Pps~!gfRdxUZYfQ*iwwqJaw^a$&`( zXy@u#WZK9MtklN?Olm%nyWgF0ZLup#e3K>2y1N=rGfW1{Gacla8x}j{F^qMxq_szL zSw8S`D5_*S(CGx{Rz&l*SxV^xFZZC|9e_7!ZM$AcycX( z8jF&U!CY6Q{jnEgi}x(&^NzdFp*OyX^s@@!;0GDnk9&Zm-Y0>_N)fGna8s=G2Vk{z zf{OVz^vE{8veci3ZoY!re=33t z(>Q<5eTmonu7{fsPSWD^>72`vXnq>QSfxW!yngy2IB8Wz{&BaiJ-G!s*}WKBp#B3n zZRAMx)gSoKJy&$(T9%+Nf1|j3h#~L)!kcQPrlI`dlfm%#TC%(>9vjMjfPojS=|PoN4^wN&^}Kj|!+R{~7Y7pSib`z0e+-|L=SttXIC7)(_kn(P z5}E9qgI71YqG`XgguGHGk!jZm2-v1i%r(B^Y2O|~%K?^A?zRgbi2jKzr#MJ3R;5%7 zGcB~~YQ_J=9!!5RX%6Gy4fO-hi5p>)eIiK?WEqG-A#h#w2icA%aaA`oQ5@$gMEHNg z-o9b5`t>_vFf#>LvMjTC|9J0aRk-scX8uJw^uHzJIMG=<2p(A}>G#Lh+<+;qUBv2r zFn8>*D>7WcIKT{7U(SjIkIZ^fm1u?yr)l#gPRHnlZILM1#~z9c2hbz&NqEl@Kd^h; z#&j8ZPe1=wcsK-e5j!t^?3e)gEc`&QJDze)SB_VS9f6J zlKE8jumfJ;7tPOeP)c9CVh5-Unh6&bgCsM7S)qPVF56BFn+I}zHoGEgwsSlsUn{;G zw2>Dad}($5dX(%v0seejN!nL5<3GO|;rfEJv_Peb%exTTC{r;ONX^T@7;q}|KWWakLtSM6m<=xga zf;Da8=bup0Yjbj>v=K*7b%mtvPBPq15nms03obKlNc1B>(?8B&Ufd4k>C+l~xX2aF zEX$Vcu+A5?@bQCYrEjjwg0#n;p!_(6a84OmJ3$2seB#O5Z3WnDLJ3MxSxSESwPF61 z8`D!%Nig%&Kv(oVJxekN@P9fBvRVDP=0qcoA0WWjk)7mE;&rjj<51qVQYpRp=4J3SQM^g6Qu@X@J!tjt9u)Q0oSb2Lu|`vGIDfd6EJ`1Qk0mYT=P&Z1<$Ge#@`o-c zg7NBSw9La(LJj#RO1^a7fj=TaGaDW)?L!Uc$D?|qD846?&iQ=;kE2Ur4 zmEtd{9|YS+WfJYc!PAJZE4@pPhkKw~;_qmcFGrkAf8Z6&Z+Xq!Y~kdpjpE5C4EfQ6 zeW^~X7*!`Jg86Qy`&f{G+n2wCHOW?V-ynvc`F$b6-a*0>2)n^NbN+r72BhrZMs?_d zfol*sG_4GeRB}aa2HC=nj!~ixk0a<_d6*#E?-RC&jfH$#OU~?#$1P_SpzU{{WL~=pXuYBR?Uqjf{m`EzZbMdvcK}`Gbm82+-=Z^l?K!=H| zgrlW??k@AodPnkJB;$R_s{GPfhvkq{Msnm6Y)8YW_Q{20qha2blF3Ib6@HIeL< zoR8lI1U91x-+uFo6tci31HV750xpl^Nsv_mKK|qt zGSyy6zT33n6i+t@`BO>Uex%}Wvs{tD&fdRWQr!TiRoChutA<<`H_i{`CosON&Z5^q zT(^R5nq4h2o^~FEw#!MfZhw4pf|$&HG;!NKZ1GD0zF9a(`uB+eK~QbW zbVE8F;xTNRm8_W~=uVo%HHL#&_Koy zUwt@7vK#W1*WkGyN9mbkd1&-D9_Ak@mdrng502zr*!v=t{~LktFC^=AfF;N^V!274 zaPDLa$^CC2CXbfzbxuBX@PQcQ&Ahdp zFuvM^ulU>t-EXzTV{klPe0dBsnFdL;{4dt-hV7FdkiMf>1~l7`C&}apMGa0Ox&5gy zkbWTx?(D+BeZHfk=N*WH{(I~<^(m}w(xP7ZTg59{lliU7mC|jl`@){=_29;Ii2r)< zoewWV^yW`w_f`e2;DH9}AK)g*rHz{Di}Dhf$Je}DVpB_1{`}N7d)Lk5aHvS>P@vhG}qWdoBc&pGwE1hs#UIcF&qLjWf zd^=21oDNgj9r@>XI%&HPY?f&!{fq~4yR5y@WycS~@ibHJCgVli4$2maV`{~l5`7V8 z%`)Yu`if#kjfd&w`owZvGcMP94~~|nXumP#T-C8Fs9^F~GIo9^e)P^6VxM*s8|Oeg zzk3;$2>*!beI9#2?PqCvK4%72tXjw4zLQAB%D>SEsp*jY z&VdXMtHG}*^KIUcE1WR>sPp544@%sXEm$8o&K+Fo0kUUPN#ybjT*EJf!lkSi+g*S! zE-gZ>!AprSxeaR#cZKOeRfNZ>xM-LQnq`zD^vxoo)}21+VRDwRp?DR}y8R3sH9E-K z^`YX{-@$x&hf=!g$k*`x;UmdTKCthlE@=&x8|jTMEMtD!V}jEx4{hNsCU{cu zgs*7o4+MX!n6{nu;}1ga@kwu)XRPUObU&#JMWi1fd2Wrk0z5$da|?OAc_2Qeyo66( z;!B^G$DsSI&gigDj&N6CJNHRGDB?+$FiCfjZp-HT(6dp8b{kw5hj`rMFT7MrA7AYP z)pJF#V|k(kOH;?|@dNKf(VIRT!m{!xTJMOkIlqtKKa$}R&Jh9+hKm=O_@L)wvL#sh zrg|ZqZQM`J{cXg%3nO6MK6N^M?GI6v#yx(*1*LSa*uStLW@KV*-zXLoe2`yKme8(uSt8AQE|}6bI|Npt`>-XT(8XRKDjh zI`Sf1GUxnqJ_Zgby(3SBI9&L0694(ceY$f`IWj*w8v0%il4$mQCz-$kzXv2@S`L;y z!*cPqrG2?^S8^BgH%E)dCxtEjEID?g|d=tO5=Ba zuYchET-UwN{hsIh46dWg32h5{D@-@36o0? z;I`9r=ldeg(LE3ad#Opd%}*Ila4PCIQ9BTb4ZW80(G@YYeMbh;JfsA={mseg$Xcw; z^4>Y=OkvEj=SgB&FLak(zuD;V+==A}pr|H@q(8{Rf?heSI%r3$ou;9)m%pOAN9JS= z^H5(cbc1!Xq-l8GM7*iYls{M&O*gFTL`%nvhi$X$NzIcAJeFw`mr606aQIiFcfOuz zZBUwUBkCwO>y{flZhB6FMX7j4(+GZFU=)40M+W}3Oow8trxKnsuhj<%S+@D?sh-^M z+#J-uM2|fB*^YZwJHw{oB}Dnnb8L|2gba>n3Re55=tH9?3S!qEkhU2Al6eCC6l=+h zXTD;GtHJz)Zq4M4FNq}Y1Bsya~FMZJ&9)7_hN52 z(?vwd%h7P32RQq^4``2jx@i1G##WMIp| zktunSom8J$5xjMSW^zFP-)QlWZd9skA;ITiEH7^J;}&9lUI92=U*Ip6E?{nowx@R-|@E2e{4y zl6-&={|6x5JfF%g?Gz~|-Q`2<*sMG2A9(!U2a5bB@=)nDF3mIM^IRh6Dq|1im(hqu zDkCB~){3M3oX{w@OyT9?bzQ{IT;B=*&Js_n$LI zJ)@*xG-prjgi8D`&{jW7W+H8sT^h8Ls zru&&5a_i1Y(qQ)(kBJ*G)(MK_JT!k{F1{`kT ziAKCn6Oy7s#kY(f!@y%TM7q9<)7~o!erp5Bo-0N8$(FOAGNVK?1OJ{F0u@KQ$>_U5 zoD%Dd=+EB4|NUA1xgN}Lo+_*wzChft;4wTsT|=^Oj6o6G&p_^A1zPtx25Sm>JlyET z=aVCyQJ*bYf}x)hHj3~>>nElQd0Qunem?a>tJftDG;F__F$S-TcQFaw@>cj~ec>g1JCOrU^BQ^3Py9+-}bApKn{t(sI zflP<9l%E{+l%|!Yp`5Nk@ZkGFvSfcP-p=N zWRVT?C0QO%6K1!XVi|@H6B#~Ki+sgp1A=+KIOZi^RSa?(YeChwK$2nAb;buy<;qf- z`-R+tgZ*HBWG_DB7;jiQqMmGSJC7fZaz@!(vjlawf1>T-%y+=@*u7+?;8k-UL+rsC z;x2X*r6e9l_33iNdgD+0cApd6`5;eco{PlVOamV`T#nvALlA5n2E&)wOSDzTa{XW( z!=lo{PVpz^k=$$aPFTEUG^fupu7B@K6&klHU`6+6m^!nTW#FviA_u-lvbPQrgQK-r z{!1j7q8aq+8*AKn#2e&)$!k7wNBm$NfS zL{tx&G^rD<+G0UQ@O5|=D zU6n38zdXbEPE`Zi>}|@9>XPG?ORqa0W9rXO4)DA)&{! zaLXUyTihaPR4#|wKMg^a!;cB0jAVrVOPtW#h%6yO_n!FJY!9Tyyj14t8KO&frUPc* zK6M?oyZo-qM{N$L#(Oq!=KJpOk64D!kA}ZscGV1CCw(Fz<6mPZHZu9PRx{( z;B(;4?Qnf^9BKTPfwxyXp?^N_1k=^dBKp-GIZR9wj#pXWz9*yM{IFV56txi#boqwH zjT6?=C`^9@fO>6oHm@urvF5P;;U#$ro^$ujU88%q}NXMBZnAgtcnLGB$H#pS!} zBgKtwl8l0-V?9v8$uyx|CR98#E*gFvs3nV+b#pQ%{o&lH08+K5h~@gefZ52Hs(e=C z9_pTfeeESA*entMYz_p^j82laDv-P1>4XkEekc5&S8#y1Bg*`wURO=TyAz|q>sT$3 zE**o6@G01MLV>z!Ji~d)JkvLZ(jC(qP_r8Akzsz5l(ouuBkMY8Vz~z+$OMtCmLF=8 zPmyF4q`_?%en*c^ZFRzK>=_&XMl-oMaSNnB9s_sw^kQ}YFyQyhi==DTh`D3?-O=Lu zYT@mDGcI9;Ga5QOTj-kmMXWrT`2sGb3G<>oMb+okq2u&&;&-YEqpl(tJ;9F79h%RD zX8WN#c50GNmb+a}uyxpZriK~p{T)PNB0u1nl^#^-tZzuj@GOz z;u7m*z}nh^_-)#(ADb_n?UpA<|DGnfy}lFgDPlfxlkcSL zsS|b|GmE!l*`z|k6{M@820AVlqt!a7U%CX@UY|hzifKyqe<&$r{F|>8!j51F8+E z&znxswDxe`#aAeTD1rKx;~M_--)=dt0A8<=N|n49;m9T9*I*C*}S3^b3VbK zzqo-sA7+DV4cyTSrepVsm*%Xdn}A;X74qvv86N!nBRDO#rbDPD8tU^GJ&x&}Z%b$J zy!6ON^h(%hm{dI%bnSzP_nZPe=-_o&$Fk6s&8Bk^r_GVwvwM;(tnE`Cz?=J(L^>rJ zPs>;1Rm4$r%9#SRVCWD?niwR>BFIqL25&FN5%n(__?jK-v7O>gT@{Vc&Oz>|nCaQR z-?6}06a%vhzmti(w_^vhdQ>vro?Psy#Hl+Q;L`;gs%qvYR#~$YZmf?%YuHOog6?sPZr^*W30zK*@(K$SL5_zPC=Jt zDYD}!a&0=($^%A%fBoG=USJL?S(D)c#0b;kxCOZrr=5B4m89zS3rO9?wCOMD$ z8-5k-2~lJF&@P;i-~{s>q-fB_5PZGTl($iTM&}()N2v(|pg_ffq#4%Y>a6P!W!+4? zk9-urJ>`aeyQc|VN5*m;jeA(9Mld<){Q=)QRSbW}outjTr=vXwJ|pkj7NlFR4x2u7 zg$W1yQmMGf__e_EA3~z(vJ35KrTiG^qP^I-rB4uC8e30vR!NKgcCwt?^{k^L>j+o$ zjOE|%dLiK%ZfC3VdGDg=@g`}O_dJF9ePYPrx_3Bf8HTxo=TUB;m{Z%BiLR{EC!AJ0 z-a5_^RGySdJOWl0h}UFYPDOt`P$kQ+9zxTE6Sa%*g(oblZRStXRCiq*u*aYGkkU$a z#YIdbzXGBseF}>IKg98+o|;A|9Y)%)3px zO4kR*BhzVaNMJle%|0!h_EDbKA7DWL94QyQx@L{u%gal4VOs8v%&V?Q^(vz9+|5kO z9odVYze;`K#e!B6d7x9QafRatO!KEhu2&=9kFH2nlj&OZ6>v@DO8!=~J8fS4mutA5 zg&IbflZx53c&Ob22rQXF@4dCgx9g@reqIon{rDrUycz&Uk93n-pUcKt8<{ShWqWoX zD-vI*(txnoCuGW!9Bewd3FJdh(cBx~IG=IRsH$bMq?=p$og-9?VID4)x$4t7gZCSE zm5#o71mjGO zR&+$pQi7i|Hn@Qv)4uk}AAm11U-pwE#x*@C$NJCMu6!TUlFipK9(k;TkE)!M+#Fc~ z@3{!@K5j@YuU{8e28Z##@3Xx|t`iLYJP$e+JR?8%W#R3~YW)4nF7#8A8d{||7@e*= zCRmP@5oA~U!j#g_Bt1PIo3a0U##oknygftoz-KD#syj%Od~5N?w0p2n*O=O}PVg|F zFn;GPHkVHR3oQn_;nUngGOa8TSK2c!@lAweFLw5P9h#y7#8$f%|I7@6tS>CPUfTwr zj&?)A>?{ynD9ss;}U7T`LeDT5>{!ySOeKS4?t)A2u zlpiM>i$nts!@wBB?Dhs&gniFs{tdvZfpNQ8b`@t2f4sx)_pDTYT4Jxyi5{;l1 zobt~V-Q1fdyc=X9p0jKf->vRJ&0Gbv$M8H%zpX@LbzZPemKx|QZ%w~tA4kcjIo@98 z7L9sYkCKiq1fKTd?f%_v$gn9*IMp*=WOm*cEq>UGw+Y8@fyoy=>XX2He{aHg?jzHd z4BrCd&WwV)MM1=5Yav$uuEw|BbD?fCg1M|!?nvIORyZ*E0M{?x66}KG$rhD#T>rnO zo%tO)q&!91>S~}Gyn+ztCcL|@0MsWmg$Vc{CFKyCbba7>W|_PHmvhSHeE7{D(u(;dsYV%wY?v3 zS#~~jn_E*?*D1*3R0SHp%z`WwYVpKXFG2aKE}dPn8)HMBU+5D}$1iV3W)DZh@??9W zG`s?T^9h87f9go>L}`)EbasF4rU}XK4s%f_T|oEb3vyy+DsEe#%0FS}or0Ir5EnKD z4iD?aTQ8>ddBf?GaX;Fy)=LM7ur4KYZa>F%gE_uB-;d5@=f5Wln2#Wp^*CoO!ZW|V z1YOe}LPp&b_v`WFL)d;t^>PuEOj-dZ+8@c`(_*~vWi+qtpqV`2b6+t2C=IXjEXayi zwfNs)FZkW{jmRIph)?uIe4UR!^||r_DKn2r$akIhOSi z2YIn60n8sjHBkTV09P}4hN-!2Ja7F7G|28=yDCv*=YQ9e= z%dQ{Sgs$G057|EXd9<$EUg)-O|vBCIknhivn%6jy2#hUk~$2}@W{#B!!_3equ-e$~cr{V^%oep(5rg*Pw{h!fR` zD;LiQp9@QZdhzzQt13T`^~+>FP(zE>Dx=sN))F2-W{D5z{rOCK&ctIOnDyW+W0~p- z8KOELZ3yMeN%*Q-yzB05c*Yyhy)!#Rsv~dl!1mOCpZ$SnPj|v0|3XswF%c^o>hV>( zZ&UkoF36^`2L0rLJowUrHI0JcT;4abIlu-#t93<4oG#%3&I|<*+uDKTR$Oye0#-3G{^_2C{9RGdy5a!OQC0oXBz_z|$Q4PE1 z-}#j|M57L7U9h8%l-$Lwa~|=A=QWeB&hduyU8bNL7E3-Szr`DO`9tMCmJPUjG{=wD zMHegF1b^IslXknJcR$mFmIXJ(G-EY?X_6N`v?&N3ESCn?3g%(&U|IdE>YyUtjykhU z_?IJ(!{&lg5+j$0=Ou&#W}5asC3m>>f)rS+TT15Yx8T?8nnT$&W6X<399qerb@8Bc zZwu(sw6h?ar$p5zy})6~Um)=3G3vANINI(L4)cs<>5d(XP{#5FaBe^dL8A+>KkJja zb~Qtg{XRid>hFU(%Tk1n#BVr!YAC#zpig^ZoN)BETf9-3W^xJL47-_sJl80g_}LfY zbxT+VxK6#`Z+nnC!aC;sM?NRFW~F1D<9qTk<^R53TRq$nbr2n7&^B(8I!Z2(4 zq={v5c={kYZFOR_r3=4f9M*f*^S*TY4g9p9A{4h+5cRRO*x-H$XlFGO*^B~l;8Itl zme-51Kd$Y9ijH24O*G2`-*{WPBVHRhW|tzaUje4)sPeY8s~~yBh!V`1CMYWC!8Vfz)SLWT`Jz% zK9s+h6GhLsO2ZFdO?dk}MsoI7_(R}Fl`);UEt%VYAsvk%`jYIdyjk|}y0w(7-uoO& zjdn$QUN9{#n`1XcKZo`azsTYz*TtKj`tliLw36=_6@kpsrH~T-QQ~#gUlYZzW1Qa4 zyL~~tLJCg0Sdwv}wRp`U53t|RNQCkWxHQ3#ui*XYQqAW`li{H)>mT`lj-7a5A%9QD znO3|V%Z+$+7|lG;i?JIkyy47uHF~!$5x+k*nE8wx$la3_xOt5?94~4i&TZ}DikWkG zlS$sRPi-+;DdU2soJkX&zmdlsd*u0t$Bby$y-2PP+iR}M?VV%2t0G|6x|y{9ZENiK zSrc?F^-ax8C9Aq>H?xZ{;I}Nii-=>73>un@n*VYr>&~vnslpl@9 z*ABQMk$r}QYt_$$gv0HV>^f}NfOLRNYs$?R{7)%953{`?FH#->UmIQ+z(sBmRC zGioUR?@JVoJ#!D`yzfShMh=n=7o&6vnkpQv`1v)-^R*uMT?i(7SvH#Tx)4~`)J$Gi zOy}-&??W$Z?@RcBH)TwRKcR|j&U%FBkfA*N!`_ALe5QjN1jI9l6!k5_W-Tv(v(l&G zpQmw-r5nL+Nj$N=kbw`_%;l@b`AE2eLT4A`!Mw5S>&)@4BM(4{bsxXCSdT{(RHN2- zd-9;E65mj%g}l(?wDy#{cyw|kufqH?BYv^H(4a*S)euWw$G&9;$*W-Tx|8_)9m(yD zoP`Dixl8!fOCw#857UACKi{@bSi@Hy@us`h2BVCxQUEgp$>8Bd_}}(g$ZtGOl{YNp zZZEZkKT>599c+D37#vKHr3;(yaE94^K;ht0(l@yo`(ATFQk$8tkj=MRtdB;q#*=Q5 zrl^1YDcJl~i7Iy_;KEzgaHP$eN_{_$l%9kED-EVi){Bs~t_cj<5kjJd7T|Hr=Vhgl zA>k9wba|uTQ*VU0;%_)CT;vt9F zdAO}naF4U(Gjvfi&<_^TWwH$x*3S-lwhFW-niF+YHM&3b`+!3C{nzi)6=3;QqH!oMyEVCVN) zT)#eMhL5gP|9!(OvqjP-Z%g5oW$B^hR z)6jbOGQD&cIcIvw_?pZr-lOmiJ)}Mpk~X=Z^ZPOcW3M7{appo^|C$Re+O-nhGE{}n z$Dfi-C^UriVF(q_g1)J zu4DXj2lJTpnVfundNJHosD;aKooG>Nx!4xzL(YO&$)4*~ev$0c$ud}53krbb%toT^Y=eap%xl2rrT_WZ?b|u9 z)N&xcm&@>s^(uTqZ4`Au_t0mMY>t8cO_CAp8wn*I_=yRZoi2Wa7*$5SWz@kTVXmLKu z3t^eYxk2QxQW5UDumPrAjwjnTW#Dhq4fx^P{AgMsheDZ#{Ktq4VgG&$oRateij?Zf z?UW68_xLJw<9jbRYqaknpX;ibyp(!Dv*JQ3vnLP_AOFr5+-ar#H}?r2oI$b$k$crxP)~Hm7UBGH1>Fk(&yxY z(kM13M19~E^kI6!HNBWQYNj)skMBnVcizM_={fJPn(YWw4Pohbd5CrB#mrB)gJ7^+ zGwD8`FAil`)OS;cF!I`1?&rgu@HRDs{LTJ=@uXbPk+-8UH?%(ukJ$wlbun1xC?5^%@FdfOtIGwZ+=#*X7cm!LU1iz4Eb9> z5z#d<{=$4irq@~T4A&Q|^!vb`H4 z!enmU7JZoapg`iudM5i7F65k~_wwhWpH<(`^G%0{GO5LCC*0uP!+#{nMH$y_W}ZQl zINAkys4tof->*54^Ha+4mhsHraqX=jcS*4*d#|CeD&Q*VvZX z@Wm-s!pDw^NduehEFZfkiyOCW5E@c#E16w;d_6(>Qzg;viNjyjTu_+DTj5M~hG_56 zFtF)sOdlt7iJE_3<87X4CbxwChI8Au!qt)@a;P&A7h_#Mt$zePz zOA9WY;SbvT8_AGBYrK{Dj830=E75Ds{xO(uY>J{YUK3e(b1GMUa4%{;{XpVl-9BIlZ#wu9{brhvUK}3) z@GFQs`B8}L8Alq?IfrWF>72CgdeAM3C$6h9aIM>Q7(T9>7*7r7d@GoicrNSF7;A}t z&-{$)l^w|c{OXDp=D%R?PM)I|93mz#@>LwmsDFz)hkApQaR*U2G=lTXnT6c*JcX$` zO}L2p1UKD(E8H>(6^qaLpl6C1f`?tcX!@mp=**Qsf*T5157be3VO~bi$yb;}{6$?O zml2h#&Dia=Gny{*R)91U@nk z1aKwv8rfc3fRBE0MxLU#!pe0ML_-F7qw@pPBzyd2Js}`xsZSkNIAMom;QQRqrT63e zgN=qdC<(!2$;d*y=0ZArQJ+su1D12PCZ@bvN+i8>N(*K;><79xfvj7cj%ST#bEZGj zLg#skVy}851;!a3I=&zOoj#a%o%4uxh=!sOWgaMZzdG6L*ogylo#1qQe>zho6f3Qd zX`z!eH=Hs%L~bOqzOk( z%i)s-xiEg!DY{m3I*L#HguLVrk?5FO{Bp-L5RaKnBV2Z2k3AYNK*N!|oL+&qS%*M` zey8Lt@63EFeP6wm?5BP*kH8V;wK>+FFMj<_nP2oHimn+T4JjWdK%M_H$ywfPP%^he!2f({5_qG*Oq(>TD^QeuZ78T!J|&8ya&SP;7a&v4(ELf?xcc4q(0(UPLR{K# z+g@kTnfaS!J9=VgYY{&#=q|0k=8F<{4}oD;hscfzwfIu56I#Ze;oFMANqm|YT019Q z2s50_NpGAD+Q$pXkU{}FEc^`P`W~mDw)*IIQ#}fIKSW+Q*W&m`t`IT554DR?#*>wn z@oO(Up>786P}1&6aORH#FF4sF6?_AD>=(2SH|)~*<2J}_Y&m}7>JtQ*-AQG&ZK(47K zy|*H3<{4RkBTd+zy#U8(HN)KRUbIhtLr&2%gjZm?f*#Y~(C77LSZPp9Ml>g4ohzSF zlPpiZmp9|-Mt;!$T_Xv#vBr-BoKfJuOhKBL;f}2LLMsB&gkuLL)8aR3uqznlmVM0FsV(kx;a1-&K;I(2m z(O@kRp3HZ%=Q{JANLk|b1M2 zL;A*M8OrPT2c0^#jM!Q?<22T#k~k?-*uH;(ct<~PWbT{NTJ?lXpHHU};(?u+w>I`0kz7f0QXL0mrJ^ud6tF+xB7VTxv zvpu^fpI=PDcV>Gcbq%%)J8Nk?==cGYeY6*QE4H}9{Qz}(#UT+})((W`d5#k79iHO` z<*XCRzM)loNZScLPhj7L7YevF#S^9KvYZ+F*&>%$6n$y6AdcNN7*Dth@wIG^x#0xf zuQHMO7p_VCupNG$;1|+KEY&Xcv~rAa{@*C_^8Gs^D#Fm+%qm*={r<3l(Nggx{AP$@#c)ti9D4 zJ-Cu3l&+m&y#Bo>D(2IL{h?PlN4^p~Ry)(z_shjGp(FUu_EGd)kR04podw?6v1GJV z7IvjRu)bE7TDb*sL&gq39|qe=_Eyo=?vV4KisTl>;gHqNXtrIJF!9q{QT0?$bZ0Bu zyQwa~ix$@dH{OFD7&VuBCko~<%Qx`o?183Rn_zfTG5KWp8uw$KmwFXB8Wmc_{V=aU z`o26_q|$=d4ZR9`o;H%OkH>I1>)DBF%@lms$#6gWc(M#lrlkp;gk`2G@#XA&X}%GG zviG$hi~f$J&8`yP)lC95bwqF9{F*fVkq>P8AWP>CI*E4toB;0RE1rW8LA`06^mxY`40w5JMfPJ!Z(V@mwV^^fSbo;*~+^4azt4JI023vvGA zHIR1Wx#WyLEuC=(9$jRgS{OI5(g{UoW(t9&mW;pkMD4yzGxJzqyjZUkshT>FZ2w9; zV_PIVBZhS4=XK)oDiQoQw#!>P#0!S8G5Lm3Jc*2YixrE!AUmg%E{F66JKur7vFEtvYm3?ACOAX5J6_`yJDq@=_& z{JLJEqmw+5Bm0IP$}+=2yK7At(j*{Kh z>VH8n)U=a~N|hCD9pj9$rm&8N%%hz21*ZMppDOJBnJb>vF^Ja_qNwd-DHy9Y9*kc+ zBk|b`pG%ryp@$uPhJSL~3JCK3sZVq#x8j4NFG7q?IjQ{^kCPtg@j6n6_V^QG47fj!Sk;*lM5fn zfZpLAbWqWXTw79$A1!qTr+eSX~J*!&3^qBjRQg&qcS7$jvYM?$%AU31v_dBc-uRE)dEW9=HDT6Xg z__+S729LVngz{*XFq{iXs#@iNL^oLnLGwgTCwB%6TvtF6rVDt~y9#jWIz`9l%tZ^V zYf!}iDqFsGP_wOp5P5@Snq(vnLtihsEF=+ z_2RRej63*BR}(pL95$cAelzWzkoY81w5XG5AV;y?_bwA0T@}cWF4j!Gc&`U04&Dff zi%KLu+}(xVV9NCQj(e-P3$M%2)WS8n`b4d7k}&p6WT0ZRVBuV0|JCI)|wKldnnBSg$MYBS$ZN zKYebyIcl28V<+0cnGGU1Y<`{14+XeX(*;Q{%MqH5CyU19?MBdeOL+g_HGbGX1d5{O zQ}<#QJbk$a|1lzpzH}}@kvE5dn0+h%u+HWDT5qTq$S7$l>_+A;~r5dg`?>0%MWN|=OOaVu@)cM6A8LEXV4J?w&L59ykW%# zIr@IQF$#871*>dFGGCzr&l?v48;|vn2cr~3h73bIV^f8}R=Hy9*8}){^6WRSN7^uh$}y1iB|Fj&rh&y8^G9vLUMDn7|W`CgHO&j zv?|>gIrMa)zI&`lU11HLQ||=%)=lKa;0w4dScjKB?oHFQpP6%+Dsff{C;SU15`mb$b-y#DiWO{_5rm(ihsuyr?$ui7$vB zm=sDsg#SQC*sOJINRH5d;6S`G-5qtatWm>cT~W|njE1eZlwk5z+b~!@O^;slwZk8M z#=*q}*Cc$!!iDZI*|U>)Dx5cNVA=i$Cw-C3&!(I$gay1Ji;U9nc0G6W-9Ak~#r~ol z1Q`__8RD*ni5zTU8X0|4}=M-}Z&P8(f@KO=>U2 z;m?oV&<)lb;_b!be!BJWq{@p1Of%rR&js+WN;Q)|FYE!2N9&>NZ3$7`@EXtAU5c8O zO(b}`)Y}^dEp8;W`;X!SU32-8k)Cu}O&ofW?S@b*>#d8Lh;JSkz>gpFh*r#qK=IqZ zBk=-9a&$^1o|M=CCjxEgk@L#pOQq8x`%5pzKC!tD8b$v||AlinMT;FMxZt4>H?p-jEylsL+ zyS2P;5Df6@CVP~^xLXEtaPQA*Vt{{O^&4*J8S91I-91~ZIJFSv+B%SSgG&7R>pfV) zatP}`tQButa+_~tT5;7Uo=~DDVtdJW^2FdRw%IZVH7NxOdy0PIlfV5T-}?*sUHlZw z#JHnC#z$FQ$Q9KO?m}{AK@u+a!}16i6*`})yQpy1A1uI)uOLz3uW)CWG5@6KK2_ha z7>zpGg=}suBSjiNu+pS!kaC*c+refy{G2#v#I zcH$1?h3tWx`!9)8zYIKUlp){d{*QHu0j=56dXydR7$wIas22Cqo*gE@BX675!4jvKn!kS2tTmBm(P z75SqKKj+3CL09|dBI$)zl9|?e!$Xi)pGgBvw_+2U;jp#IkqpWy$0?D15Wcsa4D0A8 zvVZT2#(Jd+7wLO((k4azg5o23VV@KfCX9w%tncan+12WLBaE1Of}S`0#cgR2BeUak zNzj*8Y;^Dpgh^G90LOTINMjcN=K57Cci06PF-~J}k`*cbSc6w?azk6p(j=HUu9amv zO)Vm2He#H#r53JdAEQ>IjZmUZC)(C%MTU0N;FkjHU9D*$<8NKU>ql(hPoI5CkIH{S zk(;K&rZh(qxUmdtvyAjWhcuxtSQxK3z8hU_P$2(j503ur48taAQ0ujcI7~$mm4NIDT<$DDBzx1G%fN0BxsGviI~S95UVw*_~iH74EY{_Wnso z>tQcW4lN7?_d$B}f}9;{Ve=WgYkGv4%w;iO`X@N$S9xBizk zRLLchAd@t_bS~==@J|y)y7`NgLzUolO7HAC>GCJm9cf4Z&Hlpi;&9Y@UrWO4ULj6U zoFYZ%1o_}e?SsH*(qRcst}ng;)u&sD*1b6Kcyl*YTAU`xZJfw`s+RW$sy1F{oU0rmy~$iNzkOd_hJOy*yP8#M7sP zhkq|--uo+u+OF6M;W5&}bKVs$#a5H!PH|WjHqnaqDzfZc7ysA-=G@sDiA zOHO$)%x@&N?MJZN2obN9cMH-lOj$n$>U@t-1CMopo^} z*Z4{-JH8&?tJ%_b9?D|fjAX9nVMYi`R!=p;Yi8;OM~f|&u8>v zY11DCUY5NVpI>}HyK#R|5C@Z<)rHvDKOWjQ8dJrEx?GahO1S$pzqPvDDTmQi1mMe06nJV-Pnk}AqXIyC* zugT7Fua0{{T!|5!FOMgLe~Z_QaD`FN+sO)db#9@;JXCrwSjfBe2hSPp52Jp5A<1u^ z;$5+B=&~vEdJM`HRSoDs;~)0UuF6~P1NY3Bu6G;G?Hpweo1H4iPWxAQTg`laPE7=L zzPS)_l^y6K>yMcKs|l~!6AT63-^kR*d+<3^H;Gqnmv(<{?3N<{_A2xu>pMuepvwPv z8AZQ@JwmMqdEV)KG!3-;g~)e9@cw+A#BD0T`3j-To7PV16-+priEe1j=`>;Gv<8;r z9SAmK4QODN3wAoA%ImN_dtqZSvPLT4=N>|~?)`*k?kPIXYy{Wvz~QKOxTO9W`Bk(;zr{vzjIpE&L~4p zgIxREfyFh^yunG$WRn^5!8eY1G)k;UVn7YvbN4EQnzWINf%)PwrHH441E`N%0}^d< zLp$Cu9;~51KG8>!pTfS;H!mDPE7rYdbCDJKWmJp9r5-|t!A!bp!&ba$>2T;C?L_wd zEyrdR0pNP8o4lMQCt7gb6)CW}^nZ-KR;j>uF-?oANDA&A91X+0dogzIr6zbCbBe~q z{N}7&#c1WZxx^#46$kd5hGWAkNE+*;`1)ohpL**m-L=yN-PTfv_GBxf^STEAN78lp zQ~CXIWED-6v?toK=W{-fh)PT4+uqwwQ%iDlvaQ|N^+D=*{2a+7H2j2EbH{A}oZ=0o_!4fr{G<{b9SzEgY6mC`pM zTN5S8?(CVaFTBarpp$ZP@Bx!SkPQM!@6~6f|E&MhL(=tnL|&R4U;6Ai)i?iyl(d#W z_kim}CZPsz%=Ski%q!&iLB}GlHV0WY?js2o+3wOZ8pe;+r#ICO;^iIV;n07P#8ST+ zZ&W&mKAmV6Bh5qH*>qR9;+aD_78T;`v;HVxD0|NtuBMv~0ri?x^7PSDd|SPoX(nCi z71YE%_lQAxyMh2ZZtM!fp-TQmZK(R=wJaQm1ONqWFIitm>p z^5I7^vNuKaQr90fMHGq!Ia9dT*JncGrD}5glo;<{{|Xi~9i_H0hRA!t8x%3XiQJWE z9<)UdA?WXX+O27W`5Bf>Cze73*Oj93go!YDg+QVuKu@ni(SmOz{me28DSdx*K8n3p zU8lJXlV8FgkuSZj{#v9wZX`dUD2YD)rT~dgXTq3A>BRU!DUL`H@{U=W`I}uHqLB)U zXn3)QxGP*nJiy2g+#bCp8oKGY$jg{tcH$y^r+fi9b@`!Yy+U!C5|3M6Hi2SDAa#f{ z;7n-<@9>%Zj-r1;SjY;{JY7!;momI%&%eu_Kl0Wf*qrea)izra&$3V0>h5`H54JhWn>KRS4#Q0%>ODqfvFkoTM|q-E7{D6O~yZGGfJ<}G`J8)Vv{ zZ;S^W)G z-;KX_`l0#kfB!$mmLIA_p%wk}s;A&R?3^c{>L)IV4j;VEt1zEw37m)aQ>IYBH1+{A zO7NpEhWxoRx9G~n&p7D=#^}+YD6zh;l=$taPzasUN=i=O!(KQ2(Q>A_&GdS15hwo@ zJ?XkE(ZTB7z5%xEB7-h3_^Q<2=v73zkuKb3MS}q}%Uv}Ze zD(rJ;V?BKbw&5nGjjP*GBtE`Wo_l<3KPVfjP@O^9*lOxXe*5zzN)HH8+v0rKpJGmz zomJ00`~djm#mTgKuYuaff%s<6+*2zcz@MT(>>IC=IP@g7nnR$lxbe@_XA zVcMoNeWO3VeOHZ-w@IR}m0uys__TiyBFIL|8mwX`hL{4Dm#e*m`}H7;cN(pkKe+7% z+zs6X(rVf4tSrJaMi}#(r(dLNR2QO7=FQ2vUnm|bw+&zVP!BcV0_acUPVU+O0qQf; zAb%phW5ehO*y1&rzAnwhX*o&!{6x)s+1EyJeZ>G+>*+*>9AopL`$brJ_Y0}mSRqo2 zGTJ?f6T9F|_=W2~580hsHiF z6x)n?AyU>;%ZxY9}bw*?1N^cqo%41x?xexGo=TQkJpEu7%4&8?2XwnzFTJ11M zMK+S9D>5+X#)6`c0#%szi~D+O6gZr5A~VC<@DP@BK9TKPk7pjpTe`>`rp$aL*{S{9 z`4$}CxKh(#Q{>qB1!*63BDWYv8s5Qj`bPDTE$h$VvN0^z_ml#ycbtlb@0$tTHUe@* zuK}mX`XfK4J^26J8~SAf%W+d8HT)*pF)Qh4uoVU zfn>iH@ZAqS?(8F*HG4(-Sh}eu^Fy81UW`&a7s2Y+(PX+*4PJBH4`Jr1NuQ}>5xzPb zJu%-;PF`=ryN_LkS@-qmpjjUH(ED-FcO#NGaMf60sVe{SxPV?Y8)zXa2|zb0I>enS zhq+rPU0_#x4l!O?i2oS)BNL|EvF!@8xG;Dy7^>WtV0B5?bEsY5M#D3kxZLg6k?AyT z30L6x&=-ES$x{1^p?KJu!O%U{Suz9Hv%P~+Mi==wELEf*;D=P$yZwKB4)dG=sU|f9 zUWoB;?+Vz0JZPt>E-FfGM9tg!@p(<#)c|*3p@WBeO^6?DNG|nKJ?WNe-K8Zig zd?ofXA0q9y3TUy%A<0fHnw^hYg>T8+S7~_XSwsFc^FzIY^Jv3FcE58k6tAlRytb_# z0$tBhrEWbg&@GrB|4lPrVEq#cES5vrpL(*|ITy#ROyb|L8Q8#W5R9{}MFEo+NM_)< zfq_t7^pRvaIpbMPmi)|=2)g+}KKjGn=TmGaC>_o)d6Xg_!TdGbtm4qDo_ENe-Glx= z1CN{f4%%!F(#oyFMQha9xi&RQqLo$q6a$BY*?zE(<*53&ER6hng?x~&#lqBgFrn!n4Hxg?+`X4T{J|{ZdAbC*b;rPR z_DmbWUGBv+Iq>UVP9~4;!kH8NkP`bG{@bN1I{UU9m5uk2%)p9`?NHz$pi@IGi4-S9 z^9fHh^J9jb2iHX=FvhVTpS@S8@mhO)X~DuoE@!F<`tszeI5S&X+&3l!c38JcdTrFN zv3FRzNWAjFM~jbySo@D3I{lzX>})2_?RVY_SJtY~Up-m4XNVe4CkkoGSt0s~L=a|Y zLVpFQ$xC!gZaB!cMUeD4HTb8p803eU(IZB7+)BHLeApz-{L`^Fz<%0BkhjeyIR}}3 zOklw8*JphS8?4ZI_Py6Zk!0?5E~o>>tI}5^yEvcXvuNHD4YJw(JC-@cG!?~@>5S*O zc*){Byb;qG7Ka*v|5X_{r0q<0r?z3)A3*@mzmm%L6{6Gg^?C7|3$);LBXS?@hg`N5 ziO~spe6do24|yP@UIJ%y>|ZHz(Q=aDa97kFIHhMmG2Vhp^Hg985lHrB$4Nf>C za+0crwbf$&@Y)y}{Mi^*DYyx7CCG+Fn-&6pMl-tIxkZ*#Oy{WHQ@ zPGsxZHXM-c3*D^y#!bc>9~~A0qEz+{+fPM)XJ&x@RRQT_KA<%#{7^zyKMo(rT8E;J zD@pi=DW}gum!}5RYt6><%bQ_Mn>*cKeiFqjQv~0e0tpu(`soiH_P+@V|0$AbzYa|W z3RJ^(F!jgM>^g`(Y9GW;5 zF6Kp&*D}>ObhQfqAX7jW=?}CR&vGy8rt2&z2>7)?J;c$7tu1q7q*>|qv1b7@o+C?sE_Q&VaoxR zLH21E=@#7+z5L~iYV(T3N$;j`JLhSGD(mh2e;?xEu4ka`%=%tqb-ynLlR)x2F!m>Am6<}7SHjH3*oG-F7FA~3=#^an1bM_sGSu?TNf>g=T(@#UMy{RgGdi7LdsipRoA$Ie4MnN!G7$ z#x>as_(y?J)IR<(D*x$=>~s4u*>Q&g-;g4t8E@i{$)Gmmt|1_D25+!cdphXn04=d< z&AUDB66jj1(m{KCP-Lw(nA=5>N1rS4y?|h7*XkvPH|B7AtN%k)?n#oJTF_#qBh_Wu z>5T84zD9vhxF)3IgUV5h!vOG`96{#1tHCWd^!cIQlvZ&MxbnG+;bJk{^&BZ-+E+_H zZb>{H;J6C4?UMzaT`MH`+|G0+z&zK|OLaxHrOy%3^daNtyuo6G27Tz1tqSUtFj{OQfY^G1F~su@ej&fQ(u zs~{Z4zWhiQIc~)t*88D5i;E>Q^YZ<>VM@3Py(E>5_ob`wfAobk&_ReoMiZEjV?j4p zsOSEB`+!d}(ae7$?F!p6j9_~8RS8E?y6iG2E$k-SADMG&Qct1i>|F63sd}8)djS@% zHK2}1eef7r72au2679M8l4Z{ig|O+7609Ck`+$EmS2I6o^9?}p>w)*mmgsvwhF*n^ z$X+tq{0^6}+7IpLizR&Tn0s~5&hi{i=XP5B#?6p42S$>Zr( z3j9xB=4YAhj64pMqC!0<2}j{L?GC8w8&JErE!gI2A|K_;IJdZ6aNkJ<9+e5m+gGpg zuH(UQb6792@s_tJRawN(D7;ROY8k@}HWM!JEEc!vl#4R76!^65Lh7g@4I70T@L_d2 znNm=OS3hlmlkx|tAL->3W@n>SErvu}6+h;;?IQu+-q?HY40shJAQ2;&Pm^QaI+KgVr?%`h_bd1hp}YO~ zeACDqt{&5%+pcEgGP!2xwDh1=)u+&~;|j3tk3f>6xQOl4Vz2)p#yftA7RXt{!QyL@ z&hCMid{Ne&V)2;@9gE3RGLeq7Bbk-ghL0VHfYI@Kv}4NwoPTEw7>tf08k1O-7ylH# z&$OWBD~P$b{yFs0u1kEQ;23A(-~=Y)^GL$OLR|TjX|DeD&&Drq4}zHF`w|_RLVP*A z`*oOpUD(D|JiCh84r@zvXb0B{pr%fa{umvG=S3+&>n~>lkJ@mB%Vkhp^O;OExi31( ze!r7f7K=rHrf}QSHKAu*E!n9?u+f0$aPo}@y`iOx8aLOYMeN-FKX-AgAPu&S*QGVw zLTr3DgWv1LIxd?L?7lJ%Zod^se7jehA|d5P4@q9O+#=+ZFIviS?ElXX=WH&AW#@gV z*PD9LALbXRWIFJ_M-?Dtrxr~4lR?xpp5WCm&Uqj^!ee7FVat4fk>b2%{Q}di0vLcex~sf&c8iJt>yH&UD+4dZbd8K`o<5) z>R1B80}T?LLzH6zKZ!lx<9FL7 zsQCob?XXUtlQmPB??9d}C>GK`;y6??t_4l77D)DPH^S0@*?(y0($+kc^Wk72twyCQ zeNa}178K?7&&+pjIw04IejL7V*%$p5_T#X|cR4;YhUq_T%Td8f8IX2lyP@CAV<@A? zU-YMR(a#KS!3SHgn3*k^lTXO;yzcOLDwk@H;=%{O%lj*c+51ks$%JWx**pATn4YNc z?NfAVsSmN8^adYI8OV!A-k^#<(nS~SqWFUhhgZf1g0ZI|+ z+>Ew=QRPC0Z-q%*6A3QM!s{M(BkwtOB;#-wJ|lGr5|q11j_h`Ph3Tt@v){%4=j00W zogm0ip&{*ASk+_%|9+~FK9vVeh4QA8_~AOHe9lO2LEb~W`6F_8&ElZ9SBpiC3!WDYEkfNS}##MpUCB>`JzwN z#p0ls+i;fuOL#r*Jgw~P=4uy&apdw=zF$P*pTz^2drbFyMXBg~lLK~q+qLOWvQA$plF z+11jBQ{VUlrz1rj;{S+rEfzrUrE6sB>k91rOn~eaOT+;=Iu={qGSERwM~R-{`;sfL zPFbH`yKn%XI;8=ZY@#Hy@zG^vAl+<1?e7xv>FfQ`RE18lP3IA=bi5-xy_!d&o)+Sp zO#Ax1xJ0~TM!1FlhJm2eaG!WoKgIQ>!}y!*t`{FU0nJU0LVKQQ6Mwz0c-B{6m=LE( zBi>)aL01Psk&X+oKi!6HZbm?|xQ86C%n*4#6rk?bV)1j8shsYz=^(mLEAjJsh|9sw z?-=coGeqt?UZIQgok{$?He5gBKF|@mROyv9ww;^Km-{f^VgQ0a2gkzce*z-%WS{5Y z2w3^-JDUNPSsb=y8O5xxAtuj@yCU@zrc4mflkiIPHF_A2J|s~~O9gllsR^&k9+1~5 zPq3NPZ9bB9^vqh6i7L;^p&Y9tlHA2fUT2~1b_;XKHVbVx7zT494d9h;CTUq&f@j$mz~=2Nmrrjex2?~Bbst<4CqI`K>r4!StFK$h zKHn7P0~MenMkV6XYtJnzT;HSNH~VMcUCtjN$TyI7Z{Nt(xow7fVNK)!$-)b5yO3Q( zKlVP43WE>AF0y9kHr$@=i;VV`vb&xF=eA)xs4A$^e?zkIl%`=kHWE@H>k5%h$%a3% zrj&o7mTTOb#@}C|nSb8I1<(Nl80mOT!W;j)7X`9|f0AN1D=y*UG4xBEBVJPT5@(?c zaM9G5b{qQQR`X$e)8Qm~?O!bt<`0H)=9SwrwFW;?cmP@74Cu=%*4+4(G`^eD%%4;q z3ubTrgTE7VB-xC?K@lJq+d~2?61X^a{_Y-JDju4=9e+7j3;AEpQ*F7=+_zI+XiBFB zsWknLhp~B>51LLBL5z*0;`zOd3mTtg2myKjm=DB-r1Nc9c#q`}3VO-nswz?bA3c7z zY6!g}^A?SY6`)X3BGE;N9uDB|77FRtcqjCTd3CqfJCT9k+VGarIM&I?cKX9N;g>Im z!P`T=5?w^h(m>dM;wza~Gr*$xHPZ|qe=BZL^yXBgeNpw!Qt^?xa?!x>0ldOJA^rD4 z3fzZ`g0Pl!k`_{idleet`WFxC65hj2fBFEO`C=sDE2cNOg4>2S625{rM7-atcv`qQ z0x8Ii<$81CRb+}H#8=Do?!;s7F zR5{rc&FubwNSQO4u&xbn4`%oD!apQ%uMhtH)|L-mnL@wFRiODrns6`Fm$17lPJApt z*}A3TYO{Ujp5Chvyig*$9`xaQ3op2=Iff=QW#i(`dbp%}fEsn2Kp(HmLDz9#V)~>J zThBZP3CCn;bgdLVI>-{vy}U-WX$98z6`*xfOU0WP&$pPKkcPZ=vE8B<j^tuPa`>!sN+4!2zC7?IIlA390qNxm%IpqEXMBiPZZx{Iv2OC@;~aSBW(q%sdXG8P`Nx#~|rjW8magUozqj zQd;pTIJA#+Q1}<}~C3`QA}l`9)GcpzVk)1Qj(9&$l`FM$j$(7R#Lz1`ULb z%gWKk*;eH5_)mD?Hb3}>I!XI?N4!u^kB_Vgrix=8B3<_PZx)q`55Ad(HP;T{4_684 z{Pl5Yvt<*S&bY7tWAf>JBX~4Bmj0?R7i}q>4l}o2m1N;o)UHCQyikI}?IHm>bfi?g zE#;DE)%pRveJ%5}{(gb7G^C)Vi1{MxYp}h>SYD+jiMpA_a1$D=!PY&S%vWNV9A?R9 zkGn%>|8zh)&C*a~x{^FS-igUJ0b15sBHmx2C(4yCMXN%6NWsr0{PKr9pP+byp5B@+ z^0_^h_i`7~HwweRJysvewI52n7#STGVPONy{14IM_QdF;uAkS$;y7vXl>yNVVdo9^(SI;V+GE~cq?elQI&8Mo$H74 zU)6>5(cvVdJw6M5-#4Y_ud3y?e7y)2Z3=YS7eMd!>Vt1-|7`r<)G!Dw?j|-}X55?Y zN0IL0T=Br3m-zbp%h3GQnr;{rjD_Vx_&FX)v^udCg$a~lS!yKN)mDwKXlF3a(2y=v zUdYkbix9$m4YfMnNa~matai*HMM_23&FeC3G5t=8y>4>_R=#Nbf+ymjGdr-E`em5$ z!kW%_kic!(>xFKt>z|DaJuX93)^w`vAZESBxA+>?gYfl?AuQba4;8z+Ncf5!8LWeB z&{wkR*$dGi)>n1+ajCc@RRM<%y9^@>t!YBMB1)cJfcoA!kpr!5IIZ?3*lpCKkCtr2 z_71oB^S3nfOCxrI_OW4*>fuW+B)!H)R~g?F^^K%$l(o2-&+@uWn#JYDXSk2diPfsrq^GqmM9Wm9NXNI803p$Q8sdKc5aVG=DUZ$eY7)ImBwiahA5!p9X@R^)6&dMUx* ze3tHBs4)-`m9Ro=c2Iy^!k>uml!RNX|0)kw2h${83>sPjrV$6JVE9`uS2qIn8O@PwhX6ViP7cc?t5-e2sR3OeHNb-|eJqQ%K9xcIy2E0#V>06CdERV~*+yb2)9_(C z9lk31B8^`Yh}^sdXmHXK@qow$SpIrAg!fw03r13$C^3NFJ60=SKdBG8C)vQqjjzcM zwOl;v2-i?lGvqI1RJV&7sR>W=ICwxK459BX*k*pU^cxM^Q&q)ZOj(O~E$L>?B zBg(|#(wca$PdNBgS<}yzX6XKu*JxdWfUJ4Zgcn65fa5At%GuQC#imVz14;e(-22Fw zzukI+rmSh(EU8FT+3m*GPfOak~ z6US#Na5MjH0!J%V+WR^S=hhA8$Nx^E(PNU3{r4a^KUR@uH3N!VrUz@rMoah#g>QQN zq=-=ZXk?KA2y?vN+Pd)}p!lm0)*!BpFd( zjdets@Zy^(eZ6uqm-{6MG?;n!|Cp?2zXqzib0m3>edQ70_30-`9GJw}GChCO<}z`* z(M}vz7zRp43u#hH0(Z0SB+5Q9hP3bdj%NgggTg#bn!j0$ql|9ynVpOSF*Ahrkl*O~ z1Xp6{*oH&b1;D0{UrE-R7ov`8A2jXu6Y-~f1$-_yjAaHcq=Ctb$QJU^VuoW2i`uZ< z>ljGr(4{?^8}LcxoBVFJ`{O^E(?#>CxFe@h)RYhgywyT_k`F^;&#Quzdj_$ND#PBBUcsN?9`s!2H?I0r8k$;T zL>{mDjE|{0gQ0&jiMf%1w+Kx5SwV3$Bk>Zd&>sQnoi3!Ltrd@{6CkwlsW`goaNduN zo_tG?R=$gE6g`DYa#luhd0{oDoyEJ@p zq=PN5m!3+?2Uek<klYE{AgVJ_76*%1^f901Q+d?i}As>T3#wqKUcwUNPtFWB%imZVbkodZBMjahc~ zMU(og6*$83DqIiiCI-t_a2~$*P$cgp;gcusyaM@=Oo#LND867YnlG$MqM9~ukk;r? zkoSpsGoM%CmCS4NCP0xkKK3_Ho0G>oTd;h~OUdl6zZ>X95pnY=#9iTX@HZfh+$ejB z^?tksrO4uoD-_dn@(n$^S#H=39~A+TGNHZ`Ly9_4R@e< z%{=<#8IQN<1i?>#MLKopSoASyG>jv@k{#bw#&=yY{Xohp7Fb+zQsxC;lW1X@JRJ0x z0_#?0N_KgZSAK+smID+#WznxJX>@_{#Hs`n0pVyeAl`rGa2k$mngP!MW$!vUV?|V4^(T%9yPQJh}ZijJhLqxOy`=?V~^_cwnR+@^Y8uGD|OY9@A@dD9`8SM&8zH@ zcJ5vAv!)Kb*(w~~*0m6o2MKsmfD~Uqh4lUE7s#{y7usXO{5Wh*zVRjzPOvH+84Vrg zz*ztllXE0<@~FA26Jb&UT^Y3siT{&=I(d8Izp)dmWJE%=PA9p(VE=2oP1QNf- z@1Je3df$0^>&I15`X6;(mUS22sviQHS-KG7nMKw*mEu2sx@df6v}9*jZxIOSGV9v= zl8kS)y+tE6S+;FSEe<}|0k4>T`{Qd%~{r}JRtt>D zt7D&WnZOaeel|p|;ehak z{NgLAbkd1RRFyUrO2ALDo2#t52G(c3lCtgREMVeNv}1rWSvRr|FVQ~(0fQ#d!pQ_b zsTjpCYGK_#*YBfe^)fJjfgd^XsS%GDkOK#6b*X9eJp5j60YC3SGTmV;4UGpmD2|IJ z7Y}*1>U#o%6 z(5pl>x(YX>=I~v%n)%v`lVOa*E|9Gkky(2Raa@owKhzZKkn@K}hY^VH$@ zBtOy~!nD~|p|Ei1H!`tkvBl5$Lb!9ym(K936J=;B@yo^tslp9;*or2DUuvc#m+bw2 zA7S5^L)7V@92(sxg-Qk=5eICN5#N2{1+%xjlVGWxnGV0BE`%n(JCB4T$H2Hq7xH0j zE3Q!~fU0u>x}s+mXVmA*Kb)bJuddVw4RThnd1#|#j@_D8hMZnlk=>!)c#NGNOzdSD zDaLMi<8@s=vnq^+reveV3w1#2vmZHrr~%LM`U}4rh4h~ICUUcXg>(n_68xwM8?TtE!sz!?yze|bV&pHPqaJ5>j2 zHb)cvx=Os7KMzCI-;>V^47p7$9_aPVJjuKoR(2mYw7XN+9rtkLa3%i7za-kczZS`l zW}WYbQA9nu8lP56<{#|U%s){a1JgBDLC2sxNruCwJeL1o^^I80jOUt}S7+eOHIhv7 zZSM+UU$HNJ9oWjbR(c}coG}s|+M;=3ko;JaUW^mtE3&bC{vFNyx&8)_@a+e>u*H?= zjBdkMuLQvMA-!b%fJ)Kd8_VGQju=v*S&4rv{|ly=X%E63k>(VFW;XU?>6_x~k{pBu#`5n-8Z!mo1{UrM}A)9-DUGI_1s7}+5faX2SIyfHV>qdVeHJNc- zR#IT~c?5jU&5&@pKEhYv6>^v=_w;hkm8r;nmNChN&v^VoN6HFGd;i602-|CkEaiI1LKF$63nOo2Ry8Z!lt?EDS?cH!B8ZlF%bBMir6UP3SNf$FO zt^F~1FumtSPDQohSu;aGRr4F6()UFs%?A9d^%p2(=vg=4cy@Nal5hq4S@+NmJt1v* zdK5YReSu76T*>kqZP?rGF5ERWpxW^^xUO2r$Hi&pAAD~Cw^K*K_2qs<)3pK1ow)!H z26mB^YpgA{_1f`K_A&HZ-6G)6K8Eb;zVxAGo#-Chze_WJ*`dvh|M)x+(3ebdd&3hv zZ2L#3+<1gW9+XGRZb+eMzoQZ#agv-DjB9>J0%oUUFYX5H@=~Dt6J^juTMbZ}?@FX+ zv|^-G2zo+4diTg&?rV~Of5~a(Pk7M_c#b7pQEepWpR@cHjaFEY=}MbFTB1K{PtfA8 zR^+N(H?Fqu1Fwc}L~zp`%T2xkkM}4rzpyqk`aBn+zWI^x-}P8S{0n3ngw(mr=G96hVLEA~|A zV85?WQ2EtDOa>)jwbQ+*Ix>>D7S>?-+8Yoy-h{3=GK=H>0Dx95k>6W_GcM}$yR~l8 z)82N-e(fJL?{YuJYOZHqS~jDayRE?D)A@*+3&^L=ChWiM4J;@LqD2kIc7!0X~$ZPMaRRsqoay^TybnT+q181X8#L3C6`2-7Dw zqAwm1geKPF8E;=hqscisyl^cSlIs9YNzLSGYZjgv*M>CtWs-TdjClYj-{~aX<(u#d zJ!5{!jEnT=l00-UY72;sHK@}iF;+P|kYC7l8QZ7aL7|u1Va!$!I`$akIzANg6PTW= zbF~x970iRom}oMjs1pCJWH?~+kF0fF$Q|3_fy#_UVjtaCIN9k2(4m{@=z>@*TriMd zb~1??d)A=(-wNzuOz#(3joWVtd2N>QI6Z)6|KpWlzAcZq1{UElsy9HB^;SGspUJ8J z7zp>DtRY_Gy6~rKk3hM_mumB^T(s*E6f$M3gcGF@<%%v zz&`z6R6M|qtW#>k%7H9*%k(Fk&8kIHZDN6QV0zt&%aLj@>!~3z#H6tTk6lb5ZM}eQ zzHW#bY(>assSCN6)rQ~fzXsz6>C=IJ8?fW2Xg=bHW_}0S0cXZ5L)o2v>^;JtLx-Ms zh?iRXaMuzK!qmB95-;@_+gAL5M0STN9WMojal=6CZw6VgxeU9Esex0c4pVcBUJmD` zpx4ig$+O*`@$P4Pp<`ML`T8{jH+SgqEoW}hyqYj17daF-T{m(dwUvSTWiYw^ku**{ zFZ%Du0p34QE8p^PB}6LE1*eVm#7swo<+@+M+(b8;>}!l}eriU&LtM%48?D&>kf0s-F%(+g;wC|6H(Az`<3{{+H;dHC!subXNk7KJ~9j@d6?4qO2@EUxhg+9 zE{VQl9vPz>Dqwe@ABR)39`Xb2*skZ+UD)Qf9TxAv#D01qPTOI?hsy@ht-;ICi^tM1 zX9V-@#y-V+Tk64dHtgaU z%zSF!2#mZh`Zn5t|51E_F8khsdL72WPy1J-V==+Q$1C#Y%okrFK7xM#eTGiFbs^W7 zPH*QFA&lK`z&a&u@aMBhd^_`+olLO+lkAb;e};WN|21I81+fs$y16~?Z?)(QTguD* zj-?NLmH_WhK*w4@x0Kh4rv6pn`_3iNeU);+J(&Q{mpqi@mY+)NfV~Na>8S=ev~PkG znizIWqA|-dIt_nNyJWugkd6hD;|g@$HW_q_8x2QSxsqK^TX6VXF>GApLu-D`;L^7H z@QW<9@(-Npg?TXmQOg_2wY(ghJoYWr3tj2ma7#4zZ3zn6WlhewcH`Dpez2vbm%N#K z5NCg4o*HKb>NH0i6;{lFr)vIWbap+i=6}G&ZXu1{eG_RGS0i-9SHczOrQC$oMP}49 zu0BsxGZ8dxuaQKbN<1u8jo%jHOU*)Zxmn|uq2D&i5-*07Q3&WQZ6&QAZew2k2gsER z>5b^;C}Y=mbfGYk)aBM-(*6ZrsRYtN(Oz7S0>IS#Tw;(}f=$*L@Qu@N(X_Z_=;7yI z$Vq0EWY+DnzYPDa=p;kNuE30jKq4Q3L}PX*{57219!NjUixLg0RORL3lW4|*A#iQV zJUEq*O@3#TVy)E#VurA;mP32EDOvN-gTXQ4&=E4?MGh=Gbm}`Y)HWGEwlv`L-(R4g z4g@2o0}V(!t{;;*tp<=iagLU?tmT~a)`0cDW`Y~Du)16;s@}JZphul}r0E6NwYi&Y z{k0j(?^wXE`Wr$26ci(~qnn^?tp+vp7UL&WksowcNY5qTK{qbEgGbvAQn^0JRkKOr zcb?SDH*0o;2`lD8LSZzSb)^#9%!~!6>#S4$ggrMS{s3atP~wxxukdE3J)U)8GyUEj zi!0L=`TcB%n8VIV+b(&)(NVoYQQ)3~Rkr={=U&*?WEk;Nm<9 zw_ram7Lr+4MT$)(_r#dx8tFO^`ypL;V!$Ifx7weo?|#RvcRPeCj*OM~RV7aO;he(e}5-Bw@^FY&c>M%e`-rWSSM_Wbz#@n)$I4 z)M0z#5K!}XBQE}}c%4xs_`z3lwD6*6M7=BD6sDCQZC(k!uCw7lSUm|G$9j8JUqI?# zcUo^{f?V|9Aa18CX$xz`JGS~lmYp1JycK}$OC~XYu|J9URF50dqG0#E@5JfBIg5E` zZBP)y=k&#WST^eftQAh8!qMzCQ&Hu6omke&miy?cvJ_Ny_0Psbr#=8k=*Q>dn=<*p z158u889pJS&~;LiEX4>Icyu{B@M?QKp(X-o_Ee}7y~QV{G@H>6)$4&cGN zRrrStpO@WjL>bN_!13}`;$c^X4-0ajq1T9xUY=z>-7=HEv`#bMbJJb$soe@(FearR z3b1ARRj7{dB~O>9aW9TYfu~tIc^&i=m#nCR|HS8L`!Xr??7vVnC9Ho=-rpDl5sI_u zt|CUIdSe#ZX}COO;2z5-r=Vz)uPg(#8Ab*_~rNw4Qw^;UcpBHG>0o zr+@#-ph50`xK)3SO0pxAHk<_Sh3#bcvo!3tA_i9fR-mV@$e>~7>M;F^E9nbt!OjJF zkTKqeR-c%`$ta)YC)#M`@0{NY_s1c4meEMeOLFj{9nCO)v^$-Gtr&IQw3f`t zGynL4&89vHR;QW8K;nA^YU!$t9Hr;LqEr6Fv8^6&750F(;$7;$=qCD-UWpR?`{(3# zvq8M5FNQY0G8Lr+On^rluaVb?-ANl&`Ac7!cRM$i+wWtC>g|)ogK#@`FbIYdCt8U` z%5CiL(F1>)gtWuyIT~sH6;1iukJTFMKf^ddAQe`5aoZPikdl-u;U$vS8t~hE;%RKp za#SGm6I~p(iYyEHhz~svhmH9kiBM}fF6hH(W@0}t@pHZuU%KTc>&!|Q&2&-WXD2gW zS9J&+_&f)ERda}Cbt(Q8jX_n$oKE_)n+uemi{z`WOY{$?SNg$P%Xeg?Y%=~KZOpgL z3!zs$!jSr?I`la?ft+%96%xe4z-V957=zexA^unZOV4Y1<|^QFd!@g64yUh1-t&hoi~WZDw>Phpz* z+b=o7kyUeG&;0AeQ&fqC>q24I&mZKD7tb|pIe;RUi^Z;Sby)tN5EiAm(~sdPc*1%G z{{AT;ouSR}`GXwTeU2iI3DtP2P@m7SrgV?_Gmn*MfU`4#VTw?j_IxF{ z@@O+?&2y(6^SqH~(>IjNaO~`#Ry-&@0JhoxA$^*)qS}p%A?1Dy$nT{R`4>mp^dtJ-$;X5k4 zG25r89hiy4(#c3y)kMNw1YFn+X1iL55NF^<^GyEHYR&uw-$%iH&mr*Rfg5>zsTD7r za~0GpdWd6rh{#CCmA5~xl|OfQB^+Nd8ycGGC4Fi!-YWdx$L#qxy^$^BPc{7d=jZ=w zePQZfIhwot99Ec>$se&|Gu{VlXmyzcrrmy|JCk{8MqGm5j9asOCa`edW{sLM`nlh4 zJ3L{{%SlvDnc#-J5&T*|AsuFP9~Hj;gDPbFB|Ek0^V1>SR+qY0&B3b88T{j8n)y>2 z55lr!6PO)+oy03t;87RDpfBnpx$U-utFlW#pRu!Kr#6}}?bdb^`tH+V{IGL4A05i( z8E8a%XAg&|!mH%huqxcTDGLf+jOcNXhvp02wm|MXOtcybu;+hK;I_AyT)_7^Ty3^T(~##QnXdcL(W9)7^a-kqa+S=?)GQI^+%%vi z6KwF=hy-3yteO9FpauNSQib|2e#F9{0sGVkf&73TvNw0Jg%MfA`yY&@&EFTnf(aOO zf_&-Lb+1IOGV=V&^Q_0gLLN>Sje~=)`e){~n_6JqfkSj@p)8tf^NUlGJtomMZ2NE= zzQ1iJ`#z;%(Qm{D%iN+frbVObQ=`D#){Pjax8R?HazSN_4?PhzgIn?N3@^1pE8o1M z2fiJ!fZ3gm zO&@x(dKKBb{Uct|7Y5zXNiI!Zj@_k2=QZ_?t-bdf3Zww%mNqLbPN zL+H`j(4wD1YHyX|n2Lv>-)czPmT%>*x6ejDC&x%|)pe6E=%08;R#o1`%g-6|*4iO- z&FC=nXZTAb?uj6y!)o!ql$UU2S|F`nxsKD`Y7bAwwGiJq**JelGiujdPClh|;sEX( zcuwdd1+5#g^i%_Wno=;`V~~gHHm!q~%^H+T6XV50<@q;O6;x^ch5?!_B0e+$Zt|(xqz#+@(RRHI||TtJOa zmx86Uh%}xp!ip<-e(Usjx-@k&8h%~@%9=R+$>nm9E0BCK(nLABRY ztlZlKVJ05*)Msy`{PQy!G|^o$_o@{Jzz$C-Iy>~0=+Gl8Uh7vPecd7r+WNK-I53tB zuPw)?-sixJRRX%;odMHdWTDw>T_tnxvVtox=v6<)j$|1KfA{-Kc50%qGPu3Rf{GOu zTUg%kM{@T*inpi5KOzAW1*dwHqV*kg|b@z;egl~p1oA&I88QW5ey-`npWxIF6J^FH6t z*K_ov_$NbQ(ZdWf!TcpY`S>+hfCHUa*Ui1X6OWqyTP)_fza96(@7J~B4m9n`G+v(l z%&#V@!UB0k$ceHMYr+!mLg4=C9&%qUNZ?A3@ei}KMZ(%raI={Kw@p8hmj(hn&F&54 z?{cKuZW^J>`Jd1}rPCzqY#mnPJpj4N(HbXT9GaWP7kOxjQhkkK`}PSyCVLW-C6(B4 zeJB`Q=_AM9`WhVzUXE5sD2jRS(czBpOnNfi(J#c_6P5WjW~`?rGX+(R{ez~j_7wYj zdq$-~h+saQ{A)Je;=BkJ)Z8Kee!Rh*k=H;J&_-4znQ@<^Vp$i;DKVB#WlzgznI*Kt z?krC89L~CKm=@8^GQM?6@G>iuoO)4)cPM592z*qBj!kr2HjgDHU5#v?GSV|_!?U=u4d@@!>Ug`69%yzipnbzkaN~@7{Cbx0u@@MELaYjGSMwx| zEWsJXqAnG_h^RvpLvi#k(LacCSxJ7 zIZM2G5%jhOrcOCaPdG}W((QfRwUy_^n()}FbCB8INJ67h@q0FFJ399+4e|>^6Z}R) ze(Y&6*WIm_1BcGB4hr`foW?Ge&0!d;5ZnXN$x9(bx|%pU<>Jm;m2h>rHLW${(NS7} zqAnPduO@BSYP%;?jQU3|emaMj%v{a4p@;O+)(Z6U)l9hb)sqzXR^ke~Jm{I}PWNAQ zLcgnCBcp0}axK0ZCtsE0uT6`hm*STSB1eq}pSUn`tg#f&KJf&$8!e;{UpaA$Hm*V6 zP?8vXM^E+##r!&wHR&E6zN-VyvcH|Tmaovk$8G4(dWIWe@9^ibZSZ9)>%Cmy!u>mC z2zw?ANaeUf{KGblmtuQBLmf(xUsDgd@@6AZux-Ixk6eSM1#P7B@;cn0mxspm4{+V= zWq-kx+@;I+rVBFChVv_4##2YC2$IG+P#%#h)`uTS%|b=75#r3noV{+)aj${&h9u&l zO7rOChOkuKVOY{POTI3 z+i?rLz>aGpngKiT$cOs;Zq{>{|5kts5MJrFWpd5S%%JCnK)kb-lOqE^xvfOyZY!SPk_-;RFVY8U<($%^ zQz-H8fc86v_2rt%&7{Kx6k8szf`e(cbe!#F?CN4#s|R! z!t*Bt_o-&G1l;H}fukmo|QE@zd+|_{OR?9(gq^J1q#&+*u;YCCGDRGt2$e*X6IEsk5>-!yTP=1WP3ot%) zGEf18l9{CZ5Yv9$zX8O0Q>VlssA>8Gq!hlGczx}_m5F;{hh&{NLm@bs$}hjq?uKVn zL7+Mmqq)xiRASBYU|1-@ zd_kEWM&%!Qbk!X@K{3d1|0%IwH+5J5EvJ_1F#i?!7AXF>4t3d<`Y@6UuP+7fJrMhby%hC2ch5^CQ0MJi8sZCBQyz z2P7H_iR$4e*vIuIbYwA{bWGuF2K_>z5oyF06=SPM{%Gw=9kE|GE;JPMwRGrm>0CT^ z%wPzNwk3V5>hYdrUwE>pht#E|2*%7^&tI2dp69W$5IIp5hQUWMk3D!ql8-G&peH)d zqP3HrBh4wN#Te_>9|Ol6^yx5D6P%S7!+&B~-A)@rC`=v!8rudiw&0`>d>!(GykPG; zg7I%` z>F3)&>c*t0QLLAsp1vxlz3Z>Q(}sUJ-|i;^RQw zWiefHZbaV6n=$-^crB5n<1tuMJOe`7?ht9FtE;i^@yjQEk(N5d?Rs?y75yIIy`R%= z!3LY%wB}hP*4`?~_c1>Jx$+L>-W&|xS3|}3IO)(&KtpV)mx2p-nPqBJqgXfEx;yYp z(G->r$7IIIXPDW7_@Np1Xu+4=NNI`;Ed9Hc^tQKR-DfFa*5gb|4^?o>SDiw!rsKuh z!aL@TT>Nk*J+nuI-&T#~y*J0x#+)n^vaKCGu(Tm>{OWM%D{oNzHkjUk9NWzOEK4=_c5_$1DZp_}Td}TNoOlzI`g(}+k3hkBhr|53 zNNrKv*;1Gutqp}4pGfO+0e;6aHCJ2Wsq@Us$hF`j3cNOe!%H@M!uDYbbWo{3KCBQ3 z{;y=I@y&^7<0uWdY2`^e6)SPU@*udt-tnzMU5)yC5bC+AD9*CY>$in5YLn@tKp`Gg zr^pwx?<1R(WF$Z1CmInypdl1BCc_J+hd(u+gJb&qp}$L(`kpmL7v>wl6UPW*`SlH! z^}Y^YPj-{yl=WOAibhZTPKj@Dk8^_|tkam56kf*nu_AvVlHGzWtIz}=#`6`zNRMwB z4hYDC`|eBWk)T||T$XnTVj5;@3F}H1SV8&)A#qvu1m`Xbft;#eq;y*~^`UU$AVxKdDeU7w_5;8|m(GkW-QDGfka5owz_%EO{`d47z^>_Jo zA6Uo8Ohd3wRfZ+kJjn*;6WCwk4XK?!NMz(HqsQyKQOm>{p;MVJH?8v){NAyT{;|yv zyz3vt*E7Df`<*nTu2yHii)^v3tM>FGxW2QcU4p^r@X{VG+3mczqw=o31FU%Pjg-2j z;$SJv$E;_1^8N{MH*zG%SlEyqy0y4KkO8Mhy3xrsGr0J}|MBM-4y*j?2B%Yt;GbJH z`Mxt3Pg_s{m%f~$>vsdn{7um~9TPFv-TIz+W)=>j1`GegJ-K?sWO!i|D<~OEh|c2k8&5#`$l?06#69h{{Uw36%iY&oT%XZI^KO zF04Y!oCdJ>h_Nq-*4LB9x3T!m+-4Z>&+cw=uaM{QCX~v$ApXa1YaYLVip%!&xXT_c z@5o~4KRSTDrcwbg_OC2$*%`;ZOzJ`w_M6CMy%wx6HV`faGM#FUIi9*U3(Z^XF7`i+ z%M6C&EygtX*fzoVCPluEc@()_im>kOba;LukA(FX;zW&fC>^|r8nAyW{p1Yf+ZG|t zN|>3s!gh~uWT*KIs49o7)={dgc~6Gp_G-SLT7_^{6d>`JqdQxv&E6vW6vOHyca6g8RTBDMzasLG~(AK?(O)y{2Aue z*){YIoH@1{-cH8iOtDJ~$G;qZpZfjUjrL8GhBy^VlIhxt)8}SGXN`y03&EQoLoW`E z7keRQ8~Q@Dh7KKmRD_p&eG6vzBz?5g89mBwLGlZ1#e8^{iVwW*m!kUp)q?MC%lML6 z2{hx`V6aYE4llJLiFa*u;AZzPC?>A68Xl)-D0= zQc&bKPf4KV{VoV{E0Ef98!;c=WZ=&_j^yZ!GZWFR_2Z!9jVB2oT#0XY+=PFPeZ*>t zuhAG~4h=0<6mJbr5T1s4>nGEsU?JZ1cqkvkKC|FiGU}S#gASH@iu)&v6_Q}=K|Q)L zeKzZ?_J_h%a#Z`KF_NiV0JlRT$neNF_|xlo{Pu4_H1*MM?$WhLwB_9Z_Ue5|gWr`l zG&eBKsJ56KvyVNQ)-+d_a;e?4fa8Xhlto~z9OD%pFn(4F7klk`LvBw)N(BB3% zsX}sF^$E^AeiK&N_mPVIsa(yAE=1bX$n^2WxX6%Yhzi}Q`=eg&s3G&eX6cBv+__Ie zAX8t5#$U|A9(w=l0%bP{GjkMRA_4E#*@5=H=qi zY%g$1*J-Mq&m*<-1f?A?A%CZ|;l@jzAlo^Z?jG)pSKc({W%ne}yVezGVXQWc^!Fm; z7gXZ8jp>jv$erdJ|HpL8LL_hHA=ZBX+dYPNt4W|Oe^g=aHFdBy4kr=OrTF=7f6!%F z660q}xZBOEQRBQ+q4oO~{Cueo2u{|Mss6Fpifu_>WzR;2X)(Gi(})6J+$IKx-{E&M zi(o~PfLy)z0b9} zBd<7q{=PUm_S|4((c+BuzAF_PZEnX|;WyywusyV*JQ5p+OYq91Ea#U+20n>hl zl5rQyv5NBpQ0g?Ie;2ReRwYI8CG6eYv@jgp+E>Ekt(e6Ad5R+z8u7iq@6oy2cB7NJ zQc$OFN$$>Q#TG+T;ZTh$eboDzi_krSmc)-2XD*!deBf%34qX;2!c7;|_~|SImF1L$ zu12%(TmxHjc1siVL<8>%gsEZXg@0K&6HLSn=9e*uma0zgtw|NmJPd;@U1Eyy{`} z;qg)wm8(d0A7nYT8>c|)_GEfGL5LTeP~ejc66lD~WTdg|2Z~bmBERpkeP^GCFy!I_ zddqPR&i$bW7sf@3Ik0UB>x-W7lk8XD$m#sKgA|Rd#acwku~dlmw51765m<7+0>4ow zfnGXVg%V5^!1P=gDRyKx+|X~Z`gGz?mN((j5*_+}aSm4b(2rC_0~nhc>kX3> z)ir78dp#QFugW38enoho!m9yd2u$4OtORH4oxKEJnJ-*%;Pim zGmqa})@`Y-0CUPO6!laKX0>~f?VBrc z#`83|p6^cOt(?#v^XF*F9S^bBcl8i;{>R`%s#mEB7Jh0_&wQ$5Nh#jmD1><{SXbB< zC+@&>GZY+`A$-@>fdf~1LqtM7xwj`4o4l_>+WiAq+Vs5|Znt<*)$>lA6YKBtY!;9S z0Wa{y%N=N*=4KKm-GYY>@`n-SEo7Is86L4S4Lv^YPC|03arvu$FllGE`~CTXBXbq_ z8|)p>O+gV}ZqNeJ^nB7gtq9j#xx*i?nkt&=vCUk!ui)e)H++4%O<22ilHW_`j#kf8lNYB0AT zp0C)wPsDT^_b$RE?#4TA>GJ-{SLxlC`RJk6RB&clv;S!e#;^O~D*J!lzZ8dVEMnUn z&ll5KgGb~&)Q;p^gS13DrW^&$n_A$}9YGq>%J7|4>io2G9<;Z-gge;fgv>Nbg(IZe zuzznbe4V$4UJ*v()i3(tax>FBf0iS2w|)e=VPgCoF}VVqH`~#Y(o5X^;gNi&BkTL! z77kyNOknUcEbcDrFgM_1^`dE(RvbPg9oDzG)AZFfoZRNaXzjxR zuKV$lH_Wxrp*xm|u>V_CzJu+-{WmWQxu`cG`D3+Dh2ZnEragjNTOI%f_KtXsO)v4AItPn!J0?t{$Lwopv<;zkK6zm=_S;5{~m1h zMwMU3y4eF=>(T0k(op8=Mf^Lf@JSiwNjtufCXZfbw31~d^yRfg;ZeCTDe5TjYbe<+ z{}|tkt%Dfm#Y)}v7x^JsNDIy+WiwymaIPAhoV;j7jU39(h(S*`4`69w*>)Izr;coR zmxe#Ak!QU$c4B@jZxaL)Jv+(FqkaOVKbnvcTqV{S+Ia>3tYiYsOmIPy_LrlbJ8g)` zygJ-y;RbOJ6xf!5Kfbq^-D~u`h>3b79@ZTI(?@iWtW-Cnj^~Tf^|}EpU6Fnq^7l`s z5^NXJU2X{9zc7J*-I0u1XLX_=T`%z_rs!)ToH(UV?~I;{Jtime{j3w?^nbSCS2Q2G z4nz{^_iyl-Wx=30;}==xy^)id8;%NCe(-<(u_dkYeEaAG+R*BE#qOm=@xjfjFA1c1=#aL8>(P=>PUlP{BY(Iu>0XohgkJ; zjW%8=J70&ivd-kuwbx;-o(`@4mW>~1)Pc`lYg*l~25px4iy~C*iQUgSJVL@7a(sS~ z-${=INj^q=@Q^!n)xAEH{C+swM6M)L`h<9>!XJ=oN}y_$4rts`iWY9Q5%X9}%?Riu z`m|=3F_uw_;8lCsGrVOftj!(<6`U6ddS8iCn6@Jq*h2~)uQF=8^(<#?XG@FQ2BC(o@7&t={|S#y zloS@MvVkQjP2|v9~KS9B+%jozWSpLjd$Km`nsF3Y_uO3 zjA(^Uk{Dumg*F(XGxYFhvbMDtD z)@jK+Z;f8rSYEyre3H*nP~XHF-ZKGozqmn=Eaxn2l<@ zG$GLOC*jV9;F$5TaPXQTt?N7XjvIiYR zN;r{=BYKWri+3(khW&vnEsW=+mZNiL|DaIj8~I;;E#O-eoNrk~uNbf3^lR_%dCW@_ zWf>0Zcw^91V0i?_Q6oJU@Q&S4^zZYn$f;m3B(2#-W^Zl9usj9Mg}c)&+rDxJzxN~g z2^wPWuI5os=y%egGh{{BD`pfwS`<&0RI&S5e?78#U`uSI>aebJ4)g~vp#PqzF^|~_ z{%~~)-M2{w?Ct|79F8LMyG!t&(iD)NXEURBy1}268jmp>g0js8Us4l0*uD*%I1q!Gmnr(E)11B3=T)<6q7DhU zUgBGu%HBv==`2gPI^Qs=Xjq736o-j9?Xasy;pVN$)JIo{|1Or}UDz#b@s%XB-lhZP z+j@z02Czs3nL`G2t6(mEFJPM^ENies-4llbdUF9jyde_Q<7H{@RKj&0YC)I6(#5*2`CkHlXWi)S?LWBRY@0^HS%+M> z`yKDP84N>Bbm*GwY`l4V4V>R-O=~>Yput;yBOUg0u4<~o^HV%w(v)9hvhpLr6}G3K z#2`7*CMpxRu2|cRM|12=z@A9!!VR{(K-lYuB zF4>Xrt+lvqdouJ~aHk_{XL6a7Z23u^+9K}X515`l56(^cLR8Cga9L6bNS{AV_nimS zBcG32&@UuG9boqk*S%ebB4e#*m zai3tiu{WJ_!ik$9(u21qnBY|}@Yy%dMWhwEjy)z?ZiAQ_LBiiD#q>!&|cjruCyzau{7iU+M57M zt0VC?*;xPiH^|%PK7Co?-*@MhL`q21a`CRXjkN0lO><+Lm{P@RqX zyC%V(w?D~!w-Eer!Y{C6ori}j?xPz07wBW3B?>(x;Klz!?LA0dQ~X9iDgz@wh@Q1t$4m~ zGCWA~pc>UR+<}jKk;Wbk;-1ot!=`zFN}LXT@SWm)?j!k;8VPjm&rIZQSBFj++L4}F zby(|J7SuZ|pg#|(Vd3~J-ji*^jj+D}4$lzW=!qhQhHr3uTr%AL;6c?&7ozNkiD*KM zjaWknE4>O+1D4QK{XO{6;*q??hj{A#wGKUr9SlP!dy6^nmpKBk`?#3i%3f|1P?O19 zY}68MmB@vivWK8^r%23!3m#X&u>|%r>H34l-Is)0a#`fS&m!!_H1OI>-ZW~LJes8v zg`W2>A?DT{*vfh0otuYMLsMm>hKk2m!7779Zb=~hrdvG=KyCmR`!C3+TTPs zIaRRq*Bvmv&9*{5ZbXGCicn=yNg_o;9O_MAWQ;p~-wo*A3jy+YV?(Yzti!|J+<_~l zizqj46?XGunFZEGV=&(xE%-4M&Q*Acy=MkCBYBCV?$rE6rO_EPZ!~gdi*ROFAopz* z(`}sHY3rg2!IG#R_{n+?eAT4kP3H)xkY=8Lw<0{@+eYrWWerZ6a1?8OJPF<_n~9}% zDh|7;&o>0b(zvN%=xXqAI55FptV;xqeF&1<-RT35nOumYHUG~;TNIT11H${~g7LC1 zWYNPM{AF?pM9#3K@?Jc8){~3YWvmqIy^rUxKI9qF)M4! z4)!6ENtJl>#47mBFoZcuk*=2rH4pI=>%DUhe+G{kel+`qrl98INIq|5BK0s-g{$(T zz-a0n5_h;1k8oyK9krAmD01dHUT;BBRgZ;x#|{$yJK+KIOdE*Gs~Bt$Rt3r<5~<^v zVq`n-Ga7y(l&qWo4!_9w2(7QZY3T5aoaci1Fl+}F_vf^(f57Ln4LE7_SLknVGb%t^ z#5(XDFCTcaocSJI&2Uu7L*)0(UEEzZdY&ds5$22i52uDtMf+|J@Z_@JE-?9L8)=J4 z#x|!TKxdE~Exag;WL=)34P$SU=UNqbm6QPbXS&jn8_c*jIV<2qLmk<wCvPzym$+Hw_;h9W1DBA(VHehmgz6z7#)IN zu;2T3c2h7aypL=vqabLzAx*VX$qO63oY&h|LTdw+LC$dsaFS7C&TRY80iFC&BK(V* z*?U|soX||9R@UXnO8zIREFaJ!J}>Nq<0U>cds75_p%mUS#L)sPOQU4ZJBU!_5!LoLJeyT&*Z!QP7_@XIuE&&EE)_q zhk1+dZazn4d71sLbm4X%qgO*Rd6i$&L~TwvFmu^K*gIDw=E;{ne1ep72{icTA9P@a zBQC_V^2=(sly*^{b7M#7rEQ!D?nP7{Nhq=Q5d{|LNWo~F`xYZaM;*QmdDI97V6}J zuC>2LzuRnxQ)(^F?1}(Z(m{j!ld$lR8u-b0lh7%ZxPy78trz_udvraFW^I{|(#I>3 z#ri#XrR-6dTrrg{_7t(s85#ZoO`wzJC!=q>TF`1C(`1f)#&tdqK=!!-E%BI(ZU7`yip|tb=6susr&2k&Ykh#_{E04NxFk&jAZ!GaHfep`GgMj z%fROI;bPB2{n7x~W}!p}v2GJfi4E{$BqfV)7vPin4JfiLoopIejAvgYFm{3`9qj*; z<=Whkev=M4;r|`?Jqv;f8+53^ARBxC_zbrnh@KAOguR>F(^&$lj=?sO)o0VeE!wHFeh-i1E_e?l+ctbuix3wk9dsq)xInNL4 zE}{JN|pax|$uRf|(>b>$RR6`sFJg&mX~02A_cJi_OG#P%8EvlfmzBX7{_C@emTJ z1pW5*;yapJV?1!n-RbQ`Gr31KC-@+ib1b+00q?WsfL8YxVl0u1zb3qbg|BSsOc9UN zEpyQDS1ZZ9&&&r^;|83p3_a6)3G+%Be4o9RXx<}J=&_sv7f$(zGi&(2k8n9Xfy%2! zqB+3?rOx&g>kp&ueuDp;{ixj!O~L#9D*QOcfgSor!_zz!$e4eJRIxnc&fEErcVH=v zJM7HGuiuPRH4B8s@`Hp12i)P^-UhPHBL*vWeSqC76R7T*m#9?n6WSXaO6m;X;r0jb z!L8Gq7XEPJO7nCf-yIY6+UMBz`+eU3la?s?T`?jH*}cYk3weF789N^Hfx*Ap$)G@U ztnfGiS$uaVqpwwCJ+BVb(^eQS%FpJDCl>3((%VPa{B7a;j2MC zF*nb~vG*H*L^;x@e}|#0b!AARXFWMD(TexSdBCv4zlqeGgDlIrmUppDq2s33AmwBY z=*#&<{>u%)Wox>?`Uu-3)w+*nK5T~}DLz#F?zX&)W}g48@P^vGP=@^-lfk?`l2n~8 z!{g_U(9wThaVvf~p!k|n;lB13Jmkb}_voe2bGrJGo&qR7z zU(l>%JJRu?7C)bt4$i|D(0LxJSaV!D-}E2LSb3g@_0x=C+Qw+|>wO8XpLGi&((LH@ z&r^`uga>HLAX_pfz8=qDx@3R*4x0Dn3ZA%MnIFdZ@Q-{e5YHqyn;?b_adZTS`>=+i|?&CO9**fqcB5hGlB+@%S6dN4SrI$_>)s@#>7& zlV)oW06Cq#WWt;Pf$`H2Xxm{&H+)is5{dD!{Yo{N{Y-$TFO%jsvds?vLoTdeyciWT z??n5rT6{h%9L~?yp^IK7Vdb2AygTcEvrkzDi*AkvB^z(CC+&`eAFMI_K^#-vjnvl9 zN9Rk~2wL+`oV4fwj9fm2YFQIJeX=wk*2liD=Om-Wo14)4Ixn(+!)M&RHx5qfFQo1F z=i=TI_xN3GLm{K6avUXEFew`5qlMQWY zU-lg=_f3l5$N1I9fKMo}> zVD$xU;8*X7rN+mOp|&@*XdYyU^<)c@14U)7RNJ(ZTkh$Kt~t*lRIw8Wp9}<@L+m?U zHXEBa)Ii^R2m0gdI^>qnjrJOyA=jY3PwvSR?cne_@KY=>3KzApAW9 zmYaKvy=snMUxF;lt$!bV+i3oEPjpVERruvgAUEoE2%Jo|qwPghARW;G2T!p+a2qM` zn>ZXcF3T0?GOp;Cz&%Zq$cJXKspk>ah)v_We6>X5 z&X0$4iNheV(4Lq~sm1#uL*QJF9j(k7!+l$Mj8DIpSFl+?8lTB-J!KnA!E2T#Z1wXYZPAtZ zs2l5j^|zx-KJG&v4=~EL9KiE`o$p}7Y9DHDTRQRM3ZEn~?Y%-g1YJfKkIn_a0yv%XRuy_<=QKadp$8) znT@CJsRH?m(^SQL2s)x%igNrmkbGdB!#_RYZTmkGTXO{8DKO>H-emgG;tOgS#{S0V z_K~#}Ay_st4+3=D>Dz?Ms5P<$=J7t%GR87*dx!=<%Ob4_s_oIu3 zU+4O^-{MO?Yl(VKhk^Pp1o6iRF_3zOr+KCEl6G36HL9ObRbfAxLRfX-}Rs*5W5$ z(?DvAKE1X{4WEomXu72GjuIG@Y%ChO$t(4NEpP~lT=@s4MfjTFBkh~Yqux6#v6sr>oF zS|SJ891w{1g6+x2M7~~xC%i3(5h<+aU-J*LI{ps@-^e0k%8RfD+lEex37{??717$~ zVJPePQX=2nj`eglzE44YW~1G~#VUo{F^R!YIBjx*%wqB?xT#UG~U{3L6( z1_&(J{_pK{JG$wcD)b&13nyu{co*YRJKHH>-4tf4T+qCcMQCfOEm?n~7B^~#!8(T9 zqg<2l&;zlEE7zO)R6-xvk$iQZyAn_C>~QP=7u-YeXUOl5VEoM4!^<2OHbALz?W zrT%IZzuMY}>_&JKGn3DF9NU`?$TFad8|UDgLt^={wOXRR(WhbR?%8l(jeS23FU1>d zfq&9>k4~;oM2YdiD4F>K|A*D9jc>u9FxD{=7laS_N%CK^+4E-c301bR?Zt_A#JRa` z*W=)e=3;92EW?oO3jo)D%Jg;rRWz(_Ex0nQ9=EgrADZ|Tz1)}~=GDq=EStkJ=Bj-^ zxW4sQ(9hffd{!D3z-}cv^g?kKetoPGyxULHRae)b;Xk^ND1HE+-=%qjb^KuJxGP&= zG)^8ijQb?UWJVm|#}rpum}H3Hc{W6^%pSdf+1abE5zt3cMleRbfdEWl?z4>ZiDqstP5h36s-9)4AO&g#T~!# znal^SkU;;f(nl%6wcKafT3nxe1nXNKfrQRxvLO2rmOc~+rvGGV;q-sp`R9soZ|NDL zt6Ga)zs17aU^lw+?{rT6{$c)980&v->;jj^IuQK!D^XdLi|2@xcq?`06&&G-s=G6h zPtz*$>}VSf`04>|hlfzBR9CFKJrHJg%TlX=sVHInWZ2NT`Nr4Q{rI+1%WVe!)N1E|MwoNnWK^HNtTZfA!;*iY>57H7*jb#sJ!{r@r^wsbn zf&F@C{w>>%xv%C4f~Bmd;?4kn?q?fe>pN`e{M;Z8HcmntCq|3)8Y-KnPQS}vm%!LuK%dwE+nmU#04a%Ndm zt;zD}nnwwmP_;qq8E#(a3r9yw(Ph2X_`>6ryxFFQbQ7vV9ec;Z(cnJf+8lxll-nT5 zGl7~`-9u9}nxJTs54|?YGEWkX<4v4dE?{jd!Zs6O?b0X$Q&}IKNg()sk!A0X=G={2 zj>tT}LilO-cdX2wD|7Z-t@>Do7WsTfj|0QS_dZ`i6TG_QL*M_o$~pAh$S8(Uw;nV z`^;`#2IuEG^o$7t{&fkKn^q3%nBH4vc^EBgx`!_B8{p3!2biaV?P5F&JAoZ9D)DB| z;;Bn~E&3YQkHV?9I8Qh1XEq!dvXovbTW(Y#69`*lWa;wQ>*#azUI;6COzup5j5CzW zq4hS)9CiIhN{{-{p6gkp=W!9vyLSVQj5nc)3q)MVtuUk)zm#ZA>A+f{>mg@G18G{5 zh8H!&@LQPn-l;SSPO3}6-?0uvXk3T?wfI4+{!eoKm%l*W!GaI2(-x(~mcYu9V7kG-p+h&VWSfK4F?=w)$1T!X2A0O7 z;8M6ZS^4%O?yzKAP6oZ?qqL`ytK%HB7nF$Vq+j^^^F2)GpGxIVQSA6T7&Hc%P+P6l zXr*&KTDZxZoZIyoKgo=Nm)8x%y=srH-sQW$uy+dm)39ghELeMR0F(cd@rSTOeI!GA z12_E7RWv(d0F$@W+yuKRyXl0tLHMiGb-1NyLUS{mkVn2GJX(H7>?{7bPMMGX6G64# zjyLL#3WQSsk+go(b>w}?96mp#EJ{jvzw9F>JyIXf{{ zn+M;37BHYEXRN^c0><$FEs3WJGgw}AkUT7B&(i-qZx*HjP{no!n385RVs8wrmU5>o z>>~*0n&CR*HWHdrVCJF-UG)Ds^T=8aa zAppEO*j@EnKew=TDE!J9z-rNg7+~8)bgj+|u3qgR-~K>bv@oR$3ii%~&4+48_32!! zbzm58%)GnCO&+LuRR%iVxr%tHv|-&l9+196fky0i!$-yiKvJtL4O%!A)tzDYsV%|LD%)pxAMT$g}(Jg4-6zF|9zD z{ZK;K-FXFUM2&4v48$c^n6`8I;tK&Lq+ZO&~~;~+q$fz)VbW8GU-5OezsZM-%V zS(Uv)GJ`gX?|oSd0>DpNj^2CdfDh=J@bx<%Qu^T&lF3j9(XT#|(;tG}OETfSz>Plb za6v2l$MD?Zc$(OZp&Oq11)Vo1($B z#Ff6p0_?E88S>l`==r-W|2MB41tf=yJ#TB8U%=q?_VlB~B`z<1EWgj5^)@e=1U`QZ z!Qmw#UThn;MkfFkvFwb&mq*;?kl)NRy`5CD9;9I-?nC}YFFI{|9d}~>7Ua;XL4-rQ zapRdw(ABF$1O5=)W~s=({u@uH{+EHCvaQ>)JND#ybS-u^O9kI<#$l$b;~f!fFUCNQ zUOuq~JsrLTYQyh}?|o|rzX7>!b}L+a80jyLLCSON#D0u6WtQ(?8yPO~C-9T?ihS>o z1iI0#7I|L$jpP^khY`W;f=@Qt9)Ie+b7cnOHmR*Cr(@m%-V-))D z^)qxZeE^dW?79UOW~`%TbP~4mkLKHCwMCm-d5FEL0;W@Z$dBfa_>wx);BI~=nkQV1 zbRB1*9ft=nSyEmLGSYiV`G!E8eeD|jP@sbMnsjlU5go`T?@f^Tpt6!;1_h1@Seg|hc!Ug4@m`(cjbYgq(g+q=y zw9PaNn?=8eS37O#Ax%>>!oLH3334DhPIdU4l|Mx9kfXZ!LP6fxW&GH=%&YcH8jgOD zhQH=4+jv!oh0K3ztLR3BZbnEwBm=2dF>Q_cF~&Cp!x}jQs&scbUX-QI52=f%1t9`7 zWV9S~DEf%+ecev}ul@1jE@6#e#okZt2TQ^8jYFYgPM$d5 z@jkQ`q5{3?7h4sy_rw~Go~se-7^WW%z-+%3VjlDeXRP*z6f-$Gq_Cg6AU71Y%y1xM zht%R-2czNQNO!7&W^l9J_VHb5+M>_)U10cWI{3e+5oe#(`-k${T1@lL@<8*Rq@l*C ztHr*!jEVPPEBj9WdMyU8v-bysGjd}7d~eZ2P(9=;)-gT}FM;y11p50@1lpXRjkaZb zlJgs?@t_GxAfv#1vyE@C+k#Bc^Ib~!@E5ry$KIk=IR9t>lPA>F zpr(SYB-XMS8=v!mIbEz*JbMEU(v3mm0tWcA!Q%}0bH$xn{0tJL?my2Lu^pK+FFoMu z&2eC@hs7R@G=q51I>XVOw-0a=`3Xp}AzG|Oo8EVV%B7v8V}A+`2+Zd_*bY~p#8e1) zn}>AAhKlj|Ur`oJk@cik`z<)DONOAmuYq(<&&Dlx-@&LUr)e7}k0x6dBi|hZ_-tY1 z1sj|tX~^JHxb1~8?`+M!_Y0Wk;g}k95Bfuj&)mYgd5thGD1okUzK0SosPlHrf9sB0 zkc6ZLTnmpPMa`vn?~$`8XYohj;MrZcu_Y4hDqX4TZ2>-C(g?MY%(w4ahPan4XbS7b ze6gt<&#JG5g92}Qhz4=Z|Bd0tvHOu4KMDSwSqk5}37O>m6x;m!g+@ni7xQF8*44H# z+MW(NQOHsIO-RCVg4h?geZDhn(3nMsHxQhtIFvu4!FCOHWS|!M0X>>^S| zSY0!qUBPPDa`0lfCL2SfE#KgTm|}QpnLv-AL#W0&8bw*!iL-Sr9SXdvGTXJEUW;rN z|6+RG@of)6R@&Jsk)mWvTx5jMJ@=d|n~XvcitL7zHox=x+<)NvdVRb1KA!Wu zpMhV!-UtKBTF86XC*-_bDW;5&XJV^&fh-0cw3^s=j{uq_82D7Rv}IZb%x`@4`N(5B`R*15M; z30fH5es`>4T?B3*%#!#TIXGWh^q_~sTyvV8#TH~Y)47A1Piz|Fj1vPb+9=YNiZ*JjJ9 z!L0NZpR&9m1*yw4cqsa1`&Bs+&KWI2EHZUp<+DEGYPWT?ay_ZK5DH>K?5hB=X)oTJN=;U zkq)g4dc<11Q%kgo^0gU>W1)0cIFi>?NU z1~rj+wwd@r&|vPv9QJ$hbV2$)$w-`NNX*z~*$3_-nEx&H);H)!BI$0+6{5+%hk{^b2vMpp$GL}$P*v}9@!F&P z#Dmjruy?#G65O%NHq$&`6BEa z*iG(7B;rvrS=<-49ltwzI(XVE?CWNKc7HP?O_=Eb2P{n{v}p< zfw**IGi#?6(rXS6QO%h)i2UMBJ(c!nO&F!hX+4Ui2`4)dm5c}b+%R(Sc?F&_oPzx< zUD}!MA?TQ4jcETGvFG`(I9xjfI@O$bKAg6%8QvAM-`9ngXxr^}RQN}Vz2~|cU_+`K zRj~CDh<>SZm*Rx9=+k7l^-~vqvs|#@kzBR|`x7;O*h^+?@5DIx793%Da~DCOz|3(g zQa&|_&p3;7E`xX{!(Jtd?;jh?t!Md~vJt6h%D2~O^&o4~=G=rIeoKUFc}r>gB{kfu zyNvnqB6xk+&$I**a)s1@9AkISFjUUo@7pgo(wu4V`QuWN3?(G!X^x&AJ)*t{R!lsqSTe+=clnOc!;F#|O8Ca=#qe#%LG7mT^jurR70F>}zm->?8eI~AAIEVUr;q*KBXNAXx_;N^nvN*|HomjDh&SfUPixp&%+jLL%6O^ zbxHA1bJh{A2{MNw$Tw|vui2=|tqgIYXF8e$btPVC(;^E}sL_l+t@MMvLl083wp-XR zD-h1gZlzw6oKZj+%Npy4@Ew&KOd`Nophp9qrmo-$e4t3AN=5krDEikr_2hqHz>ONNnl}q8LjG*;&7ge8)W;kjB{fe z9`vaSHV?C=UE+->T=gT`c-)rfy<<~zz+n}lX$R%7!FP@u+Z0c|cgex=(*BTL`<9qS zi}BuriC`1#L@k>1kzBuIGAW;g6XD zv~9{F=M;*t>`F!M&2k}qZMhh29&ad6*wl>ey-woPC5OOP<|BEqDG6&D$8m=fnO3hg z9_lwLg3>fwo&!Je35DMNt`xRt3$(WG=X|m>B!54Dh4U9?0v^}I-}1(+R^-kJg!IR8 z7j*S&BAS;Y<-p&sN5H&&+BC&968p(b1UrcollOisgbSa9bk3>}6xjF#T^Q`f^Iq@# zY$z{vqW?9iiGo^(z)_zNlJT`1pVZxml5XXQuekLS`z&yT+rK`MxR25JaAhI%s}a)t zXx0gO;RV{vFj@6wC9YhW4Z<@{^v^E~fxn?9jBk@_5v1?~aMYX@mMWnM!42rx_FZJ+ zxDNaw*b}Cx_7a&%JMrKhp-52X!uu}dMkYbQbZ6doF>Z!6x0Lm?T)OH4TYsv-o)XM= zO(?N@hk2GheJ%H&z*>6(k`qSox#s<=96){aH?l)539H^=n=gmdC8N$whs3?EJVje;QAxN8^L+jzPxbEM(&@>d*5gc-9$iP%TAIMk*Ndh^@5$1M z8_m5>ilu+XcA^`%#({Hh7}=gwfi?eFp?XP;IIrw0wzeM!qH0;Hwo4DcOK*hpjOS>t zeu?7tvaO}L!8`|U|Hy8OHEwj=Ngu)4hhw<@r9yi11>5NgS_V3{QXF>BjpI(72}S1HKO90lv_-jRL!A{@N_H>CY!U6f8&(G^z-%JezU-|W;`r)ZstHqF`? zkH3X}0QW5xbk-YpG}&|n6h=vTa@%zm&~xu0t$UsI=L^))G2w8&gF?dmLbi{7l8Xm@ zunhc$IVN$mNh1Miv3#=LS9kJrbUj{N5ek>Jbg6aSJiNW_0hiRLE)h{P@Nd+B{^b$G zZ%+lD)H<5`e$j;nqb9+f!Jf!|s|A_Jc2XWbO8}!DCo1gs7>5iFgp>o@=%{jMbSt?R zeda>=`W5R*?Z?w*RjCpBOJ%k_Z>ZxX=XzA>)OK=&I#;-e1u) z{5BlDtw)XG4e-Z)D%`b`Yy*1!Gco zY+ne5tdl|bNtRkXGZuMfHGsrlNR7f|q5U7*x!a#bu2&V}1-0*B=>#vTe@z7)y<#Bv z6D`H$Lc0U-Ytu*4rJsc7*2i*7*!MiAV;syppa7XyZONz4jreQ<>$IQjMhAJ$7Nq9v z;e2y7Bsu9{!MJZatn_FiH&12aPuB9>Al9!E_`(_G`aMQ#rmyGo(GfGkp})O0)mR*f z*S?759>=OnPHi!SxxdGQ?;lUH0M+7llL9a=iKBPgLePV%WE4K0`O;@MU}o0?)4z_? zNUSO{(39tS%wnmPiZXQ2!SEnYs#oL&tw-{yIXr(pV&usD$z7y(N(?@+qX0IR$5HW} zVx)JW7_BG{;%|I+oy8Eg!;x-$VlD_DtN~UggpBdZ$MJvJcYB&8H6N&q;{Vnm+n`!`v@kLjYD%XB6y7=qt6~__c!wCcoIGnufvs2jiNfuVd(DcRHS%C ziq*4bJ%;0k&U8+Yk>Hc(Qn)H;B`G7H;%$xPP z8`i0C+3a>)Q`~|29UKe&7l)HM!4-JvL;^ZC%jxSbPr=0!OZ4DIEw5c{*slhLVp)1% zpdLQZ?;X5m@03k{D$vZK%?P#zlPOS%pZ7Mxl=I$n%^-il5&h9zW|ff2-<=GsYCt=oDL5M=BIT4lVlOeqAC;7712jB1RfzM1Q zadnMH&R1*E`dJ=4mpdL z^6vw#LbgI5%KP<}oZKhI2am=>s;e_?6AKV`D*^R1NICQ2I$tPfoOw`{0lsoVnNvI{ zq=$b#LmPAkz}X?5JU&OoWWturr8IGppT5c2G)`xoy2L}R5FXf$VLjfmbld@Bk;xRc zea5uDr#EE5Eol%84bLL4>I?Dv(t7x`+KVo?RY6aK*9uP8w%{SBPvPK)`{9i9M-nh0 z2|Jm^aC6!BSvGzg$l1%oi;uRX`h6q5wLKW_#=B8-r8$CWI=i@Gr5cjrOJ8A9{4^+D z_JQ9^8d4|6y~-3)yOS_a{qTqBg`3GDeMu zAKSf%`N3KoESH2D_eeQ&O)G{K2c77={%WG)M~YxPER^TWjoyanVEiUw>mak}M zvpJ`hpdrDFT%c&>7?`$6io@Ujc7dad2Ti>4P*AgHEb{y#%lR!#DrdRK-8-|Y8%A-)G?vQRb)aoi)L`1)aMEB~fpdlvc&(^UA2oOh#WaY(Tnc) zZxukHsM{X{Gf5MHVv+i!{@8s!`t3-wD6ES+PZc)JW=o@ z-yhcC=WCU@1YKu(d#18ru--JZyhqBP_a#n*ipXDNai|Zz^y(`dVej++lQ^X5@dj<* zE5+m~^FzU0VFk?`wh-q|xzA~i){x8_YX(u~GvU8|@ScEZWk|*f$;Z{; z?wn2HUu9#Bf`we$)=1iGcofw|zCbxs)5x|<#aNrff|45BJ>2qD&^+4~LE2n0BlIiw zKIsO_3g^>JFWSWvIm>rndg7PP9%mQ1c`!q?tqf}N)>Jrdm?r>LZIi_fV` z##CK_|K|KfS5MTD37%pc@J|RmBVA~+AwnvD;?UTA*1WbXyy*+!?knh;WrjFo^eArc zW!BeM#(EL;WWjK)6rcMp58`}19GOP?O24}83D;ntE}4>A0MkQNV9yUJJ_kC~fNzA5 zE;}d-DtfGAC_0PWX1fyM!8O1Q^`yW4j6$0{RtYq&H1oc=A7A!DQq4!=pv1UbZ#3u2 zvc}$L$HD%4a&YjN9golN4hMp+mJ3xDX$d|Gw{zJw8j?MRUm;g86*h`Lka1r!akTXy z<}ncj>sGoW?kG|KoaIXLj8a0ys>YHkL(T>+WbSfv~@Rsq0wJ@i>^~<;C}1$Pavs znpxI(i1Jj zFP9fV;p7ym9P$!6lOOQ-ocJgU(tRE2I2Uul)>Sj0x|Hy@yj0}|_`CcZJ$6V5 zB@e4bXRqw$HH}^A?$FD&A(n62h5IhuL!HxH$?Y=@Sl90!lwd2m_WN~_Mc-FY8^U%^ zup%rfQGug>d*QwZ*g)m$?_~MeB;2i<%FSmU z-E%jmvA07a%KCAi-$II77YBJ8U8p#5lVIYd#qfJl8=1>J#WNo&ao7GbkAxwI?mFin z`OIzP=fzHZlXZG**r-6ynAqTBa;bdY!TpK};KY&e?ovOhnRXwi8`Z#tD?-{}ABE1x zz5#P{587+HBP-yd5|>*TOB-i(paHDYFYRGCvAkA+N4tqYfBp(u@z+zZDbO5Efw#Qx zVi((Gb8Tc9fyoQ8ZrK~inZRyOapmY%_&X#f!NhufB_65s1`=j?P)*HSg7+&K{--c} z{xb<~A6X3Z*GY(_AQzW)M008x>XH!j25n01LWXPh6Qw^Lc=n|r$QgtWq)8~OG)ayK-E3tHlgGhfHs^oeLZ#y-R zTM#UyrkfklsD+==WF1d($h;00@45*Ui$>6zt{`+jXa^*l<&w%$3BGAq2>aBY(6WiL zu-?2K4IGm}R0E4}1zSYY&32+y<^54yv@aSuL%{1B;YZhiiD^3-5}txP4eDUlH*-3C z?-o=#!L#A~zH_w91jv>BP2R@)U>*4`IKu9~rX&uvTU4WQ)*hs|w+@?S zhrr7N`cyc45q=*N$n`3+g}{er;giY?*tI*72s>EEru!&vPMHgRbFq>6ZC#MVY)f8$ zzLFIH$t70QZcH%tP4tJ7yd6|j<$~rO{)v9i4JFfNyuyj66*!BmFdFq{f_`gIAot-f z>#>)QhV+rE;mG0V!cvi>ND* zX#5LBR@afzEHS6tChMYCXIVh~{*ZiCipi;_ z1G#_xj&$*bSNbomr*QurX8nFv1)$>*0Hs&0=-b+-sP306?EjNR+(m_W@E1-HR3*jU zeMWo0e)T6ZSTzZM33s%;SqSv<%e8i zHp_;Xu7iwTHRvn!;G}CJ0(at0{GU7l3HmJyiCH78qoJdu4$Xgyv zQ$tD8>eKlymjyLVYtTBKTye(Wequ#WN62OU0N+G$_~6AN2+2*Q6Wyy& zzvdj|viAY+uLw=ffR#c=`r^2`pu2V&Y#vPc+uuUQTW%~oPw#suqet`JpwaHT$>wM6 z_->aQ46W)%TQBdz3+w|>6U!kgtz{e2Q2{V4){53=Ul)CM{sKNr*v>_&BFL|0+R8cR z+3+mHjh{b5@CYxuup(M;(sB$k_J|OVtnVi_b2|?UzkDY*=Op3h57_7Bpe`|8Hw_fT z3Fz>cAin?Y&&vRa|87MCPU{Mk8W+M2+crKY;@pspR9m)@K^r?+rq~Tk*D2D!(YAQE zcM7L^mfZr>O<>8b5%7a`N84Eh;o$)Ru*%`1nS{A75vH;!WGs9(b_*354-q~v!&{ilD5}q z^3pG8m3TkTjn8G>gRpHLbjFYtfpywibZ72lUZb#{=m8V@8PY1Ynbnj00e-c@k1p`A28 zPr>J|y@i^k7Ie(at!VPqpXi~PJvq$$!vi*Wz^|JAbn~j)qLyoVTUx~wtFD7vPSPxQH-*c2|KLj+w z7$0W7i`y$EA-UNj_zw9kkHLh{co`Ob=!eh=aBKjx)em4FMk_n<6G zDc7Co*A9yFJm{waIeo$Q0IuH%4N2MShoG*s3jUMJA+?X5c24Uy&0 z*q9h}ufGlNVf%Ds1eeG3UPIGosOPv0*jIXz;~U@N^?C!iZJv&_VB{^kT?m9>b?iNOwpOHkx)P?b%!{n1EL=?P4~J(xBg;|?@ycphu8zGWMOBNC-D4!E zF>1zJD~@BW>$@QO=qGZ!BM}!ajN*i~j5G9%g&}%Eob4!#!B#2(gt)DwexwoCEWFFFYPinQsI^AULC zgedMi(>lzDtb>@psvzn0A_`iySlzx9v`7|xJ2D=H83>Vkt{eHVrUB14eG0uZoT%4) zRneDgauD$&lsM{C;P-jsxuaFF)VueCpnKaI^xHU(zw24QbcFQTzsbkB33y@n3vlnv zq(d&gMZxLWsKZ*yflp*Uh0Nnl)ZOZwz)?6Ao}XoX;7<8iQdkEw=UY+#)KLf*R-+%^ zcav{L?O0=wJEV5WQ1xHCu|x13baJgLS$4f+HvNJxkKE5h?u zC6K$tIvmav;_hLi(OBCEv35{D@tuKIaN>LqDOj0=D_CYB%mm~j}CI(Ce%|#1<+bkif(K*=sco+DVSyFw~ ziOBxoCsg`kKbf7tZl=!zfGl&TpQe8hyvSRF4o{v;gm1s$8_V5b&nN@hwY?6Tq{woV z{r2^@KS3?}FHlj6lXim!8xGP>vvJvlk>dSVpu>R1QAn;b#LG;k7T)>x7qKd@jaTF*NMh54ztvu4*y)F z#F+^~=%iJV`fl~xAiPD&b#D}u!bgQ?^!^ih$Z&5#hBq>ZOEKHWX~={x-<|2{0$H^2 zhYz~CO~7lywdYqsT4_6mZ$*gh2& z^+obp@%FVhA)a~EFK;|3NXff_eiPOmy`~w*Iz)my(<0i3B(VHT2UIc5$6?7Eq|wri zzPg9m|7J5X40sjBv;ylXIWr;5p#W*WOM z3%$?;wf87?qCKxm{OwBxO>14c@1qP}WN;HM_sP++sm5r|rf!tErJnD*(CMxKvs!lZ zy=;l%qoPs3dnxbro;{574T`1Ja#`r0aX;AcRmyv}_ojp9rR8+hSbzN|cN4koM_IpC zW@Q3L9HPkxmg<#7JB&hn> z!gmU7c)SBL0zVP`fVzWj+KdS9 zCwntq%{PD>>@7Ub(3|g&7j1h1VMZc)YFh#l8O5MM%~D+=%p(mNcREqm<*Fj_)3R3$73qUdu^n+Pfh-uN4 zG5Iiq$vQ_`~dxYw3joBf&Y}c`$stgq+-)gCBH#2Db}VG#*VvGv0Ti-3F#) zkEjFdH{OP4Wp4E4geHOip_M2mYBG7L_Z<%&r~$K!evm~cUGb&qY%iN-c04W{quu&N zXxk)Po*Q4g7zOJ#ETdiWs`yFdTv%%tMdtP^!>&h*;lw@>bvSVmxv<=B`dZdM!}MX1 zd>|NYJWP)bb;6G9Zhn?!+&pcrp+hEZXk(!#@%*n2e^!Zvk>xtnYvc<3wGYF&iad46 z%*s@@-LVA(r}KzkiUh~cD2A~sMbvzs0-P**kIGXsNNiXUwz-)Mhi=}W4Z8i1@+EIH zCqO{-48P!O{s2o(bny86`bQ;{+L_T@<<02Hu7N~KfGnoGne?@Xvr@*~|QLI$Kvh*fl^BYWbpepD-@3xxD+(rXmLdgJ}VLy55UC9V$32XV=H z`sKvO6$c&1az<`Knv^?>-Le2=<8z36*mFGEg#Gtd$kR&GEWxYw&(Zn^X~YK=Z`}4tZ>>Vfw@u1fhzZID*D1(m@AwAaCAAA0Fvzc%9U^u7TtuEPfeJr@>4*>mB7kK`h#WI^|{XOY} z8S?}i{WfrAd-2SCUu5Ja<__Y}^Ovj&!HS`jLWHLzPkT=15+zXiGJREQ=q+cz+W9YU>UC4#`u? z^ZQhu`o|GIVu64!gtRrlKjlhy(1`ZAgKD(`Wb z3G!AyNlB0^-aoq^m%;unysJ+^bM6(OLw9Y7`@cqP`6~i)wlAYEUyi|B_J?s#8`$pW zE^F9oH3v9x6dC`c6wm1PMT^~}Se;&V7j!lMqd`ZVu-BM=+`k<5HsAgpO>}5M^(tOu zs7oC#QICQ)u`ZpHFVH`)7seH{JxV*TRPg`08752e$n`i0j$2j0@?|2bsG|T5$_*&F zEQ9wg&#Fj+E(2HE8$JL%Uf_l1wF>wyxL#QV%9S1bT`#Gt5|*W$qd`d~s6)RSEqi)_ z*D+?0MV!t=Ey<25xhQ}zhex{)%ZvDHQizv%x2j2O~~Kx zbi+%Lyp|`A&r8%<_mqNw&W&D(M;}$?ymDe`srgsbV>}sVtcfB=V#@JWb203{xRefC zc~{W7=_(2zW5w&kULK*ab%HZpQXh|RfB67L%b0iN#A`I>>}TZL7fObYd&RnIn&9bU z54tH)PT$m4jZ6Q-y12j10@HB_`U!H$sJGAYO$kMR%hJey>xyxucO=}fb)$;IehB21 zPovG{QcTX+=?+_NE~ne`b8vFWU@mJq^V6>OLjF7I(4+hIWIpTnm}Z>0Bo&(5NTB48-_HLJ73L6;k_N3#7g<5@p-i@S3n@HS@8vyk6kMEY#`w7cF4_hX3Dp zK0B`+PBvLkqinJM=gfF+{tb1>pDFpQ@81u!hk4M$V{1iC(@Ws)3D&K2wLcu$_z$(E zKO2zn3w~y{@R{hKSzF=WjL&38cp@(E4&{7*s!IY^kA=$u zSy=S&0->)O@rg8lI4kg??N0Lrk`ad7=6;%z&P83I6FL?)gtd^Pd$RC8|2~+*yu`;Z zIV1g$D708>BcH#!d^`Zk+ZZ=449B%~q1>zYOvlzRfX|AfVSTkXuN7a`DTU)VvgxX{ z6!h3Q3cXNsC!Wd;ICts*@Jo{7?W3*;uxnpN-5=Qq)LsDU?4K{5wY8tP&(#qc*tV&Y zQ4%gbDnj4%gGuDs6B9}Wj`YX+I>o>G$B$f|Gl3$OVtdH|M@}OER*n&4G&S%hahq%r5c}@ z7zUf~IMYYhHVW4G&xYC$Qe4gHd=Jhk?(}5hc(lqxgluxQlj{W?_}q~wu=Qj8t`h?B zFP1y=dd0r0?UBfTW)1|7bfP7@H)PdD4Ca=0#nQtGZOF27Bxu@45Z$(Ne8SiYH7;%E z@$)px;8bO?Jyzp#H1b#_(((@>)2CMAj~8>H^%r{=zjhZ~iE-gv)@Vq=C4n%hdNzc9 zmGWB@)d7=_Tha2E3FyS_Hniun6f-Z5^@pu&J0SjQtDtx{Let(!`R&A6GeM{0CplW? zinVO|K#A#EH7xV==1o4zbh9OLFB`F5VFYO4Wpt5>Dn9otl+$K?4uS#J@OSVWxK<;@ zOzjh;V3?duLnPNwz!6_`%*&ehq>U;_fsrSi=`p)tJlpFIB&ckpXsr_pNNPq?<-ADx z&N@8*VJN5iNL`Y>Ar-!E-VC}L_f9&k1=9;?0Q#v@%{j0mE(yb zUkk{5oiF%Kpa8CRNO3Y<^%d04GpE`cHlxqsUy(`l1!5Y|gf;i&!q3S9TJxk@G|_Y+ z*KMdNxxh5D&`I*}IjND9gov=vDhYxfInpr8HK(hi;D?*t1KYmg<%0r)?O6vMWdMIlHkrDv(G15wp?0IPrKB z%o`m?$3q-)ds2c%AMoVwYib?-;E=3GWmnI`%0tI+N9tqg@8*BI+M-tQVtC%IT!`a4`-K2?v89DQ31NoIq1X&nH~rSG@3w zJ9w7q)0ZuIxa+ziXT3&96J~oM-^5yEG2sHwV;{Xv0vU#xB}4|dZD~U*_en9+egw?LvB zxeMwN{fs=Qn&bRVAnZ6QdKgw)5sKTJ&gje34c`RbnLYzT~DefV>RAQG%6 z*uA@r&ubKJHi6rlJ`;0?MBHBW0aTpL>2217b$Wk)P#y2UW9A+!Ke)zx#qA5`3tl*{ z<;>(XC1d)&fN7g5Xo*`$m0lK>Y4{6Mx>>KzHfI#p8i78mZ6w{!AF=MAJ7D@rn}T;Z zK5HAo4P}}1qWZNER;vtwpS?-SzZxvIEry^ZDQ2!PjX)xODQ3QFP6Q>E-Pob4DoXv; zAM!qg@p|w4`C~W-c_DpU+9XK5hEUM?d|pp5#y6l~H@k(MOTtMJFQ66Z30;Q5PnyuVGt&8BhOl5lm22J3ylGCUGZl6^qv zqiVL<8U{MZl{&oGB=GB;1^Z`p@Onba=LRr(=T7Bg$D^NJS?Kb=?d1KV4y-vd63$m> z(|4l+@#nR1oT7)iERCR)3kx**OuKl~lU`h}Pz1^h19$0_ zqZfS@s33~@JlU=7LYf55*ErJ3YicXT6yt$?*W@&u7G`42PvmQ z#x5fm_B4+bTu^+cq8M~$<q^60eLL= zjN@aML$7%!c@&?54HQOm#$RG-ztgu7w)~9#TkAlQFR`x6bz<)SBSQ@&f#=T zH6`*#UVsHR5V%QAJof(8O+h8`QjYph#tq&n%%*Rs5WnbF;bK_cFeXBRga_onKhcZV z69WHa!a-RbY8>%g|M_SY^ekVh@m5RZBH;zSfRTGClDBxn`xG@8Oi67uB4ipnoiSG^aKq zj-I_b3;JDO0ooJt$odgExMP-(yV1&gP%W%%Hsl$qRZr)+>ujY6uqpDO-yi=LcrIa? zNkb_PC-=I;QGcMnybE!lNS=F897~Pvc%n0nZ%~H$1(F-Va)@`6AjW?=9pl^|dtYis zJFDx-Mkg`;mRgt4@g2h>AG2UqPfQk;8tQBtzIMx zT@!wyrAS0t;tKJQ%M||DIZ?Ng!AO1WQbD(43*RHLG}stoBR`XO)`>W9Q6oHHJw=a$ z_Mm+?WFX~%1MfFeI_3+PXL{4$TNVgHey!rhD`-mg(l1bmScm(!7P5417OtH88-Tq9 zmdn1ti>1s`C|KnuFNz#9!|9|fn-O;R_i7GGId z49W(%^mb<|n)+WDI3 z+C#^K>F{h)k)4mnvaYk2doNJa`q3!brW9?OvX|@`*^WJryTBW{f%Mqa{dm~`FLb&? zsv-P!W}Xd}S%@1nRAl|T0hY4-_<%nOu%m1+#O)wNx3d86eEk;W_qnqk&IrNg`Vokn zj1vEtEFd!SEcf)Wx+Lq#6i_b+LtSGY5H-JQyt^@kVY?fh_sUqH z>!<~GMIB^S!c+V{`5k2EdD7K>6VWxpOjI|02kElyz~5Ovz%2G&$o>$3*Ehv-F=6Tw zoyo?q`jZAc88)3B%gw=4UD$?oaU8vVB??`hNMV_d6OA3VA!~b}JU2WfmOc$=MNgj& zhs$b_#ASE|PE9H1IJu00Kc3#T06Z0-K#G{3qDG91Bd<;YNk2Sgb+7@@efDt z=Ozsa+7}2u4zpnSzijfkI0xHaXavi}=G5ZcSmZaj85!?7KzwF)V7=~}U@_Kn7rC14ipMSZ3746dX1`7f@>73~l6TsXJ?V`&mUR&M*{q<) zuZ+bO=~{5@%tLZ5z7)4LXmh*nX-Z~)Yd{M`Ug-D=8=m)GdKnJ`W;@fkln1zKjz9FS z-b^)E2H)_^J5(L)#e2-I4i5)YpXKx~MfwKAA8;l;>XL0Qo`9fZ14IqYC-E(m?ITp9 zjGj7q)gF9b4$&IoUoD!wXg)-kDS$-QG z5Pd{hVh5t&(S&6;h#-n>4$c#mi{dV5bDL~5B?Gp+fcwd^pmmaMcE^eE(B1@iwA_X2 zgselWE+wI^UMVK4e{_YqlsRRFR~hixMu%qR zKG%QrP6^G*8bMOl|HQg7qX32Uk>omGtg)&ds`cY&-GDgcOA3&8rj!F~etZViBhJyA zUW;+liwLX2EI4Q z(kYr+Sf_s-$TQ9AUwSpVqu+`=cS4OdMUgW)@hOFNebg zd1TD-9IWy*hO7CkF4^VMj9M0FB6quVa{YWUz8xP7g|FP`kgq+0-XH&=2eI?XX~k~5 z>bN`XZ06{xgd$uxN}h{k-q+VNyim%N*Jx_F6q8jv6Jg7|6?9uhe{6a=h8vy6c6|0; zf@A(H_s%u&zK97~!D!hB8=_Sb~bdkmN7IL3AFz0X8b{d&;(zfx`C zU`{h6H=n0R=Td#AqcL3M1GbByod*|Adc*h4o^<%dx1u3K@?hboIM%}^3pdVxN4spK zn7pDv4E7aHtT$#b((0!puv*i~`y%dqHG*sXzwns+`09H&y!#y8?Xwr1Vma|4N*8%d z_AU1WS+P5P{du zIk&-Rz--zyJsdCURbm}bH>J0>;~^-@#+@AeQ;+>}i0)+fgL~%Td>8TU zHRTXgXGxtNhYF(nSD*&j0$xve^!hryN|K=lvB}srDh-7QgNdC%6|RYihZYxS+Ly~b z4=H2e$lh!cQIwC%`br`4umxSWY9wm?Sc1k~lH%7ystzA2ve{M#p^idY@=5_@*C>LQF(Cor1=!+K6C7OUL%(&$2)3RcjXR@dZKLE1&~cFfC#x)~3;y1Mt*yF`P1cFB|1=0@;h|V5T^O zN(xvGq634Ah7*06x;|_4Cpj+PSxCoUZA1EOGtt&5lKeBMz*e)&(ArfUJl7rD;0Zg5 z-RVoeZ2a@g3)J&1glILr!X}Kf{XOACJ+j;c%OY-Yf;}3Ne)9ui+7d1BKlYp~>de6< z#qS_3P>QhwjGB<1-vOfVs~tP6zX`&*UbH#ARghz@i{jL#5~J-s_|AqYkZJOp6i;-+ zdU8Kt3iI^N`IC$+!?RKGZ7J^^w>A=T;svyP*?27P8^kHKF#r63^YFw<3j%~v-YYjx zo2!e}l;GbDC`jE4>C9(+lIG3Ww>b_1m}fxozyoY?_zqY`ZJ`}Q+*rSO11hxhA|4a! z@U>mxu-Re-b-D%mPU|Er867dYOe8Fy#WgTr znJE*&&g_$g;b)u3{)Zy`*E#_yvcgA8tk|8DXcVELJjP)^;K#|AW5whV{g123AWez(Xq~ccrd$7 z6t7^J?s6e=EX!kA2~XbJu(MW)tNF=zqo506qj4~|-$Nc(-+q4vjtuz4zYZ ztCUJ5sgO;`NZF%MA<8 z^=|ZF>mO13p*=9<#Z)1W?0?J!``a#}b7vNlY2w}-6tHZXoEuzOQw}*}FA3Ug-hf9q zWTgr1?JrAo)b4RBDC-sfZH<$?>%iEjPUsm<)(XXyWp32#hZ($Gc^5WEpBFTTdp-|P z2Yia=WEqDsF3ZJ1<}R3K?m`0}Rf@;4 z{99f}0`>jS8$-fBvu(Qu70k$wKQS7}X%vW}7EIz@)qz^l|!Wk?uiFRC}5w>~Y+``vP-Dou+}8RAJEK z=a7=Vjo0|xOiHVr@K?SP&6&TSOq$~auja7LDdtazcE62_1~^j9gEz(UY&*%^h3)eu zD&d%%J~((2&ksLZKz=3n=Ke50K;Yj3(MwJl{`p9;RJ8pNeyIG#|6yIA#>4M%tDose zB8uvMMe8$0?~0`n%Mzh7nFl*{cJIikC;e6gqkE$<-RZ4K znr3m_IQ3Gxu5Kt6Jk@2r8_|NVtV>3h%gNG{OvtGNt;x=Cz~!8vGn@)xx7tr<=$Z5G zWEkrK{xM(^^$B(XKRwp_S?0#?)~g{IEIa>wBhVLp7MNa`ew*9)jcsGiO2VYNCHU_~ zKCkSN~*M;+_oY;Y*w*Y6dnaZ%vDvi%(mGTzi+h8j1sj^*NA^>M+5Irw69 zK7U&yhZNRCam#w^N}iQB0F)&?+T(M1dQ|^xMntT|s@-YjB=@i49ABAUm?+Fp#}jT;k^WZ%(kty&nQ8wfA2O0hcTR{+}XbfRuCt3<(h!FupYwvp?0JDq~IrgruIT;L#G$&3N4Z~i>% zmU%D5=Rnh9==&;-zjvUJjLl+uAEPX(Xl|>hvegb0lu_7Aa-TO7kN#@swW}YK0~b`d z@*!;JH`*Kcbsu47jTE1M7^Yye=UlpcUy0a6W;{3Cp53M^icsC62l&hng74SU%MU}o zvs}-8BS;??2M+00LdLCkr4wE_HiM>(e@u=N6)w!0=`*7wpm0bI_eHt$A)6}6Z|02~ zWP5b28qHzv^?31?pWzVmTvSz{VA4|D6y584-43U{}rv%a`_up@Qa{D?^Azk_}+r8t~(ryLjQ zxKc9(Mbn?+SvcD?pWpW(o50FQPQ9JI(N;EqszD<3gg@mMjeJfbyx8VN5BvOI{w})u zXd68Cn=14_nAtgFZTu42)b}NMt0>PIG3@P(cLj06OK{D)#4B9-Ks>@?Ft&Rhoxh+L zc{w?f+xlEbBGI+R@da-|{#2dN|KK*h0JA4x|Wb_Q5gNep8C$y5QkZI;GJ!;)a0NVMm_xv&f4Mps~seIoSsDQ278d2z4j1!*@-7CXXlXSkFUl! z(}(N5#UYMmY=0q^u4jH69ogR4oWk=T))bIOe_rEUbrtjZcH}T@$tt5T;U3Skkq+_-GNs@jfH--65o8PQpy$4ztxNJP_^kJR7 zF~vBrBAsSTe+>6#rDBS|JzXDao^Dzu$Kf585svu?BhA=WbUqF{Ns~O1Ll2zXUTbBXBWa>?s!dHMXC57 z>i}#!=_DE!bA_9GPFHgEzCXS=Jb`&ma(LYhxs1|OqkbFH`3;A|(%!XzQ+M;C-7O^b z9oy0!?M`JQn? z%l4I?K1P!%i*dJh0e`8K62s^haHKPhe{rsmEM6ar$*dzqaexB!IN3q?02DTl`aGV2 z_D$`)M&@IZ^J5_Qg8B4@p7Msg*G;gx*_v0}$F$#BPw`N%xwKbIu^5k!tmZpCY^2Lo`@1wStBmMk-DU2wKh252`dyVx!y!hsfeP9;#Y)&F{uL?&Fu=mtA z3a3~vfpaS3#(OKt0eyMS?6e)7t2|KjFt0BZ&r=n&-{O7)F!@j~S~13l%rba|#SGI{ z*2e&=B!h{w+<2q=HDp<+GWVM4)hlLnfha)(=RJ~g~Ygr$xcLbK|%*67o z`MhC#Ho5g9oEy+jS7J1%0r+~hnKvRu(0DBm`QnupC#tITU35jV8Gap`%3liqL^M-n zx&1#`7a6;?-Rmd;qHQhU@bH#s%y~MOj+!Pzj*7#%l42c+qxcf8vnYe$!*%=7kHtZa(Xn>a5E_Gi`fR-{C@SOe)3Cmb^fZ$ztmFO_|+qTUaKU2;SYe zeX00k{tcR3*dJ8KP7|$7Y$fx1jxep#3?l}85;$;h&>O6_JVDJ*Y=%9lzrbS8WnP!{ zyceTVN+D=nO>Th0Xkp8R=xje713x!h9Wi48zt2LQMGz z{(yfw`FqP9>&F_>pk<*X%xpNfK9c>ttSNx{E@hl?+f&ecPn`Dyr4P=$QhqJ#aEQRe zO-y54tsy@4rWFSsWf}iPYUp|VCoJD0#pJH(O}J*CGnLPLB6{_57W_1NCU|$3mtMiS zbL42yb=Ifd{Qz>DgZWW+%E>hnfdQ=FUQ}^H^tksBESQun_;r=XJj16QXDGC*!X@iG zSRK5bpCV}{SH|7P`>PD;-jnWZL-RV=drS3-5g&aqXs0usaN1k!()tp$?z29PO-lHj zZT^jn=J~0z1%xiSg(ek?=&6)LqF!$tkojFJK9(#Y3G-!r;-J0ZsFyIMKttlmB{-r>uO#v#pGT) z15u~afbI$OBl;}2a{QOOD=QJFP9Q zw6-RP4BYgBZDWaPvTP&VeUJlR>q3MaTn>GTXVjS2j_Jd8$(OnGtGbe^D{LdN_jnBY zBgJH$={5L1$dbB6jes+Yt0Dc+Za#T>3)!uH1I@(lGI94b*(8h;%NXGgWboGs;f9h)C z^U89#aNM1rHKT@vo-DwYSW9|nm6d6!mM=Gr@!<;V$LKs@5qf?s;6KSp$i#uqplW0~ ze|>!+8L;6V8clMh{g)_!#?EW(mXE^z(L2rQI5eY!H~h`^L-Pl4^%Gb=-P{{q-TnXt z+b;7DCVe0W<77E;7u(q>9YQ=tYjNF-4@cQCpXrP5Ap7D2|3_U+wsEBx+{V29PM6_T z?mbwu`+|VUlUF(8@4`7WUH&PtT{VDPe?Nw{h4Qe~wHH30=^Jsi@^b*nbjwl4Z@w%yT7qeBVrlN97?6v|1l%RXeh|((Tk@yc8_22QeKCEn z3^lDDM;z~!;MZ!V)?LP7pmV_2|dGWSP#IvU3+O(#D8R3Umu*zzF*82Z-ge+)7|<` z%AYfjhU4&^vuM&ichhqV!nmpI#;5I-gDcIhd6rgvF%;?U}hDeNC{3*GSM|M~NdsK1NApUq0c za0dH(->^kPJY;b*@`sq#G>mD>s^4Mi$#B89rrDB@VOf^+d{&6)ZSG8Hd-E)F-+7tL z7t{vVY?q^3jy@((5ep9=NwL~)VK~k?<-oSrPl}9V2cgA|Y@t8x?52F&ImnX!c%cgZ zKbVHrxSe-TY$jjR?qS~6Ni?O zDOUga!*tsU1FEsxk7OJR<2+ctV9KHuXfk~yj`})*?#F!MmsE&TS;jCLk|5|x66%k$ zr%~sYrUwW3;H)oZ)bp@C^eyg#ADI91|6aB4I#u}6!ICO(e=KS;IRNBZTjq$G9oOMd#!CG7EYmvMh?H!mt#)RPuu`T17;2BmrkOxZh)A`TK3dwhf!b3Bi zX|sU>1XS9>q&vv}EAJ$QgQjA)X9sU`=P}XW)1N!5!#vMJyrK3L+rOYvd{%!jlFRYY zlbkqKgbJ6wfPUi#KK)My@o6Z+ON`I2-)#+nBnlqD1-_8=c0RwzeCZ0twBuI_;m!MV zf5xzl$oD*a+a`kxjXn5~nU&;UWDsEM;`@?M>H}1`wz9 zMYv`O+bsKfAM_H$@ZzQ$Z=PI3Lc05L5gN?f@Sqb0tRI3hjEKDJEFr72nz6^sf;PO# z64@m0g}Mi9tD>fXyt=A{o5On1uPY~z%^QpG)l$~OzqK61$0}gJiZH&&>J_>3_XekP zR9B+Luy{m^IFR3xGadC>!5g`d<9cyxK^s`R4=*Wrn zFlW{@VSA3dIsxl{|K#64w9s;#mEUb>Xt@7{^qA zLoIMs-9ykWWSpaL;T>bT)yd0rXIluT&)&bow&&o^5!Y~>r7JDFRVBXH{v7v@rL^vz zDz3C@0N>k0(2BnlCSz0#(-zqMuBU#oXv6Jxa(Brw(rL8-*E@gWmkx+0IYY|OLG~0a zHrN7H$G(I60UH5(lTKVmuHKD4_&h~4ZO?S>?+87~J5eX=EAEF!@}$_yMLfny10AUP zy4CO~%pcaetQ0cHi{7#Bk*S8Xs3C;B4<5>WD~+LlKITIg?T<(5J$dJ*N^Oj<^Oz>w zBK8)i40?g1KgO~y5hX0X-wTI);Q7S-d{SGUgXdSU9C2QtDD7e&5EVoTeu?bxowzW& zo8RS?K&H!uaxa@%R*`jxHB9sZ?R+U`4oSO(TbXz3vGw}@Hx-~qeFy)aBg5g2e;CO) zMv99Fe9k_C{4OaDPv-scx`rXO-Qq`1{R-id*=}-E>vFXHHw>%h>d>HL`NZgCF;1|} zq8GbULG8p7tRCk`pYkixZ5R(XP&KD_*WG}D!HPH~J(A!3r<5!zDaYsEEU4GC1ktRb zeGoFXUEs{NZr9OT-kqM*$RjUZ-~1KPzDNpWVD+?-mkqb?~768cd0ka^@|qA-Huq z`#0aaL;5~!#C_*usp{@pfV;0?ZJ-pBwWs=Uo?lsy%D+T>I)5Q5oi616Q^_KSlX79j zqI7=e0+!v-j6|WfbE7JE4o8O~L$^9fEeT>wP~ifcX>D>%8E*?|V3< zVIyc4Tk4vz-+l}F(@c@nj~dBo+386FR~F&l7oTBt^9SDGdj^^FqX^eB@Aquw%P`(9 z3jVP!m;Y~bc$Ks424_l_j7ukqb^W*}Oeg$5PoA(^1}~oR5PWN;lUi7}l?5GgvX|(b zyaH6cR26!A!dMqym9rsrv&bd-XA7~UC6;y^h=GgZbm+`t_f1+uJ{V-c?|>~kmB=Rw+Z<2C%ZMwyhd)W?ZI>3*v@!g zSLnT~5T+GKdGgnd5xBW&9=&u#hQ#g;=8iBPdvU`>v|Z13D~G=m@R=Rg(C}S0{mD8w z^^3fqTjqj*)n2KIIQ0vATWxV8{~~%&Y#2w^KS+i1%RVx_*MonVTtx~PPySXhmmcZz zG@U*-m>cV+BguY}ji$D?*!MTf3(u|=kJwa%87s1BNfYauO?eNsV!|)G{*0LHh({HD zdkPc!g7%cjBBR-zq}%5>8BomO#+FZfg<3qxzw{D+ZahhE7;lEGqhH~qzYVW;yq+Z4 zIbms)FEwwTCkn2a!X=Jo-|782v5w`_{d>0vJX!PCBXqB3`;x{h;q4+nn9#XW$i(%y zJL9<(hO{9&gapjc;LKTGawqF7SIq8*7J4@Yp1iu9y`$eSK2tdi2gcllR8trJOnNQp z;}MKk3YZVSTtj?b;{&c@_np_wr=t#^ATv2!=(IdBx(>hVI8%s87Hv(N4r{Sc@V0Fq zY|T1><>|^XNyPDPGz>Qm;pwMxqWUWY%etAi<76S~iBZ8Mmu&u&Zaztl?#nHl%s9-7 zWiX?fdF5|Ov3iVLBo+o3(uD7Bu^p(L^M@~#O(c)sH{kRGC+U=X z`(SmA2h^9`<-d)1LmYT-EHH7S53j5j=?oZ!eTH}PE3H$B!t5T5e$Tp|)`~#4=m88+ z+sqffZXx65_@U^p0oCi{M^v1Hxdg_;(RVp|7-(W+n+|o*EFe`z#TclbOV=;RfaIg` zj4QGoaE+zu4;TBQy7vlt?Wz+jbnA_8)T8(Z+Am4p346iXQHsxZ(ywCvT6b!+J&%lB zRg5uHa_IwuF7Te6$$F$id5a@urFbkhu<=!g-qLZ4Le*ssq)h{QRg#V_|dG*tLA?r#l=H# zm?QJPzI7%;`X^#Ps~hy@R~JxO_XK_pyCiVt=?}}$%D|qMuG~Zh?NsLsSXTX0%MXa& ztc?S*@AK2Ym5`ltH94h5J;~@dwV>F?7Mw&@LXV}<*;qYiq(3UUO8sfWcodQ0ej#T1y%!{R>bT4RHT?;+|HoUy?2Xfdw3Ez(w(fssR z;&zrPejTPKnWR^Qp9i$V?IjHYKF9kPAQ=@$&-A$rYu1HB_m>O&Pu8)#S=I%&z6A>N z#l-un5?8`9xfWY^kWA=-eV-UU2Ue2rg-uv6;S9Z4+)GqUWg#O$%9&rhnTFw)4C(7> zxkRK>fVq?7C|-_%NBdGi)vCWH){`cq{GU8tGKzUAtv+DLkW)00bs;w`iv;auDSVOa za}vMyCMte%rIwz*Mg7>Gim z(f>fQuSVh)ma}%;D$6<_g1GC%Z$gpB z1tIJ4kHn)}zZ*1gsT--&>&8H~`O+Ga3a*PAVbTdHKJV8F!vmA&(doZDO_K%%ala~b zBp}Yl;}$`4*68;T=lrsx68)7>oqh|}4PGU1=^+=K@%^_+G+8~2{Iwp! zRbGvuciZydo*TzD@cQN|TMJy%qRP9g_nKC01{>};EE7Qx# zy+gt5Htk5)sGSy-tsjU-tFrmQv-3$@Wgo6JHioV~Y7Xiglb&mK@ah?5PD^PUBQ~`F4i^@DECzI)3whbe;_wZdhiNtP@d)n4N5_R=DgB< z1TKl{>ijEpaum>SY*c|Rg=5X1#BURSVwInJ?D z$DU*zTJtcU^m{&uYjtOSumQ}2SNagA-n6IkhnaR^;g2$6?QZT6 znfpwDzN5$T0d?OLv(y7*s{)+|L=#o zmpEfvB1i4s5_0jSA~%k8IE2S!vV8h)$n57Sc#m&AXSstFmNajstjOxM3=HU06*_#T zteS$ZY)j~uS}uwIFAu9()+|>emTk;Eg(1D%`O$Z4$Y-+zoc!WE-MZue3C>mI)Kr;{ z5#9lVUa8`WmS{mwcJHXife98=-H73^>1NnG_^iN_y#~3VR+%#m{g^-|uE@jC$~byF z;tg!s^%BgUgz<;XUXcma1bg1u(d3DLP2lr&uFQ({liv)-GZlttvn!uZHp(LEvp?Ww znbY((Hx4YGg+bSi6v2;i?1~3Yn&U=Km;V+mR$KwgUryuOmwhJduZ+Rv2EX}Zzir8x z>K|CgIP>|3F5ps|2m9QlnEZCeN4$2)p4M=)h<)}QE}}cx`fXdSs1TUOt&_gt4TW0yg-AFV2fm`aCKeHhPevkeDAYJtov3IzY^*WNAGucS)TVwZqcY58nRy;<}fMaA-a@@xn`{-1|n=gdl zvE~_(^L>Ep=djM_w!W~^OkXrSyj}1ok2oYkbNA1JzH#gNV6H@wZDz^e23pVsnNzRu ze|FZB{{Puw!B}5hb?^a?sQ@=O27xoPV}P5dU&tn z1DEwy33tFBpPX^;rl}N$M3DH=0d4S-<-*+9yL;p6Ivk|UbSLFh(ZQ)xV1asJX2Jb` zWKX0O$~4QJr*4vd<+WUx|*xy3p zCd$w7%qKGv*Hxr|7-a`{C~a7l>rotEKjaRF`|8 z$lZ-v`K=e_HVwnbubq5zN-FtfB1W^!>r}-_4gT|qfg>k3^UmHa#EkPnr+U`Kalx1L zeSC*gY-JljUzXuYhaos{mmYPqe@3iU8F0V-^dwzfT6kadfb|vI(*nuT^q|-uSoo6l zsu?ta{wjGq!EzJ-&wW^_y~NL#&d?J!38J-EcY^hw_Dt5GLDWZC!6dNz~^nI85axJ-57Fr2KX~>q{Cd_>-Lm4#p0aS$KZlh2YUz z9M~_8cAriF(aPrxJ*U4|q2-+9jS)3ZoJCxL0r>4N9&>#8t}&vd10brhj8>mr!S%olpy zUHckfm1Yfc5RyC@y2lz>c6*C9P@Mt_tRHT z;?VpYQzDxo`bPslV2zmM9}R^*{uhP2-j?HTXrH}^u6Q9KK12F&m8?Uud>0RG+ke9a z8BZbmY@^kLzlNTrlYM1HHxhb8ONOfn{g(a04N?1~A)Qc=Lnym1g!O$)7q-QNepoV$ z(3j$Hc-I5mUwM|QPTNPORrcn@(JW&!wi8@}RPf>0dxD<))8ix34_5SCe7BWhKbCIXk`Kd{^})2$H~9n0 zScXW3<;Kfggx;Pk{X4jPt`pVN93~EfD%=+tOOKpa#l^>3z;1s8uQco>>CAkGsn*9lUKBCCi@$L*>17{RgZBci!4ro`T%FXp?4h_obQ5v z@48U&4{z~+i$9?|hYA|9{NW5-8D>W>%(^Y=x-AFiu0&^!OO(kxwP`b+pYoS?o0dpi zJnQh;vQxBY&puFC>I89%r5t!&w=2FccBKc+*NJi_YNDog7oQfDN~ZTt$Dh&HX$Gpn zEZzH{P`R0(nAAdsc6s3-mRo$c&6kA74Z@k4`c&1VkmyzGal7y9Nv2k7q5Sh$oPNfE z^)Q&H+t>QxmnR$PcMT8Fo+*b~f1~)6{V&P6P`2kKbB4~Tix)+|*$&-1I|S_QS!IR0 zecb6X%p)r*^f-qoDfSMXngSYip@P@KTQv}s#_*R#)PF$q%a?S(f~0 z9v`TgOX7ySz++P^sNz6PSZ4DQSgMt`%x@-#-&o<>3!YSGV4G-kZ*4ezNXmx?zfi@i zTY6DVJy-H(UIofA@6GIs@nEw)0W!~9^Yum_h|+j9Zo@y;=TP?@7Azix67?9NsJM80$*hH?Lf)DF4#MNCo8|0$ zMM#N13$0`43*BfM3VOKpN*C|WZW&yq0=F(XmS#A5!N;h#plftRz}{}vN9b*BN?-pd z71K?sTxf!xq=A2qLxbv}WpE?ACyI&E$7d+dCDEI=u0zhOAgJtnN$?w|7r5e=nkCee zb$WC@QQ*RY*u8rw52;VS!?Ar*9JcH|gzH=$LQ5X$i}c_B6#3+<^0M!K5X+$xvFfZL z&4|b$D`ys@pG$7Nc5C?wA*%;9<<95`K?+5-}jysbcqcKPS||Mg}(MpB-Uj`aCt)q3<-i{pS6PwjK=&V*oBwaiXUsnqs$q{ur_I41FE@9G3rSf~!}h zy!YUPYW%s!olcsPChBr91dBE)_L`rz#NxpUwD#v?5@{O*zu7j2d}%q^8gLt1*qz19 z`;6%Ho4&YYR1W_;HIEE%Q{d(@pW(SWbC|E40oyk3LvDXEyN!Y$D#zSqc^z_1Y zBE#hxIAUlQKjvsE>A#-fIolgFccnV4eh>|HGq&)TvRlZerkfal!I1uS@+EhF1aRi; z9sS_sGHg>&!{KTZ>2cP@I(e%Ow?3Bb0;g$V|FHr1-S-SFUNjnMqW4#Hih{3<2FdcVf)BZLm_wY6S2E?FAMSa|wv|IJ!omHI;F6QI&{tVe z^&I5~+S47MH;~C0D%=uT=DTqC4yZm7XKt5ba-W*B=&|)Cl{EzjVA+OYDi?$dNWc^o z^h@tW#~)KCrv4vLZo312hvkD>poic?p5;`AqC98%{ep|>KL=Oth?%aWs4#)O ziA`|!^&)`}_lkH5pVnpY8aoQf)%|xd;*J}=b6XLnmz;*&dGm!Hwm-HyxIyU?uQ)P^ z=-JD26}hprVZRrsW|gz9v@87Dl6sP|Bo@;~8B;^qVsUPlGS``_CwcVvIciR;1IfTf zKCm-`T<`k~(>s&t^@nzVEAGI-L6-!rSkli0=Y%eys-LsTLtlCB6?=~x&E&y6{VSA( zdI}kk%re$HePa$amdi4YNdG3Xuuv0roD&0evB|}d-tfvHlp*3DYs!%U%MzXk;YZbWh zB-H=wgks!L4h<&WNs8ygpDiodCpV}1tf*_*41eV(vADYnV-|4q8c$7Q&FoeOpU zk}PtIF@WZ#=R#LogTWcxbVotZic5#yfrkkpf<&tU>*+iBstL_xqiZmBCQYUf?cB+Npu=D|*ICet%?ljxaF#Re zDe@9`?km78ZQ*=ruQ*+w} zd~)|6e=9bTMEN9KFm9unwv8mo0Z>AML9WZ>&@TwAoB#5TqpUF#l0%b_qn=S&%S zdOjNES3A&>G)GZh<6%xsqAU3{)ekpOO^ocx6Y|vi=c#a(EJu7Ha}($+C1r_wRmu0UtH}Xxs9LGOqI~~{JVQBh8xO>Z* zPh>meZ#xQc(kJ%wiQYgyO;F)f8e`~e)9+xvc?3F-h~d9|C??kelsVm>dJ>fxwQxlC zG#uBGVzpme8F~dXjd4&7e6Yy_hkH_d-f-hBt~GR{|GjcE^;L4^OeX6}9&1zKSjZ!=4V7va z>Ca`kKl$wbxU~b?hq7Er%RNCi_6d21=jK__k5ltRr$fzIugy6@uZZUC@zz=wYS@}U z<}WS6n;q%Ymi4slJ5T^4eZvL+TlelK*tgV<{(bSsGayDC^0rlTHe>KF1a zNH#IJTZu}(7F4c78&Y-sAvh<6@0(pnPADvZPxjLVt$4=5;ds;G4}U25DoIdH!9fEY zXiD%F*iyiQ*I~Yb6ZP`xb4-V%xM6>=Y@)w-k+5hL#_k7iswb@$ zwBpmZU2s9h9J=~P3^`k;%q?YnY{#HH*z-poPd41-?|rNwQ{0Kx%aaaTtXDS92Sr*A?B!P1ZjfM-(9 z>^aZ_SFroI%y3__W9)D)aC;1$QSyTM9R{Fn@2uP$R-3zgPfzm6LJKRhBZQ8} zSK&+2M=Wl`NynI;Y1;r3cm9Kj7%3*Z+IQf#Aa}a;La}J+gw3E_-6{Crd@i2A*Cw9S zb`~3bXx#FH+_QXLiJp=lrp_OV zC&%XV|KF;6_(qv)SBRw}tv12d!$sgDvyb2RUo)wcJ%O3FH)-0;c2UFP;UHTg)iF$8 z55y5K<>>)O53;4D6fZoFrRpo=fpo<}toCJrKQ~7BphMRpx@*vAvRX}<+c}(dBK`aZ zX>7OPZ%B-=)1jJw0$+~sq9eZp7@8i3Pv@nW>>B5T2Uk1M7`0#$ms5((&zNtju^Lu= z%Yx~J9=vl|HF0GB&4VFk^oP5d>7zGJoZVtw$)05iIBnfryrBAmcV~V8)s=~G<4gwY zR4gP{|B$brTDCLXB-YP{LJrnP9ja#KDhkTBD&U04~|WI1y94I z_~!eFJ;zh)#B}Q`C#ZPl56{?r z^Z)+jcdV~td(d9m-dV#uFh02H#UlFg+IINo*#(C>n5HqYlI{9MA#s~aXIf{OPOEGe zy-b$kvt`^^bh%?li&;*ylWmS1-XW%E52t~m(*wu~W<9sNYX~itCd0@2 z;OT#h=+z;Pp!c>PdduABy$VW5P!7}OE?=MtAM->>I*Vaet5nm7pKpf)x4O~-^~c0> z)N}OOD5mrJx4~1$gQ)y)!E2%aItfoPFWhyl9+M==B`z|Q=^LS8=&)QD{d^0B%=NX9 zO8m`|PHyAI!SuVgpsXl`_q<<7T*DB|A4#!#af~Kfe*DAxKe|djrYE5@>*dZb*aQn| z2z2$jBJk&wTushwR}6Li(gQnvp1>2U_k8U6Oma(8i&JGj$^73fpzP@YVNAFGKW9!h z3db(i$*g(Eg&b{c#`7+*w9nC}&?8#`gHL<%A1_rAx%^vPnUbz#omv)lOh1V`^}K0z zRD*ay-Dqw;^O-w8xr7JpUce}}r>6U_fOOCC!AE|Uf{rol)mTwP@+Xod{~sAqG86lB zec{XM9+7i*1_+y^vtIWgc}&ZXB_-8Nl`QV)>wqT+mgK z$D0OT0#B~~a~(Pcy7Dy-Ysm)A4^5W3(&Nn|#M%EN={o$WZ2z!qDpAR5XbI7xU7qjv zX=~Tp-dlT@R6_RNt6`LeQIrrmx92`aA)}=tDiWFqmDKP4J?9^IKYd>3T<5y4?=>El zV?azIeep~aRT|$yW>cIHCOjcgb3)K;%pAJg$&oYKVFHey9*diyULl8Yn}#wSb>tq| zaV8wxBr#%VCVd=^QAIv9XZ0zr%tjeo7Uc^)Cp;t->~pnWZVvToY~%`0Wia-#SqN8Y zB#U=M<25plHu?mRet)(Aw_T=VM5H*QZjLt{dLdY%=rVzS#@-7h+g$MEmM@^QN-AhM zJ|cX4I@+IQoynIka)y(;xUTOqOx7w`h86wg=z6BJ75{yXqfZ~88Vff=^E5|zav(|= zTF$&5F|IhL#Fr-ZTER^;WO*2S874berelqN zjfbIRfu24;IxB%{wU)xy6W!6ahZ&W0J|@rfud>^X8?7sxm;Io;5ht8Yq^2uBz~Js( zu<(gYySVc26IvejqwBwxa(j(dK}_zqoT%t767Xvfub*rp#ZB|kabGe>m`~~de0cWf ztN1s~jV8SE;O-P{=j|UFOVz8w@RyOA0(xid6H!!tlq%0Ulh{*F+KVH8{$w{fbQ0=RO^tdRYsTx|8&2x z)M4Bmd>c0jjR%(sKdYtWlUFhvJ@Y`=pju2$?T)~-N3U;`Z+vS}^QAIjclcb5Di;@3o1veBEQL zA6WslgFcEGYPV+Q+c_km+X_6P&O98P|DF-M-P|lAaNLmXG|8-nRP2%C50gBJ(c#Il4qq_*~rzu?Jew8{zWbt494~dbGpDNpIGfFWP1S; z`g2tl^uLe@#ua`-&8cc~E;$%Y-R9DbZ65IOqB`Cj9WQ)IFDJwLRiNXK!?aWoxXC3m z;q=6l!q=P+M)kT!#%dMfdLs#a8TtvfwC2I!b{XDotGtT`Cb8U5=b!11 z2ix(+32bML?bx(_GQz0lVnMkzkBs6gu|4htbubzZrAomt?z;?c{l{`p-((@~hh|pl zqF3%;Vc_}mWMax)Y|~{supz5qtDOYaA9fH99;hR|Zt3zVIn2}2|1V_Pr^4aP_oAPz zN8A8DuG&PZSJ?zJ8(ctL>5RC4WOF1IYc{#j2xo6%>-P~AOW6I6;lVSjmvFK?K(L`z zWZ3dA*gqwJZu<1rs%mEle}iqI>J&?{@X&5FyBtXO>eotg+1Bbk*3YAS{|qi~FNTLT zIl>{sBGP#<2qUwOQ>ACWxveh;bI*L6MZa z53{y83Llo$l1sLGux3UO-7$PTS37?IA8611{olS|Qsi$?e)>uDv-KZcir=oYt&`Kv zQ0?mt^B>8u_kx}eHdrl*n}7zzs;Vub(iaio6_!_?otGt^yEeew{jAsMX$|R!KabUKedvS45J{e*CI4)viFC5H3u;K4V96Dk zE|KhZ2fs{lp=wVfxP#T5T<43MVg}^Enxz=#EJs`G?~<>AF5jJbt*bZ2z@*P-;lSxA z!7i(UlrlWm`NK4^5i7VGYc)|V{JUVFn8|dE6ukM&nJx*^0t>%bwh_NhsJz-le*X2w z7yZp?+qzJ4>y9p8o5#8ll1jnRObzW9o6%oJC1l~H0sO)j%oD!O5ETx@;`sG$)JnrT zd-L#*SYe+?m$9yZ`L};Vp!!WwH(skzi%Yh7QTg0QT<>=);A!}Gkpuhc>_)?#f%NB* zBJ$F40H2;=BJIb`#{(m8LGcF}2QHr! zR(0l+RmMH|W!j0JSkisF005OX;PfpFw!IgGD&5W1wb*c^Mlzg&&CqT zZDSSQhv}9@(;p*VeF2;1eH7jtkr3A#WoW)Omp<<02bvsQ)KpatJ{V4i z3MWgk&+SM~KOB7eufRQq+$LNzJAm4>)mZ)M9nAY08A~UJOL3axF3i;nrd`uN zNVXaq@DcCW26xUG3{@|L#^*W0nEFDZv7C8j?|9ND`+CA|V?!?Yg$#%3dJA-N`XStZ zo=m=1sPiMoBvQGE2zYB)2cB*+4m>q$2QKdjq&u!#a-$RV`Ah6QzRL3pz8l^FTD6~q zU)s#W_O2N1*>Ampk27fh@&wmcOT}Fe^Kx%|)y`479x0^qkvgBseB*Bx7QofwZdkt~ zNEmtTHCgb{0Wya82;UFY5bb3_n0&#TI=nHE@a2#3MS2pQen<;@tgV9N4c7##=TAsC zr97O^xQdGTEpGdCBlu}jB6`@GH}1pB5d_z|#flub{Yx-D9_CB`*`MO( zIV<3_uzX>t%0u$xb{EcQVz>4C)^OkL9&9w+BI*(m8J97Ax+T55B#@Z4u7OI1$=#D` zh*O;-womk>d5s~Gcg|z^=?6@tSI4+u>5q?)S0K|RLMGhB-HY6)r8?`@KKGOBv*o6! zOB`ufgoz8}=$%z}N$64?KJR$~{Wc&5u5LU9=iQ=&vbYM;JJl2Y--J<}30t{?i5h79 zQijQ4ZFe!M+KonM^@T5;(eU`#I?>w}ujY+Q6U^!0m{4LmQ-^nBUejmmN+I1{89fJ^ z(e$FnWssS&Rm`FYP&quXa3E-`GRpiFP z>R9})>_OMod2)xMH}Q!tjHN$(!tnKwzSy_T`@NRPw}CS4hk2MNWIrk+d2FbD(Ut#tj`b?!vaF2l zcsy{VRDb{}c|JA)#$`SbCUq2%6ZwI-Ji>=wR8)rMbvxnA(wQPAFYRxLPd~N_uPoA7 z?`0(#)5S%oW-WLj~^We4nJJyAzK-XqG) zZ?|nloY3y`jF|qpjS+`jMSb{H+cDmiX;w-sCs9x_6o=qru~Vq_^ecS2{1gp5U<5By zeL+<%Q#fMJK5yThuq`!!zMA`woBDYQ=yh5OaT{C7xEgJA87fB;6`jdGJ9cMX?M`>6 zt^^cBg!*5SXqP$b7Yy|P;|a^e4&?MO zA2c(ZL9Mgzl9fx;_~A?^Y--4d{xxzK{vb#=_vAHMg7)y|gpZi@@X!jxH~V~OTXcWP zvpJErGwOOacRAWLqbuBs7svOvlnMKD^ugg z_eg+U0A#$65qAH5L6&b1!uP4ZG!5;zKmFvuh{|5objXl;4sM?`O&-{^KWPObwRoLAK;IA zu6V!O*>x97&Uw&o+b(m#Kiav2Ch=ltMdj3mc*jSM{$DHBYtiN%*^SBfYc$-|I1c7n zQNrT<3R3md9j*9qYJPbum)q3?-F2Epo*dJff)kqE=;W(?!OK1h;)`TFxtEa-$~_%J z?;Ays5+`lGX=egG8dd^l7As=ZX){Xul#r$?y8JWt9bY<-dERcuVq|YGI&|dX?2K>k za3ky3)VN&-Km6NZr{zsCE4`uT2UI!bM^U$wOI2D5r=q{*99#5&id2T=Hofvn{eAyhRLQR8Xq3?pz@|(T!H=u{$PW#bm`$R=F#howFZSkerrDQ zYggrO1t-u^_g2EAp3IZKdWXo9=VWZdm$O3Y=c_GT%S$a#R2wF4g9fFHMdd_uT5X+8 zwnjff&DTkEO7E#q!<#%65pdK}?a3Dq-*Ih^y z?{~W%%kj#_rqabh)v)5_M%c}E$#+bsCmQ#CQ9s;^4sMGkC-ywTu!n5x&8iyIS$~n% z?f~JPW>zsrXO*Q9BZ<$DIV%kCdP9UT*@83P< z{Tp-qA_grxOvlXlL~I&=VuL~wWziovuGIjSy;-iR@-^9=)tx`TH---RY0ODI-f$M? zeMG(Df`=aZ-8QG``FTY9z%{Tn@fY0ZRg;1IPmKG{`cis)fo=U%aAvzq6Fxq;1s@Oc zroDF5aDiv0KtsVvA-D7cLH)DnVC+XVO74+v;|XL$#R+rLn5RPZHojwArKj=V>5FC` z;REuFrBPpF@!FCh7`FGZ&=8bIT9W(no7k-?a`z56tKba|s+ofEx?*y?!vTNR2GCVD z|G4SHCqeB8OL5EN=E%NyYPB3~(sd?ZHY8)mN_QG{WF2gkyAN+`9K_z^JLXSuA@gz= zQVWvH`uUH(WqrU)fS$?PieXE)JlfQpB7(1-4i}^W@|5af3`ojwzXNj-)+_%gQHfp z2~mHNi8AwqlrRl#$=(P^S^E|yzHk&yYSogl1shOdWe_EAEV;k++WgZ%6RGj(FL-Om zci3e7S=ig2MSgsJh|WE3(UU`6!1%Kp^fX!~Tv+~vOc>{j?)}+zIi``RoGRbEKap-T zD1dJJ|H0|TSGpVjE>fXV#Wd3IkRRmmGM?ORvOm@)`OxU8 zww%LFIo$aA=DTE&M_+#KCzhW|jfRF9hhW&{D8b&Yf=p_1MgPm;bmQ->T!VfO zY)@|y%KB!J_cN36!VGt+{IoCF%3X%{gV&4R2eB0CtIUYB~95fgGmUY_u(xUgp z+=`xyAusM*&Xkr;vN~r9why+Yu9}G?)vzD0|I9?{U1yCB^RL6?)mO!v-QU|$xO|x> z)%fJawQqWhnMaf8&{YPgzG%h$;O&BZxZu1)NF3Wp#@yb3 znzMtb5&6O$8LtJAGlmInDQ%=9eGCqdG^Zzxv&oZ=t1w&RoZu2)OMLz%q3@tl;qqHbZoIw@ ze(xR#abJr_Q$K&)>Fq;1%9X%6V=G+PI#cYQzp-Q>D(C$W!a~zXoaRp)&Gg0%(*t3{ z-eTCY)=}uZP)iOBk3$8PgMPleT;i4f4^`fqNLRKN<8tN4(ER12;NvPGqhrkYC+ybq z-;s9kJQ4^b^{nV^)A)7)UHcuT-8-AejDH>2n`t1sj}b_C`4Lv$3ltWrRgy1ZY%5uH zDz(dyTKPM_;_O$*G>Q@3bujD!)3|Quk(Dl2p?wGI9^YS0=4fW1c{hLRe*Zj~H#rog zmzLAdul!-FyfW@uogjKAw#AgA@$X~w$REl*`aJ>6-pTagwtlD3n`iklriVX&lnoc} z#EHFa$Mcgg@P`}ysr_$y_r!zz@={}|UT!QV#~I?~U5^EcbsiZ|QG$ol57Y2BhH!{^ z7F@nEYQ-5csm#=9k9KPl@?owXJY zTckrbHAfM9H|g}@FW0eM>HI&ClY1RHXVr=xgiZ%WhY7&wyjsOTmN>6oMC3k*Tro@Dk@wha7ujb>pKSzkZ~# z^lm1_U2&^%r6iEXCBK*ajqk$;R+>m}8lJ(i#R9aC6NJ$0LNYQx1|R?Np(|HuLg+Mo zE_h|L=rNW%I|{oOw+Xv+Q;4>f3h#0!kw)!~fUrZ=FzlD3VBPVa{5iD-|63G9C#G3) zc8B}$dm>DvwJW|LsC|Lw3qK1*jah{DE5>7ncPV}E4vK-U@Y;Wws7oB3>5FbQb7|(# z405zfncvHJ*As64J0i#&!M#a zn$Vl=wkKS9z`D3y=*7@PZu|Nn;2mBnYQigL*b2-KNc>RUI;RPbbZa$xlmHEyT`WnE|G}fouvPJZ*4XlmCw{qj@(V2n7Z_Oh3 znd>E_=hu*+7tWYi98SL_M@!bKoAM28qhV6LGwyS*frVppg|yX=$OV@5{?X!2Z|}Io z%~xyTqE5w&`3~Qi*66sn8$I1EmDrf~;WskxR-St_q^j+M>bFrsTyh0jQs<0zRpGS7 zWE+=qSskPQYZcr#WRVNklkgzx+hOABlA0+&ZXddC3hCH-*P7PskqU zN(@=a?u-hBoT26-_*n8iXWyegB=_J%j5}vbODq$K=iNTM%?GwSTyBl+AFo2tj;o@V z*l*Bfba?1VuUdI?eiN$M8!CzZbuqw!mA!C#T%o85n<=aCK@4Mc4zn?h@Lc#T*&!_L z(@0dAE_T3HhO0ND%hO#5J~W|C0)q>N0e=|Gsw^oPyWke0X#Zm69WuBg|OT1zk7G{u`b z?TR6fsxshWrA%`eu`L^|@3Za{Wf!ZV@0|G4zQ)pA-4t}(Fa|$5lnT}lDCsxh3d|WI z5iz!>pEsJ_@uAv+5*WYQ0Qcf&iXHNy^#*v)q+O_-nNDt)Jc2Wkj>00xS_1vpJL0)3 z&6w4PRI7L3jV=>uT17FQ>|X#AM>L4qZ{}2EK8oq>tFRp+dia5P(OKcJdL0?|Vj!+* z{Vj~tKStgsHRD=I0&QX*SZYuQ6V-#nyPMaBXpFC#MkDp}th~EF=k|{3BliD{^Y4p2 zO3kToDUTS~#==!6nYJ*bC=Czi_|q@EGcgPg#dN2YwCq|SR6JM2D;E+3cljs8nB{Sv ztvyDQEGT#Ff(6_$u@yaOx1CSmE=zxES(!#!JTrm+94A;LJ|k*>_wn5e8UA?1;{Gv% z@aXl&!u}a~WKCrm<{ddfx91H7rx&j9ePO2Xds{K-+F*zI$C%#RO%B$pSis5=<3+t! zZHpF~v+v08r_RK)C;>~=-KpW}wO};-9z-fQ3R&Ii$h?82xaN@y-DYP&zGrChD_Q1! z`I$eUnROLxF4PK}Zsd^bi?w)_Zl=<{gPXv6pdGmPJ1g>7eXlj>-c2^-MufM`` z>k_H&k2Dx|{V^!p28w#`M~9cV;FTBMX7j@8T8J-i%Na`>-6*@otzsK@ z0tzbyfln2fbjn#HW#>q0YJJGfow7?47~-d5tbu+M7Mgb4T^ zSOtbdodnCK_hj$Sb!gEMM$Hya;fh~s^1qLpNUybj#!p3!usBf0UEkg+#wv|8+MRiv zKP$OFa?&zEW5*ZL^xPZAU1VD)dKqM7iW2{uWr*DB@?p=aP8eq$ENZ;Hdmn*ykv@X! z*&34a-V;;Yz3HDR29o2SpFnSw>!OC>RCNdU=iAd;JFarqvJ64>TB)cZ1bFYn93@ry z@jx1BEb@ffEwMtjaRqra+#91yeW9G0$Qo7a}gd&-)Yq#GHUz`o3YRwUnTCWlOFL$Qv7CYnW4^`k} zC*!M?rz7!s{4pAN*qigc{*60uTZX0N;avQZ(v3>zrxK$FTKr%jq)ht^YMcn7n|`h3vN$z-GvbGkRF*}?9gAc;t;eV}>%5Kq90{pOGAupkz_N9Z zCs5;Cmq=!#7T;*b`mC6Spa7jPG02=Q{9Qt-7HIL5eSa<94Z=y^BeAm7gBB$&$W~a) zc6qiPqx;sy!0ymzD@(rDD3LDQ^eBT)vfqpsi{=e$^$s_?%;8KnCSa$(Kp3mmbnoXNddzy9%SMfcS)k#}WTn>5!S5UkM~{SGAw{X5Et@6Q%IGsRT; ze0nv!-~1n#pE@mOmgm@bpc1=_d56W2p-;)m4+vt~ zd|O8Y9tZX7Z;HSnqC;g@&bmFl|iRtE!*UpDRx~(oYBW0pW20@ zm~^sdRTf@jJ60+kTVc(}0(f-8QD~pfvb3Y>(D0HQ-Pq8Fz@QfF!#LHMJH@zODuu-s z4WhRph7RZZOHHIl^xNUc5g!=2#$LRy#itFx=TrX(xqXk5ep=tL!a0!^x=G;cnD_8_ zIm6gNm1If4Cp7NuO<#9talJQ{bM3)>guJQ0h>c=zY$`IRg~#&9h&9n*=;zP6N~%ey z{Wtu;Zm+HZpP=6*1=J~(@m1wBn!J)pB2A1^1~GUx6QrWg6s=L+eh zzi|fpo?jFBs$6k6djC8|!xnv*9(8aJKkhZ_ledY*DK`gTYUyLa#3+wwTr5W~dW!Oy z!=X3t4CO~Ng~$7f$%2*>c&9y(+N_lW{?Hg$$&D8lzinYXoV{>pNjJLK(uM3u4oBXE>w?{VeF^6Vl>Qlq3xy?WZ)uAehKSz$}#u@rH(N`Zr2Ku$Q&Z~OoJcG za+DWa8zIT$1VGIhVceh(WYpeX*f_r%J+@PcjDH%A`ijTt-w%$kC98;a-^jFra@Q9a zrNlOCw!W|mpX|d6vss7d9Ev?{mg6|Z5USt!L1LMw!G|y{;!@RVj9Qcp=MM?OWwu$_ zzUngC=J?Wm&o#k3MTZ+;(JFcy27EEa?vvWZe4P1KMSgP`>)X_ifRGDp2YkAd&`RHv zpLbWGWA|`6&3X!_9jL))r9mRMDZCCn57s}I ziJKiGW?aX{?}w;HMHP7xt;i1_k|b&c2Ydel`R&2N%Tuq3Y1@97eo4k%U!QVkxgd5g zzOOHtn_33T7hV_dXn{H@SgLo9n%P|C$~F#yZ|Y^@PDj$q?Ko|fDqR_tM)vG;hosH1 zqGsF3mc2rmUOjfKE$8$7C!lYEp#HXi1hr(~f8$+fp@jjI?nwgEEn9_-js}ud8iopW zmNZNfKr(jCh5@g=1k30e(!=j0b}kR1xv7zoJ-WmBHQ^@GkSu3B-QzX12FbW<$ex?{ zvc!#cJ-EO{+I{BUE{o4uI!i7mu3IEnq z5U+hIc)|RKfY-8!VLRK8VBN??2m8REE$na5BE#5m=z~AEPofuITqeHPHThb$V>0x7 z352g`hflF=U-eT7Nlw+^KQo=yB6biS-xqxkhwwt z(~UcYVTz69*HU%36f5JdmHkZc#vOASke5aLHH1g)|KQfDDw4;4^N!>1Ge1I!jHa5qL25vZ8JKJH~I%OQ8fX;B~8-0qHw zcf6^*G=@|=l;Mw`Su`c`8@NtLgCM)k{?AeSSjVuomUW|8UNul4q22q=x zU^bk;&GL+szO_Lz>x`2dVK2Dr){*{u2jIpne*~YA#|c^c4YhZ$oZV^()P%o-JzS9J zXZZN036FpAq6zt0T)N3)ZplTNR-ok53#Y#|r$ct-k)1m(!*RB_{QsUbiPJUwGsKNf z-E)E@zWj{$nfCJIzfUmsv^;tnCJLjpS@YGcMpO=GJ=jmGIipZBSiag;_`jDd{qaE@ zIyHdKs!b={_j_<;_BBzbEmOXRHWF8Qr?YdqLBlTI=PSzyTgRf0IootrE)m>x^2o#9 zz4)OF&((%)hYO*O&}5q_tYEiViw<)bcS6Q#t?PT@r(4~qd#f`U)BFqz*xhrVttX^; zq(Ihk8Qwk!E5gI`TxstF3zGF!gK>-mdak4s7Oc4p?v=G--tFby9(0Mlh;A z0+uVz3O=hpkb@&Nu>aR?^yz0MGOg_yYCdPYrB^!m+F?6+;+r=nr`X^Hb=C%lR+(H zcg8-lEyNffU1$?lFG(ix8VbBlE!%}@4+lx-OSY@%B~EsUw*Ovz7R=sck)c(k*rVeC4UqW5DRn1y_gpUOv73&?VNnmZZI@U@W;Mz4 zeeWjHzN_;=ueBZC2L%iCz-!XIemBHi_YoqkYDg+^MFU^9C(@-a8FRP<7JFS6J!2WF zDVW#hK>H|PV}@w9M#AepzDhrcymf`@Aj zF)BTRgL($hs|zC~e*%Z_%Y#j%k1sgm${`i-kElPO0y@DM0sD!>bKZK@+EHb3) z8J?CB7II{B+ykx%j!WAz_<nsO(TIJ9n@U}(-azTjg>bC?wCEX|cikDcy!E21!lFsum=Y|S zA)#f1TRjl0Ov< zm}qJ$O-w$7>79{KH%%gZ4lg1*Lp^ZhShlsDstTqNDqg_=ZG(H~SR|WiZkMfU$v>*Xlc1|KxIxTK zR9rFS1Fo4!&$_k2`VT#m`xCx(JV3~0<30U{8hL&_0 zzvXq6`R-R@soGy-&ambow<$>GRZx`giC-$sshL$CnQC(p&V7+-2qs6aB4K!Yz~}_o z4ow)qbUd%&pCHM!8!op@6uk=0dWE<<@;HrMMY-_hPSQ*_FM9QURrZk8NEdcBlBrHE%MfUCq!I>6wXs%AU)ruvayj4Gz z6*?#21?d7jc`%gvmVcD2EL7vy)|p6S51qzdWoZzYAj4ib5rMDA`O?|{dO@>wU(V>h zjNk4oF+#i2HX)HqCYGB+FmCu9s?{+XHukRo!+SD4;mzm8C{M$w^xG6J$z6@#9%Lf* zz3>?y2{lmO{fmgbds!ZG*&YcU+v*Rm(i|YxYq^+Z%lC^!%iL}B*^Dx>e0m5D@0d-K z#&3s7Pk+EnX|RyA?KNpt-wEf-W&GB@#ThFqylJVqf#i&4F|1CxE^4#dP5012&6Vb^ zP2?7P_XqcTWui8FJbW`c*s9WX)6&TN((`cHIaWxlenCb%x#FyIte-Q&mYdww0^M#E z2(JTJC+ewmyg1s8jvPDyY*xjCx!yLh^Pw}`4|_R{qA$mKlU|NiVBaRg-lqxs@sLX( z9eE`}Vy|n+UyNj#6lZ5N#%G|Plq+a!J|ed_$04nEqj%3=;KJe>xc7S!L{CENtQlxN zQl7q?no8FA_vF{9v3qoE6kNN#21>s~367I1h>80lY?>QP@20Qgw#`>Wn~`n8?4H@= z?B1I=XtEcTPS$}r^Fv{#oeYO>*ZQE3>2!L{IhJ_2^yH_ojWE{}kKs$fXXxK%PS5u& zB?Iq;;EW7*pE|HGyUyYX#%Cwely$Yxd&@`2KOHajPtI@(L5<~e=-(7yF1v6J950q( zZ;OE`E^j?W(;g<0pfWYS`)3pBaBKNKq;oCV9dS$TyJ=8D2n~gHAduu`j>kr>XNBCF}vrEC~zH<)! z#(d(ybc{OHTcS^_J+TgpR+>t;cfA4sws{~lpB8-xlgpg(7V{1M(Y!+boi4&UhQqN< z&G4r<8AhL$aotgR>8SVFjot`!wHh+}G{5Smu{3Q?GLDNhMfZdxK|jVQk=~WH7_MU~ePLUSE%P#AX1PqijXXGz-}0Ps-N-f=!nSC4 z%bgQ5Yb#cco^o-xb4o_GMyzgEKRhcd1kp#BI?4?jU)@A+qCUz5w- z4DTa$KD@Z8&NhS1sq>gTlHkn-zy}71S&1(b*$x!z{?c`^CC_fNZsE{GdZ@YyHd)Kz z^ZZ2N#L6e+``KD{r}m;BJ*v3ss^Oq_$5!+tM9xlu;m5Cu-mtSbV)4doH+uHipXqo> z4>RAD2nsfNU1yxbux5^2_m zH0X@YgI$wlc&lhxfLSbCrx#Le|8;vs}D|&C-cL1?}xrepwljtd!&JD-!8KxqP_uw*~I@3=wZ(lLv2w zY=*ar<7$XX%y~TFz#&rX3-b4N6ZZy9viR=_m$sx4tLu)iK3ayib#I+<@Bg;ZgmGlbHo7bTlMZ7Ld+NxG`3POcKfMeR>C7`xknFkwiuy(iri&|>_O%)T~>3q-pQk4VVj__KAYSryMeAdyy=(Kx}f?r7|4AY#!jyBMV&oB)AZxWoryj8 zpNedMdGce3>)QaYx@26pz)gjB{m1mc1A{PdXees@W^cgICE2Y+TouZ6*gN7*DDHLep(;y!xrGzT(eiH+buQOO+@OjlO^Sp$3-bxj{?;#FB+{+3 zR>Hs2*>HdAF5%&a2J$sY0oqK5i`|kYQG@Xx(-mj!%_3H#%5nXkTxw@m0J9cGg5Pon z@fIfe5r&G_7SK^+{o&54^n+fN3HS>Q$18905e2i2`{v(lPp$NPI2OTYI`Mw5A_ z2n}U|&nrr%^sdFd(@dqKFCW5@FTE07`ap(9_A?`#TN$c62U$r=q z-rc+n`d>K;E(w`}+UQ~uywM0==Z_coq85^TVhU~y8cWZ4-y^u|F*-9p+qbcvP(M8p z(o19*TUe*g$M#R8JnMNi>Kg)9hwFsHg*jy9C?%e-_fGY>MmX5l2K)oh3a;`Wi2jBk ztYDhDkp} zop#=hp{SPBE^sH4i9?^i*o%4UO817t)uT_LMgF{qtBzylV#JmR8hU0b_d%-2(@Sh? zd(~&WH2oEPU-w1uVRszoVWn6#GmlRC5CW1-rvbBN8iLcmDC}i&nEoeUMM@3+VpRpriF+)t-{ESkl!T3)qp5RjF0xAUyBSRLys50o^Cfpoi=`cDtf$iqx+ZL z;uKT$AZ1#)$YXDXZNOdg)o9n#H1hnCJ*dRR3ST8Jh$_3U-H?P)-q@KN{@)k4^07ep zwzYuFj=7Dy);rTIdp&5jx(-%}G9G*5eF)lSO{T|-gUJTDiLhXTx0rWGa<#!r?!k10 z#|6o(xdwbP>o>T)mU#@Gl|bmvT%q~jL*n|RmTOE&5Pb!w_i&gzPhRwHJ*!veO$V{8 z$E+w=`)Ud3D@F_Qdh8Z9U?&Ft4W#i-YdHDua=0+0O_->XO%AjCX8?N>l{riWm;d*1 zcgk?JGCmMGe8(FQnrR`omrI9@v_AOT2ltbiT$@j04{;djmclJnUX8!_vTC z4yf(II=81?A+JJ8urMv3O2__zc-KT292+R8-+e=N1~6T~#Fc8eI$J6KJU>{RNM!a&yg`WcHH#v2f$}|e) zbQzXb+w?)j?B9Zc{eANA>m5AE?&GCHw!?dlRu(7{7|NBrP4U|kFCyid? z{=ufw;+>mQiX2~(?NT0u_x8}$6-NjHCc z&HZc~2ywqMBi#u|9NQxf4Iw7 z>JuJ=rltMxn0u+Xzq$LW8h^{0Z3L)ogB=SGz|>orLO|bQqN}$V555YZTi$kY9XE%< zuI%w*FPTEXL`+#RmQEXbkBl!a#0Hfls;1=$*Z0Rm*AE%S8n8Dtj7X%?nBP#<5&-++ z>xB2!IV3n;p4T-pl{Tzu1eNgZ@bURsp-S@u*_%*^Uq2<%;vH$Qf0+OZdt|uk)k$#> z`)rKXDYnY+apjx$vCl?d0ndG7RV%~7Xq{7o#PX6nFI6y=F6n<7`Lnm+o*)RttTU?4 zI~Z#nS>N>+O)$FKlUww-S=>hsDI1LX1?@upie&O&Z6{{5Fr8#tIJ|Z(hl(NRg*W%! zlOKjNP>%VF)<~vs({{`A16aT1(~Y08=JRvV^_Jmk;qDUrw5x!|YzYHRKU=Ws^PhPC z@;1ASDU%P=J7twbQu7s>972R{{;$bb`L(dJ)<;PES55X8I$&=FKUzO_fW&cl9(a$x zA!-6=eQ%>ywF@oxO5m0o>%yUJ<>Jlj=7x1RmtpC=z%;T?*$&3tj}_LYz92T=-En)b zaC(2aGnc?Mf&ZHVVe7C0B7gr54w&msO{xZff+P;cXm1zJO=u*J*L^YHe;i#}=}YXo zTfj+P#!-(f+JTd%htO>!FG_-6>hcrsvmX2TtW)7r5q$icD}=G#;l#huXtcqDhNNEP zuDZPCoGlY_){d6TQOlf;|9Q#Nom#16-W)Z4z>5Sr^U-BUKfVAKjf@tOMpckX3mYVZ z80On<;+{qRg`w?jg7ffflBj+Sof3TLxZQdXa6bUnOy4MKvo*hB(58MPZON06t&`OF zvr+V1TL}reDbK%Qnbz`ogYf&IAPhR_OZC<-%U;ah+VgUf=*_NL z7;o?v*44%f_Qg*~&9Hp@yTY9&pP*c80T1WOT19R4Ne1G3A&g!>R!$CImghGqnM!B1 z&qJ?U!C=dJ>Cg0hLAF==q4_UQ8gSl=Q)T_kj)6tOaI1XsmY3rAwXT#5Hi9h+?!%Mj zT|(QB2C{$F3k+m$cDn+17@ge74SX?N*y_?w7I*36^Ja6ZIXa7cT+4XdoC3PJ{t@(K zdx#E6GQMi`Aq2G~i)r}V09aeCj)#BW5_q+8vcK{75@cD79_+tqcKZ*|>+ulvO{N2Q9=wgSYF(*$KNqXli;waFcbFb~^){|K zZG@lSmWz3WOtoL^?LV7VF&};Het-CpED`eEipVt8^LS@L5WNTLF#3u$MAXSJmaoym z(si9esq{WkV%dgl4|jUx-gX#tCL7iXGQOHJ;2EamxzKCznq<|Q=jb-tR9ZN#7?&g@ zgZAl0!77sVqW93@=P+KBVb%t31t)kEbWVsesw0}iwb3F(jyf!{B?J84Vrdo26a+tj zmaEUfiurc_pG~kC^alUAcv1V2nw;Xy3{K%@A91U~Vu%7pbePjK&vQwyMZqw8eSqjU zC|j$GF)0dEsQ)TS6>9MAb#^x~YJ#lXpRlt>lGw+4>Q)tcxOvf0VU=7*f&t93KP40y z*Aue`8*woSVwjvsE}f1CeZA`m7>3nPti1y)}4;Qee<<(UuvoF z-@!am{9c7uVwuX=0b3#0YB#)Tkm<4i7HmeBhb)J+s~hNy8Vsktj~9l=w2;<;V=`>g>?s zZUP)GV>yMMg+$`#kDbXrRJTI|$`Pk!e6Sy}i{Xp-!42QLQtwpsOHF{S& zoqP>E4xj2`1*b?Z}nvk&=Xymk`4@nO4BuKF-|&Q&P) z-Y)J?=&tv{Zo)V^ywsN*?l&67E%FvN2C-g+qOG|8P$*Sjc1fbYxgS4`u!*N0s z=sueRF@vLpH3}6Z>FY)u{x*nicUjBzrN6ffr7w?MUt?er?oF&8IlBsh1y@96Ex=Dj@Wj8EUexTV7gv@ygI_k;M7pehC>FLW;P-1q!b07A;`Nze zq@xRseLD=ilhOfa+K4zD4;`>;$ZQ&+6~)~@^qZSA$Vl+4Z6~D)`q=!+oNiFfB4!Ic0a$?js&vz@TJMiABfrv^4d ztU-CuY;jw&ZyD@LeZ!Q}rX?CwQb<~omiN9-1MP36y;Gqyl~P7ok-hiGh>S?6a31e-5D}GVYiN*) zD52r^{ND3_pFZ_DT<3bO`x?t1;}Z6H?VMPN0ZN%LBBF`^mM$jRc1ogwY_B=H-%l{# zco7;Lq+GXU=twMkE<9mUNI4K=u`rZk~by;Si^w~@NeC0CL<`lVm z%WrZcUP-;R>tbZ^c;_@4n^Q~_5BS5QNIxO7us&W1Xg*iTUR(zBj=S zgARz$N$3B+*Y;ff1#bC$nJUP<YUg$z1MPCwmbPG@HMz7cxxTlcPBU0 zhMwy?iENuBFDhgD*nn%@@OtlMI289@@F6@)`HfR&X-ht-G_kIu9k64$z2N&YTQPKKifilE-x}qOrr~xV?b`( zV#uB=#oH_SJJBYN-7!z>P zT~E-oLDeL1guE!$KaE-yR>H^2kD=Fpx^&d1Dss5Y3tjtoQIC&n3W6foJAHOG-I)3r zCU1BFhnJ-aT(`F|2fKFt5cJrf&-3up*-$ED@Q56`_!}>Oc#G5KE^ySn^P_K~-OKzGA ze%eVgh>!APY0g&}=#|yRy{MLP?g!2- zQjCpnO~c1yFVSBmrlc&V4G*@mKH=A`Fz9eUJbvoBzeS+ju83~UT^#Z&j;yJm$YKCWrr`UDwJZW+vVpdX7|v7f+kqh!1DDc(gof1c=9vc zY3oUwZC`Q+vPZyTD&?_$WE0-24y38>`DA%fBJA04Rq%18PYlPF`lEQrWo$O~@OTQaTRW5-zz)Tr_;^isGts}b!$uV^K9|(nk4wHPI*nGd#sj?nQ>S>qf_VsyR9n58*|*Kx`q|(epdl8!A^X*_dBv` z_+0#tgweCE3%IzY9q9CmY41b7Am35}6BWM+d^KsjrpWyc^DtbLLF4+PKt4$EbJ6Qi z%ui&wXFqWDL*@W)HUii^VpI$oQ zN0fD@z-lv3KKtxz^7hUq^sWq~DF-9OCZ~pq+$vcY?qFw}?<;|x!zKJ)!Zg^e5qRsJ zJN;D?$!QFF#@+Ht6}Bv$+vj5Fqh3_?ZZ^4H)JJ5&zC&x@Mnl_YL)dH@%j*t#LcX5g zj@ctZsp5&; zKBD(m(&$C^N|H62P!#;5=&HtFvSXM&Uj7tHD{ed@-*0x{a^__k zS!jX|&R+0!mK0Z$Vm;CBmlrjhbrH(ULel3qptAGAR3@g5S_kLPGZDW9eck zuAcC_38zO`@D3B3h|#-+c&;^;X3EQg_{&%Bo6=@D!y>N}XukjJ^9*M&aD*+qBp z@j-2g>DE`^`auuoKRD0NQ~5}~x}8Ll??Y!#NFaH~CW~U3H+6c*MqKZc01G!tF?M`- z80v|wsZYi+!{+2eqV|WZXL7=Id}J~a|NHca->54g*4CF`?FTXcc{|J7ZWTeN(K5cH zm~FIV4@Pm*U*2_eKAFKhJaba5sk`Ay@STtc_KTeaZT6$nef-OQmsOh-NVno$+|TZ4 zh20hCH0>&+j{VF>^J4OpDlk1$OCq}Q1J>Kw!YHu=-<;DxCL9`tokjBW=8cQw+WIiG z4!5S+nJ%Dvpc)zr1NpAotp7i#4xa>Erg@19TtDqJF06gHu&t)+@C!!vOryOWiph={ z-eAi3>X^axM3HSnEXnBM`!4(>{`n&m?IW$}r*(;N=hSzWWk?q~81JV)K`zLXwr_vQ z?OZz)fIrKt4*W>QKV6UR-vVh(Kt3546Ax-WSNV&N9~0eAp%`oJPPhE|wZh?##6zCLi`OOoFa|4a_G@)KzHBV+Db zD)WASWIpQdW*qUi3?`oY#^?XZC*LI+A}wA^QhQhi=Qkb(#jXv4e?VbyE55s&Mib+kx1h&<*l`BuZ(*MQvlGPQM-_mxQi`wv1z zgpg7)b7C0Qy|<>ha|Xk#{V`BBX}^%4{bJ^Yw(AY(`&57OCqx}ogQd5vDBJZ|krqhn zbR)!9RTV_@A8JW@bvfZkSsunFNqMRK(r}z`-Gj=6L~%KrpRm2mG(iVY+C3Go@95x7 zMy8NJ2RTs+>rS^TiiXE2^I?yL6jzUQ?MJ)xIO<|^gj+S{JES&t@Hgfb5Lgp~vU7dt znX{uIF!?e}*}O~GZJ%A1j4R?#P@kkK(ou2`E}||S7*j?14r{|Rx-9F|t%^4N-7(wL zlPY9fz@pypW}e6L6qx?(zyW?|w82g=FkaFrPgSYOZ&p}*_NgIW0P z8oOgA){r>4HXOq4u#-bgaKzTjaC>ti|LjgJxtHmIbL7408YOSeVC6y)w@gct#%`w@ zEPCMj{7ODtwv=e}+`=_o&eSD_^+|NyfZ+cu1de+2F5BZ%il?o2dckUz*J$M?^Isx6 z$e^HM`0L9wy7R^zvMf|Xbe#E+_pY6aRcCx)YPTbAy1#)eZAxalmTq*-qxGbtp#?V` zVSbEh-$608FIIV97d%?#W~G>Er!5(Bz=N8+;A8f{po?hw~RGS*K+ zG{%eJ)t-&0&>at>Edqr6SMJhe{Eua|5|%j|j=pUvI>$DK7XHjY>%kMT6l?e|RuZC7 z>;|vji}}qPD#+KOGx$3ofVNK?0I*jCcNL6;oyt+02V>Xxf4tw^e6qUNQ|x^^jc(Ln z`*fbU5UuaTuiVl=ik(@H)=w9DX^|okjVQ%x18vEK?-e*SDhW0%`OMe95R+>Q6-0GE zSjI5&2R#3A779BZ_~~yNNF?LKEp|+g-C;xee0YMPacOk z+rAf8Mr;6s6;g~{>$C@ZKa8XG`vyUi=_rW4tuN$l8`7s>;8tDgwLXiixLt)S_ZHBh zK|!#8X&h|wx+v^armwk;dAY81{QOyjPUiV|zb=f*z~)Cl9}|zLXF1 z7{9G`5Vjg7#07TG!`rpKIW51%Fy0*mG!4`XW#=?Saly~ZLkC<_u==s=> z7Q_#OhZTLf`)NM~kHOwAD#*?05_$|2hTXxwOWbHy#$iz3R|X&dO0joM@C+R88^Lt2 zMclDhUvO22mgLRnX6(o)fsE_lge+LtaCOl>KP|~O9T{|5VhKObnF>3VkI#l+ts%ot zVBN)AzM?wA;fL)KNDqAvk^aF#_Eu@;GFYeY&2PA0Pi*o};1~~o`smDf@$-<|AQ_(` z>;i}0y^30o+~{KEbnc#mA`BY!s3^d-hq!31L){|-=)h;WB=zJz(3um@m!#B@L;X)+ zv?}Xp-C@T$-hKfK7nJd`mrBX~;A^-`*@LbbsRsXQqd@-Le&H^r^2iHMJ)TdO*#wep zp=#_lDb-^?#QleF4+Ybz#z--}Hc0fFbz{bTa6(H(G0crC;Z0W&$EtbKmrP?^ zJF=D&+ouURg_>WQc;ebme&&H>VyoU;^owWxlYY@)K2{$dSjF-#opog5jSU#dx?&oB z?dE!CeudGKfARdH0updE3V+-9(A{C9VWx@)%n6p_aJ%wVoZWVUK2ND4zsB_zWixEo z8dnJpUrLzYLzg~_uObCnUvUuY6}<3971!Nz!%b>lw8>>n!K8~1FshfBE*;Ye#TJj@ zb$hCiS>PP9@LazObj;UW?xo{=aLW2Abc|RL;$0W<(E8d-}Es6Fv!6yUU zAd>VH`xG&1UeuO!Eq(=R zZ>E9EbUWc*HvW$lTA%i#zh5R28>b1PCB>|(Ve>}pb37KFMoal^n_?m+-(y__OPmeq zxdWnr_nMMpWo&2LK@G#xYWRv>5@J8y2^P;IeB9{@Vm^GJXffmeYsbfc`hi7YvcQPn z;?zol{|>+#-+TCug#|<>um&R;ud|o+1>23;u-#6I$)leHVNl01I!8pY(@s{x{m3fhvx$A3WBsgp2dvLmnZsDZd<_Qx5w|MCl~PLgdF zH8}ry8eQX20Ct)cFmpf+(LB9m9$zX)wn|++{6-JEHrP=$6 ziR>s3kgM_I`^vJ-O4eCadR&$&XEuq4*FHkaYUX=UYJ&KdFYs_~hR}O3kbTCtn6G|t zY6LfF$pF~(MykyY{J0WVss+>9rv=0_Kbq|gUllyGmJz{Nt#O%(AIKQK-18U{Mr6>i zT^iUNHW;fGKH%?=ViMvVgcHUY(L?IJVB*p>uy1)jZ#J%y%xxI~*9Xky-SyhZOMMNj zw9%!fR%DUetfv>*K1CGs!pJax2P0rTTWFO4ftnkU{WF@O1P@iDtb(?P9$zpRlJ{OL9}* z7VV}*!;1ry_xw^$c5Id75`2FM+HCD%Wjy%0i@&-%i;OvT3-7U9_KMzC(C2a~oYr<0 zcyCaDeRQx(pj{h`xp{Jp7|Px|$q$;baVZ50$v1vXYd(p~7%vKD-EOH*zeThZeBfatH|7SF8I9MlMa8mx?tgB_J-9KQ}5xOP}%Dd3{g)L z@YdM!4*nkMPNS44mlA0JHDx~qA3~hPRJ_v=PEA#7$=MZ+SUFQ$;$Uuq@mF1;%`TCD z8Bt64Pb|lG+M6mGdvig?b47L=83#TegvJ}XVD*kl{!2~?>7SX0zKpM`R%(D2`{rHQ zBh?dJ*UiAFepjeco-C_ka;iT@sYV3{X^H21H+n-OG%@B3R{sDO*Qq6u!@pHUn+vogt0rtjFN z1!JFo=DFU4+_vf`(qsK&5gUHMsj5a;ePqItWRXQ?KJ8@phH&@@<{9%jyl;ddqR-IFFhkhWu}UvTw@f!`^Sp+8{-!T1oo>tj zWLnKBKLOoHZ0o%^XpB3807OyzgLh^femz>%}FWtI)wzHX`2zE+9pQI_F?gTY*wQ=YAXgc^tn^<;b1D1@{mfY5|MJJO8 zDEW`_D{qvOH=9&N51%uR>U0gN4))@rH~$dyhqkv$xc+Q6Ulx@`+LUw9F58tBPCNt^ zdy8TG1ZRHgs&^zMR2T1jjiVyfrJS601DZ0w+2EXJY!c*+9|N$;Z(sSz~ZNT<~p^j(U> z6Pvbxl~O$ai>o6hd51A(OdyS)=g4J`uLG?}DF<$hyNVU+m+7cBH6XF!kkI#lz=1Wl z+{9}P-}Y}RBE_krAn}@1l8TJZ{0KA5sn+w?72m z*Ll&kd9mC)wFlfRhH9{0N+}Mv9h4DOm8H?)?ECO&qYk{>9?NH^)sa5d8?Z_y zhHh4|J8DT= zxC@^D&xcOzQq zcDDRJ>wHW0qsA>vi&&^C>Q|^Gp(8fpz7)2-n-d`9cEA0)f|R`h3%#5T6T0?_xEf7K z&G8HjY8;0-=N|K=+z-KI1v5Y-d`r zn=4&X-=EWY7{PfQmfp_x+-ZPY%r{stznFY@;sT@J`0>uSUXe3X1Mw95z8;iiM`AOM*Jj)sLdMz(J_M~5OELEYdmDxo5{oxs zkeqW>*k=#&3C3XxKGb`LoZ*gP)%a#u2JMm4K+n_xXnaG8y_p*SP{gt=6`S_JfYv3@ z8j>$$$BY~5vDaB`i7(4Q?MqVt+p%*6{h?>fc+7Crr5OXV$gGM82>B(&+eM~1c;)0J zdbD9S(byD(ht*cl-7Eazpw%%L(&qy|->it#lY0EJgZXOg8$o@cG1SkJ;_X}O3pi2P zi*`1%eC~U;DHBvoM@jC(-G7-Nx)&&Pd=+Kch-y!0N)i5DKHVQ{I$q(Y|@>iaoLc^xdi9ATpQbCO7{Sd|$VAj>Jt9fAjJmv&cu* zqjf*Tm7V-8VOAc6{fC@+=L_%1`rv8!Y)c}2F~fulT~&{+eVLy;xEa^j=0jlXHzCVV z^>mDAKkI2!8zF;l2JeB%PfUeOuCXKlLyw%HYpvdpVP-c`Q|v|;Muh>_n{65Y4i+-G zmRsgSt*eyl<_xsL;2|NjZK#I0iES6|x+CSfTZjAOezwK7PbQKpIWUNI(MU1Yvd>C9 zO$N~UUb&?6s3}}AjOQn?%>I;E3ru(uNGa*3iEsLwCsx1T8`26tFq;CmV^3|$6q zTSLK4=YWvOeHL*8?Y^C$^H&rRtDNCrlI_XAI{ccf3|@-5%pdEsJxW}$zK`e`%czEA zIH9~}4k*@_@E$wM$lm{g@b()oY8e^JMQh&YbZpXuJ6g$Wbu5dOV(j}l|ImoNF%1=> zVbN(#kUJC0U&^Z^vcv>0tO}=d2JPb{x8A{#(Z6_maXvX@#&TXCz3Fx@6=*SafnL*g z3;x?)C*p8G*9n^SgKadd`-h!BSbtzp12CEU;QFZ zWcYtcVQs&!}W6+V7B8ut7x~X79EWx@aa$G(#=p0D3m~Drp@uTI62M zdSc(2;)x;QO!o`mcSpP;D~82lWvLtOdEjg~w_vBp_>ZQf|B?*+aBvLn>VC}EJ&=&k zD^7!zE8!K6RFIjs%V$DPGg6lZvpw9}jxd-x+DXuO@44SV$u~D@-ZP7spZJZA%#*x3 zqZ2NbSU`OJdp>Vk5t;e+8Lr)}EqS-A5t37v!0cU8ynWZ{h-;sFQ?D>T((s@Pdra@r zfz}To{c{HReV5|xSG60c740VE9UM2D68*cXDLFrwVA*VS%()vw&9Z-pHzhs8<;+*M zTE-R)YJ;H3i}Kwm<)qo^uVDh?w1W;GBB`yzabVkTUSatSGBW1|-d4Co>CeLu^r{H1 z2TSqRbFd~JaZ8{XD#o1usb@HaWs6RoZ$^V7Y(v7fg*O>nK;#dpi2kzvlTrO-aM_z3 z@co&o(5YzgZ!})%?oE62j*vSC8Zd@+d`-J40iVAw;Ml?tfzu|M=)=0pQeC&`j3t`R z52Y~+CyRBKXTp~zDW|PxICJZ)JAG`E!THM!grt-jA@5)Y|Do-31v)~$kmT`eL7w65 zzB%l^roA5*Fu!zroFj)W4Sk{5svH%fiDgRg!|gHF;{SL!%o^c zJCl9yD?nk5r_euh%}|6t--pnY;nCuA?|O+gw=*sj>4d93+yH~grTjztGV*&}Ag28E zrc*NGxSr(|+`KXA!hP+)(uruI{EKf7N+xTL{>EKQbKAhQ*RTdAuya$SfX+j6W z=Ia@FtH+t{zLw9;9yc3CEbS2PYu4>*_&79@{?UFyWbZ!1+7;RoRb3N&Im!X@qY`d#AG<&bh1~erR?jZ)jOU^d@KE>JVqDKXW43$6bT* z5te*-T_af<`iOHJJ4MiMe_fKp5(6o&CgqP3ZD8Nmzwc{fzK#oM`bqVKlyVhZryxfg z-rg5`jeCo$^3v$Lt`;bq&;zp*GI@QE2gIu58t%ElHp^6A!Mi*)@Gq9?w`sn+uyaHJ z_2jOSY@bnVhKXg>Z<^wo$)ONCF;K|oPGP>~tPk$Aw8+)4MPs{Yoh;jA$_$vLdbT*OKxrWvIv?VWsDlo4m0P4(} zd4)-Y98i)KebCXC@Gb42qqZNe_(-+fNeOzmVZsdR7?Vu0H16S;ujzExmjdA5Q*f^c z5_}6@2aC|~hznK2e%$M20UTK^#aKD|47wS{s>&6UKG!e6*xvs9lE7DFL#iLXJMK-- zjd3Jb{mL=(E$g-LX@YHS@4)A&6l0r8B{*&9CF&Me!)cm#a`QB7g}$#37k&ZhT1xxa zo+0H+gTQ1c^BNs}Om0o|!xdk==)_OG3}bWUapSm${N0pda&ZFBdV^hQmX9u+-7p{4 zU6Jayc1Z(Z)w#L6ty(+TFl`KKWj4sp-`aX#NRJ$AP;3T zv6SVMk8YbqO73)Ge0>^K+tUe0!uEl|%n!Wfjw0eDQ;TX0V;>qeg8OKM0uL$1YAmqF zcd9;gDfJ_>PfQbSi_nr>(3^=xchcaaOpuV(m1p~F7cAXrs!x?+bI}RWZgy|geJjST zdTJQ=#U$wT$*T&oW5^1E4#Y^1c1aiPqPPxW*!YHpLBx3w?eY4zu|w zXu13ShhY};3a%@@L2Q_AWybEg(TbL^ZwP@!<<5dntoqDEY>bGf&)+ZOUSDDTQLLkk zKiG`!%W@#Op@qM@x_}sdP!bJh-O;YqJTv8UA?L9Pb=bD`UW@Z zq*G;A3BWKV<9k`~LWz{3?xP{U8 zVdT(q{_?R>lFE9G=6H&$u9h@#` zxtA`F$Ai12c)Pcx6Xh6B_>~p~l}FUzq^A^bTcdu#G{t4q!+R(lbx}4)Cb>UywIq8NIaM z0RBC7!rBvow9Il#f#$AhqI{MSn7U;<`dXC1l6Pr>pCQ#U16A1Wz*@6H?%Cv7aQ=#v z(`NP>i~6IZ=-J{YBqsP5tQ)Y5Ce&DfOtLK~K2PLdpRXm#gFSKkb@pd|vn{q&(?rEK zEH5xP2xrax3Vd88KY?|Y`WmKV1M`IYj8unjf0IGxlN4{A!qqW>B+#juz2S=e15T@C zvXC#c_vno^!*uDA;djUaq9j7*IeZ$cjp_c*a6DeBA^5&mM(%xYI>ht7_{_jJXb_o3 z>+@S+q}xBhkC}W*(F4-4Ed>u=W*xb2Uc!wiRnR1Mf;X(rV>f2{2U7W_WWtpwiR5`L z$(9gPEMFD^eqRIlH#V=xhygJeGt-^!>Fa8^V9_>_1>5vF{52hin5*F5g|&QQzJw&X z9fet;QZ0AQ(%pF7ERa6gJ^+jyXTr5-M*Qkytz_rx-Z=V)4DI*5fD~;@h0k)%e4Ba$ z={%W*Pf|`(DDF*;O-Vr~rX?P`P=P9g1K^8cGk^V$m@K(0BXVONzv!xV*mlqi#DP+b zbzD3Pw=y5~wHHYw|3o>;-A$+Zw+q0?h{B=tAb#zI=VX+17WTS!nyNqgZFpg=4=47P z-pj(DKZce?x>WABgjAV0z;iVz#wO%@A&K{-d&K97qSYHX{5wPNgU!pnj(xwKru*&@ zF3aOP_i?wByPmr@4}+9K>Cd}j(q8TlX9gtmri<7HSr7B5zh`eK+RN}@Hj1oPv7I&9 zSj>RFn7BoXu~%!vsLOVBou}%;6!|$2k(AFD4y+`^xD9rhE~Br`rE-2t`$6clx%`cj z?L<9T89mZ<>5u!FWYoZ^qO~m7Y2LRlW-JZ{(~VC2zKRA?+b;u+vfOCvvRTA-YzLaN zck2zEPKcVt_Fk7u@zzM84K_?>e}8vhuuNM7P9GeEEW?)1wx|^2Llrgs$(?W7qN!2r zb}(cnRu^4^dxk-RhLB&Hj)knp&-hq{p}W#C(OZ`9zHmj1&T%TZ8)E2?jCOI>lkZT| zxs<+Ne8HDU^@N1t3%J%hkSbpr0n66^G^{$(POht2lA<|7v83)Vuf8OkOjwqV zXH=MuS7Zq%XBR?lyA*G4wU5Q?Sy!mTjip@blWM%Jt}WTHtr@TV%Yr8LRz7!60ahR!=6dxSGN~dOi|={Rqh;5*2?P6q`=rMLznu=N z@Y{Svsy?WY9KK=%iHD^8)@klG3}^YQ(K{TtMS1t&^W<_~X-g@oycv(ZlziyuYISg) z5y<+n4+@&CLzg`KYm;JZug*oNd@+I=rNoJQ$^XF==0Bf(-U)ewbm&@H%AeU-M!q}w z;3ac!+UssCr}(Fo%V|z8nv^Y5q|v2{${&C6W<|+lhfW9j{Yj$}eWD#EiskbT zv5ea=L(~Y3pyhsM+;{FNw0Qp#I&6O&^1(Z-kNS+0GW5CW2v2|S7Cd8pzW>DfM`<)K z`5s)~o(vaVbZPnGDq_TTg6)EtZ+7*rg6@~vB5&3!(xAN^7pj-S4Bd2L%SQAi1H<-S zqN92hamF|UGID+iec(Mq9-tiS?jHWf7#F@f1$nQedaS;~B{UL6(!<9ixVHP+qJ;A- zlgN4z_QPj*BCh0*D3lO=y;NLz-i3-kPlR(WSK-XjLxML9lgl`nipl)yjU8mn_kVCg zSC^Ljy-myuhl$3st}5!RjcXGxfM3G}!4Fm>MOF_A`0tY zdC*%{ZiWxLHi|s^u{-bWbZmXE#Cp$a`5Y=COWI@6I8<9=V|NsTv<|@NQYn5OVc&@p z*bQrBWHhXc(t**c#sYq>xc3+2694hxi|?@hjS4g;*|g(+Ak^z6L)AuSK@;e=Hv>nH zx1m38_a+m3Vlnb4^YYnLV1$VmgxzlDr_Uth(BV#8$UOOm+3gVE!!W_akw1Tw-2@*_ z!zGt=scmHvx%agKGbi1ovL+Jv7App|VZnm;z_2|Z2Z9UTlrPUsop+hD&XDS{6Tel% zauZ#;{i}rNtUU*#R{9H?fHm`DcU-$n_3zq}DXsT#9{V@@{%i&A_bXUF?Ye-gqpS)r z@0|<1eyf^mE&I$(Es);A?CBg#-x5l<_abDDr7y^-C-XS_F>x#Oz)37mk(4B3XgHk{ zX)~?f{A~=&Maki3yN7}%P>`9AZ@0TpN7-qxr)4@!Xps8BPQL2{2j&{^U+%V(z`jao znyO2kQ!+`sho;Dh>F0Nw``}-zK*+X{VyW`XRE$-2qt8~%Buj2?WV@ap_%7ojlC--5 z_nl#$obipI_j(@eA`bk;C+~@jjt#cF^Py#I%k=}x2*|Bx8d2B`9G034H_fE@sVj2> zr=RhpRq2lm7rR@DYVT^YZXYqeDNsVo?pV6qphJ93uL7OdYfA#k&*FV|FWAWNbMTpR z(mm!p=2L%4`C*Xru+6aM@(-Z{q3>%2)P4DnA6lJFUiW)}UF_yKvsW;P_vXWC4HqGY zJ6%r&BO)1Jy|au9k*&ZSrVH7Lnz7h5gWa-Q`6;3T(%LmtWWl_GPcQa>vAij0Ufw8p zZYS#u!w)vH^l_&-IkNUS9x_g&helF>l3IB2K1A3HGqTVI_d2N_n}2c}KIjUje=biF z|JN%82I^lEd|x4RVlnfh7k%TA&3%xS2epy4MUEaaMb8vhV48^{&2A_lUw??e#v-0i z8d*nZ*H-+L7|gQ&7q~SFW#E6VoY!?MCD*^iVfY~*dRTrEoObtzAftnVK9Kk68m@SK zg2ovWvVXiB;Ak(QTV_2s4+k!bprcIV#Mv6Z@Eq$A-DT;7XO>@s1B*-fL6gf!pGhpk ztKm(XH^y??K1w)Kr*t6~c3}TFoO-B}fATq*v<)c4H|v<6d9O9-pc1S;9m@~dSVz_^ zo5#A}Bj|wMX51R3TBuj*6uN5te7$hJzm%_z8*dLeBlie;ED#^u@@6lcf1Hr;%r-PR zo<_|&%AuEMJgiBUa#z?{fxAv?OSUX+J<4*SXd^g6D702PHOcJkeUQ0ss z>`>_d>j7}~=bTn)ihej~NeUkZVjO&eoi&xb=J#T!(guy!Yg1^f&VFQ+I38Z#A zl1a6JqDZ+#OLBORDJG@(!5l7-A9(l`Svx)oFP`(Hsr8o(_4G&Llbl*!)k#9Qs@>rH zT8gV}Z`#pzE&H8viH7I7S`a_USkPK;xpzaAP7j}DcZW=1-CL*1bLk+R5Ex*b1aXI@ z994g80Xmht(uK|n#5yMe)y%ae)mti9rVzRu5R{hhw24eA@!d0 z&Shpg6+c|jrAmAf*<@Fa>HBWd8QUfBgciW8L%~9~%rl2OXqe+dhxY5ojnufrMSU5` zyt3WIrf&sI+N?`O?h*>0xO}xIjU6Uy zSRJxZl(JGwaxgOnH_z;isbLR!-_ym!cvmYbvQGH$@?8*=tPMNA$|POmCyRbDkEK>a9~|T34^_TWO+a}-D?YbneY~GKz|?Xr9JnaG zZOM6-Vv+;vnH<;%gOBRN%0Z4oXVD%YcSWoqvb2!1Ajc+$p+SZ$l_w>^??sh9~UWzWQtN4uhKuHNZlV7kQY{lFw`xc zpFh5i6zjgg(@#_+Whrv-?|cb3ek$h+#HFM~B^H0(@}Y(LlVC%SFOaJTg)T&w$H_P- z_5>Zv{N#sKWWZk0OVC{xnzUij5cWH})d`0LT!jf|OZn;gWn>TAG&!N;P30EGa^nhk zZuRGM!9zRZ`4}|l>Eu7DrLg~RD;oH)PNcF(n0tRH{P2$D-|em=o+fi}XL}PL& z6&V{)ieeXb`><2RGs&m%?ofZ4bHcPB>7#~dW2Ba3(Cclu#hr(Of^`1&{u;8!E{yfr zo}#-Krg6@y)1a$dik~uvOHs>ATQd5UG2Zn%4E_U?1by`%J&74xeQD}mA5Q6ohRB&= zvNH)pBZK#_{&gk4uA-QnGEGCxYwpx0aSF_tkpLTh91^^;+cHOBV?jL4%iRJf`_i3ZmWP3>b%=QYWHIS+mY@_X>2Yq9(iS*NcipSE~ zCWU+p?C$P>SvFbx(ZmO2rECN`WNAzO-FpdBz7L1;k@kXTpl|DXjOPRC@(RXXw0ngnblOiQnS2PWKs`Q}s=O`ac-D^p0x7dIkJLv(yDyVrG418nt|Fg&<(jRbQjdi zWa6zV2kQ5;gnJwDl5-YIJp-E+r{mMn;dF6to^%yn20KgX+uvo-C44Z?i%zJPH8fY7 zFOu1*C0QO8gC2Ke@n?+`OUKR2!wZvLXyzIn7;B>e`-T<>o`JwD8JM`&fPZzPomg}z z;^Z7%`s5hP`(O8kb16>z+{^}YUYvwmpSjZ3pc&-2#aGO9V?Y1t9q^{e1SYNhz<-*| zd;+(5+etF|t<|ea>aQD>rAbz1jp=d^Jee zSUlsCgr>|l)f`lAcyhJ5=q<|wdMJq5R_buvs(Y2ryU-*463pWj3vG#f%31u|;RgNh zQ(kRZIca)sjn|nRHuFN2q6q5%@ z$6N$W^}i$q%w5W`RBIVmw28;Q>@KD|tQpluC&Rj@t-M}f0lBI&Sae}9dkY))z}3lX zz`x%n;f-$@KL{Ou^zi;q_LD!kwXCNxjlO3((ChdS(!>yTFo zp_aCj#KU&6|9h(KYLisW^K9PBY|A zeo60EI;%$GHUBRD=Y|xr=*S(Mcg~F}emDgYdV|5$K9=`k_q8EbGq8G91a-f+kK0*P z1rK$)_?6ZLB;>rhNSpbQjvmN?1;sX?b9#^9#k#ZeD}G`gq=6pgu=!>fY{`~lsU(g^ zos-%U?aiv#c<2Q7AL&nh*O(R*nW>8`8J5~z--cGN#o(1GeeWl0rQoQlOLXin!c8%l z3R%xP1#duIJdZM`v?Ur(jPZKqK?on5#QW*hlE;IO;e)Hb)GE-2v)imL%JgBIw#?UQ zG~+FJf3DG;1uEQ z|4y0p4lp0DP1S9(({7+>0Q;GV-_Eqt0cSv|KkEz})<7~348|XiWa){6<>I4%YVcr9 z8V#=c2G7&mp!!-CuW;r8v3%u^eFTYk9r# z5^|`~6oxbse(EE1m@}O_2dW`+57V<=U8xl!Tt zvo}v>u62iF$CLTdYLAJbgDd)%d(q=_dl|Zk=ZbbYYe`&!V{o*w3|fwS#J{yGCYdF9 z7(T*{=7#CQF8%Qkpf1H#^L2kX4{zz)zi#;u9O9)*JEvrlkO$t7&pYukR~ksa+5~j& zbfw@ugXolh#&;}-0w+75#d;%zP*1IwxU5h94M&W8Gxw`9-NzQ0p$hB2dh=R0>zU_g6)v_4ru!1r#dTlf;Ni_{ zLMMzO3Bjp7m+7nMOs=|LFTfv<1;6X+nNu*V{3ri@Wh}WrZVqT%is#oi*AmqW>u`N% z7!^l4b2SeL+kCnwbQ+|*h``17d}vdbI_$gd1x5YLg}494hv8@$x{qEAzd;iAv~p^b zyo64JXM^uP)9WP>)_Jl2pTiXj5~6* z0zN$I;%8MCkjNnuM0Si{9Wu>1^5~BdF^Zt0z z78fl^@u@(poL3L8PvWjbcCUaW$CtjD?`76M!j3w*V2Oak-?SW4IVM{&oE za=Bf*rwARhzADYIXOk{Xy?L8B$@dq%Q`DAtp*C(0vWC42FA7T5l!> z#~K(|A8n6El1oJOyBSL zA4%8!P~+Rii&9AxvW1KmWp6##b;zDydt_yX?3vZxMO%Am@2phk?zvCegHot$DY7b> z%6q@h`3KGqoUZe^KQopOuA{JoI;_un{h_mIB*Pp@c(xpQP`@WD*t zH@_Hfn1~ri9SBR4L%_7$TJQkuV4DtxEPwP|p-DVxiwoYr&bCqJ72&Oh8zA$gkss44 zCWqQS;R>c(oxm2jslN`?zDhaO&4uIf$_ss}X&*`A2Nt8zUNQaYRRW2u$A4IiHy`0# zO%%ENxQum8e_O4{^&C0R)hepa6InH!R zgE<+tuLylaVtQpz54=)+4ka&=_-6lSB}|(-48-*?&|ME44WxMW zQ20?iP=A|_`sG2^d1{EpJ!M@+R#S0^VF-M$_Y!gh3bkPv-q((r#uga1X_|<7KCmop zQWmbc83vDc8_~e~-s0KsAL4e#Q8XXEjN@-wf`yDkxT_X*M=@TN;hAtX=Kc6$ICX0$ z`ASZbeMkCY{uNoeQ|19tQe@c^hKua_dqK>rG#K~ThX23EHO@N>K3z7VkFNhTEQ)%F z6Bu5d_3|tJcO?{-t!(0HS|)Lvt|;2dv`Ynf1_d#zIJy4`jq!x=twx)t*Su&i8p zzLZ}*``QbmraRNM_mjEC&oYpoQ<=T&kW9APor!o+)XL8}7DA3VhQU8mBO0}TADnic z3S$DK_qJyITD;oZkFIyO=1l7|L2pGNe?B;uEF0*LmTI@@=4BHB$2-HTLq`NoU=HJ3 zR{S-guToPGafSi5&eCw}de_cH`A7@?Y z9r<8c?*@DGnI5E9N^XvPgu4T!n0DZ#V_5sron9KVCDZJbhUk6_%gdYW#GZbS;cmY~ z;r1S%;E9tG&eN`cah!Rl7Cb8M$R51Chlq2+pgP5fW}mbpslOg#8pF4%BbTGmmEEv< zuJrb*Xr989KVDQR%#({fpdlK?bk!ZlJn`|W8aObigb%-wLprL;@X;35FFkz&oSGgC zaamG)dn+;wrn?wX5BorFoaH^vcA1vo4S2if3*6Yna<$3nr2l9|k%f$|($x%}j9bvb(*QZT*CczQ5-}L0)PJK-lUiHPvk*;*A zlcV9tPpd>WsyY&vmUz7Vd;o@htmG5xDS0zJ6vPFK>9m;+AUkj!^sgg49Z*EJ{P>7l znQv|Kv>-_RZ!An>9KydBKS}lUW^hT6rHd7_NaLUo(9N{w7r*~NQWxJrtws|no7E(q z>2n>@en@Yxy7{N2cE~zX1iZ?{LD5&+MUwyX0)!P z?O8ok&e8_|6*q+r8Jog`_^-D+)&K25{!ShxdXUFFGux)(JFOs4Y4#HGv$H)zvC+?t z9#~sw=p43J^zI$&^uCzIbiy>;%sgG@co~<++<>Sq)?F~FfZVA&$ht}0sf(K$YzTX2 z7&qfL`J8-|oV(Z;S1s#JhwpwwGCE6eDf5Zh&i8_Izf+(g--d@BAIQCAIn3~iq!z6! zxK`~nJixL%Bj0{SyF)<`9ni#wzRD!;D&<8VnHTFzaSv?KTM9O2TLld(`CuQM^`eKL zJ?jAJXe~jF8g_3}dFXgo2#;)h`5kju|1b@N{QgVn(H~R6^z;xY>~ZD0{oW8``Q>Qr z>`SX86U9^~kntL^!rtP|_iT@BxGT+XPUR}b^l+n=RtkMGYO)is*{7A?bUuWXi34FV z^9!lS?+5#llVO{8IPYClNtEWT!W-RwG-rzq_haf~kUd%`bjw^(@WnynZ_$*26IdsS zBk1!-_=5+(kZT{kFk<&UT5~p;D2#m1C9iQ2I%dV$apLL2-(p|Z#~w1; z3PVo?K<}ryd}?0A-X}lWMQ8S{8FP#xfoKx@Pv^)0n z;DC#;r1~Eh>KDR)9#chFDFbd87fMxSk8?YgJb|#(PJZs}EHd?j9Ugk*L1nB*L!OZt zEUe$he?9w^Jectr*Qh2?dc6QLPCLPIRRh}lWGQJkO+!rwUCH$s8YrG-hE0se9_g|x zGib~xkv{XW++4jA50pNH#KnocDOW*u?sUi2=<{^LvpDXD&Lo)oq9gmx$Q}~$?H}kw zhETJik|j9acGIrENSpIfZ|Q^%cC8$3!B%sQ_!cY5OI z)|aevxP(7fokQZgOEBvl>nMxZ0KpZ3pt1G@UkzV~Yg;@wcB_`q&DCuE9!xIl(@Wv$ zqNfsJDeceUvqqN$EIwQh_dHEMFA0!7A$&`r2O&koxCJo()!uSvF&2c{M~Qw>LZ z!=I(gL_O1)rdAk_FD|H{|Jf>GL!teYD@?vOhw{-kq3gF1SSn`=cXeof4Q4Q2u5n@z zw3Utowi(Y)oAZlU<~M@!Ls|N_B9k1xU5ZUjPw0&1Fz6f~2&iQv?Az8nJ_FNB8-=X| z-k}Do+2=$IZGk_q9F9$5elw?!BrZt<+p_ej?373%qgaAp19IreUlpLIoeD|=e1zOq z?+GbbecYBBw<<7K??KMeQk@^qcMuiFR5*M@pN_pLA$IlqLH?sVzdhtNY29%HH>tSL zr*c=x1DR4hF)EkJDa)b$x-#gRpDb_%0b5hCDvI^?{C&#Bc4l+UI_5%eOmNW{>@_@q zPM#LTW~) z;{GdaYtKp_)T33w(I`{Uvz|Uo#FBVj$vHI-XdLmKoAOqQZ;K`5U>w5AJAc4&!&IogQpZ=yWfRAk zM63y7nc3KSn00XiC^8P=M*JsoF~J12P1xU*p%+<|I9zm&-P_g~Q&GOnA1-uz@i)3_ zNc+|hT)5VrPMT0;=rwV-=uwBZWbn=`JaefXPNjs>RXMHVH#ZY;EaTO`8C}NO_RB2S zL3yvQ`Q*6CAvBrbMO7^aLsj25hBMau5jX@hCuMAy-iLOqV!M84iqNu|VciK{5Fncj z?eA=Ob@)K6CUwJ*tO%+Yy^Q;{EfL2sEj7RBE4q#K2epPKeriW1S+~Ep=m^VMZ;0xF zwfz=D{*|plzQBC8JoX%cd)He(7C!qnyC7!l{Y%Y zwqK8E!B@s1EDo(C%l5Cv_dA2Bs=Nbt*8U-A(n8)fH+6<4pW#;{qslE@)e`1AA~I24=9 ztKQEe!5?h!XM+c=l#k>jrT00>3n_=tXWw9KUhS4sMG>fmtYNUAaPEa&-$2XBooKJ8Ez*=lNy3s<<)wAztyOXV2s@3&vz5Jt@# ziFGZ#Y1}en5^(DyN`@r}e1dG1Eu6k)K(D?oC2GY7FnJW)ZA{pjsUJIB)Iiz0c=Ar1 zvFAQqJ}$knPDbH)s>qRkZ|1qaHzvSlu2bL>Qp4I{>!eWnAhMQFuS9fU-qC*U%du?r zX7F4W$#cq;Amsr24jS=7S6^9Fj7c_7n=j=M=3Kjl4opvf(QRi~v))Lgwpd5|c`={jZ^gx+`snxkm0TD#oQoc@$FRaCclW z6}rI)IX5(c_iKp3!q((CBz{425d}>=ABfW-QF zR-|J+2+@)+#D^UTbo)Cm_&GZfyoTCJ@$I@6c(p5n25Bzi3~t2WO7=dAj{S-|<9wjk z*Czhg+e|X0T}EW4t1Efp(F1u(0DU5*H@3uhHs1R_jhIi=x?QCp^2mj# z7rwmFZ;0WUFr*xf3ds|UrttUx{W^yU1-k2RPIcl zc5a|=rJ#T12ad%J(8gc24k5iBYC`jsaK8CMB`G@64!1@wr2`FhxwY~4;N^!x!Al^S z?16PYZuEfmc#vCX2YLNiZwcG1NstLflbmyO^9(|o=RV^eZkF=2jXIh*{d*Xlm>w;z zQ*MXL&y47)CB6`y;thwN=kl6ad1TDXG%oXElE4-C4jzOHHg@wTx?@SJSt8yS+0qM3 z&p_{-@7zE{`N^D|uNb{jnyywnd$ubvQg6>lE?2~*QU>9$H4m}MWyiPvihy#ybWLzmKydk?wIvxc$$ zdFfsKVOI}6|77W){#oSkeLvW;z=mI{^pRXYl!Oap?dZyT{fT^>Dfm5UU6;Bbhv%b5TKC{u@ItiNDUHv~d`!+Bc zKmW3$k!zK>6LU9nGcwfqtF0YmP)Ib~U|xa&Ygv!Yqh?4N!up7=8$#d69gy44L&$2q z+G&nK*WBpp&KtyFqn;>%aX$8``%uBK5Qbh%<~wdYBi$BBm~r2pc8)9OX62-EVFS&D ztk&^KpK8Hha9(T2FtHTRGmKwezTYdra7Ab)%Q91c!jgQ(;8^9m)O~1wc=GB4 z*QGg6;1i~g?uB-}4XCF=GU*>;1LZ5N1rA}wpCOp?us8j9EKb~=_!`}r=j6=PKTxn` zJUlsE$7@y+vV?W4Ii=}JJl*SIjp=C6xFqFo=XvbFF)|)>Ta+gWsTeF8#qN2{K&DG4 z_`qddZ(dwoLk4*V;L8wu`e;^>q4VEuq9!@E&()EMAFb+PxMvuh_NPt!`bz{>G8~dS z`7+K~coNJECH!0E0-p)}bJ>WEW5uACqRq$vn;HIMXHGSIn z+@H9a6k?T6GHqM-1cFcHKz{E#!d;zb-52(A(z|;0Ycm|?mePN!FS2fY^a87Kal&0a z=;ekPlU(U7yHswM*B=g+R|#3Igb`!#%i0}0#m)x6v3olbws;H(3oA27d!g)sp{p)aX5Z*MoNM9=OWYV+(?%8q| z!B?>A%WzcH3#N}~g!p1%Gpw1ol)gIY3uWaV;8&T;R|n*gBTG}b`xZ&UCiu2&HC(>E zhaY4aN0!^gW2lKO{kh-_eEa^1Gn7a<0q>yEm@5-b@0gi!m0L34{NFAhN8nsIa(iXOkQk$gN`hJQP!Lf7yI5t=LB6z_81MM zlD$}<<3mHA@64S2aIh%8kYzmI?m$huWZ0II$agQVAnlQCXQ9!B-un84J3nb0n5lGS zKfl;RF1`BC^y&XZ1Rb?5fP4;HOv zTRdHAp4i@92G75i@U!f4NV<6hKC@;$jh0j3tcNeWOF1FrVbA<}2ijx9SXZqqtoRkg zWw}c6s#9<|R64MH*5P!*6?P!Uv_-uf9qc)|AMPhw@)O5?Bm=HH<9##ML6^9VD2Eo} z@lB~Tul_d_$bW+Sz0&wy0Z+-UjZIvA;dTDq8^#&>&B3*seCht7@#N2$4)kT3?9c<7 zaNYBp;923xE4`^D{rp|+5vg5YD> zg0JAf>OpX>{|doN@F(dVEc_%(t?y=%w^2HxQkIFRHB&}&wtHuBSc*$`jZHv>!7M}S zI)M1Z?1r|&M*j5~G3h;N5k$2Qj9)DcLNehy{7QJnUudM{>&h6`J!nJeRy_!7m4Oxy zDZlzF;WekQP~xKDCobvj(?v{NIvtrZ%br5N@wapsc<-)wYbSoF8D-Zzih)JPdsVQHgB?H<3Q0k z)_v{VXn-wjGj101u<4Z5kb6mf==sE+-kn=yxMuwp5wiX?@3c(3GUF4>dKpRo?e7t* zjR?VKw{#^=!!Kj@y`vDnT*A-q$|vV_+EIgfP?IOdz7m_oMpz{)@K!0)S6&stwJ1(%2D(>>4p$zRsL_Fm^6{jOF32i8zH zZXmsr?Z$mz{3JJi!TC4DRAxR7JMK@5thL2+JUt+J2kYl&JJk9OE;!KJm9A+_?&{xf$9vW@K`8`d9t(}E}|4MhR zE1qUuD30oy5YTJ|OE(`C{8ukm^IYXd>23VaWdzQNil75`$BOMsicn@X%N{maqW{p_ zaHvln-yNSvZZuxOzj3!|Kh1D%=jB9BdtH*?4JbXWiZN#Y_)Ti@qvv(TF0Hv*fSEwJ=+H_>!kQI+qN37 zv1~<7LLLm>X$v+NmQbzT^Iy)n?-(J64Js%>vznp`-2(DQ~|*9yTg!MYNy!^@eL zx(u#ejpP@9drlsR+VPZ;u4Eb00lF6r6m4Rkzq^+w+D$BhFJnsupTHXDFdW9ZybgO! z0rz*_p!N9#e>|^&h!0kSylMoU<MN%; z>4xCHs@XFW&6eGvy$2#IYjLXKTFA2Pp)*xTmgxBy*=Z+9TP308$~yH^MqfyDZ1 z`2I+S_AYx&HciqJCB0-h+5eQ$-`oq9Sl9^qltRlL^lD?<2LokEs@yi1Q_;w09TbyI zqw?|51?CxGTVv+c^B~#Uf+u%Ak`11Nam7b{s$P1RYstoY*``l*Mjx(9V6Bw&)4?XD9O;PCO&?cicgD$vNtqlEICPj^JE|nG0IgzF#Wn z`PH9xc~jEY=`@7P#t85FBcIM=S%F1f^I#n0(MO=Ijei~_;ovf6Cc%1=+Ce>Pm{>s z*B0=Od4rc7|44QOsA9RdEDhTbEzX^F2TdH#QEq+$ytEkt6^>Gz>0#!N-!oa(-mD(( z>kMIAJJNUkIM{^AmY#HPw--5CH$de2hjFK`4Dilb57>WDdRH~`?_heV12uFjHY_4F zFv692Sr7gbJ8t&J6QQ~i)nS)$pxOaYm@najpXC$J%`JFYq$^1r76VN~o*91o!#d_! zAB%T`JdXELq&970GLLNqb$xt5&4vWRPWCQXbi z#FgqBr*g|T{p8v&RtcUfh31i{Qs2)1=@&{|z72*KOq2RQ=4>fjfVnv#^vO>L?xQ;E zT*4xLSyV1r-rpHTtm~%p<2bg7W(hNsq?mKIaXPnriwnPF>06@qbSUaeBI%zi@#5{h z^3ZIDu4G}OC0>}~3bR^s`P*0X2x2@}m69Z6R3o(q;NulCbY@&U*>~U$KB+iI)pd43 zNpU$R$_U}ze^-)`!_~1MFPxh1Imtz*--F2dzx-h=3zVCep zdsWl;s$EY>Fe>0zQ7PTgV+}6j8n`pv*M**|8SXQ%?7X1PCj%s1O2fC6++$LN< z<0=II^5kchvwit^M|^zRh05QxH+=DGq3HDjru(bMV_R__+@$q_UztTo%N_$zxtlF) z9C$Ct!xQZ7*4n@_$OQvn_#7z~ZU3(t)PBm)M}sqnr-m13g-YM@#%_0T->~!a$p~38 z?%5V_YH#GbZ-|NS$UN+ON>^g<*$h?c^PudeRFhgcbTEGTBE6*vYbJ@Rf*GdLn~i;D z$1sgqdQ0b8-NAoy=jov6R>Sun7H}`)r5x#{mOHTAUZ2)1kdRevYanfq2k$fEHF>)G zH2U>r{fg=qHEFU ze|@p8EP(oiN=ReIaWLu^!ym}0AY}#PMI(aP{*Fr!u3labzC+3dEP7wD3I~0Qr$a1_ z;Z?^sP9Z;&FF9UJN^?}vcuWL+HC6>i1Xge-o)yX!%0}ED_y?Rc7A&(fArNe6|l3?_m9D$wh{uB^yL4 z19c>Qj%MN*<^?_dH-ge5UE;kK-nb-0S8}@h5*~WK8zfc|-lcZ|Id$y^E@rvrc*Ph9 zlPfiJ@of`w0iKiOFsNFQ4mBX;!G!ixJVcqZ7cM(dT=EWU=dDl)EaTQ zCf9o}GEHR;>>mrF8n6Z%>WA56u{e*QG7NlToZLVU(a#-#X+2@o z-a1-*W;{hbmRYNLVToRbPO##2Exa}dV3h2(Bt^|6@btv!P! zez$3$^9cB`Y9}-fHxV@bW3BzrSy_fYh}lfKUsd9!+;|$y-ee#0F2MzZr4$!`A$b=z z;q8Y$)L`zeOt)PsBAHJ*k|fI=7&tNp_Kr;wJX8li`Qr+I7g|)8!%aRt5;p2}3AglF z5cA7r-=wbc$>a?C{%m94pBJnt;Nq`E&>AJhrQ7Ci#Y0JV=%O$mE_1z#sF1x|^PYKN z?EXAhX)eX313w1gy^Xi%+77l45aI#8j%ETEx+1L*Le@vpP3z>~lF@DM=`?Mj+sd>^ z0=rpWtbI;8*)XpWCmS+N);lAFk!u$PK>|BxOE*(kwk2t)zSPpM{N^z-j{Y21ukj+nDTtwDaiE&>9U@z?2bs{z3#zU4>2RjM-~PM;tfqVL3EXS4ee4M|RJcuT zI&YHAN5+Y^vCqsK&h}V#XTxEw6oLOtTpx#_~?){&~|eelxc zKsu;b4*5`Z7&!K>9~@9YPAZ>7pBe5{X}i4P%w6L|-l;kglj}ij-}4icZzvbAXx`Nd zoX2*k`|L4>1tGgb}x0ImqbREmt5u#dg8y6Pp zN~UkDhaa8&VKlp?|JRrlSFgsLCQoW>=uK4q^%Z5vGYk-8fb$2sLFxr>KE|Pj7%uj~ ziq%fEd~c~?(}T65tYK_3ePJeU*WM2Fm=u5BzVZd<&SklkSJ7~PV1eP?-_p1IQL|o{ zq^Cr;TqNW!Uy2V8i|K*+;V`Q(0w$G6Z{{+meAs3fMNKxXBTJa-1G|))?K!ebxWA^p9bGOq&L&($vHH?f0M?JtRt#%rP%nNm@X))fKe?O zFp}I6a;Z}X{NYM1+<0;J8^RuJI6)jrkBu}Cn=NvN$xdreO#&krBu$N zxq&mWtrB)%t80cKsCV)sE{2j!UK!dG!};LVl_aERCf<7&M$h>>ahjVVA@*DmU+$Jm z+DylZMl=2TRsU?TUvwQrnx+EhdHz@o=d;3v?>*=(QSym~_OnLxi|T4|(uOQNyPLh2 zODxgX(jI2?%j4&6$|IM5pGOy#P53kFO z!v^}pa7CW8>I~r@>sAr(Ptj0ZYD85|t8ylF31IKWHt(#&WKi=7v|?B^W#1aFhxXG7>!@t2@!oI-4A9vu#?wj<~xg_%1 z`8LY2K8ms3%dmXpJhy9tp9db8aVZB}f=dO? z^RA3PT8Ulh+s}IN=g)1>FP7fSnYYAH+7M2~yLy55WhZVz(f;p&U5G~Yy6(-Ox1U7BN5e1UuNC!bXG5XbMF7^%CClKhkXQjFu}M zA@5+gS$no$3g6OWaE=Su+>)t zxh&~h-YoDbq^_5x28%Pu=EyOkT$Zst-P0E@zH)=K8XNw51>2_^7=gAdPj_Tpf3j9% z3EcVF$bVlVCO&u5vC@_C)uzobCrcmx+_K>38hs>%wuvFIyUDrob7<>v5k#r1_~7w&}I%jy`46w`3|Yf+CRO&kx&7 zam6>b@swymdg?Spd$L$RL;YUtUz-K9R;CCVy~U^~+;hT_+6Pr|eIwnt)4R<1VX1XQ zQ9c}u&KuEMtqa6k(FAe^#PE%F6=Z=f+saAsplj~*G3;H-e9r8Cjx-KJwQcXA?07l< zyq1!J4{QfPF@gS?Yz%&BFF2P+Qq9PJOgLQdGNMOvV>q~;&n?xRCu|qqRBQxZ&Vc^7 zmPA~GFM&#t^erD|=Yz*?xX?GEIYcpl`R7YmZb<1jG|%r1w?d^@v{)+~_6Hl$j(mC0 z-JuN6Ql&nq4bPWhVTmWb+S{A#u~8JAlVjOBdjquS?*hoSPX3QYjYoLn7F}oBbD_-e z%ed8|UhICpQq074fsGI{p_F!Zjv^*^LZK{kG3~zZ3deqJgcF%k&8V7w!V%k8oy|1?k?|Q3J8C>nFM9n`FB7R?li}s7@!T#Z(*$@WVP13unyY(w9RVbk*ofkR% zY-b#PRaYY3{S`xFtiW|zi}0?$_V5!%tY_c7SKSc)o^{YTN#FH+z-c_*&w}=`ts`ry zi*V&mF?9&7fCp9S5c}(nkfpj*`HibElfLV1gQns9z7cebW3^y<1WAW%=LA9k*&8$CYx9fMR)lwe$D4lqN|_)zAoYX1eHp%`q5PMo5gaq z6;53Jezq@pxk%{!bM8Gx)Kse@c_5b!r|Yjk=Souni*Ab#<#wKxzUzzGcWK52BRWWC zwb;@65iVe!KzL$_miKL7qh=mIX>}f1t#}eOUwG2k>5<(1+z2jPE?MxGcDnS%gnhEq zGa`YUR(gsZ8`*p0q925|J>>Y`A-o#vcu|)Lhh-;?Xx?a5F7hDjAkFROBizJfPUmrS zar2<9hem-y%O)_tBE73o>zvSjh$Wp8^OAJ`DZ|>uY^%LE7v4yY!eQIhboQNJWFPyk zPG#R!!<5_>^bFIRIwQS^s- zNT!B*pmqiiznV+=ehE3GZRIVHS2-!*&-xt=;JvblUWgk9ix)X@r=qm^n&38KH!BMc ziKY0{)Bh9Ju>Oz_hjnmK_vl)HgB#|L?SaD;aJ9te#i`jbAAfo z_Irh}hvghl1{apf(iXi8vh$CIsDN?BXBzsV>vA_3S!}~M#(f~iHNr8SZ4ht&q(b5% zL@=IZQJqJN$;EKCk;M8L2%v) z%)+{dVa#*Rba~TivRgMCgSG8waj*jS`>`fB@39n%TI_d%{1U0IB=3UYvebh=Hu5$3 zEq@4A-Y^c|$%0g$86`?*+G0-OUQFAb0cVb<2)t;>F?XCDf1ZYVXK;xz_T1L1(zkqY z&_4)V5yF;o@`$(fZqVHj!>@l_L0q~|;F(5my6wD@;faHzL|U25&tMdUv-Z4!M(=Xo zs*;kEZQ^j%-hGf((SBYOB(4A=Xdggdi$p3v{tG~qL3X-IGB z&#ZG$RLZ)Y7k?z%PO)7~8yEUdV-7h}UV<*{Ge`Kgz+JlzZl6yb5AlR_kU(gvG@`lh z<>5q)0vxKAzU!N=8sQBiZ<=%1hjgM4A#Hz(SlQYki(3xwpaOXy%5H#jzPE&O(u@M{Y4iOz?&sJ)Zv zK?Tt;$c-9W@~wiWv>>_%u1@Vsse3j#>Q;sdw{ocVv}mxA4~1XqcEYMU?XycJX z%ePj;%gBc?cA%etOQ(PP#Hlz--||Z`wa{uvFzr^GEN(bv2P8X=U*=a%{%!ooU0MD@ z;6l5))KM;~i~p?|MtlQ$fnJFeiyp|GfclaWj;Y1zkxsN*Rklj`rD{LYmY|QJ-xR9VzpJX=#aEU{(lk zDy}4t<)Yy5{UiADX4aobj0rnS2xzGtwis*V&mNsnOO8k{d@j2@R zi(i}v`+SYT;o~ZrRQQt|iD5eeXYSC?n|EhU>D@=Pu#I(pP1u3|+(N--tMoP|n)u+X z-EOoYKbPyuDM!ssB4yL8Ah7KbuA?x&5!xH;@u`a|f zI|x@>!u-`a^eNW|1G1ij{i`%S2%i%7As%o`(V0dV&xBQd^SHokHv~`q-h<;Xy2PK( zu}C6?DYdwY<%zmlH=^mgBj9_%OVHdWY_me`zD!#Qax~P~JWXVFT}Lw7m%U%zSXbKA zmjeDg)2I%y1ycO!7?F&Zd0j~=`@3vT?*$VSRtg;{PgpMEKeoq5r)3aD$q11R`|aqU zeKBZ;Gq?}874WC+=@4u#v!mt4{mC?qIWV9>dNXB~C!-AG0m|1mv+t=E>?ySny89jk zDPx(-44M)eL-Z0yh*IlyB#Nv*?_hfn^waU>*X^k$!TVYF+ABNSpr**BjvUD)4jdx% zq6}@cg?;JxcnrU)`BE>_ zzJ|x-Mu?PsWCT0q|foaAaFsvk$ zPWssw;tR#xko)t59=|K5?}1D*pqVF54q4w@3`Zar1!HuelYH{`pfsV z4qiZT%Vu*IyI~8vU=ewrDKtNp<>Z z!Hsk0Kr6~r(CCX%kAUD8`BH|-|Am$*`2 zxt*jXsRZj*=Fz1s3V616IXqyuR8RRS>73&PYvi11&6=4kS4+4v9@1M{S1}qLBLnDx zeaU2g&I>%SmT_Oj8*z2i0Wh}r67-`RhwZSEVW-n$ZyTCD(-#?Auz#Pkak$>%FHGI{ zQox^z8IBObzVlPhN+9`yDx~n){8WV^@{`7)#Utj^xElx=ZU49dOI8Y4)GRm`=F9b> z&+9UX_qAc7Crr1xQ{5K_Y;uI8xzf8jreQcv?C8zB$ByDn;;C@n=o=rnjlJv7$KhRg-5LTwbC<8si{j)Ef^Nit znmt$IObP~a8hS(c=X#w);h-hhg)vT*?WDwBod@}cJ@_pHUX!zQ5B}Empy9TbWJCB+ z(V$n1^ReEGlRY26i()A+s#G3=726#tUsKLa{BfQO^p#@KC-;7W@5xZw%zTdzIyQki z#PCT+E6DqW`|#Cxw$VxY7=CpeDiSlUKt(YK`-Qy(r&cKz4WCws-c1QqE7lltLmqL- z@1?w`TGcN&F+GePoUaTevFV&vwbc96aI+Qy78uZ!qe*0~+X+~rY{QS(@R9AL+{QQI ztb?UxHtA9?#G+RTw2Jj*DW8AGy$+Gy)iZBoVEsR7hP3IXA(|ZUp`&;ElDBJRMX!dk z4G1*Aqtq6bH%akliRmrWVV&EWer1Mk_m+st=jup8{4!AOb1qCWFQRQPN00*-?P2oM zIrQ;+8-Rqxp!HTFWSVZDslwaG*tTPAG`LL2Ff`F?74oFF8rq<}sxRH8&y$gSF-|*} zNB>(N3sx+@IccVy;CFg!cNV&ywD6CwWf2AQDqMMn`KE%p!KrKlOexyNi^hB>QA>_u zN4O=GE2}5@NyYfzraZc~*K4Rbn+9|CNpGn~g*~`+I?+L!F2kOFm7IgQ8-Mr68?x@t zX!IQ&MD5?`ilgH!;qHexzW8c6d9vj-m+ACE$cm1b!?s;kb@Oen!${Jm7S86K)Yl~I zFdiSIhSM4Sow-M!{a_9);*B=sl7z!nc+9|qmUmBtfBjCwhb&WmQ$qu3-Y^_{eeO-? z3|me99CPG$1i0`Dd*6~pzkb49pHR9ZH&Xm$Wh~BMUX1!R8qU1dn}~r7iC5wxr4)uSi%= z0p5R-K-<6N!AtoSa5icU{YRTfy;=v%`pNbM77fUJy+~GcMV5Id8n)x|y8+O1E{Wfo zUQTMWywIuqHog43fE!{k5DKijvX2-1C6@*l!urfosy<02TgGk@TuO=L!>>Fid**gP zp2||{{Yu33o+&G`Vfv=6sRzDZn+_RnWkO$H=vaNxH|7KHcd-bLp%bXzk>1j_zj<)k zx0rhPYO?R%6;822dP`k;C4qr~0eyQioz!%;!>3v!I^BH<>?mKxGFH;}`;PkS_=&x( zW;X92!+YtArk!KjipF8A?|usR3e)&EpUa4nNfxI)>;}Kxu8wT18--g{0_pU!WYYDi z9W08Bs8!Q>a5-cGvTU2_|N6VLnmxuG@ujsk?uM)WP7yhpv7VVtaX9K$7c4M+DfmAZ z=?;Lul~ON#piL}}V10m7{Q{xyl^$;Lf|Y`P^l)GP?mUIEu%K3}BDyH$GlhOz?OtK4LufL5*fGzBV3$zF7#l`-dm{ zU~bh^8u=rVScMD~{bV}b1glw?X%zr{kNFCn{L5Da;X^%pit`jX-*P4Hm%Fs{EIMir^N_cN($x_KWW&bwKn}<7FRrou&4j&J8RktJzbhKb z4^(U73?>ZlFW_aIAWJ8jae`Y6vroW3V)@YCpRY5!^N^ts#V<= z_#OAS>!tIAzP@JX7f`XxfI1l`kyk9U=F7U5|9>-M(G4A3UFhP(*#yn=@Z{SBL6=WR zuHg1&N#F1JM>@I9-BOR}Pwy5eWV;nFxMk#fZZ{sDs4Lkw-2jtGPe(HNSO)ek$O6x{5|*17MTU+xgq^igEotp2IV;=Tw0Wykgu01AB{VF!l+58fjE|BpsK2k=$qsa7%}fASpJOT zCmdz?^L91&x#NY+m`?w`{+DVEt*K0O` zZ*eqTqn#+0x4MgUEMtB>$Py1*oQIHb>HA$p+n?)`oGf^m4lNysBOFz!(@LJq-{{Fb zW4H1D*is|(C$xy8XvwW}-20CK;II9UpE-pPjZ@3vF&q&3NxrVNLD|Pv)WxrwI6Pkj zL*&*{mGRAF!0<&lx!i0VcqRkqJqwH@E6`$6HwBwo>@oZK14HrICDqI@WO z%ciNqRQM}wo?7IMgX?jTeB{pOBr4eu?N$Bhl*_){O1EwtF2i)>ogNsx`T7AKlY;MEKF5@s7NgClVH=69kAz!G4Fs=yAEtvV9cRCl+B$gs zA=~S*m*U3n8JE!{+l~I4x{GMb=!)LmVZ3P9A+-Hk45^du@p2tyY-2Hndz>l7iji!K zD(>M@y5jW(s9UuQEFVknn`MACCKdV8&NO$!jjwb>i#?dXXigk{Kh_F``O^EQP%01R zO1$82FOd(!<|tiB=Gj1ayz4jjhTXUSXWsSp5qLVI7Y%RBAns;^L?3&zJn8Me_|nQ2 zULLgNF`apy>(x=OmHlphaS*Gl84qP@-}vLIVq#jsHWTl$-Q=Nci{tSqu&%Y>`{{fn zCc$zzB5WqzxjvSxnm0%^lJUu&+h<|0t1mb>`0||_tI0#wYx-fAJvG-;(shSp`M&RrM2M6Y4J9GbKtK@pj8&PBcZTUxq79B*(p_1JGsfpp+v|V8`EfbQEaCO>=bGI}R?0=JiSIM|3}aU1Idw+>{kH+a=;jFbh?T+NgCo3JH;s1UP<;wWq z&S>yD#dE)nuk4`cJFkP^Y^Y|r5B8kne}Q{50d_647W*&@3)S&GS0k!dd6{h2(GmJH z?`uCb#gcm2uJm0HdHx~cCokVGlLGhlPGtfCAQ#?DnSDnX?SQh)d z>s|Ewa1&~je=6QR))gva=j;EtWhyD8?DI>suOpdzt@ng{@*0Pq^(RwP1AjExC>*q9 zs>R&zK;Suczb%xm>YWNHhYrBTG4@>U({?iU&v9hq8^C4jy&wmiUxG?xGKG6-#nbOx z#u5Rn>o3w33yO|_RYV2%bxs9YsML#ZE@8LbUCm(2+bC2z?1nf~`R}+gHh8W~J%TuL zZmS=XkV_PEJkO%{&@wfRrj9s)T9-w`2-APuC=EhBA#>0^#N$}cV>kTW(4B5IY9(R6 ztMCZzn{;~XLx>tb8)@8`(#W1MZ*R<9uc0Bw}xx%F{VA;0|^YMlwF;uBM5-rYU z_cB zn$Vi{`{j(ehFiCEGd=7nHzbjgtH%d{y*4NI{HQIB$8Sqmm-y*;IMntTeLBhS4^P+L z1C{lXbok$UgXEaEwvMt>ak zWIS+3-!~8#kA;E3EbqxQm(wF9aOJu=G_fy@bX6-0i`c#*lJ#(Jw2Ocf$x+;ur7dJo zOBCw}W|p|31l$b9%grSVw4y%u~@9*O-w^JXUELCb?_ z)Y`dV`Y#Giktq`QCTTBh0rQqrx@N&JNNr6==b!NS_9vwV!fXsEm}irqnY&=(d=HL} zdqeaheXyRgKi%wLNR&5K;k`1q*-6QNF#lgZvajOtZK--E%GP!fcO}&)wu1%ZMT<8r zVfR?OaS8L)}e%n?}yXbt-ZAFI)T5oneZ~Z52B-U57**3&^x|V zJkN&xslb80%%AC=1~VVz3c7aniuZ&EyE;M7U!JbWXZgOnT0(8c)B3`cvFq7L2#@74 zO;>U|RQ%yJlt=F>umtmj{6v3&$g0EXE7syZ&$P1bIJ(-6O0WM&4&-PFmoi`LmQ+)` zxjhpiD`L3+<-{xHijZ|GpVL`&QWcNzNT!3%&MdxPc@lCaW^${yH;_xQr*T(IDD^D5 zgEp^tj1a{qj34%6l%`-qdhxAV7@`M_!g2% z?@9cW-5j^N&iXum?tyM~d#;-OKb;hyj2-MG=&H+0h|@efG%1?rX0P8#PM>AMEAp*%a@_O_a6(y{lI-J@Z zrsUCzYV7ignMS@QLDErIG)N~=tVb7pm&PX*D(S{Kp=inXa2Qqmk9)YEkU3I4*p6wb zf3M}iC3PW`rP+!-=RK~jcvq`CO&-%mO0}!83F{;`Osa>AI@4g6rzI^+`A&xIHo~v6 zV(4Md?S-SicjN!2u-r|WHEt7zgU2Ht_r4qZW9h;`dRndwt+P^uC4c)%Uc3AyW;@3K z+~#r5eCJ%;w=<3w#YUsn+HM>n&$22;q1e4J2P9_IiEnmX&({*(zN;fjSFeIiI-Vdi z%Yl0n-A`v#AJ-fAcD)}CN0HPlbQ`Dh8dyjae+F9Ux+^Bo>2HH+ug zEDbebfo#*IRvzgSs#shfE}b`8Zh zN4Ud=W1gJg;%jnzts2}M*2xw27m>qKarjF%+vj(GgSU=jz*@pp?As~q>H{QcKr>&b zkW_|I#*BlJ=|=c27Y^BuQQVr|W|DU?7OxQc(YNo0qW>yi3H~+lzMc8nPLTCy5zWnQ zB_W@+;n9^)Zu+k_Vvkni1)sxcW{De_@<35|h;;p*w+Q=q%gs{m=LKA?P8@{gq5Vc2^PC=NQ5r(>aT|k4W{CwK%IRf=;cH6|@#8 z3ayxD>Dcvn{IRbZ;#wYYWBVw%8FvYXdDU_WxbaU zgZeiq$VuBoob`SleIHua8PI2%*~I054f7OvaC(Yw$mldLoMGrshdLRO_vaq4`RF$7 znmq{T7+pt|@7{6Bd4#-be2YS6xQP4YH?oY4Pi{1wye)=2p7sSN&1G8WSACpN=*&9* zBe}x%GyVazw{lm;I+WC>1B|IN>;!#={n40+mI%#jBcn!@=Hbwrcd4GsUOaOTJ2G4P@P z4lo!TPLK7?L0eyMgr^1FoXylCVyP^`ZHz0vpY|7)b&r8T`Mg###&R1jO>n38E_IL^ zLrtL*>%%|lZi=5i&47r(v0{$br?wXEjP<7*x1555y*E(+n_K_4->Z@uf#>$6QdyNb z#fC#1VaUQv@vJ(x3)ddni+zt)KB2hoxd+u< z_mB+PyB=94@Yr~=t{z7DU!k>G*NP{)T!vqUMpQDz7eqo^D0ivgEI*Z#k`-U@N0vGI zvC0evT?s{&zj$nXV55lltE9{X#XE zebbWuto=^>GUwy>OOxnq+XIEcqrTux?3aHp$QoCdgh1rmY%VUYf%r)K;$5kMbQ>u} zvo^`YyB9nsG#I%RLKH)2=h6xykvjt36<^`j&1U>?{d}zRH<7-QO+YVyeP&%ZtiN3= z6jyz|4l|wV#P{P4jnWj3h}03yyI%=a;qH(T>mb&klWNyP&ggKeP}Ye~pR+{TOgH)8 z{M!jpAn-Pz(~svfzc;~x^SUDcUTyp$+ZY~J@bmAYT}N=uxQjHgY#S+vpDgSvVcK`p z9=v^68Qb68uX+8WbJoq}nfsB8yKf4xxIBf<0>chD? zer+Vm^f~dNctMj8|xq3gy<|uS}H6gKV%hzy2Euv87qh4)AR!Dz2wQYyS*ldlp?X$ z8DBccQkm#FC_#i~C#Uzbh?pM^#SRa7{9O8dIP9Co^TwG&zr*z@tZ(X33VHiXUbvQV z(I*N5me3Xf(XkgoFpYCelV$V&@Ct z)P06K@mnJ=Y-D);rhYrV@i!gD9^kp+zr;wK=qB610=mB3gp>W=O=7Qz;1T1BcgJLtGgX`6p(E>8 z*M38KVm)vZyT4;$ZAdPKKE$Czis_LFgYoPAm(lTmyw~y9iD&4UhKso8ZNG*dE?pKw zPriyF*(*D64`RL9&-C%|l}^xgG?F{-*h=DTy|Bi(Kx)!fCy<;mPq_LZ>zZpXz)sUv z!NU3BG`0P8@%NG1P$pH%Nu}KdbsH}tbY|3W9-B3`;7Su zbq%WUxWHQ6=XU40HQw{uof>@XARhS|LS?2mdF(dDpHkBxc}lFx!U>VWOd0QoGE#c)^$yW)Z!hG@XB7SBbzf$ zpc6g7os?QcuKSpy4@?vJ-;BJ*tpcWrQt9VM8N~ydu}n8Lq*dE}LGP*!w1re~3*M9y zr|$Jw?PM%f&do#)BQK)TUf!Rhe_0;y_EVw8D@EjR-9zk-ifR4~mTCI61HD|FDE5k1 z_;$mKjg{1QeJI+i5Co^^4Wd_y3CXeTz}J{B^ln5R!|@Ig7ouY}fkU{f%RSIrU6 z&X*m%v8PcGeYB+v>6Obt->JW14mtRx1$>_tLLb{!koK-&a5d`+Cnfio*e{=h%Wht# zA-VBr+WU{VfN3IEyF;+w+YHD!S;s|wEG6m}HH23~bVMg2D?#CfD>Rfli1p=5L5tz+ zj0h@!;xn4S?h1tUYI7A1zsS`cp)etl=a!x-_wY;mn414|v474?jWrxpm>UrO0- zV3bocSL#kl8Ph9|0lz=&znBUo>^6G*_S zoN)X|mcue0il@`F@Uwu&Ous{s_+<&}-1b%>`|ruZVyRB9>R}Ois+I~J9Lpm}DuC%u zHghg<6?=8+#&y9~V*~o8Duop7mlK+^-{Z{hhWOvlAkZ0z;#QlrkZRcoJUP&h&TSZq zVx39^g;Jx$9mQ6$uCO$9H{B@uOHQe$K-_zCnl{M{{>z#KsZ~7xY+bkvXKoFrWxZ}B z;*+fK27A6-`F3pTbQPMsayjXx^`xvd8q2x`(R#;bH078E8k70|xtm>~pzC;nc_b1@ z=dWb&DKMw+WDmpq74sm-J)Kh;`-phASh74qG##fdFF4jDE6id1_Ng1Ybu*y?Y8LUh z>NFyTWu}6t+z4YZqmJm35s#}4u^-`5L=}5y^ug1Y^#g3>adl;UG4!l8pzD5Tk!IbE zAQj8{)tT?nM$sKlF88NK?+uCTkZL^4s+ew{IT&~Ng`!ssSO3?uQMjTJX&Cc6My>J8 zXOb90v$bMLg8e(3iP;QZs*ls=9fw1yk(?mBmDqZEV5LogR8_uSpm)_s`1Od6Xdx-U zm$D~Al0MHr4V?1v$tc#Xv4&+n##|NTNd6Y@6-UXwhJI@WI?0|A6RU~BXODG67OR!< z(BzBI*yP1oR=y%$$CiWF#ldb@pl21&IXmm-K$ez2{bO?qbQy0i%H{nz%S)NJ-`Sjoe0W^6 z)pQ@!Y|P{y;|6j)@(503y&|=hcahP=DwO2IV`;{%q4*B-VE6A&C7Ig_QLA=}xHlvC zb~4ZPKw2|H68x7TcVOhiQ@j@Ge6tGQ>KbaR)r$L zEkBTU8AQ*HC?O}e&x594w&Fg_m2;i(M|M-}>a^!1ZE!VSx3ZW9Wi&%nt2E3SXGI$f zyNT?^ci4{gPP|@kjW0e300oAbCw!O})X)p7vA*S%r^?as+9A-m`LB52_+#}#n6n^? z&P=N%D>e^>g2pS{AnnKG#m`yT^hPrM>3y!?!==vcEhKH@S9 z>I!(A{NB3{ccll@%GX=T2*ZiOPi*HC&UChE4>*wLZgQzrwWKJ8`J*Wk;?_i z5bt14r;=^txg~ptnV+F!*;*_)bU74!;rZl0$3ytD1IvI+2oU6spD0wmtRpf`&A_VY zBculLd~(c-XK3(NPJG|ZI4>D8_nOoC$G6bby=`bg!E$jYM*HO)m^o5PJcFO_krj#< zHcp#06mPG023g8u<7RgIqqxhDmM0GTqC3So8mEWJ;OA{lZ#2onb2mls(RCGf z3T^oE39LpN&^zfVB>$tVaOV()?H>*CWuG93kd78(V=lwSs&9TYOJ5$1Zp#*Y(H_Os zw)T>#RZj5j_ilPed4QCxyabb2u0*S90nkh8;KOd&|Id39{mUF*QIDWkgWQS0QAXIy zp8qa(I~Ki3fl=ZAKb!kR;M02osZDSb8g_UD8Yty8m)a$l;8vtLUG?A)q(seuzRT&{ z6m}DQ_owB!_gOSuvsqp+Z?B9{u1`mF$RQrrTa-d|)MIYd3=xq#wGACsD-!1r9ZOz7 zu}lqhOErKgMd9dkmkD<|riVym=R?a51G?aA79qRVLUV=(_u1$TS={f6o7w{CDJ^4C zt6jtH7*g7NV+fvH<%v>ezURKTvi|mwwdft@F)++q6L;>3rB9n^KV}raSKSQ*Gc!5k?t1b$%^t6o z4yQT4?xOiGE0E=>r{cMLw!J)l|4NG598V)RhUFn|l@#vo=qIEsN&>&UpGcp|`68G1 zo^Us;noGpx#I3{{;-A=ax-spft92@Bzr^RVtAe6nX_X&!90)3&krfP^;tlC1>l zvR^!P8fzze(aN3|r2kwso_v&}){4*II{A*&7F$up9oes!n-M0|BTCWnl`8XK7t^bzjwfB>KRfFN6%vEmn>c>Q9 zlP>=L<}&pzh(~h!Ug9ooU6Dsm2tNHS1!AIk+`Cw%F08B55pn*Na8&a=6j>h?>&Vk5 z&qgbsYjZlfzsTAmAL#Ejpug_slkihFa29(v92&K8%i-zptA)qCFVk&t$>0!LaMOke zG}VNo?(2wphVQ}4E)~J8A-BZ1_t3=?W#{p@C-uG$76xCYL+0NkzD76j^H81>KK&;I zjIv!piCbpK-zgHnVK>%D|DDZ(+o*X6|P+B~rgDQH2AKd*i$% zaLlMHRPXH=XtroT6K*aS_otn^mI2*?QnYg>^WWx43wP@3iav}UikF(4gxc>s?nz69 z;p46WR7GI~S#|Ok(mvhE^^anm(y~Lqc>_N?-*0*iOBD@h(D4*lp9xWq0h*%;LmkPXACa)C6mt`QwyKNtlS^4!n9 zJ{XeT_|e$M*U72^eXt2j=NkGN$kCxIvHs^v)S^{MFzuI=uwIgBcH81{vl$1rnUA@x zqebM~-5Tt&yNr&BKLu;umm=NeMcm~R)y%sR3>TXH=)B-BX!GJ=^zyoixW7W_^-ahQ zFrZ$t+2ml16#%=Z^S?RT^neS#eTZp)_l(Jv;u?0xs*IlaAcv1#JBEnNd-3k^TOGSq z%Ko0p4BIs%@1rm~UVm{?)xZuL;;86O9B~r0;`oiaB6?LHuQ_fHy%|ghwrV97FI@3* z*K&@JwOcejSnCjsm>%#b^k1Efx3omORPEC$8#>yymkxS}{?OaE-^kTbV7; z)2cuhx3F%LjpKyc&vZmh>dJV+pg?dz-eNytPVE9PvE;d*d3`okXZR_2+YgE53Sh=? zuiLAOWWG?wGASk$E~gOR<>Q2V*beiVgefjiOM(dBSn(Z-F+L;NePMs0e zc|7i|aQXvzIqde0xk2$imPI;qI+L5B-#|LQ*y1Hlp>$;DZS-_T87h%z7Hcs+C*`qO z-C$ZM${@cw)6qfA6md6&@Y4W%{ggtlW%#3kuWm5Ix0>@AS57Ll_uv{FMz5G?L9E*b z5UCy%YcUg~hTuM530m=SG1;A+f?SeVpJt~^2h|Bapv0jb1>XyH|&O_B}3Rq z322tSD%PV%mTKXdEs6AS^d)pHvK42ret5Nx5Ip;JBJ>2*i8C+XE8X$VsUb9JhCV#s zbp~F{Im&sTX(wBgwbA<~UYD7_&I6X*oJm6t6_EGgnJm-6FyW3iKKOVVNDR1%d(yhi zcjEDHL#W29?L@C|jL`cfy9F=32Mea%gLr(4t9n*T!dlOv+SmNNJdJ59HGeKsoOF`} z?a9QL<@lbPti}B?0=Tad!R794BQ_rU@y-2F^kD2oK_l}{Cl#}Av0VoKq5KN&YqW6h zLRhwXb_x39#)>l^Ac|v>oTvB|v^zE~l(qPu`5Zh`*Z! zP>F+2PE%$$RcO(+uI_BDNbAM$l;s8o&tL`wOgScZq1>OG|6K{h;hFreR? zvdHod3s}(1bHCBS>@LRFKw4}zmzdwE#?h#P4pWxLk7PF^|MBm|eLjZAN>CN+kfvHQP^ z3vjEN4>Zg8Q+MYo2tKU>)p@1dtdS3h<&bMQGlzZa4btFmZk%A&5q=ha@uU&Vq!p>l zS4xHq9wXeS$h;HU%J}aje`w$1%{?0Pn&g-p!>!UDZdrU0`73=5Z_Uyb89(iZ0P}})r(ni2e{{Kx z*QWD-bVFVZ^U3U=Squr*(B;bS6*v5}!B4G2Xzc!5hzq62HmzCQA?cVg8Fy@$K;2$F zAaBwyBV*MRE?Dvj`7-JUya`I73s?E0i^?tl3Dq3)#G%|CTZ@*?rDks)8J81ia>16isG* z6@^>9(AB&fV&7oiRcYL}dnDDER7TWms&Ve-3L27-14^I9peeSz=A!R)A8u4t(@lM0 zNX^=Xb;V0iMONh0sbv7)zwo%1cI+fBZ}Oo93*M0Fx2y5CMHST9;tlw6B7|cs=_jx6 zq7YRm$&sAj=u+PmE_3{2QYE8_Z{;OZlZ}^ACTYYCEWdoVB?QkJ zp8)?}@tiPVog0pB51~rk`fx+j3H1GriuGul(Nj?!)1yz`{7JU{$-pEpS}fRY28J3DoY%27B71l*zS$m0xiJ?7`qx?h;u?G3 zmSkY3nir7W+|22lQ?mGQ5n6ka_u`fLTiUxh;w{*y|2I_DQW6? zyNFz4cO@P(kM4z^a@hOCQD|52;zCZoCdVdU#7h@59+<2`HdKE=#`k!vJCh*^7W;S} zcp~l%C>}PX-)z&#(Lf2|e{7CUi!#Js%06&wO*D5^tA!wwV2o}3=|O=!dbi_@Aj6Kw zx+(Y8z>1}|)KoA)4o^~ss|@Q#eQG04Q+q&V$YN?7u1`!Y2Jm_Ick{5?jt?x1hndZ} z-2T6HWPWfcjwCD-E!Tz?t!@ykPd~#IoqR`v99+PWagVRMS>%uQRFFwZ=OWq~i1y4L zC{|ib1tas!j3*7?JIr(SRgZZK_uYdn8c(=HLlN2eX1Z`1o8w+vHo_yh3Fz;*BJq6( zn_)$;v!umPrvlu*$Irjxbgy9b z3|*1Ss5GD^(So{*Jnmgodj#`Ak-AS7k&lk5LbabdqLaUs@O(L6h}hsQ-T^*r(uYdv z9&xXDuJIKte}`$}5BlLSCj&2|`T5uT_M;}1Xr>fWbzF> z4~(sLN0S)V{ZDKD*!}^2JWiwsO!bQkMC;&fNG5kfxq*z`v;_|lh0u*Px6q-(1c`1o zi+jcIyq$#AIwnxLBb6lYd?e}`&tn}N{|JrkNz}N_7scH^0~Wf~T(3tN39}u*CyZH_ zMPxAqcUZxs<2?7ff6y0yy6a6dg6he=x19p@d%V^>x}^wIGHR&W%}2#6^MzpbuY%KU zEhmF)dZ5d2F?|@Y1!YybqeTqs^x_AVwA4xB4P_(g`qO1(f75i~`T`wMiPM~lT6$hF>>bUrurKInS3%-s+slAB-NTeQzoFty(-APwP7anMf z`x`&}Ny5^Xbw$fkwDFjgli;|dJ2#=`HEF-F84HxcsM)riZin1&l(OGd?44FQ+5+jGhV;kkbRu`44~OdOiX_h&;-w2bK;|Ojbxbb~+8>Bx z*0H?IHwConxwYVr(Zn`t(FNq(l00|Sr#D1HQ_n+YbdpC+I^-0^- zUhFYhSCpr<9S^@91H(IWIoeT2QknyB&dflXbE*-wZM-c=dBN}W%+2zE+1f(>W2oS%K`*Xly7u8=@tBLe3vH*La9%q^}4h>VC)~M+1JpH?`&h8m4Z_*?aU5vyZ88*VTaLiL%JZ6^o#wi}%=ET5t*%O$es1 zo#qh}BORd<)4zlp58}7`wNTdccic8NLOeBdQG+dyX`Jo|9F-MIU$@4RxeIIXP6vi3 zPWpIlp$(8<{A>#$&e&QZgc_zi5%g;52+Nq}byuzce{dZF4y~o)+lymu67iCo>^n6q z4Vm662nEdldFhoB4%YF831_`I+oo4!@G5QSbm z*JTClb3Mp;`L+|q0bjgvtskAe?FlhhQzJP4kmqvVp?P33u9hCqd{S&~Vg}=9+!yck z-Xg#zNeR^RUJk05?20~x@-wXMd@~QA z8`5+|!dPuA?W+!Q((at&jn~9~!bW^BGmHjI+eO-}hYK^YgayoMtq(h^YZ1zy|j{X7Ia->#xlmz%;8)_FZ~yoFfX zE$NSg;M>x4uR}4(?D&BVRxsaDqa4KaDaRPWo?g5#TeSYA$76g(&%|Mj{B)Q?@}SuP?*ueF40*bb_&_X#-O_#n_S<^9s4GykFZ z1EyR`a}U|6p2+^pfDV0`Mb-oYBuaUTy@G`cPT(zqU@CEL9uaa{!YX!W^W(gOc+mv~ zRDa8-2Wf-e#EnGLjvhYbD8hT=0{5QPj)j zx!`G%masWMM-=)Z9}8Ib@uT`uaer)LWE}n{(iNRoNCSgyp@PPYKCv&l9jf8Mv|&_x zaw&P~p)9On^Z2DICH!fYC!F*1=H?f@BImYf!2aDmVjrMHP#lgdU|rwQ{ovv=2s~3Z zi|@RoTMx!xqvakb zdP9mhv$p>BVC>>vNuAv@(cfbZ5bwfc*Mn<4_~%kx(eT5?@MO+1$j|1n%PhqQFH-cU z=a)AUF8R7Zv!2JU&q;IPGv@KiOaWu{nJH8w>lW(2avnK%@f=L!;Q$PMp-N9Amy<6K zw1f$_m>1}$DpvSiCg{&jmW+?hp@yeKe~PRd(us`geTbyl_7(1tb+^M&+tk@^Eb(H+zo4udAypaI0|g zuI42kak!s(fQ50|tQ%VmW~sP~XUwVD8?e!VaC*daH~DU>EL3I~uDZ_-M;hkBiM6-5 z>+5UD-cwe{mhmo;(>vlRY67rJrW>Z+A)UwKuoAl={^IKzd?bD*7#c@#+vc^Aqn4X- z_?Jj(-xMr3VWlj*&$=sr|4GNQjT%}0u$i0P$`SPsap;C4@7bIFrV*^~B~h6eRnU?z zKwYnvi*I2U9FBwc@`GvU+hX$IQV;H6J~4Lm4HwAlfj$c_?){e6L@Cw>cS`xw+uxPR zKD`n&{7WZy)}okLS$sjgr+D7w^|uB_%r>C4b5jU+rU!dZ(-m!BYl!oipX5*q(^b`4 z$mg?u7`_D1vwIbg#N^Qehk;StJGDO~^o$-jAGD?Sg#$#bTnbbd^ZT?7?1s~Ar)au) zv=^}p|AIfTXX?GT!AoMpVI=DqKT%dk&JOd%UoWx#Pp%QoSmZ3Im30>1x4Qpm6u8|^ z=ge<5khi*Xu+MbXmHkISAQ|)p+e~3T!`?VH?&iXuJRYOAoYEB9v23z&*ApniMFJDm zBFxBgOu-U(!mzvF&QA!K-JGO9Y_!s%RkOO6GI@Qq_kJ6NfYXQ^)hN98E)pI$3b zQ#*zISU>iD(kzIXp(&gk%WlM%<>Rq4d(p_TWn7Kf1A<-*XSY(=y@Qh)(A^d!*jB}3 z)OmL2R62ARZDaS^OjL&nYlg92paLb_cf=iD)Om|Dwn|sW!QWJ#Umds~iOV0b-99`@HjC>sb~421p$6Ecd`>G zud_zR?YwW~byz)YDNCj0t7aDuj93ilY9^Qeq@EbPzlCyd^ZaV`A~igF&m>w|RYipT z{~-w@er6nhs1~}|T@T58KNMGV0JP$Gj0!IQf*Y9c_rvO9*sHi0MkpNO4(GR%J+r;> z_&k4VGq#CDbp{A#RqZ#`WRj=R=9N037)=aJ-+{;8kT0tTw7uiUjJlX*Vm@j(F;Z4Y@c@G4>l%R9{IC98M zgnJI?idMAef{)>3xVeYNtGT0Dmpi+Qk*m=~u9#^G?=ZY-Z(}v#MQaiATT2_@H(Ad# z++5Z@b!33)0t3ppe`+!n<{c<}lIaAm?b(D%FO; z3IDks09fcK)&jH#cMDvVd43h~FCM1nT%d**hm=%@hGFg&%c6Q}sutpz@n&N69vy~wVz4!n`+J~>S`_=RF97-{5j4|D5C{5fwt za#j%Ccccl8QePw}UEnOfGqpul1zH()jlbML_A1T6&lN7yp$C)&7uh|zYIZ;F{hK(P z@H88)&1vM6V?|_3lZJ2>)2{==pTOYJp@Pvfc`cx+kNIq;v!C;+K@jlYF7)%bDHmSa zLs~~g!jeb>x+*z~3>!Wl>Spjzx9laq;riUs^t8r(GLw0y{g@wnV}>f;=66Q$q?Df-&retdQ&^ws66;M! zxoJDJ4ws}H$C0ACVtgl%am!!1P%~sAM91tA`#=h#4`H9%!Bj4@i;S++5H4oBwUMQO zH?G!1*EX%CyO@8`=k-Fs4Bx7LUx0runyYOjTgY$Py z1qs&(u5C*ji5Pm#kT3bw%DM1EH$ zUGW@Cjvf)HaB^JHt<#%NguUb$|JkQzanJOqqn@^kWUndoh-(yGSU7W9Mht!1ol4|!PfKnD{EV@sDZ2)U?wy}#h)EdtnB5(?lCF)V zZp2ViS#M(a;~k#AnEl)y*x;x=!H_>Zk83_%N90R9+5MX!y6kBa`Wi1UkR0GO(DvI4 zL1JnYHLfotZOawmLphIuWyShf%ltC!_f-~LzxNI&sxfZE#bH{*@}$cfxx@Y<(w4Pa zFvNu4kJUGCM9Mo&#h$krQ$rv#mSt)pv&bXXv0^yelN6blhJR`&M9Twv>6Y`I_ng$I%7^%CQ#(n z;w3Pj(<}D<&XnW8?hB85vAS}?abtBwHv^UM%JUcC*e4$MZem zkId=O87kl<{RRD)%j4ejGHtx!>nR$0rj=NZkrVD?vuX*jJ9xz*V7oPrlaX&B8;ZuU z{u)23xWox&Po9q~*{_z`N)R#Kxp>*B+93t(L(KX0CHvclc(qN#~uF}hKg zjpAfl#JjR9uSemN<&&u1mnxEZb1ga$n!;^8_=L>6)B(lUs;KhT>!{drJFKeZxm^E< z_joXSS7WCa!_pZDwv0H$EwXPXKfB!VnUnxJSN|#bXf<9i^j84qT}sMp599kPVf0#n0W8eg4cB8F#k;aWp3Q<;V|h$#@{NT+ z87~?zYgow>`xNlMXihu63ZZa@GOS#{@5<(+F2`RKSSQ~7-RxexobVv)`dd864&RN= zfKB)LIrQ5bO_Z;HL3}6l^F&SX^5U^;g}D{Jbt;;^8X6*q`yngb)uba@nVZh$;~Mzk z(juNW4@;avheJ4VpR?nd4*0phipDmZK+&vpRJqbZ>}}h3>>>=>JD6rnAY`-Td;F8l z-Je6{@PmTQFfD=SY&?9CG+vt$Tkp#7Zone}86^ z8(r^kI`g15j5Wk-hB!gZgJ^C|6Z^hX4;^d4H1Ak}P(Qgv} zNT|}_+ppotASV(1iIZ(=d*6?R<6vT`XlIJGkX^5^Gq`tEh4C;5t5&_5op zj)%&E|MPTiRz?F^I8zU=U|I>%QxQb=yu^cMGG9bd9RA#%4&A|x+>LY*86rDgc;T;( zXz=+bkaxPzOv#q_uqhs2iGDbna$eazWY+2c&?z;bC$h81(TlTS^#-1sjk>TGE9iyL z^9N0c?jv>Kl2RQ}Y_L6E7dBeZJMSHLysMbVbp)WrE-u`optod#bOJicJvu;goJFn#IGz4U%X zez?ejgJv(cB%y@7nVbO6yUgi{IV$kxQ9GI|+#>eqmL|&xZ?jw8^EFLyr&BPf*u`=8 zKQE>dmn7J_L13zOP+OQsfu}h?` zvn$Ydt?Ot)dW%@29D8jfe*0w-UD{hkVwPgm9-PA6-}!{d4u1g|K~;3c{Oc(Ft~G3v zt>HXN%Sg7-D~uSg=pIoFX~G4tx#*DCoAJrQ4d2mV_byAGlE}z=W-FR_ZZ>VD2J>?8 z9*i)_>3Ft$B0be|18pCE5Y3F@`Pc*BZ!p(w42=kSKy2Tr3!7M9nOCSP{ye?WY}(gE zPUdMN*_ON-e%nY=Z)HlxjJSmZJlJg!nhT1z$G|$}yq zhhT?;zA)0UUc4Xk*WHJ&M~2Xu*Jr@U1v|j9$dS|A)=r);EfDNh(GlN2TJ=5%HZ`&y z^}oYP;`E1t|6!hAJ)B{VQ!FECx|1E*CeJ#YS%xV7wJk0px2s}8|uBe)xr+DJg{GCWf@mUiw473jQ^7G@066%{osnU4E1|Th+F(K{P(b~ zXoHU&9y)s+2%EjQ|7BP0YhCd2d4Y81RTWa0cmb)5>k{w5Y-WXueJ{0{=CEOXHS#Uu z=gL`+MexIM0o`DlL)Ke8!(VpkipC5x#A!Yb&^@ll*;)>Ut2%@L06;Ypr%YwXJ zd}p$3TQ`b7ZAVL&|04&-y+^)mt|aW<=wnF@e5xvzPJZc4Tus{WJWG}@xM+hHI{Cq@ z{dwHuh&r;?VVv+i)A|d0&%y19PZubB<+VuNRw>B%!SBRYEYig@N>b>2$B}|@liG02 zeDXCvEgj}6T|FACWy?rxa zg0H7IOO;_@i`SNhur7B~@^jNT;hYCLqWOF689!ZQ_WZ+JZdH0QQ6ZiPMf05Mx@<4J zKYy9ZuDMLGMGn>qXPBv`kL~^}0L{uIoW_Then zzal5sOTe@Tzd6&DCFEA=Yt(PgbEkiX(n2SeS>CB+g0C$L1T_yHi_XZ8Me>7r{CRxj zA{=LX>6lfciW5?1gKTRiXP;G1(rwLgU}_ZYT2_cYUrtAF4O_%_h!VY3@PnBe^o~X~ zsT^*A+KN-S?1(2Ma9}OiOyV(Tk4+oy+t0rH62+kVb{>pqIwbB~+L-8quSK!W{AJCg zX-fBkNq6{+!2hvy9sX3mf7B=?*((~_MN=wCKF{-9QB+!p_Mp#0_YW5xEPeP8`a%;-|EsQwcuR1{R^J`+2gc030}km9pSWBcBtZY9NaZ6M>OB{?ft{t)^!zi zt_`M)gVIr)_I_ujInr;9B;h}TnAeUHylIqUpYyqo4ty+t6O>!>-(Cg4hy33Gb zthd*pi5ql;+tR|((!w~nDdja=c2S6bNRHz@qPyKjtyggE%LVztdYr~JGfN+Q6f9?} zB7RVv%^g+*>5_!q>G*qxHvF~yI$Qg?4GX+>BPp7PY~pB$PdBOaZqaUzOoPK{Ux{V@ zvi=Y3w;VqHAbA=1MRT~MG4C6kwW}*HTAa5J1zB>WvWW}@B zuh8DK!=+HRq=H|GFyPOjLvOOSzd&pG-rxJ+b6)VHQZR+5@)eWr{L^A9{a=DGC~7 zFF_(N68!3V3TjED`f6S#G($>I zYcq#e_a5y=(@p(J!;){fpk1B!i+X7ss6^HFryyUee=})+(vOwvd*L6Y7!tJZK%Tfm z3R>tzd90%i`jJHE)_3V_Vn+=wU%3m}Tl$gy?C0Q-Y&*C-R*c=h@-Hq8j0cN1ar?xd ztG`1@=~yzP9SMAGQ_w4lR~Zg|NNcM*Bvv&nZ(;$~C>7`VQM@uXD}n#4ZQ(MpQ)~_M z3HK#OGdca7cdJyx13t6yB>O!T1SWkW;4yP|cHH?kd@hVZeYrto;HVu=ej?6$Liv*P z13P5*Iu;^@9CqF8DjZq%g9%;4;Z@acbtoOq>Fw5@gYfDUQ*vqP3ML>`ocC^k&bcm> zBh4y+^ENcHC7J~PTd)jtW^)|rFbDx%ace~RmVueq;YCR);+l)`p`bxnKgX2xS8Bmt zi}ld6h1(AvmU2aM({B@HXJy>Acn`SshRe6qvJwLO*sE-2ZyPpo&xTQ%! z7?$a9STurn16{HSpNnR%@V; zFX7~uz!N`7`w15enh-mKE3jZV)v4PS|7`f{@doQ;QpZ462hAsVx<#j{+`GhKu zNAr|~vks#(uH*R^`#8*ba^pC-n8;zyo0?BBp`3az-D0p?;yt7oMfcJF=AjLCE1U1xvLsKGsPblosLA{v6N@x!J8}Vh`mx z@x-1?fwR7!WWt~Ii*m~+sb#_=;}nRBSP{O7|Di7nbcB|SJR07A0*=-56wPi{Djz}W z!~xdfoB;1S`5I{7EYT8e!W=f=Qr{THT|B&Tu9pS(y15{Z-u{|!FJ(XXNOG>^m z^(uE*L+2J8doUkb>XwspmfQG0WVE5GQW~p7YH&#JPq>EqPdap+z!a4@;QgUqkpAl* zzA`}$8F@}2GO!$nZx{o<)Wx%JQeNT1oB8ng{0fqM;Q@GSvl{XzROjU!%j zvw=(bc2JO*De{r-k7|ca`!z_%=2AStMV0rM?u9eWRZ)>zQ-0)VjxW{iUjf&CksvgJ z68o|D5dSIdC(6x)i=^bC<0%e*wmR)VUEk;(^vv(HKV6lVPVc$&Wpvw(46?K@a?B`*7ZdVR-_t4ONmuppFug8S3@43tdZfnOYbrfJn zBGr*pnsDseZ!pfulxAmx_B~l(8u}oT~*d`mKh0e|xaYQ5)`DcpiEDy-h|;Rl%2U z=z>kP-RxRPKDME`8!ujQ97&rQfsWtxBEnPRg7SU6aQ9qOGFf>ejJ4Va4H3nqvU(gZ zxPk`H1(N))N`GHt6j3#4qi3>1}~zWJN<~ooJO#wMV8<5m(!6_mUV$MTFD}>!XC+q z=37{uA$f zhrRM`Xg?esJ z_3i=u2u?d1f9)Mq+Z#(>$i(8I*D+`ry_-ntoriqJErT^KA?)Rk4Y*8m7wQ-cCdYf4 z7>y?C!=zaBtNjT&((i`nI&_k?@{4d>bqe@BrBHP9Xm#m5jK9J87Tg_=Fq_v5;D=g= zaKYXOuddzk7hDg8K6rk9&kf#I2-Yz9(ShKP~YAi_Ta4+eB^F6Jh-fiy!713KeBW> z%$&~Q&k5gXaFK92c15cU%1fU@W}27dITc?S&qfY&7Dw`6g&v19PH*SKL~u;Br_0wl zhjPU4kU!lGST0nH-;>W}{@mk_fyXn7*>Nw5@E!H>sNs4XIk_quTsPbT#?nHbjV5A( zC3{=p<{KKseP=1|9I4D}qW%i9SQYvEEaj_Bj%6jNpP|iS3EVS9l8|14jlRX8PngcI z4>IBXQW-ePpTm|Bhis9jCcUGC-*Mfr60eT>V51cvihTTqzfZ!Ftb5*%WqjVj@dv1e zqu`KNM`F+r)d26A+MwnACZSQqEw02@R{Ju7a6&q27x7H^z%9Q71vhDaX8VlD|adR1Oi7_%-8c)m$ z?=l7Fexv6~I>I8e`$*|*F6|j_WDi|u@#Yyr%-Az5d#BsKpZ?!Qq8^usx?<{Mvm6ht*2lyC#9Q4GKLFpGV+ zvl?fvHRd~XaoSGGx?FI+D2Ut?%f)=TFe9r;qS7iY*Nai*Q>|3@~%zJW*`oC?r0yoXh~Lp=PZ;qhQBjOG;TXta+?J z%I_87wx!fJyG%#upe~P6avWffsVD1U*@|B{lmqAD0d_=}0Jp6#1#`W&iM*OObbcXk z%8L#>GC(0N*Wi!JaMqk=>1fGiG0&#nVXLpS;GM2o&_OkgC1Evqd(aA`Ru)C{9~OXg zK?LAQHj3_}Pqa&;75}D?%IoF0P_2TAQBPn${(6Or^^Bm|h6<4%;LGX~WP6j|JFxjM zo1FtsI2{w|KOR#~BTYZ*E2H_A$8xsu-LpCUr`LNVEbQep=RJ?r&}W}GvSLLxxE8+& z%yr>rsOMXop=y!_ne0%Cci&gw)zA#32jf)Hl^rhpgh?FE)Vt4zj%y^ziYY?8dus#= z66gr)BQl}JlhJTjI)^h6x2;i4ZveS-?guuBSK!rBoQdlJ=(*c;{Ah_K;g1}^7wCpfxCqX zm+pkG)|rxDBh~QV>Az4W7Gw=4mAR@ecX;RRy1)sSG~+A7^&d zrGf6^t8DSVHoRS=t5gcuX!P*WZ9E>dEX+?^+xeri{{=1oAIHg_*5e zfR0d&$ZlUa(x82gDNG$Z@tP2C>~lgA_I~v5uMeNe<@3*2(xe77ZX4ZyjX#47s~NGziSJ<@(-c!(%gFWgL02D-LU&3!$0q)IZ-i54|W^043r$%$ee5jkLZ8 zlT&w_n3WUdc)9;|CgwjuW0rMdF^^8d*ItBA91j9>Eel0A%N09nV9c3#vcX~sJa=Lz zV>W6)G+SNLNQBYqie#U{b3AunFV!C?=8Tm`_lN9Z(Q%H?xL5GOCzC;Tw=s+DZ3{qM zH8)$`#WThxJcv!CnrU@B{TG zZQ#}5;O_CYU6Y8Fl<%F*RGWo{CqtdziR?s|nE&e{j9 z1_MYMa}k(b*N0o3D_F%e>P*TkPa*yRUven73Cp?N zBmK6mhrfPm5X}drSjR|? z*C-@10mj(9D>X~QxAVmCLDQfB#du4z{;t2 zVa=9JX!(vn@=5Y1*3g#Yy`^)ReK9~|=2>E2Crc8%iQXES-U2TZyvZzQSJ=(e!n3mz zh*#T@yoZNE(4QFEOQmOn4#=&A?(;K5v(@tK*8r^-WB=RHJ7ix5*;$FAPLn(BHPEyz zo;(sn17=$Y%Ay+JJm80dCZ2!>+iTc&&xF{(p%)!B*AedPFNOxyYvA&*Q>^pkPdIOk z3KMWvo85S$51YuZgJR2XlChUm1hP{<(VKs6hPt(PK1%x#N@S7_V!4SusBejma4KVm zu9O5pFS8uhGP4p-pSpwjy@caA(|&G&qbvf6?eBZIFI^H&D-2?F|2ATDWeFAL@^1f-5;KdRe0jh=^RvMvnf5S7;r9)_X^h z37c4axlDk3eRYIjsWj3tHG+OKZ?HZy+i<=9arDN?mn3gc#Si43GbX>eoSCV&w!o3P zL8Lr)GrZUx4V=fgiE{p%cc#F!S1XBryc)P)#*#G^9w~RD}Lln2mw_k&k`m@1>r<|{nu%nTm zW+eG~+Y5iXgpt7|+V4DRC;Ab47EUkDV*L!NamU~>)N12PI&|v6r20_)E1Ki_UuS4y zwIc{1L1h2$XSiy)B@ERMBG1NV!-?~&z-MD_{&LflMI)!g5$`A^M(qGbl5{WAy*(U_ z{TTqQ57vpiMyp&-plvOFVD_4u#TvKIM0FDb$lI&p zf{6}Y=o|GnO1T>#J>@GfLOg<95?+tp57;x)^zVrJnAT3UgkWY6d89LipYu``_UUsx z%1%`ub%@0g9mitO+!qWk6*P)+6qooh~d3tzaMJ6=LlqjDAw?(VLVHXUv}g1#geBeSM#B^-)Ju6zNOEJDPCm^^d_7f}`St9aPO6-wE*G|R}gP|-i#&b3B@#1DTSF2a>DAFVAQpA70JeIXyS%)=zCc~j#NpfIFh`+CsMHi^P-&j+Wy|nvDL0#!3edgyD>!_XC7Jf8AD3$F1g>%3#O{PETsX1>{?g-c%rTT^ z@yF>1RVP!9Jbe|^TF1?CLfVCqF+Ge(<d101G}9)A?by+{=G(`DT3gIy=e zh~b(dAQkA34oB(;{a5&*`R<3I`@HokTnRrIVVB zq|G^9s7M{a$)UH1-Dg$7*@$<*GSQta3Z%1utqv+!97e=PIADkIpU@|&br=2Hhm1A` zz`mB=KUmBQI=qX*=ne(7DVn>C1M$^Veq4i<5%BP7owzT(L~}wFk@Ey z5xt~4*=Ykw=pxF5r+qj~vsF07>kQRHSC(#q>AoDkl_eiX z*Utrz91lgXC(4#DJxB`1a5t z0rosJAzK&D!*a>b&>S}%;rG!y(Lujc(7!Q@WfoTBs_f&)b95lt=-vWy-#y|7M{=De ztJt|9XjCxKHP6NC#~Z`%1A#;;FAMryD+Dp~Id1mjcmfQ6VnUYP%P`XReulp9r`pac zs(TB3VFs)d-Rs32mgfD`p?T5AUqbci(s=)~eD>?gq0U!*ckx=-LJpHV{e@R=;IF=t}cWQT@v6 z>JwCF=?V=0{M$>QosPk@Wec9Dntth_e5aV(4o`=kWTAsy%g z<#NBy7$9EXMYx2CU~d%H<5$Jg8NU1-QLnL1lLD;LN@JrPYOsrfE&}`*Qd&|3T8#og zRu8vdTl7>C^-Y*Y&Rwd&+gesIA18A2ptiBm!`&Pz^r zfxp{DpO%3!8 z)FjC~dKGaj-dB8ql>zk}Ufy#0|Uz=zhh7*zc$W?ce@_ z`2GW;JOn;{rY7{6HU$Hu`Y9C8?Y1N?9|!Q+noc;pp_Ckv^vw&|nE+E`O-P=>c{pB; z2dm68SX)62-uA-+y{ir(U!K$VtyLA!+a<>S*QYtWVJkp2iR}90FR4$v8_qjbM$ADG zFfF}>Jnm6_c!?i6alsz`iLPNKN`?4NN(aiaq?vw2#c;xG6Bs+qN#yaayUZG`)8Twa zQu=C=T`0`3-X@g8lo=qc@WqE}YkJ{?Gjp&3mYcIdRNKfHXJ<6XX) zN=zZ(_GmI*e}MWYPP?A_b^+R!7)@r*2w_atcOV}H$_aauP?uu{bb7+geJg`@Fz23d z9!UH6qo4_|Ws}B#!;e?(gX-0z$fG(Id(tf6QktVaeTFo8l&}mI*>L*OZu7%P>wz!X z?VyVH?e$=y9(S`B+Vb&!%@FWntedD$q{2J_j_@`iYZpDiPC?I*@d@gIKcR>A+iir0 zBdNY5sKAWa7c*lhLj>bX#H}ddZ2j}rtG+Twrw*(QBBnC&;N%8DP(=MBB zhmfT%z|N}e?8~=&>bKMcYl=B6a{UwqPg2jM?J_fXj-3i;)7kJ)Py;3lHY2zxij;M9 zFk@LM-WTfIFF5oBW#kjfOAiX6HN)y$Q#+3Gy`qfewQqL zJW6o>Nh{Jbqq*)o4N#*2)expeu)ojODXk0$Zu`8kd>Qgs&61o&NH^M`#}1r}Hl7 zLytX^U{@c9Kdl#yQPkDb#P-oMTydzIpBc+>rx?%z^7T3VasD0!h18d>^uQJzKE{C9 z;7q~R1!96>wF+4NM3V$=Dx-6p6wjCb@2EUiL5#~N++rEaCOOvO$yti0*u~vijDc4E8r>x+4X$=U*97kHDG7VM7-X)EXxC(pBL!J}0nzfoqPw{#hBHxEQzV&W8N@gmwjejE zvHyoZfAv#g!yt!0i#Pfh{b=CwMV&HifqBPTHgo2`u3EsVK8SheZOQp z#unc*P=>pXaLq0~wA#`PZoM7GTArxKGxph|?}fAr^}alC`+SSPPC}jaT{?t&3fqk` z{p?9H8pe+*?}B`)ZwJua)T3|^PT3kw;`aF97^w_&j?UV4?K_bD--B>OQWh)uxC(dt z?%{7b>B25IZ^!)9DR33#jsIbboPQ?xx;a^NE4TXb5Zr7YLp-V#Xs%v5GIpeXLLJ)g zl;#Z)#g_l_qlo(mo(i2!PA+~4%N6yoq(0|w?EhTCEIeT-$`0*#;0q&vdJ&CmX@Saj z8F=tDx6|(^HAWT#K}6mbVBYQ#yhZf8w{+1VRQT5hip8tO{Cfy*9u)%dc_p$xuo$D^CX{qgN7z~`holc#!*SW%jCSmj z2S~p�JkKxV47f3XSn024)s;;ky)Y(0Dt`ujs*dQ>UPg!n@?S1vkYH&WH{Pm+C{{T0miR;cr`(iC<(T9&10tXf8}(mrs68cW{%TYc0oZo@r#DcXTdWZkG?AFCGtPZ*vs&XiP7& zL;Agb#Q7M_S67q5XCHFh#`)+GhQF+v7_;B`^#ipa)v!dA`59^Y2hO<{LyW63z+k!o zX!y+WoI~?U;L6G4Np@ZtZazh`bEzJZlBc!Q0 zXO}L6+7~m}?vfh3I=2|OcXE6ACA-v^2S!1}()b~?{IwX2{hP=}g}%i3Z|}fS3#gtM zcpc1(w}n?Ip5&(p@ue?KD0dsZDfTahAyy1rbe`igsY|!!=J{|s_U7=LuK|tdPFcQCEbLjjb|Vi>sWHpCzL6-sYgT954`4e5>nK-4?7i_ z*z-48oD}Dl*H_EwNQrV5Aeddt2K?&9-_zGai;~gAPezEJx}~A?2Rgzwng4S4X&#>= zH)lQ9*^BO4_>;?JYFM$VG*9nfH`^GUk7fPbK$|8vTg99ShPT^Rk@t(9VaWw)Xl)3G zErtCnp;ts0J8WN%AFkhncD(l^fobyK(Vi%NTLhPL;wb(of6e^;Bh%2`bjMFGD}0XnJ#k*v}zsN0tW=9?sod_>mA`=H0gcyc&Snb|oZ z6+NbYd#4%U=!)+R_-tn#E2AL9e&Q0mg|n#l`_BtF-(odh_W$hSvCAGY3mJ#U=XzB<@PdkM4-=4((+}hbOrWhw> z4KhY=IK5~sPZK6p(tEU+1{@?XLx!qRBy3FwbD~9@x0L$6r zkWudCxXRtJ0k9`giLA>j#yu0?pw|>z{P}Wd%kE9ED#eqPlxoFyzMllkl7`r&dIZPc zNC3gA+eKc)&g6+menB`%UO!sUKKczpHdOaEFhE}}9*4ubBiJ$5>+ui&w!FED+^p1G z?*%RC|B;4rD>So}fZgjj-m>z*4D|d>9CG2>*iV1h`h>?2!`r znKlV*A9#&t=4(QSTy95ybyF&`rSG*jyYr!bwmQ@`aun_Bb31n|R-FW;m5IXJVWMAYqgAnga-PrJSPv@(Hj^&p}s_JNw0>4Ier@2?=__$r<4h>~UlWz67SEl=hqTJ@JM) zEga@-aW2W*@_)>ksPP_j_64!qzcu0-qnXGeEuMtt-(?0`>X06N7h9Jnp{+Cvd-dEV z(eCX1@p1X;jU0!OIJE|7k6g#*p>NpbD1C=5mnH|2gm@8?iVUbnE_i4(nkzRCdOC49 z(>!M{`Y0YiZe38vKc$xEEBJP^DQrIOleh|gO1g=5^l}ENXlfYsTJO+9GZwCdvYBD* z{R{QDYWsdPRuDuY9hE_kTsnW+IZn4((e2Nd{$x*>m|Ua18M> zxQS)AC8CRdG(Z2*4zzy8F1S%Ln~iU;!u_&4kp3xuvhY?TIHReI^G@G9-7bn?0eUpUo?I>llq45OEH zJ}PT^0nIP$z?bQb#>q?Nc)de3t&^`LguX(%~X^YoVFbSlRjK$&qlXl&DdXX z`z)GQ(>%zJ`}+^gQlp>$%K;@Ux{j^vxEudVfz8ayGLFNvG^;{{L)hd~4OlDw7yLWh zl-%2To9S)-ha~78XXn%>XqNkIF#B+!C_`zN%~GbTc}Ua?R;+age*U0DjtvxJ>zlve zUFsVwd_4oU2rb~OE>HHvs#Z*-wt%-EhgiE^1UsIO0&1(d*(W`09P;+OOSIBQ31rUv zf>9$($;m}q;32Ui(C=^r+v-@4oqV3=@6_ddK1vEhz}7B}J$0%EUs9fer02$yD+fzJ zzrhWlSlTGMSDj$?8{S_voeb`;#IGw~=I`B|z}}=8M@#ioVXA5+JJeW+f4C*0xp_2? z$SNN`Ij;hHZ#jx|(b0neWW%<1*!(7KKe=?1b?t7!r}=6$W4)7%E$ZbDY{>)j zwM#_ZUYBz_;e?5?WcuPv5aYZ6^uFZgpt7AT)crS}Xx}TxYbFmP6Y5`D@2`Spk7Kaz zS&p9=jPD1fmqw6Jeg#-XvJ3iH#1ido+VFYXdoX6@LD4<_`h;KbyS6EjS|5YA{r-p6 zQjHX81Jt~G0NYLDFy!nl0z1p9$i&KkJgE`$q2cxnHjn;&cBTA+uW1fy^wH~Jle~at zPl&O@fkU{&jOCA85=6=j9>RB9>IS8Ihi4=+@Xe@2jqRuVMpDn#NU*E<>Oi0{g)u+CGh$a#HQCb;`LP% zkh)eJnKnC&QO~SGR%>;HN1i63mhM<6ySYi^^YKeG;(OF^TxGa@DL8O_ExR|U7oYP% z(CeWzsn#pNr61#vI;$f*_-8a~be;)cB-~)z^xE(Yhiz!+ascVCR>w1iNBFC6a~PtS z<^Xmma2TQ(6^AMx=?Dv~^$>sO3YbvM%|3@KcA=M%!Gu3S1-y?E@IM-J_gpH2gZx8_ z_mii6!+6s;H&E2W>AmN}Tj6K=Jy9&ZiGzJ((JQLSt3KF)w!OE77rV09hiOw=j zkRL#jt(rlo!W0~0&heAoYzrXMf{4q@EGXU?2v%EfAW6IY{_{2)_QF>*53@#mh`({tAoXTZt@4cnnl;xSzl~^TCmh6BAxOZ? zuH-PJHeC@aeB!i}a+;mGJt&F<6?HK2(t~IPefJqDKS6<~m1qtjhaq7`y3Fs#|M1OI z$8f+oADDhjnaqqX!8Oj6i0?wVl{T`gSi>!&(p2QRTx0B@jKk%z65KAaXa+ROPBE#+fMTSbuZs| zSq6}{ED>dT7d>i)Y71jY%koUH(|8W3=X3k?$^dwB2M*ddgQ+_>49RvjKqse%66u8l zcvx!?9iK!sjd1`m4@V0=K`YXCbP#)x9B33(MFQ^yCSgky;qkUK~ie`D~S53nwAl*f-ehBLi3^4OGlUTC{FY##8)o_b$E&KSL5O+9M zqQ=uY!oHow@ZH?S&|1w|bkF`;r!(IwOq<>RxDQvhJObhGJqQ-c35q9XgBe}iyc7DN z8}3aqCEHWnA*gnT^M`ZTpYD~ob=G2j^#NDbK%)cuyA^|Qm0;3Tm4rh*%fUFr=_m1e zlg zE|%TApD4+muM$Qe{{-6A7_|eP9VMi4Bq0H;lMVRI(7)Wa zP%REP+X&~_Qvbs)WoCA21oHKv_kd#I=;((_u;^ADd%BC@g=c=DKy#{}^It&2Pi}b9 zs(jYeqa2?IKf>e+xw&TPd3$(ju{UvhEiEYQ8~}~l9wHA<%E?anU?uhK<3WBS{DnSD zr@nB;Y?}0oW*X4j z|L>1cSVTW_+PskcR$q+UpUq?zJmNe#*K}^cb!N)s)0Prk8&HD4IqDhql|v)%nnL4Z zPnwDJ4tqbH1SWS5u`0F%f1cwHtPgP*@>)v?Rm(+^M}^V?-J2z-?4*v+aEt-6S+fuB ze#p%=n&)@$AE|K|BJ21OoUuq_FD$FU3!kW?X%phfT%8i|R`n{lJ+eu}LmX7Tz$Tp; zWFxG?4u+TbqxW+da^jdY?0Hea&b(BJg$)sCkYb3#Lh1>`vhX3r5X(=W@O{lK=-~1| zl4;S3-Hw=G%>?eQVdm^?TtdB(FFyD3tEb!p5w}X%UcKjdnOi-~YmFsNy_rBPU?32mh6KzSginOxnu1RdQIN;*#r;C{Vd=;wI)J^4+myu?)nOtlqB)f&QT zWG z#8PH7A8BT-NO!%NT!NzL{2sKu7^;;oga#JQqD-?yAi=+Uj`Q2d+GPOq*X}IuNE?<7 zQ9^I-&|aZ0$FSlzH|VGMSi~#RwM_Vr8E(Jhxs4CZ<%5ZMNfI90RRW9_2aE0$F6e3? zkext0+`^ggZ6&CAHJyb+l924OD0rf?i8XFx@jS6WzThp_SF*HdHZT&dWnHU!al1Ul zidWJk#kv6BuAv@R$`f+ljYd}KQ(#^m$1&tBtAeMc5AXm8^#? zW3pN4yH)sdaxeO`gX;f_E<%$jMtHP7$2Ttfe!}-oc9Q9P6a^=u?}FFVql=2OAXIe& zrBTVET+CG%79g;VWp@@9-9?_Foa-*bA1uDUdI?BjIT^|STR5_Ff?uX@LvHSR^SsyagR zmdB{#N;%_XQpiTt6l0?mQ$^l{58;{aS{sa(2R< zNfGR0+j=~^{T9D;ET@OG2%3S`HV!wABrBmC_u@$SwPN7IzX-m+=QI%G!OyTGW(M)i zuEKr_@q95m4mT!MO2QW9N|AqWn_?*9mFWnd>*PbUV+?GobQF1sgKRb->yH8CRN6bt zEV9A|!JNJ-?e_`mp6Vn{zkB%|Sz*9oC+C5AR9X#Z8pIKM<1Em5W->64%@XZ#vZZoh zRQ^P=jB30EF1_d@^(eaAsGyt_C+vJFmYr5phr8aFfrFWx24XQo0;Rc>k*Fz_urRY4 zbTuDjch2gcE+x<^;CH-2Bk?TdfTvjkheahj@_WC^^uJ)UUA+{UhR0+4GC-Gg}UKx00e zLuk%%k88PIXfxFSH%eTDaKjqhu$}X$@KfXj{iKuV1}X}`JSR{znZuCD{U^b$Tgjp< z9f>0}?{RV&$(LEm)K3UN(UjZF?7vHO%abteW*zN@COAXTg%q~a4nE%(aR0Xu?4!nE zNO$u%=HURRft0(N!NQX?vr%%aU?8{?cue;Yc~pE-=b_0P!pP7s9$waSt@tqtx)9B5rF$IXwqm@c&IPx1Mq60FqKWHhxoY$+~vg=1+ik8^q{ z_Up%Jka{ogUy(!WQ~>Ny_F}vH-(ipO4;v*%(H?USPae$Q zfGQk=$ijv;{6%1gw;bg3kdPB{0`q+w57BYG4V2Ds`x>L)zv0&}CB)-#Gg$369^5hF zc!<1j2J|VMNY>GL|8qze+DPxeoQ+jbu!S2ISjV!}33d2SP(JuXb3TO@h4^<&KTKU) zMygsj!_;Y|;L!(eFZ_%8xxx7`(mF7RbFXzFXI&lP)>;Pf2j&Xe8m!0~G=vYlwStjT zf=ETPb>3PNP1u>wX{xWpm!PRHIczx>kO|^s#6`Xo_SFrhhnK{L*1g1?rk3!XL?B81 zeFwB1SPD1Ku4Ti*g*fahMiO2$Lwi;+94yd=-rJl-yWp_{_IxP`ZBZYGQIR>66bmB$ zTl}HQ>j>aH>YB(e=aM@Ltq?|$@(ahYZE+s*qo1RHVjt3-bsjnyaX1s6_mKaW>Zt#9 z@9Kw`f{oN)aq2@7?)qv5_tVd;cX$F9DP@6It2xZk7&QiI<#BtQ>vnnQ>_K{melZEH zkPL>lXPeo?u>_|ak;18a39H;uhU*qegW1WPHlo%&75?j!Cad?-o{^|KNWGliL{yAM zmh;tNNjJw^=AB%Nbd~8Hx{Ll8MiRbHXw z>F4)=Z)A&u7jpaJqiVWf5yhFxLaLL9?FNezxZDY?fo>S5PBY5-mN4@-+(yMIG{@k} zUDV)3ebLc%?3Z+!EfCv*ZqRp=(C7t>KNp8@j^y^m7yFuxM$cWr3M7Bwwp)f!x9t`= z;~*>8F7qB7*5zUkJmnZp@p z!(H&4d@?aub|0(wi9v&jq3kQK2K-oQF1phgPMBS7%+W<1D3IQg^AA5py5t};eiJwE z+}NVTTzNex$`ah~at>zPR3Y2zO7W2ixu}Wm)5ki>Q9rODoQAwao)f#l0LCNu54*mO z;39Jq=(#qCm`~UN9~QcTA5XX)@jaD$@LjP93DQf&m&WFzEmVs>^Ku!Qn`;HXJ&9oV z(RatvB~^U>Fqa=#cDNM$JkQ~b|A>1q?-BLVD4hiU3r~Q?rbfY3W*9HbZiNN6W)kIy zYJ7a$7k-GMBr ze@qFeP;TObpF48AMXTfi;LRFIzV9x?w-5Ee##K25#Q*tkp(Vm0@J{ zz9D=%tpn{|PVaXxgLW)25Imh}O?BNNY;U0o-&S(iGQ~+3%@@Xy$L|}!?hg;Z19@@w zzrM58r%aiHE0S1~ikCRYX(8;NR?BwKyBKTDT=bjXI*m~&hBa$vLg^FEqMN443s3Qz z#W*}MU4Iu8XkHWbUrgjDz}h_~q|s9a=Zoc{m@{;*VX+Twym1yDJ;2R7N`_DPKS#NW zvgKt~n81xFh=e_U0*y|m15d+X(Ozb2M*`$iU)E{+<;)c7KfFY}MvXQ}XdcbOzv|V@ zK2@e(0wRM)A;OjjsfWi|3dA>Y^Nz*->2O>-?Jf1Bd9&RKFeAi-97U6$gq9k7{^kbT zD$|BLUYetpv_R4rISyNIn}g@f`NDox!?@<>9B^*uXox{c590X zoO1Pm)E|zkY*~IAO2oJl+sxhgk|Xu3?l2*9dM`uIHV8{rX0tiIRajy|RL*b7BGq$Da0>M@uqP&{)oikC_g}X%7cqLx)uN7^l_)`WQkXlkL_NRIB-N$I2ylH`v zV&4_^YTXCCFJmn%PrXm@#!cTPv!YP2UC4kI_LX zRmNu<$4^opk7Y9PA5qW6ip&TjekawvSCKJ=X6CDKW@uVR>o zf4O~)iMPrl#I!^W?! z;7x~bvh$?g;+l$+VEW1uR;r9*Fm8heab-m7{991JQ4v%XWD5Q~px(&Y_u*&tNhG5U0lQ=x*bEVGaS z)m36w>_cC>9N`(>W7bTs5?`?R$ba6>WjHuz#Db<%oQ|p^5dn*Sn$Wx2<&61oCNiV5 zZS~$H~ z{7Trjzlr!P2bgiG2eQPRM~(Iiz{8jaT2pT&QDs{w?%u#OetYNRPZN!>DSIpI8Y)2j zqm5u74WWI)^pLDi5AbW#C5114K?d`g9T2*eI!;v(n+6O*-_--;nTBmD{&;aa%WOJ! z0E%Z_#+Pc@dpO+%pMP$NyR77I#pgYh!YHO$wSVZ0RgN5huiuZ!--_m5lO%4v0;&Il zJ9u8*WRxmiBd#SS5Zu`xM=N^KfXBbBT5H$ihQ@O8CX;FKoGOJs$4q3tD@$?jwW%<1 zdOF#3ClBVme>WvqYl=J*XQla5G+>ekskvAK`&JDS%$|kP^VQa%H>OgUCh%UO^X+Q5 z63H_P*Y_W2)&7k0rQOV$QA*cf(zxIS)V&=h3>Xqc!*d%XKl)V)nXET3yE#SN(?4#odcx z!^VD~MqXmJ z7Oh5?XLIb2uJXk@zMiEoR|cVTJ++We&Kp>#gW zT`~|Vg?01Tt|3e!Y^quy4&QD^OS-nhJf^q7ELUY}(rvuNT@x4OCy`;>iXk^E9@!Wx zk`~W)7~v5i_Ro!>PgLK)&ZzlTPu3=opzlvXVYD$eax0PFA*M=`gu_fHudMh4e@_~K zhgNWYQF2_YA2)ZMc4444tKTS<*b>rciUl zMD}(O(~Ldw#>Z|~k|hlUZqJ(m`i$TB_YSCO7fLo&@qLQLJ8j$vy3oPnp1=*6Cf?S5 zhIsyY17Vhepl8MQr$75ZX}5!55!XaqP6Md^P)1Yda-G=JI&Z8t*o#h>q$Cb_VSvAX z3L%PB74SLBT6p?1gq|dNs5PW7jMw42*RD!mpidm*Lgy%mpIv*f{D=T~uHR)nFHGNg z(kZhJ!1SJ;cua*kohjLchgF#2mxnkPdZ2Qipi&Y=vu3s+_am+lzLIBPS*?moFJ!ai zznNlu&QRo*&iPNl#0zg|^Q7Oe{kHPYTZs>U<$T5DgB8MuwT#2*Q;PdlGuy%8=|mct z2YCI0w3PqjeFXd2IqYW*^X#xG%|m~d@Hygw_5i`7J(Q08Weo~TD+F(A_Wty86u|Ez z^p33~_&UI_mJ4ai-*L{V{AI=u0jd+(5naWHXN{Q}x1RtSTb-k{r_`@-=D zFVg%sXOMu#CopAPht-8j-UCFw-+(X8*QI9|ANA|Qb+$iZGvH!v;nCC4xMDNsB|w+1pO~P#pq3-l7{PF1(^7~r_BrEp< z{ZAbGqjD6bJEk?#ITM|v+iGv1sn>3hA4}P8vBxhQ6Ba`~S7f8;-Rn>fk5_Up&CnN5 zvGmMPdf2HLJ{gXJ^WS1g+OTr?9$bK`mT>+v?(z@ZCq9}^{5%0ignUIWcI}bxO|ti6 z;q%cT`o8WhM3ne~=*9he-t+sI*-qnz7Z&Gb?GSB0|PqXU%LcL(;} z9Rno7+}PFPkWqGY%(FHaX5odWF;B=_H*e!Ru4?#2UJ_AURtzy8hX|XQFYCR?Dzv0I z8pWt9%6U%9oma)VhhnHl*lQ^Fc$jwIj`st5XL#W=EOTL&#b+Gyqd&H0+Ki72WYF{D zb)kZNyVcEEI9XL6t6V-vK7M%zW|xzseXV(KAWrj5Z|r@N+TPI+m6y4r9VVRroX+%b zEn1QE&5(WY3$6!mKCT)%6F!3 zcNXEYr$gz;bcX%&7`~Rrl0WL@urZUO1KI`54<`ez$UY)_N8SVMQ236kbZ5|ypZsB4 zQZNY4T=OX|9F3f9vq>w>1Z@pv^!+`r`=@lSVAT@?Xoy`A^ebaJw=dRoSN#Z_B#ihFL*r-_T5&%D?RDh6eT^5>t*?!tf6l#z(2*JGIlB@F(kz2lWBTA( zY=1G1`F$k~Oc0(hy@AI2EPO1xH?G$@BppFg*-1rHuOgXRZ_l5n$;aB@BOGl?9mBW@hIl`ik5AU587 zElKLh`}qgHBk|)~cjX$Y+asHCI@7$}y>SuUH1+|DbSKhZvmQ#P^@oM*mgHaG-d3Q1 zN}8^blHVm@o0W>;KoMQ*Gg(r;b{=lfsgUn3V_cfCGV`xn6#fm>-mQRBEOX>lejZHN znVG)t|9s%Hp6N)3W#^?Ft^u2CdV-I5g$BrGz^`AQajnV>YQD(>n=exq@2smMqs{?X z6sk*4r}O+uwW-fg-n?MB-ZI>%zwqK>EDhP#B=K5OAnam2f8oOW!j_2(q*nX+oyd~W zRaO=8zvW(PZ+b7pPFHkk)|Xs3);U^ua?eCIYl^n8SR9JKZ|C!SGeLq$FBGvc zTkf%zSMgi&*O~7nC!$OEtiu56Wmp7RX9@(59qi7oK}Tr&^Z=q)Mv=&ta+oq^HhM5r zjqVmRVT5`#s-MSub%))0LZjOidST*UsPHNf-tJ~MW&0#Tn+M3~z@))j!c_ zon*Q8>FO*4A^K(v4O&)(o_4>2d@d`>{X=dX87tMdO(37%JcX}Ab+9au?+Es4M+=`H zn8=Dtv+zSxU8c|G_`SQiR(e#G->bfQKN?o#GW>4R5ZBG#h>q&J%QXyJpI76vM`LKA z?qRt5ES&Wa>~`kYM&U)SL!ki_V0xNyjyd77Ce2zR=l!XcrRa-F2xuv75aUUc zTZqZujvZJ}@^3Z|@aTrSDPATwZ&yI>D+_@fxlCRD=%Hny6X2R1$8V3J14ZpMTj_)` z3gX!9AQ1=f{@h~sP`vFLpS#bNON99|BI(88CS*H12zFLFkx27;c(i!~Sh7C+pAO;p zk(ZJMzps&cl~UNfV;259wSrs#3VX`4g=V&2b5JP78#cWKU&h5PeV+&4k(N|u!a4lR zqX1<(h`kL!-Ot3 z7$@&;Arur&#yhI65QhZzCT*StO9pU{An)I|U?=m2Ewp!%&PP5-^B$kISIl{dhaZoo z`cJZue#~6-r;zv93L~@drUk?3M1vBDowpUVqGL(#r_aE1ej>7(%V%x#IF^fm^68$t z8}S31YE;&=hw*z2@RCdrLd8qeVQ(FnSzd#B<`MMfK{XUjRYabQpa18J_;7HGgncWy z&vSO29~J`!(AzVLK;cfdV9a=x#+N!mvbqe6m-8O`s?kXFqmLRLlaL8p9)==mk|UYF z`~!>$?IH9V7e=l6DTp&7vV}#==lsKLiSS>Ai`a0&j?UcL4u5i+&<6En`AnT@8;rJi z^P0Pn=_nhn1kg83Gq2q0EDdo^Anyj0!LBh{c*f}xvh=tN0xiRY$TZfkk}P~Wy*p+^ zro85kRrnyCpv*CQL3uiyz2HW-8f%CN>TA$xJ$JHWZ4GFfg$dW#H`P|(B$)lT0{714 zJ+o=xSjgFPg2eQwW4weDY7FFj8g)|__Iu^hlL;UR(+d-%45yvPCI}PEPvR#Tm2zDo zYB&w+v?+;B&V{PyCnYhvZAr$G7BC$15p6Tmrb)&*aA3k8p=@T+wHPVt4A@G;dMJp8^TQ=mOn9Gcn`nf)Jm!7!`NdYkJZUub zF#3W<_6mc$9Ztk}b3HT$`asf9ezW=3_`am1mDky$!BcSn;Q-?=R8x*xL`13BMl;HmoP#gYFBBep2bnh76*0 zBpZ&pQ>%9~f6INnHfsuaVXZDbGBFR_5`%?rGB#U{&=yn<55z;C@SR$UQLEJ9Ob3bg zmqF_D5y(}4jhqwv_N4^d^p8GsJ z{|$^i-bgPxIZ1Ey^+2DW-XMAFilO#U32xmMO;e(>&{h4JXx6k!`AzrdTNGPu7)FQo zE&;`w!*DN@W48b72y|vjft)8lJXS@RX_HTzZf(TJ9#o*@GCmg@&K@gFTN+FaCe*{! zswBq9c$1BH4EcrU4&e^(rQM?qXzdjZd`A3y^x7r|ZK457yXmh+pV zBm8=h3(wc^8>mrDUD2);YP7d<7Npq+qTRlHF1FOs5;`7-(lZ4eP-K`Pcrx9>?S&FS zH~X~swcL)btZIj^^XgE1mt^9A}8n-(Q~>6SpO zOv<1&rW2kXTS5+dGf%mj!9q`_Zz+G6g{zNf5}j?gHBu;Q5W52fNj70~arxAP$l` zxO+xLOgYp@W7?EN>C?67(OJHKmnL@L4UxGtF$N^=p96$)cI(>DC_&ht^7K7^bc|@TU;zcZ5y87+!+bs-r*NLmC{-5y>pI~R!#I{J#nHkOrg_td(nFT9)^KvK z9+{-r1`*pPiRV+c(DP}3LH6*dBx*_k+1{@b)&$t$Z*~E+i{J(mwiw{gRd>nim_is@ zG(pHe6G6XE`-D<&#lmw-XJU7=9+FKjNV*J6B<7~2P&RoAuD7iqbE7D%)DwkyY^RV< zN^o!ApI|g0oeXWsgTKz}rFr`;$zc6f7``SBrLj48;IL2jy}kM%B|Blg!`gZ8~%;Jm7X^gbwq*qr`|s;-gy!+e<%hJVOhXhvK$oWI~N zd}lM7zQ*PjrO5;bpK~;B^_Rypeo8 ztVU0oX2GV2WjL4ZNjLS?$HSv8px!b^@^|J3SUS10Frk8ZwRtFrYuGncV&C-6D2bqL z=`FrhSVn^kJHYSV3-ra1*XZ&BZ6T;%47IbZM4A&Wq74PSuWtDw6I+G^&`&>e;qudL z>B=(+#CHPA&~aA8KhjEwMt}?|!~6yBY!jKn)hz6p-5Fordr0oZm#m=;Ynq42v#1W8 zxCzc0C+VGQ8sdwCW@z6;&Vd(=ZpN#=KcUM?1L43;UjehaU;1>T@MywZe6n{cxw^gp z3YRQ{1Jh0rZIwEBlQRzm1aXdQ&73b-aY8O#Hx?v1%YB7;>?Uz+*92jM>>yrPQAy1A z64z9yXvm%wz4J=iYbyk%FSnWxD*0 z0XX(%nX)5z?H+Vxv}DI*t_|MoZH1;Dt%(;58&GyPkqPh_@LKggyQ-L z`Yibq`WbW`l%1SePEb9(Y+Newnw>~4uPcSEt<39$X^-F9t4aE7G{fpb1?j}*%F}_5 zgtKf;S&&_VYmX|5W%lU=%=6*-f2X9iEu7=(PiNxQtZ#SjzZJvma0IS=&lP9TN!Tzk zfuXV6WgK1W1_{OOyFT9qx@UC-d34{nvN#1>}J!+}pHGO#ACp>j_4t44H zj?C>QBZHP#axaDD)(>&vzTtGLMJWtQIS*^AV@aJ=IS7-_qW0+pBzbEF?AK_)shat; zVD3h&wmujA7|gK`PlgK{_J>gG_;+y3m%t}~-iJ%?J4r@f;Mm{3wp1c3;My3+{vLRi z*+7b47QxPakAypHcYpqlj-b*}2~KOHNZ7avm^zFtuH)3`$URx?Z}==yD&ZJ6^N+)s zC#|VW77nv_J`&UzSG;WyYw`bH6nk`DMja&`@ceW!x@?t97W`KXYj4NlVX@Y9pSe3~ ztv!#dI~3(vDg&Ey#W0fqdZ(j#j+pJh`V zKh+7}KhH7#ZF6^s?-)jgoBROZgZE+K05=+PPhIrEW6=b2j&Z+xfjEAG3*E5;!`Mx6 zIL?M?R5VWF{nKaTo(idC^^^j*pRo#pSbttJx(+Iz*&s0~h^(=A1&$dMPrMyV^=mFm zyzg8P4zgLpsW4thE!&S57F80xO$2P7$H9tEM6Tl|UX{^lv@O+mKc+qDvO(Md6&A}3@RlKHagbH|>n=e)B+DWu4 zP{Jb^4|el>1$35;6)f+u8;X2=WVXrdzA_w{lI>i4z}!mPwuI5alNVFJ|K$PZTyV>>fQy}X=gHC?;ZQTs**M%Uenk0 zAA^tVsvvD46rQ@J2nyGjhu+;1tgO>X40cE-n{D#pn?;E9wiowh>N!6MJ#zCPbD1!8 zPGqxi|@cwHAGK)+SP?`-Vhh4JLf5o{kxG|Jv)96vn zoq2G*JOW1~Skr;)24nZbJ+b4{b8@Zz+}H(>@u-6sXUU+qsT%S%P{f(Qnc$C_C(iblB|t z&qufBc?4dbXicX)4TnMNQv{#0CbDW>i4fi`SbP>`$FkSk!JsY^l?_ZLJ8g^M+zY0g zx^7L)M!Tc$Jv~u@mXaK^l8;YCOPc`NeP$kXOY95_qY}uQHDzF^@d1?|FCjUC45F$d zutTynRr*?wYU-7-&P|Tl+}(!EQ=4P*5uF; z`9a`Y9*X}P&GcYz-LS(Y0l%D>D&IrB);I{m5;=GMa@0ul_94ftExTX4o|;SN1c0P( zFGq}fRgqao2wXk%5T>*fvN|spu2z~^ow;U9-g>vdAn!=j(yc4KW0nh!Z=a)O2YBy& zclZ#&=4=?9D;)^q&E7%Pv(Mz~LlHg?Tx+%7{Uo{g-&^<`JPhyA3S?mon&O?vZ|Jxs z>%BuN;9}3=!n?DPw3n+sTHSvgOgyef(84wl!Z(NoE9~jp7Yd@@`59KmjPKI>@CtmE zYU9MQ_vE*GyNrhm51pc@dBJDYdHW+cS?WwC?|uhKe>YhfPe~;E=9EI}-{E+@Bd@tj z0+Ix;K-PPlEWz3yUBodLnNHOsAJQhX@bycUWd5pF2&*_HvGL5JFBVygYMHE0^W!!5 zxNDMd;w1BH z5#q;90%3Y4nOvIdOU`|Szje1*RCPGl$zk?Jb&!-+>_>|et{*PgRw@pFw(fC0>1C? zf=3+}4P(7%gkBp+Zr&r$FWanXB+S2hnKnxrpo;m0 zh3xbu6C$eN=#q1|8pvrC z-yiL@V)?CaJn53cg|Jc68+R`^r!K$u~?HKi%8 z+aKhw;QQY|@MRgnUFoGmxnOwqJofnJNoyU~;kCm{(5NH4hWgbE6y{`Jp#$m%fTm+B zT)Om``1y$t6+Q1!*=k-x^@p6t&EGv~yUj&h`t2k7Ig4X+!MMSKE{dcwZZtXKd+|&Ro%ry z45#^*^5N=&$I{Jr_|2^1ihJow-!rK$Oc%W@&mhfc54m?o>xZ9sja>}2aGwW;53dVK zekQW;0}g^y@)+?+R2_LYM1(yTIzenG$Lw97vUEDHk!rQRhttzS(6c~}U#mX9@YDk_ z^z!JBl0^UOf->XHTx(Kf8rjTi3+*!XX`cbjrSbs7&vI^V+!v z?6a*MStw}AdSoUbZ0HW|et$^i;m2^=;H9MUz#4K+rwNj~4aC2?hY@jp1-KmchpXQ> zeovT=MEhAN??1ne>Qpbhyq_1H+;R<#bsLH{n^wwuU{(7YSZXzb1`REPnvd7OHI3KM zOfm=c{hUv_C}zMD=5w`9!HZ^Y?TaTe-}&Fhd*vFi&&&G@$?HPt>WPier{p;xrWOCk zYw67D5aWWr(WCF%r4CQ-r?vhc%eKAlNdo8Im21HI&pLpI%`l`JR7#*N=eiIV&2}!q zI>OXPzu4~J|F!k=x3uLAYSgGW3zo{Zp)+ZGmt?rK6~nwp`oK;}>@QvyKC*Wp`?r-~ zR30O0PPU`<9&872p)9??wvk%6#HY>s!~E+e@;ZC_NgrX9b}qefUmeFSIE9X0QzFYI z{{d;@7%={jKuj~rz^f@peK9};1em6vAB`Xw$Fd;B||I?WUM_ z4kDcvyn_1aMVPKCq^4h}q(yH7hFMke{n4fIPvG_dN^<|^Lij1mw9b!g$)|`GcvR|* z5|?$Q(SEsbZ)_22-^Y3BJ&Ohk^^3x2w><-4pxzIt2;i9AetLJ>kIh`aaewUx)V7K9 zSG$i45oT_Qp~<5MpvIEjuwjXw+)MD%8)s4byaPQEpeQDfk53o%0*FHOD=-_ZfD89JhAw)|c3}oy^jgoq_;if{u5z!C z>$k^iCI|!Bjmd4761?YdFY)NxbaGp%09G44m(KO(_4IY73u?>Zn(g}Z&sb?Q$EI^b zyimoy`>l-*LhgKXv8b?4-s=ul&;xfLS7J1)7BrldVX9LjEg#qbzVW`OM-bO+yc^Su ztCC}A&B2cnt%7*rud|74bXAJbYyTE-8Iwugzsv@ggKMl7+qKK{LuW1PicbycMQ?}Y z!;r`7SiP0kS@VO7iK~~2%>GUU%02D}ee?g2RoB=Z_fRTHnZ$QVeuw(uzl?vLrd0t6 zDWUM)z=!C4t%AUk-pI-DCTU`RQ-5nRutH)Htvve&^~o|sKCk$0*Z1WUQwCPG$k*j$!c`=P?QPg@02NiN@uV{7LYljOe zKB`34K?f*po(8rV3FOt~GPqrog@W#I&DFE6Us2_kL-HKGscsTD?Z$nyzLgIYeNx@1 zmV<`azv7wX(mr=G3u@rzRwd!|Uv1f%Eze+EuW|UpCO(HQjoVJT7Z#u&HE zk5aWisNM9Q{LaE+hk>w;?afy{`hxyM7r}~1j!mKYk?6A`hQ4InOX2B}($AAQHoxZd z!d0g$NYC9AE}>}QWG2gEI9!4qbM?iIFW7EKll30DP12Ur9FNiMdyz^o*IkUQuE*1_ z#n5kg^I&fGXrU+Tjqh7K2nQRi#OAMc#K2nwbCzK=-JjRWSEf6_)4q|qYd64BowMji z7{{aerdpg>%eB+n|3(QLSf6ZO%xdK|Cm1j}lX!j1hWTxRRisUa{D$J2T_^nYdN2B8 zb^*+5RKcS)J>|NoIKL?PtffGA-^l>)|E@|@=kwX~$oHdoSa&b#(eed`jqHWb4h|zh zlPbVEF9r-49Mn((IlUZK5yN>W*uBxc5$oD?Irks&> zV%bJBrau9<;sxlh>NfcuM0jBhE_xhE%OaG-u}ll`^di%R=2!{e`Xq}#{9iLW?!_niTTx+qkNn4QB9nqFNZAJ*5Z6NM~&4c`L@< zi_qyamuS1QmNosO*v9tAzw=XsgcWCC#CVR=P1B97O5OQB zclheRXtzmkYWT4L)(DDttf8lzBN~vjl5ClxAd~uEMj!6nf(iD2N!_RnsL{J9xv`(m zr#cqfamR2kx~uzFnDev;F47Dmqm!R;29J3>R zSsnoyLBl=DV4HC!6nXQynblt%sV^%aU6*BmPDK>5J;5=nwYa-5cxNaL`O^T0e>6k? zxtz;g@}&ov=lzW`b6M%Tt3FZ^(9 zP3JxBp)2FX)1Gd00@4t5Kirb|EaiJ!lbIuM$?8c?DE_SEw1fK z-EG;w?|*o>@F$&Wly1Has<6^!Z^r7UB#o1K9dP$B1HVOl-e@Cg@5^v)-G9S zIlDc1#+)S2kzy2ohWD`nrM-l*9ZVO|r9bL5`xKO#@ILl?m9OYh>OjrQ6vZb!y`;nY zaW3eDV-DpE12di}4=jT~-kHUh*X_Se_&B2~va;|M@}sv`lhRH3w)xXRF(b zc-=hJ-h|wOdeg3l3*qR^-)O;5UN>9MZy=LZ6=bj0Uq+5qQpmMYppW`9+#KI0xif?J zu_yOxZP9!Gk~2 zBfgzj_RSMGX=;w58aeLHZ7#*reWU42MHMkLC0G~`&-{cRS_voLNk#p;%jveFzcAL8 z{hu>^2*k&y{V4QATIYDJd|08x?nZOytr6 zN(LJ}16z|=G_;Y|&DwSq!7M+Y&iK9?e{ZTnvt16$JyPcOT?u{zxtC*=<7{!lU015T zmF4kW`cE=$1LtY?J}|;-wx`Oqh(8Njop)1{`lLy0;uCvTvj=?ec zT?8XNRukVFg58yV;+V|OMCH2(6P{g^UYO5yP16sbLxX+?(ss2jqN4^yH@q&BWwGo& zD8H-VA&aJ0ru9cnJI=rxP2RhD?YJbOatC_pwW1il^M=%r>HkOkcm?}(Un3psdqn$0 zAp{QXDje;}=Fkf*$fT_nGRvLFnojTFn^~6B$2O7Nax8`9c2z87^7-+gLVz&j3A^u` zT!Mf4jugebbf#AnR2 zaL&V*x5d)I=AR^nW&VOQ>w%+hrU*A~hk@GWOwxaJ4&2}Ra*DPS=WG`@vm6K8K2&XM z5m@AXLA8TD$%*@~K{_`dLYFAeU*?&xuB#xC+Hl;JX?4agEyKvN-W6~uJq==6=5mOn z8v2aBBssAACOKbS488N0<5{`^bjt(g=Ql_LL3O1(7q!MM5O+H{l1k@3gBej35XXD~ z{>_h_+wVv^n9lH@HhAQM0MyDbm|XE5ep_e=Z)aYiC-gqR{DTT&_$rM;ob4TzpzxjVr2;OeUQ}ieY=7JnYez^*MhlQN!WQD5{C`Ib+fc zNS@OTYW(XHcpH0w_O}Fi9eg-F7){9Gdy`bgM_4Q`pldz$U_rG46up@f{&{3WJNWIt<&a#7YQJuDl3yNJCfQTXU02T2E*}~$p6utyayFI3ugL|{MU4OXw?nb}R)*#;>W?x*Ua1_j+INERsq-%MowXs1@9QJXVSgv*v>k*)SC)xg+v`Y8 zl?dH7%_Gf&d&!>6&BJAxYhdyPuJg~fore}A@m=T4+cNyPES5eNKS_pk@(~`f+nL13 z6yb0BRk*b%ljIG_ft_lxQ})dG1LKD71ng6Qp4RlC9>a>ETh9+@*=Osa3E^~IaJzAXLy$5X?Gt( zgq9E4XM+l^Q2Hr=K7A2J0#PM5|=Zi<&9Z5$Wd^5~D zuc5>1+$E;-Ie!0cw!xiP&Rvj=G4>8QkB%ktditB~@uSXK)4qOw(7H@Td^MbNL2dS3 zK;JWmM10GFnvi`G*EEjhxa$Zv>@uPghLyrO9UsAg^`chObcB%^y~I;Bk@9-F!+Q#Z z{$=^yN3&s)p#d7uf1CUkPdi$~4^T9nbwgR4+QUb9%j&6Jpq22YYp%HA(sCO4_Alsn z>_%s@ljRvz(%V6>* zZ{*MP319ok;K-`4c$Q@W-L`ZOwx}&a#k&v7xu6v@@&vK z0qexgSJ)iNH2-TYOeHS=$Lwn*ee9l>N&=QKO+w8Ea;~|V=GI=u;=WrD?(9O$yT1e1 z!Pb)SH+( z!Lo-U-@vkjI9%soO*i^vNf$Q_5;OZYlcjSAa(&TO!_MG;DUlp0C}OAzl*;_carrZzEf}C0CePPBdous zK=&7BLiN-%tC^-8gU59hvHn<&!3Uq1o|WZ^XDq9R%tbvV!2<7Bqh-G&rIx&3b!V9! z_8O+NU+yzdM<1Z@AlCvpMUR%eU(Wm0sJ9+yY6;g8#Egi12y?QDH(hHpJIqJ91=g^^1mv15ugZ9Qj#U#!p<-QPsYYo&e4 z3=${Pl=YV7qR`K)z$R3k-rAA_kA8JUnrhqRH}9YNq_P{TXu7nwia2;~B(`H3gTPa( zaN?>W(emLkYV-3C^m(!h{S4#%>X9k+IQeBBeHG8<#Hghx_8rIC(A1%X#ND86Tbdx# zFa%Di@_w~*fGf(6C?Q2%WDx#38?E1ZSbo!L8+r(6AMWGV@bQp%aEu%EZdVsC_ykz} z$95l0EVE$WaUJ~Mdyc7T-jBd!l?%~mt%v{OqpifYAmXwA74#ZE7Pp?OB0eSr{@81a z^E@fJS(OLct|`*Ar96Y+QKYWq!>?|%HZLC@Huxj^cwXaNjIZF;%(Li5dX}`e>KIX~ z(9E*T2pFd}N@tn#*|1wlfMn>yAR2qGi`e=p9#uy1U8GV;DDDx*G$;8|NzJMN@U_$< z&5zn(oc;|lXv#LaFO%K5$E!ma^TPU9<4l?f8WMSr*olQ~4RaaSzObg+&c3LI<#>#< z=QZx^Mg#bIJ(1k|SPEy(zC+>Vd^QYuc^Mxsx27{@d_{+DP7&3!d5vRT1$4@^B*{&! zpt{#ge65&8k5o?=C)D;rDs0E`&x2yoe*xH;?b?ocjt0}Um+?#sYpVLg9dC5rEM6?B zBgu6l%r;$0GADJDC3TnK>fN4#n%SQ^VAyM0`LP>FIp7)L~>!8Gg+D5 zL4(bw!tb{L|4Deg^Rv#kOe|rU%&9xz`M&FjnDnK!?CyKL`%Cn2F|T)5dK@5w+3uiX zQUD4H`vvAL3UuwvEO`2BoYjMQyhjb(@C(_`3?nKZ%fYJYDHyP<#?f=Cq4BGimB;Lx zWc$rx2q^t1Nz3K@Oq0S{9P{3kzR4?xgV$T3`AjS^cPM8^NpV&m#}p9bVHprV#T7yK zedN`U2KYFz9p|e?(4n82VA1d{qGg*G(Y#R&XYWmd6&G`eO!W!47u!fy@8F!w-aJzr z^O$3;seYjNt~`>otf_$bL$;(;QB&5Gnu8JtIzjgz>a<%+4#fRZLT00QExT(MfET^; zq$^Ioff&VEC?P+YWTq5D-#9-!a^^Xzobv!(Pnm}@$0?JihyQ?e!yp1xG1PBQ4WuVU z12(uy4$XN6&cWN!+3*q~QDr$A2LtfypPn>PV-RjzAVUqG4$Jdiml_=-5|tm6x?1Cd z<}T2{{A5P1{t4aByNcQ!F4R@*B)YELKV{Q@oICAjuZ?xPKOlws3Sjh+lf*nuQD*cb z9;;PSC}1;S{(yJj`z=nyk7Ma(uLlrzVeORtFF7Z(hk4rEx>-e%EC?jM(h)6BQi9** z!I%O0()oXRmTRO<#1xyDZnR-hK5U!hjofZ=+y&kKgZuT1qhVwy{5CWfM;>k_hY5kK zHf6Xvf@@`;O%F$d@A7`~it`Wbb2pNzXz8O9n!&I-QCF^=yYljmIDFSOYV=7-bg=CM zzM33s2ZQgU%wzY+rZa^g`TYy;_hff5^(`pYPeEMjp{a?aQsF5q`0pk1 zYONq!4zYZkFM@a>F`Zo8!8k@!4Equ-<-RTs^>alsF^d}awidT$t0TKAes|V8+8gg> z__A~z4FRE^I5O9qCR{#>8~$z+I~UiH!M{alXjwz@V!FxRC(AHSJq61yb3OdMw!Ub6 zORzlmr!m+YulwOigWaD<91~ng!le$ne(Y4xsmy_nzL}&6s~I%F0Y~31MOT;c8Sv!7V`NBPD;;0ykM2HI77f!CXp3SNe3};c z=&^+B;fo`^@hIjy@g+784?Wk6^py3au)q65%u-cNdr?UJ^08^7;1PCkIDt9TC?wYU{ql}6Bkn$7UD zcQ2adZnRsG1>;kmSLdNI?9FM!wSIb^ii6X@N^OftKG_me{o8{_WhSqAH&r|@&X zv6z(~NirQO7@xm{I*6{&fHL|=nmGtGrnIUgh@6FCM=?!OjS(^a(jx1!iz zVFJp{NtWjcUcg0I>3Kf&7dqp?N;6T?A70Be&krMZ&zNt+@fvXKd;>POC6FT{pTWGA z#i+M?3Hen|q0{&@xw@w8}$A`By9{KGsBx4%j z#6*()y%dV<>ZGab8tMH#3t7HvAu6b@AcoBEecj%f;-t)Uax#*=UAeR2mS`#Wbu{Yo zRpOS-XT9|W$^kt%h+N% z^V*W1kLKC%+3nWyb10bQ@J?4OfzWDqJdNGSJ~eZ|QJQ(^iWA>K^s6~YLccfAZp+T2 z;=@c+I6#qhW}2}@H#6xQ;(cI~JOZj2pGcNaYeiNCVww}aQUI;EU+i+x;Aer~iq8vc>vOReey-Z&+a zs{1#CiF!}5^GlAeQx6QuyG6Ow=y$O+xVt?}4$mRK4W7V(*@lvAi@S1f`6q$;*!9&Q zdcEi=G%J{hgJh8;WIwxwaSesqDH?Rb=3JPYS1d8yu}yx<+3xjDT(fvJ&0D7=+Ar8j zOtQMkl#5k`Ox=O#bv2*MK26KOQ+F27vsXG}wk|*+8p`sWLaLz&SyB^8UC&m5bn;;` z-Lapn?-(<|p-&2w2PKf_56eKDKLxcpmXJG7DD>QZ59M|`BIh=B`<*1UW4_Tllcr+> z-?K1CoA2w5h83k}IP<#p`K2;GR-a0Y3=81Ic2D9kPD$4FX#!rcsu<30b0I!+-a+83 zRIxT9h7Mhw3aiq-rkj4{nzvIy{jqB)uWLI>`->-CDLJQ+58AeE(u>o0KRICEZt17V z-D%lywl99^gq}U)I+;O|2E1%k3=O@@FqJ-COmlB0_MZvdmoVOw{ocvVHSnU|8yV#D zecz`0O}OXU1ZuqA2<_P#307x#T@y#k#Aoe0sLehVam$~{5U@CaeA-kAbk{04y}glU zPR#?KInk)yonxw&`EPi>kEf$ziFW) zsf!GGmQ;{Y(WH|7aU%_E#;hB) zn`lnxE{hI&j8{4N!A*8sJ#Ii9%l&DQkoO!%JA1!@^Zj^FSkbmE?X-HE-0PrC*oOkH z_NB*rl|afYXWV^~7cJfBfL-T4Mh)lrET(naiOd+qaMa|D3U~An{i+n`P1`I`(I`w; z`Ts0tv*07@TlGJduEQVe?~ht3qYz37O&X}AMV`-xq9ujWx1_!IltePpAeEU?B8n7B zOL?C6z4wufY>CX0(Xh2uzw5cbzd)}zpYy)wectDUla#wMh~95-KlU=tvKiD0yFOl! z%!&m&#)vdRl5vfE31t6%DTuYJmE2vv&p5_+2Tmn0yc$mH4nVwhJU+JI4SYFdDcX0Z z0Pnp<{iRK-xP;kkR;;aP;B$Io2#W56uzy35OG%*QKDyD}0RQ|ik8D;i5&3s`f_qLb z-eO0yG(Qa#e46$M4fraBGQX?y#vWtIpU~If=wXZsZZpo3pRycZE|L;=Draz=d+)-J z2MR=%-bl{(eIn4aXZ!cc&8=u`hcgK_l|hla_T!~JYT}@7dCNP)l{vK!3}3>4SzP%v zS&84w;JzW=@;937RjdZnV<$1{)fS&=ondL~4q$aE0iQ~J4Xazma@Q^}{#tr4nR8Wg zliWwAH2Pw-1s!DECZ6}IIS)1`#!LEe2hWK>wO>z?hsFI-K=K$->i@M4dEp;UWk$Lr zQ~l_&3b3NR41M~>$h{bi42&a>mpz4BkrtvO)Q8r0iy{0^i%+kv#W7PcczTURH=h#x zz$qX6`YS-WHsh(nCr?DBr&I|)F&{Rs+Rd%cXS;*`KWq4f_hSifFqUd)i&5JJ##4{- zC&OxaUwo?UJt!KU;^JPhS#d{FBkz%%K-6MJbL-Z|gPn~gJ`?^6%$#%3%JsX+6azVQ zK7TQUZ4JYd&(y#l%~*(`9UOg_Dm0Gd{)Dr+@xuKozWqTgasAfD{i;$#B-LGVJDL03 z5c_83k_vkF+B$6~Tue#A9g1Zz?Pm=9fVpW(77gBCuD%0eM_zJas%} z9b`~nci($W=j3C-hh{cIUR&ga3=cNpi&+>}6N})KAAX?}|{X={^4Z6+Opvy`X$-eRTirf^5-?APZLbN%a! zmvs*pTfLlaIdN(Z9DbgF4P?vV$HswNV+g~}hrPGCQGeO&*Z;2{o;Iw5e6;5I0lpU? z&5dCP9z>$JrjsN;vp+I(ohACYk?q}PsQ=9*$5w3K zYnuBI`O>_sZO)0{P;D=IideP}wj07n&^`F@p9nU-ABPMw2%fhtA1nfu;J?eZc$IGl zs5)kgc2=np^SFGlJ-MBeEo3-Skov%jDicV|>WOeoZwWd==RE@ffvLqNa8r|UlcB9I zw~o$xDZ4A+Qg;picWoRIyXtZ+mWhx!R#TF@)wZq>ZI<3mGwo$j?>c7~JS7a@<7&Y4 zQz_i>{6w}oy#n9h3tYe3Of$SQOy2TgegTh1`})ldp89O8PQiq({A)wi&HpH2V&hc`2N{+#-WKz4N(#uGjI~*Kgo? zR4<$rF-+xWUla94B;)(4CBT165lF?>qAuFK&ZTVSr`Jy*Rxy+hNDlQr_3>CV8`>8(bsw(EJ;LlG}%qCf@k%0Cn+U87*+p3!@&F zTzqwFHq2ay&_K(~u_X|Y$}rU}-6r@;vpdRZp828n8(i;X#z*I~&S1@VU&yIS3tnA00*>gg zTVRdcc=S@noAh+{N7ud1i=Mc#d2fjHM{d|chADgHbGRg@jT9`)GX-wf~16EbG9hduhi|zaK{0 z-m`hncx^HNFX}dV?LCUq$+`zirf6c*`@dkObUCt**hL-{$)bLByJ5owhAD9Eho*bb zF5~}RfkCGqxA@5;N!O3V^BmsgJI$_{)y~C#P(zm9?$}V+1Sb3$u!>~!-UGLOD8}m( zaR{UDrkB^b2Lmc4@1`L){_%|`3&@fqp1fni8sxfPh@I{f!1hgt!OV_n^4s&G$sGnCFA%k7|O+pUw&% zbg(%vz}p`;cQ=t3o2g(kO&WPCF{~L)Ruy*IGacjF1SL+eLYw4#ErF%-OZY{4fn=T5 zcK&qEUCuR(X@&t){qeb-O+@8zAh-PVcw{(HnjHQ761FrP7Y+QspJZsWKkdq5SX)!? z%x7AMlNIM<_{H>Iuj?%1GG5_4UOcgjsGO_hce~0U>uC1=n*2UXr2IG;OV28S+kayP zTk{yNfoKhX$kBw=1N*Ts*$%@&+8bSKvv%#)#kCRpRFaeHN*;7T{M6FW|q4 zQ#tvG2PLW^}HJ$#d_SMGr|)nicjy+Fw=zYw3ow>fpO>S8UJ{rCn{Z)19+?Bp1W z2OrbWZdobRs@=t1J35Z&ipr_>V2*k>GCcN^tp@)9MY8`;KFoh>FL*eI?Y_5)R`9tR z!DQ&X&tPRQgN0-rA&GKGSG*dlm30uA)>__l`3-^V*9Vf`^MUy1f!d+84$@DVRI0uTCtC1!D z6~NW^0`4_^i}mfV^&e*O_Brun$QT3Ik-ZMBecpl3Y$4#&kG_Nc`bhMR>@FwHzJlrb zGx#iC{#86V@I;U6&c6?SMw+-j?-v|jP>pt+*+r~g%ObUE4{$JNZ?WH}bW!v3PehIG z(62?hazjK6o2{ON*D#4Ab>BKTS0hbSK{dF(%#GU{EO!0%Ms%Z1wvEG%Xv;X-s3dTk}1FU%vPxnP>pu6Jda)qZsazqmn@3 zBGVO@mAYEApJLj6QeZuo@5!(xx1L9e+hXv(6BQ6)_Zc?SDH8l69~#Gu6c}&}Yv%Sg zeDL^SqVN2f=Jv~BJ)L!A#D8+={>=?I(5jP++)>Ay|Exf61Es{U@=3LhC}476N0q7n8`e(dvlO>Mj&_;H+J z@OJBB-gI#|8C_<~U(pWXqBk-<h*i*VxkwhjpUK< zl82&Bsy*uFzlYu}Rb1Pwbjj^}#N3N`jCvQTntzS|5Yi6sHP}0@zka?*w}E*}UJRDw z6{YI17hOvn=$ejxoFlk=TRzk+UW*6b9V4zd5zcpX(kwfB=8K-SaV|I{sFD?%>3zI{ zIcHG8@E97r0r68h@z0k8G#%H%m+9;><#Qbk9&llA1MUG zDUH09P98ZWrO6jO(n7R(Pr{GO{$7Dc6oYb_Wnlc1rL6+-I=kAGKz7d_qO@DV0gw_Son?I==u3x5bXV|O)7<@kREQ#%g$lC z;=9mm+@afy`wEuN#5yy>$pZVCT!_I;)afBjENN#)-kfC7fAsdYug76Qog(L6A5JdE z%b>ZV%=rR4+EE@5!z=uLz^%W|xG$wG7_Z3gAa;HgJeseFq@cjE?F&l zen|m_W+!8h6(yiCB0wvL73ddrrRrW&I`inu40x z!R$NdXgCJamKNfJ3$x&H&JgaMIm4rK`$e8Rc#^zY4zMt264JXAD7op|&WB+4VlD9x zBVEXlc>*`CGyP=1CVdON7i`BJbF+Zk`D+~cL;dWR-pxac?HM*Z{Py5TuWzKo`XTqB z?H9DSC=w~P0=VM!#=>_bn@f#XTku&!FO$gn9?-DwkGFyg*?dJ7Dfc#_oj3lHyY`PW zP~2F7RXy7U)RwAqzB00s``m1q>3Gw!P%_km`Wqj$!AEg|WC!=?g{7dB>i^b7G%saz zAh(BNuvpLn3UaVWU8_B(FVe_h1&K@*icqdM* zBG9O{4bNJsD?ak2j+b$DqxW@e-|ainlv~xnIPv`SXYf>mX_6;4e?n)L>?RuP<g{f7Y5{!eG4@CF3l0>Nb512aIpyz)yH9t-M5HQcOfh} z90!K`*}HG-p(C8`wF<2I0aGn{H?pFA*5lI(ASw75-f;Cdkx%=NuiJPQno7(tZ_@+z zX(uhD>lhE7Q>)~MUE;*+i`!w#f{SQT|7M&*2t3O;i5+vK#a5$J`I)`|DKmUbEQ+z2$a~Sb^yTpwerk6jx6SK1KArdmf_Dr;X~9gl4D-;$cJpZ#S<`A!&|Dq( z*+cJbFP1?6EuI3E8+9l>Sqk0l=J@4u(@56E8i=?%25HE|<5vgYKtGz}EA5~pz8=)d z-EcO8zYc}i+CB^7CM$5;#~hS+GGFu$=dXPZAp6!8LH^dsC}vNfUXr5ZOD&V3Jq?nwJjYx%95V zF(HlH6wwbopQ}Xn#TI~Rql?7^E5@6>GZb;hQWxT~Qx?T{dE*z-vSQoUU3{fiqQ%ip zre|^^l(|_+GLjy*BeJ1Yvv9)dHz7_B2Vf9$i$DzFmvh=6qwkFk8csf`46k{y=|&uZow;l z_#h5^Jl~SAbtnUVcxtVpBtT_hrATsvCOL`2wXNEfBPOs*3B+} z?|<(>@Y*CC^S%@!R=IE!Gb*s`FRGsy2Jss{29Ta$_bWY6XuiWd^*hUT3`-O91EV={bX7a-bO_=z>D;I*6!OAnA?PC4 zjN=B1p%hcCOjky{C^409PsxH{ZT4o|HpkEWuF)0zsp>7PemoRixKH1S0Gh__;k%QRJ(!As2>i{zpa&Q zH+S6ms#)9UN0MHH)fRWS^i+NFdIrVXtRTLsCxFhQX5~kKtQ}J!I#z z2b|WSfyix{5)q;T@bACSTyqoKDRk4HE2KZyw2kVGh6C}W-Zf4k@5=3sw5gmhcvfw)o%g`fm{aA!GuzWC65=4r-> z+G-x0*C021v8)*~<|o0RdIL$m)8&!*$k5TBEO|Z<@kkyz9T^Y8r|darEI$zq#}sg~ z%;2tDF;2YhaRu)#?Iix|uJM0n$)Hp7yd?KQ!ygUD=vppWu)YEMUmOP29T9k~S2aBR zmOaO9=_fMeZIwXN{XKWTt`@g6AV{*cK_1Qo|8~mXT)OY z(K?D!4TN}jO99ONbsSHnyBo_&6j{@RN78TUS)(&}ZQDQb>6}|a#tiC zmEU{(d1?A>NpRG(^s&-Gb~hMK=Z^>yE;nU*j@M#Yk*nPZVm7yoX5#sC*HhS=@l>uQ zwpbNP3Y{od)-6HKvNEJ!U=Dcd{SZAqUJ6OAru(Psgq^Atl3+pDj{>d3prE>^rJxO!>!}}rSX9+lqcE9T7qzXe^OYmq+Koqibdpj(D}M9*G`RQAK;mI8I#Ym_emy}F!sOB21$xlmn)xlqc$2M{*;CpA=_;*A!1=&+-^vx}ph2 z*cs#bWidq0BNw9OF+@*I!kaToLABJ7bGuc6p&CQPE)P_#F2r9t3gGiJKdgTIEA@yv z@~xX9;q74N8Pkx($em(v;)4ljROV-);=j{)PR@HU-FXGoFK@<|>FwmBr9Sw__f9fx zM;xzB_rx|9J~-}F6F^Wu(Zc`Fs~^fnql@8LSaWI~IPy_KDMN;}k&jM`=3E#-#zs+3 zRHX-Z=neCts86)Pul9wK3FoJC8@*Pbn^R=S2AcIGzkL84mSb4^DVPVFw!SCQO7l=^ zayvK0JeUEiL9cNvcIm$5y?#kcx+<%v9^>g+61*s&5e`6gq(;Z!f> zOazk;)uEH;q|nf?(R}vnX~b|}Eu6}mibQJhSgzy^EUWf{_yvpyFS%iX-5Iu9zvE(# zv{nV;M)`Vp<>ZdDceRjTQk|l|i#|Z5TP}8U%7$&PMhHiJU>>li6Haj(+w@7%@e26i z;>jPT-?78>`+2vSD^bSu7(C>41xV){$DZPk4(B}RqtV_=?enkAb> z=OT4%w919#C&;2sCk1>ns+*XFCuby2&=w7rPQxcli{ZzfR>9AuvXZ;?Cokt=m#rZr z*cUIdWNVzxde~+Mte33*K=A)Op_^Ti^b!fbr91eOFmfPDXjTz zfUBav!-5;HQQGSh#QBmus+n#Kz6%%+7T-M$$J{>=f3Fls?ia&_hOu2n|2IlVt^0(8 z`+`j-VyVmk8z*;!WGD!c6g0C zmk(~4`(VpoTglt7P8JbtegjDD#M7g6Xr{w{1hn5KbB;sZR(wX9xgtHOT3%l`Zp6S z`!0r>Fmpjjb;$)olJK0=QaItO!43AQz%;rFzGa_8CUqJ3aCrgf7Wm=emK{WD$x_~K z^mRzvZzjnozUOWt+WCLI)N$Z-B*<&Vs&B<0O!LK7R&6Bqdkp_DwHhk5d~nR_CMb4Z zB>MV)jdawAC3w}ga55{qS(NWH9zDLBh3~Ju}m!U?}FhM%11&l%=2?z^#E7g^4{Ai43;r{04DxAF+O;w<_( zco(2+Y%YC3`_nhSWqU*S&|&=IVbjT)o;p~&b_P24H4g88`35F7tfIP>l(=SD6*u8@ z0IXVAh+EcYfpEnwftn}d!4J+4d5wEz#Mew06&rA_7%avx5WZfYu$Z3bb z&|F-6g5JQs+#`&ZW^cn+ceZdRw;PZY>IJnf*~8zONxNWr_w&(rozW)E7|iEV%u1ca z$1gRLxQs-uYUwyMI8ll0+F1yNS;Isv^!8`(w@;9Gp@6Hp7*5VC>VhBQAvjdqh5U_> zMYfizxJ}qi)}$wAbPd`iTHDUvj0v}E1zt8xN97hQ#6_1wh|=I!5HUmr`K2Y`%#d=( zy? zPI4W}) zrzKZIMQ3?T;D=z<9yXWSZ1qJN&oXdq zegP)GQbBib<<(kwdu(+HV(XW?g-d9b|vvGB%Arm1e( zpa`Q(bx5z*YcSnp*{Y0xnhdVK`t@8X3B96y}OQweSZTpmybrP#xZOT z_Ba8T{gbhgaS1pj{BoU-$3=A4S4TWDY4YO zDlW({0y0(=;x%qr;KBt6oV*zxH=Ir2XXliWX$y4GH-ovzK|c@=`c(&msPD;JqnVgh zw2LnO{so)%vYq~>S<%9xdd8JE&+%Mof&sDKQVE&HYx(h3fh0)w0MA>kM=8oN_!I5) z)Hm_PHXECXRZ1e)G|vcGAtlm$r4YXKvlER`-ib#veF9X+6fxb1xik-Gc}-nOVCA=Obe zgyqm?y#h~{GZc5x{MUV9>7wRRc8j;{bVCK*vnwfA3%asybMxNT;zJK;o{9B(^i!MQ zU3c?=B<{lFt!2ggln?Sp4*5dSU^ctb5_#BuZ!qyWTm(bco)*Z;os)F#1P=*BQ6^p3 zcyT6ZH=V?3>r}*|DS7;}A&Id2sxSVr_5%dZi4bJ{U|Q=LlQPg)qKRYmd*O+jE_n7jJjPl zkj^n|@+R2=_x%i;YXBm>-DOI(3qtv*LK!gP#HE`QTsFTXCy8QFNw><#;PyU4eyESDF2x zS=19e4L$VC!fPG!V1s+6aGed)RO7A~f%hUEvLfa+bk6kVTG9eYjqx^qwrC00g9EVr zwR-T_?}*Q5QcZQi3~uA;UFgCj8B#YS7qZ=r;K{Ew5?_th`LAH^UQ5#YPNG}SaW725 ziKasg@7unEJKe&tIdY~x%J~%}(Q}SAoPm(F%nPa#RbX*q9osDi50vL`>dqiBW8T5| zy&O7}6o+-My@5dwV|%?5BpL;hVBT>u-W!P6#JIF zE01|&LE8a_Q&%Ym+7?E6^BnC{xTuAm(M;go3FTm(+#>o#GhX`cWZRo&aKDc;Y<{!x zq_|EYhT?(zyaJkyb)4z0d}9mJUE)DZH}*q|=$`%XGN!vO-98wdpxoCt-wuA@%`IJ% zF3FvE@9K%iy-6XSH@EPw77jsrQ%~S6Gnyc7hC5u!X7_#Pu{yG*StS|j)q+&JtDH_% zE#8!bU`~=JK2nfEAdy$5Y^=+_RATiXpsMyZp`(Zw)D&0df~ zwb{NttUI)KV}o@VnKpe0@Ha1@EaxsP@Xv(QFNd+7ikvvd>^Z+GBNf7PeQ_B608&;v zXc1@>c2c6VP5l!7c5^6sXr#hTFM9(A$~AC=|8E#AHwdpgwwJ^!$fG}z>+zlE9puHv zCcfN4Dzp-2<|Dja#`XUd*er$R^4nG?U%ijyCzh z-8edfJUR0Y!VY@jr{hz}Ui&g1t%i=`2Q{)fle-SWLq|J!w{$bCjsKa{$skmy3r*XM?V9hw$}GhU-)Ap9SjW z24wk_O4xQG!iKo>zD{2CvHAK$4>6QDDbKth=$Bl-R%LmsT1s{8>!o)I-;N0VCaoaHj=XJLs7iEGk2=gK2 z^Lji&y^{p3UCaO7cMev8t)vfYY0M8eT&PY0MwGw-p{2lS2%B~9Ke~t({OiIhsxRPl z^?LkUrjrbOilSeJ#+pyqc2g$wF#3vb+!0Q=|PjCM*5_EiHy3pniGpS$8P4Xr+ zOPP+3{s<+~HP670>!ev-N!VyY8KidD3C``Vz>QZh_+K~YA5(9}E|ppQ)cXPGUvmbI z*;ELp&tAl1wzu0Vu*f3)sogC9=Ro`a19pW zv|~MnPYSo;%rv9%?lBc`c9Stu`x7Mb?KIOFVUx!|adP2h(Rz9x^xKu;aeCu&i`H9g z?k)e(!2P{GgXrIX2N6XJkX%BXL<=%%Ne3?rhC9Bp*fzlW zQ#|Bm2vI*4DH-(V0(D%1D# z!m>SRMd1w`LVK%kk2;Un?QbTby@}kRCDv%8x-toyN4qAEKN7jCviD~45p(|U#BefX zz%730GkrY%=muhWifV>CRd8!;9;qA?oN-EB398nn;eSg@;NFZl!Rr879I5>mqRUp} zL*GJ3m}Wlsjv9?dCorsqB#(hF!%HREhEJ`uxp-i2%)*#^xVx&EoYyhu&r217{~rU% zouI|#aWq>ik?gKEK~C}OvEd2y4yICRRuWLFSANm{Ib|m3jTgu@0hH8ruD=Ki8ABM;0f>4gC5G$t@g7vr%EXevy zR(xH|$2mR)D@!v;HvZUMRmdnejI;|iP=rFKXuw4f-OC?3gvI~9lHmO% z+>}EvAZB7A4%nXsCUQqDF1a(TRkk^xq=o>=z9aRl8FoGxMl|+c6=mCKplt_p@ub_? zP@XYT^m{VHnt$dbfjDYBk&S!{<96%uBj?jRf#&^ugY`jl;_eL$v?sb<^&-}I(?ncu zCUWy?ZINS@68R!s1dnbMiWHR?*7P?{#D0G_5Wg?-$Z?b=&W*|=lO_dcEcl@dRa4Wj z&Pa-{gJA;OlWZ=Pp_<&YWv|Gr)Pbl)q>m2Jewn`a<0i!=_~1_^vEb?eUS_>Hq|YeD zO{c{0$z>qd_L5=Ez#|o}+1*TzzBA*Oo-Kp1-whT-0eKWMh zJAH;(PJ8MLx2Q+%w-N1{ziY!u=dk-Gsg4rtFiBDDmh+ImUON)K`{gNlKNc+x2l74w zpLtddiGO!<`PsEtA z`!;HINFYU9N1%wN$~hf&Y%U$A+X#{LCbtidX8FUhIzCALBn&_`N8iI_nup)nQv*G6 z325urTSQlU34-SzopWgb(|P7}2~g{EH_6T5%3^bzGB<>*{QMLqPn1D+hm-Jo-!kwP z2hSOFxXZ4gv$>_$TqQDAvmxhgUX&R;d>3u4LH!aOO59 zbKa5xdE>#Ud?EUNE(_0ooCgn2t-|$ID&qV11Nn|Ke}snZza`n)e;-_fR7{(y?!N&O zEmdxF4a26|i&VU4UK1(Zd!DnsaSC-EkR|%tU%_jqwcydd2AkBiLfPmwC@rdnOzY*4 zgOaU9hAHjIS{lRmwvFM2=`kL(<7c3iO+k|Em-8o6pm{UnzSUbJ%su{(O`F&ZE=y}B zxjy?njQwSgqHnVKb8Vv=c6r@HuADCB&TKD&w4v;cxm-AQ&awdZ#+)E@Lc{65d5&2< zaOVZsZF?BG;(k?hJ!u#^O?l8FB^$0>nI>xb|6TlX@5VVw-Q&r=0af6!MU~$%K9Ce9 z?dNabb4Azg+`ty}&7vC@f?fTaNq_S@+>T0TG(At1JlpvOj9ptq(`nvspYFOt#|U5X z-at~G$fJy5I(SNZ0ofiInqitZ6*l)iz_*)<;b6*X!Rs`3)8Skdg}WSI5vQDisD9-n z^d%qxZ*3}v8Ez|ZNQAO@53j&G=h(xMsSKM;y79Zn7a*cH zU;RsE#M;l&`6a`%p&^H1)1F&C=ca(|M?8W*g48li+`qRMuEy!&cS{cu-GK^dZ`UVC zFbTsZ!)oC}zOOJt>oNXQQV6nsR;Vo1O_HZ%BgNzEbLfle&r?|3Dv#E>B;kT%W$^cG zl<@n!3T*F6{YWGP#eU4de)-hzI)?TFQxqWjbiZNQsn4IyV$bwAmPXc>|m%OPQ4w-Z&}(;bfNo~q({bhKq?Gbphsr! zt$^?QrMQ8VAN#Z&&DUqp>`ocFE6IbQbGG3A!D?a^nK%6UdpqIjdxk+du`BvEzmCWq zwnW_aRW!#SoY*al;T5M0=E5gMV;|!R2-{|cdOCx!&bd1Hqj4C|3;9R}M|y~!Tcktj zYKF(yt1%g1U5Dmxl|tX|C2-XVGl^T{dnmr`g!)CrVT}R&c^S- zSe){l;}c)a7e(eU4feI{SK&>50^#;l!KN9tTv<)0-i_U+mBnws%c4_=EBYB z@pn~n3En`Htu(CqyF-G4$c@1UiiPBQdT7S9Dr<1>&)$81$_@y; zZnJk^g-!?_H#CDBy()u_=uAORXy4+X-!ywl#t!S2$cSrw{&5D@I{*(Z#U}g2FzDO| z!Q0o2D{sp^#g>*WWLgo$V^A&BYmCRW#Xn%Dv^x%|A1*G>)Ute|76RRrAN%m=_FbDB zOJ~uA)F<*hr4WaAQcqWK68~f9cyv74Q?mQGv(p_Psva(0IEAx}LARm2J_4JTP_NGC z+1!Op_BL#YJc&F@F@B<005v{d_=a6OIb!0%%hQ>sf@a9*Np(TvWnWkFIQJMdM5h~Hy7vN>ZSujdK6aC+1^4)4#joK>rZ3hW(g=R(&BCJTlpjA< zz~Ap*U_gWhUex&;I!=zpc2^IPH?|7sb5l2HT8H5?3u_@`_E3@KclHLXm9atZ9NZ+{ zImOfSu!UU+X_}l)^Wc>c>`B79u{0+kdYZ^?Oa)e6h2c+HIKqE3@O-5rSV4WtMrEDk zL7+YVCm|b*?wjFHR$pP}=W%fL5yNI%ffelD{)rUD2E*pn>1e>A7Ob`V1>AV6h-OUj z#ut1WA>DNxet0^U4Bws$qKR{06uqzi7xNYrE3F{>@Fz0=ngMrRD;f7+@s_v@p8#)F zRv-oQEZiAN`zH%m;JCLk;^4@WeAeWFBF`emk1LJEkQb*%BD-nV)yR55`Ul33`({Pp z$~Ym>S+s*ItUix&dS!_j^`nh?yayW{R}-J^Dd%UW9fhn9Yb2g?1v=~;4z49DYIw9z z;h*5jWQNV(u>$nIAqc01*TGI(cRZk;e&@d(7kOP3gVp|IY`?Aqrrw?{oV%H6u+j=4 z90{CB1_;nP<|vw=(&S=%g_Dm zgF#EF>{V8EMHFH>ir|5?h;od0GP3Ljw{MKB2ie~n1nKBP6el-@;b4UKm z+%+Pj2`u~KSw^7f(0>z%#`!9^u6YuTh`E7h+g8G1$G77HAC%db5tF!x6UJ}X^AJIY6M zt_ijH4(Nq5Zal1a!%QG*1hl|WH} zj_A-g_O3krD-NyR)Q#WEWPxdbFD{blASc4_@Sh5*VRAad=?;q-B7JN2u6%9R2^TXo zaIZ7%ftNafW`$h%yjCTJ%q;ssxRLYwtH;X3yWqpW=hZmxC|1sYDbZr6lqW&mV z=XCfNsfyyL$F&cq15!?l3P&-Vo?jY?&QqL*7#BfaKpaj=r#KC<=N*sbL)dXMNnWV? z8dDgb&h%0_(-4?{{1b^z2?m)v8R&FK3*MFZ0u*KpLKD@zal=;HJE=Db@5#?4@sJBE z&)I_dXU3tO6GNbM_b1YD*??QP8C6%7} zP_*y}{`a4nxTma~*SqTtqh2yTHJTrS>TlPOi&{K-IJicjOW&J)x%a=%TcJzMLHKY+ z9Y`NKfe*JekwHI?iIgwCg2Q9kJ#yxpK;hGk45tr9dvPa1XOf}hJv9GVho<_*;SzJ& zk-F?8zS`14$|GNL2b{a%8+~u~;Z$vymT3Nb<~fgiQp~Mv3MXFXRMl|Va03JNQ z9yTY~;+2l!WXi)R(S_?1(PUFL-j`E$mHl$Jx70G{wM59@_S!okd|J)ya&))+E z-3*U6q-F~C-eY*&w>BJ)U7JoE8>P^^U9*w$0;b_qr>(;4rKH7U#`JRG&VdkR!SGnz zdspDp$vo#rU7zFaTFoR?$(*;}_5luLGCXe5IgEeZQWgJ#L6&~~u0d|nDSYZq19*Ry z;%@q<9xq$D`uRZanS3Ea;kD3sK3wxZi+ASX+>SP9=sB@kAxGzhbUv|8KUJ zd~o3_Xx`Vr39h{$7dsJOIevs(_ftf!{bbONVGNIt-dz#t_AuUjN8kPfwB00`y`8i( zdG@{#np2t%^&2(OY&(WW^6`miwhDVoT7J2Tq{=er$E65F!%JaDrWqa+@fGAQ%>|_l zcI%;Z?IkGD9S}SWh6T0=nY?Sku_{?mX?+-bJx(D%rtarUBh}EuqLa8ds4a$(h;X3Qj^?eC%F>SpxqKpfs`Q$c&)eQ=v= zGZ7!j;uh)sgCgrf9F&y>^)_}Q#T5r7T}~-=DcrhO;bgaVJ@hWzic$_x-ltk?PvbId zKQEkI&4?0BSw97>uw-0$-P%Vq@ioib_>-#&--k^kV!A7@&yVFIBLc|zYy0?l+x+Oa z_XfT=qZ0Ptaz~kuRmg6ga(L`D9=0~JIW{xK97mXKA}x9YkdxASeCmjlcpZM4(f|8N zcr2HOzbTi%SD#^ms%WOEit@s-*Y(Hby#8O1(G?)|X$+4y1J>gqASI4}{+rWQy$o1` zy(?GEyhOcZ$0XTMPn-eo)M+H~iL?2q?q6V3r2*dl@dvaunc)2Nt7HK;4z(@v!Ya-x zVkLTOX?!FRbRM0;{mU94=b%uK6Tq-(np%!Mc1VeRuO{%PkO|uF>52WKs3%i%D*o3U zNovqN__~qq5+`Yk6|y-?pH>8S=)GhgZx*}O3-YaNaj`Ul+pR5l!!#xFLu(sL6}qRp zkcn|E%?HkKJBN+kI!HA zEKm9A0IKwEtEBur*s1iw>_D35CJY7>B1T`nw%~C#SumpV7%o;%CH8Oj^P{b4mL0|N zS))d{uC|YAcMQwfn!UgWeLske|vnlHKOllvis zZv|NTOcsEekLaoDK}nzKHlrZ!9L4NG~ z%!pz3n{lA1?E<@jS+zK|8z5vz8-84&B+hc0 zZ+YZ+0D2J5@avO%9w*Y9i{jI3`AsV`Kw|@&fxlBP^;u7KA{1(>vJ=eEz=_ zlr^;*Z<@!D)dW`s|T}o8@WV%TGmo_;Ueq2%0VUA4}KaSM&SD zO9PRX3Yn$s^^GEQKUYXrA$w*d*^w1WLWQi-5Jgi_NTG4hbDohH&Uv5rII2GoJfyzi5EF!mLu|kPl86)SGvV0t^EkCWn%?>}gnM392r3mu zXe-qLpI7dL?af!vtG5hNO^1*yf5!1hyUlvmJCc)CgYC;xp!Vf?y!|tpx~DRpcIOZh zlIw)mH!yFj`A(3f?1vFO`JlLH2=Vi&qiv#bf}^+3qxefS9qS`49JgdYQJ=u~=w(db z&+Y3YzOvbg+p=JS=x867$(g?&v`XZN?bp#%6q^r^Y|V_jy7?Y`W5a#2_L409^duej zGme<4hm!d3!Oz@1OHWvyw*|Y$HbCy8J;p~i1>l!W-(csdm1MoY2Np#a!}4dY_|>?I zKJYs&8uzyrJXt2xKVJgv1Z9z+i?8d8L*)cw**UcId<9%*y4u3|d@t_xal?$1YWn79 zir|<00AkvkE}4fbHr*F3JH+2#Qgt^9q<`}BaQUc1WZfdZuE~sz=q-DfalHLSpCjgy z$RT`PTiv=VvS1u|m0~IKY4$dlF>Mkp{8I>P>X!%{L$1=H(TBOTNp7Uy@j#4yng5{qq$pK|A_^cj-i}bT$ z{I{g}tt~QW9@_)XBRtVe_>^{>YG!#srsR5Gz8A{}MZ@tveE-!`)i)mWgU6BX8&dR| zT2B2;XLD+HEpW}ApNId8hye?739ojSgOBSa<4FO$&P#A61uZAm(9oMc+}NXrq|)Y` zM1y(b&kP)0=|zW`J%%kT`_n_u2TM*Cf(rqRZE8ykv+=Jo7T*UkwmR3S)%SOD*cKlcKMhZKMT;ZmQ z9|{x-Kw;ETqGz6hZzg_((%;iW>8E&%sG)5TF{>XSw>fQ18`b#C;EZ_@x+1 z%UdDMBnp4qWy8#%38L>Ed>xIdePw*ZW)7Y9y8PYglR^NJYS0}{Or)tpcX!tsS7N%ylIPT2`pp<{laXw?pWubgnu8I~TLM8zwMp!>RlpfKtx)k!+c)t|dcR1XH? zf9ZLktrCH*>#Jy)YJ_0)emBzRo)V3i^%a`GnZun9KC5(l#bSKO>gdJV{$zHa0H|iS zl7Dy1spZb|RonPFlDAk+jQaCMnc(wc{1P?wSq>lJ)(z=1;0`lDg2zMP*|g=V)% zas#4YE%SqV@*XtDtw3iHtDWzbBriyf79PxoiJxmkqjUHiil`BZV&0y{;RYgm=2c>VR`2TT=PRl ztY{_XG-3mxJ%z6|tHh`CL$>h!Yx{$BWao7cG$<>E64}{!rRWaLJ~dj@r==V64n?8( z74wJ01){|1{4TlQe5vu7+jD6A#7fxMc7nX>%l9vhPdD)1uxgrnBSk=OXpq#e=@`uZ z_Gue(LeHzB@Ej*H5IUV@f8EOvC2h z_mF-tLR4$d&!xYVSW5iwN%UmDV&Inf7>7T<$~x`X5zv z()|d*wb<+A%4a1idh`_z_uC4}j7!jKS`YqtW>~d+H!Ysb>TbwmFdP_z-{xgQnv(K- zkFm1orqT=L$9z!z&=cDCSrc?hts-Mv!X!75^CosEE^nt!@0tYRuJ2%tX%6ba+!oQC1VC$1hXf>b$9`>I< zKk5H9IMw_Urd_L~YsPzXPycdc+pn{dzP6h)!kEiLDbpLg4cMHiED_%$bsl)SIOzi(0?Cn5*yoBE4&CMIzU-sliFKfd>wxb4SpR7;${ZKQDQ zWIuqROiMDk0Im)4!~f4I^0afjR!e>8Dr58bG|1w zZXZLQE+0b$rwZ8ny=7j*|7&)tryrJeMbefqOToB~aPsk$EUmK0fHO?nH|xBNI4*~B z!-_-U@k_pDmwh@j@0>l~9~<^=BIDNbGiQCF47qH>a%3Z#}ZW8dAX^Nsb4 z=(Cba`0nXIDqDlFi+S$a@4bT=OiMLa^_^heh2i8;PdaW-PXXtU2GOsBJeNS}&1n); z?=Hc4u9tb{_lj)!h#V}#U zO>&a;!Ea;pA?^J$3}*g&!c7qZtDCn-8S8^%t-r!f^9}fSfRgyKg%@YA*%k!MBTML3 z4?ES(@v^lwJ$F@s^fUT`gWDCv-?jS)*Jtj>{AMljOXEet@0u}iz7JoseMA{^e-4(# zk1ahA+s6<4Zi=Lvwl%{1=WB^uK3}ty$tSVQUaO)7dEQ)LuaNA^Ka0a6tKj_3xo9{24&CDz3P&R=A-dEX z-Io-C@4FtN|G0;y?`t&9aEY4tvaS&OJq6g9=}9Wu5&MtG0OzZ|c*d}qUVXovQ<2Yv zETa_|_^SmlZWr;qt3hL5eT60O`@%}*C-twEUmLxi|JJ0A+F#rc@RSgF?Ji6i{s|_Y zti)x;GsQJ7Qo^OlvgAV-(+@K(Ne@>_Ms#@64OD?dUmXf*oxJB{$CTIeujZ$ZQ~=@#Cq<(x=yh0$HfaG z>6L?WVDrt19GH@VVOv=L?eBmJf@TVN2f6!gCZdj&JjT0+n@G;w8biO97C^^YgQUxh zul~<7xqFf?`eugFiQ(pg_sLI)K@r1<9%n$qOE=VA$MX1??`7JXClK<8uj|prpOU@z zg6W#vK}4I;wnQ*nl_AZmOYKo8Aj%$Z3<}_H>-_H3e36$^en$y+mf%oFmPd ze2ptKM&Q-Le7a_0rO0aLYLX?LhU&_xpjp2SrFIMw54b;^>#-DxDg$_2H@7YUj;)wX zot%py>sW}J-T>4jiAe*k`Z*TXn7jmE1$Q52R}h}91OjMn>- z!@-EFWHO+f;r9iV%=0;BJNNrw9w<=0FOMF1m}RXFrk3MAgH+rYFk*Q(lTVkz$?jqB zlJRiXKiUuGYu}On=ey85^b_3L8-PO_ny5lYBxk|yE{3IiEf3m08(QWv9ueb;)Jz%; zmMiM$8+9we!<2rc!R2AG`O0U6`FB(xBY^H+D7=_lXmFsy$e4SUD5PFIm8{! zC8w6xVEls=xI8Ws>p%AqTZhGP>kdsMrSqLIzp?_n7M;O!X2ZlCe})UcjE)4+bmsqK zT>vZUnC^K4>&t#}urll-u^-L2?gu}DA!Xt>_M5-Fe~|N8wM_Iqil3!pJoH%}))-2R zzQeV7-;%nE`1-9*y@x;lgi%F#3xO7SMyB-2QuD41_%PlB2mX~6Pd0eVJ$U~Do*mkP z?rLmreHBMOJPfAJm4nFaRUJtqECZ03e}gOfJ4xbX{!Uu3R*?iP;AiQjy_ZCflRqTAUoC7A+EA2OgaeKPf# zQ397!J;@r@qt83!L$UK+OwmuGyHu_T&N}##$9I$@_t4DVwJ7^jM!fo?8)uz%0Zx|h zlg!U;K5H?4r8Tv9sX$&%DZz!+1I634Wrcx>C(#Y6shw_EqTQ&oc>f@~MZQ@mY^Evj zR3iox4rIgD^kqr+Kl8PGp7B21gCgnqu`K6&aVffZD~b==j2Et{-A1$$!tk|HF1UNv z!SgLSIBHNboLsPm=sk<33oMs&vA0N)Xw+#*c2#O<7J7<`X^5Etw|=)gS=Fv5;RM#t zT#b{v?$NcndSo%1m80DFd0Y1IBGJq6H)t?19qw3t#bo~qYEpTZ%QId^3KyQ0cqaUL zvlyo{-VQAdh3@HpL6>D2Z?`Oj5yw=Kl=V=BltyFU$45lQVTI^?9N@(Uf6~7UaXQna zcWf+%2YJi!T2>3J5u7H+L7k3y{ROrd%zy^U@4w$mE`XCQyGK0P51Xt%kQ>r}@sB|| zj3R@`8f2WL1r=bCWCru~cy7aQdl#6xsg648SP4dr8bBsIR+H#cv~_gI;V^#2zNj`4 zM~0+P>h>H??>Y=Y+Hu&TkO_xsZHVEl|M%Z`b`!Qpps%`rfZdvTWYN7yT$T6*;(koQ zE~5&cbW?~mf=q$({Dt#@U?*eMB^u3AkioXxnkf4ZRh?i>l{!S?+F zs9_#JhR@33zXSQi{Bt$#wMv2QIXQTe^bxy8#&E}`P9@CW$e0JYYu9#)w_xdq?b zHo&(H3q(?D_&PnY$ePU6;jyOpQSAS=f$20a>xc?XRY@z$j5Gd{4INu*c>`s}|t9UkFK7Dl^c%^J4z z?)AY}x{1_r@mo>Yv#sR6K52M?ONE(t)?>&)De>Ixid?=^w#dni@3S9`%i&n%WSYos zL{VeCNx=R<%nHqior3$s-HgYS4$j_&y1Qh>_LlBk+7egTmAnt54eNp0Z@_-Ahen-I zAo@1vabk8g9cdbtIO}UB_-MsonPWDLOAkzXk;B(xis?g?VxBWRMT zYP_)F=`J$xMHucFn+roK9C7XBTAGkpA(&;~0k^m3;DQm!(D>Jy92P~>fd`gz-rqGv zC%SoTYLZ$G=JYM0@wW}Q>~wizeLxRodVWFOr(%e+yo8%ymjeyhDJp)?Yp&nN|3Hrg zUG!>M2v_5`oV49NE6FTwpRfdr4&I@26vLpnq6dtbZsi}YD>wX#=<8ElJN!yKllQM6Sw1}04cHZ zoV~`?L;T>F2CwUUeCs6arKW`Zk^v835QVgU?{XrcEwLg z@{#Vxy?Uk+0Lhx%@ZF zGlT=j?-L>84gTZweoPI-AM#9(aL_`qNA5KVj+dolGMMKCo8?n3Hq)tG3^(aCz|OcW z7fl>#WxpG>AnE$Ir0r$M>ONH-(7Um$|_ENx-D5Q?ScJMivf>W zV8X_`RO+FQsBWDmnSLw^`!k-1R^S6s*I{03Hb80&=;;e7_%%RX8PoD+chg@p1`AJ4 zy+R6`f^b;nH%N2WCthrR{yFd+JWpSaKAz*msok$RSO3W%8pz{XCJrt{&(2+qX~#)DJn5#>^l z_x2^zE(GGEmVB_<{*a8YRH7O?zQU?s9uVBV51UW1`B`o&dj7Vi25Scp&%G7s|I-0ufT+Y4UVJ_O2&(GBkMFqI{ zY&m@!Jcs-7Oo6;N(?bvS-yjv>j*({W{czANn`po7 z!a1wb;YYRj7cPwgaHDhSjop9s~-1G94`A|ID!xXm3#> z3*6KsTqd^%>#_W_6SZwuA-4@Dkq4_hQC_+TzW2EXzu3LzKGQBW|2#|t^(QdtUNs0k zd@%lFEWNOy3iO&65rb2axF_Wc2(F|c{#~qO~(_KbnmB74BL1;fboSuxe z5KQ}?Komu?w6`q-wy=!5Z(+^!)6p2Nx9%;hZQg?Q6%FwGWfHkz?MXvwq==qVA*i8?MxJ2GR%Po^CCsj zA$(uH_J?IN$p~2%RRerX|Ahtey;LBtEiArbhBTD_!u=i9d7+PCno3E7k zc%&j{nN=kUV%&*;H&!z*IkN8A6xw>Y6za?Gk#mOvaT(LsG%$U$qH-)dLc-G%otySGjGa?3;TC*o8nz?d0QnNG$b@}j8rAW z>%`!+&}^7}bAZTFna939&#%GVRtn<0rm;fObASvz!Pm9!@yqzCxkl2jE0`YS*U%ia z{UwGy4VQ`1(P(O}y`0n8e^KNa$NMwrJTJzq)^eIP)rfOYRwU*|JPy{|unr%Vd(lTN zqsR~K>v%G}i3(yHxF24vU}VH|CtA5;kptVE4=+lGN~?8bmCae)J(b-_-mSsQ?sw>f z<6#gi&2F68-Z(3)5C&SyL!w6^T3G`)6aF#(BV&y_rwT%b&rF)y`mORWU8 zn^nl6jcO7u@r%owG31sL?KfGKycl>Md)ap@YJAM~giRya=lOe+%aprND8twOq#ehI zNi1LcM9LRE4P&TyemVT?K8MNW(X>wXD|bC?DT!JYiN-I!!0dZAnEI-VmLJ+_T%h*? zcGl-&)Lw*VpWcwp4T(7CKo&GF6yv=&6||w!lyi)gBhAz1NHQyL(^x2;;fgn^%0Y2d z1$ko3&)$vWD^M#?PFy1Un!D0x4)Gu9g#U8Erp0>T`6bO%&#?u5rn%sNmr7#kL#jg8 z{7>K`U^v*T0vH<=f)y=c)MmE~?CJC%wk$hrT-Ha}YUF`m829Ye3!R|G7q__S$T6Gn}q0n_K z6U>w9{uv{R8#sncSrUb_lyjIL&nrqjN7nT_np8{ML?92(@{(A9qf8x3i|!{+E3l6L_WFa za87D8o%FS@u)XmRDeg{1ZMRg&&EJoSb9?E4;DMZ=sZmsv8Y9U?%3h{Ko%U1`8)|c}b_#9`Zl_k0opU;^) zHsIu3FS@Q_6iIGt2W9n3nCnpvvRyw#v!mX4k4$zQXxlC0+%leL%_eTSY64Fj=Y zAbIuH8+Y6*gdt)@P_Qq=sjC2l_e03sZbV1fOc)dK9?KZEe|q}`uE?et>IN@I)8#Gj z{fIkxpQ%n&)W1URX*10Gr6I0g+syrm+Qo9d-OzAo8JxVAOQu}=i*t1{z{X-28F1Vg zU5Bvyl;H(f;_r{)BoAW3)yVG?YLc6jQr0%+RpLZ{{ZS$KMxT7$#P7>47J<;WH5Qlt zX8XeJ6J(v>gyb$9ddC+(e}6{94zRu9qB;4wl<(K=^F&}$n~S}N5cHxFiSMCA%zVLc ztq*VUMrt{=Gcx5qUg}58t>#GX!i6?T5ID^hb=%4zqo{;<8TQh(6#+2(Xf+wHQ;oUy zDd2H_9y#9XDA|h-InKg0S7)E~KpzqFd@lY-(Z8fkXRy4&yK}Qe_doF- zgFnZ5pkn)VTIW7pV5cP}nkV_%oVDyWu4A|Oyvs4%P>XCR%GrY3I~w5pCFc8jj`eFL zX|}sGiU#lG`}Oc+Cy0N|b(Tj^0w+f6kr;L_mSQ)S1;dg>lWy^Sd2i$`=uH&Tmlloi zN9aL5-w8|_77|QJ$6LeSF)s94&>O+?or2FAk=63QY5uC& zdF=`C+mx>}+9x73l@ho#N;Sm_g*y4Zj^~|4kFLw6b zOV#2Bkk3$zd%sGF54yB)ht|zPhiEUFb$ml&)y+MqF@SkneHkLuU-SnG=fq%0G2_fj zFBYjj;WYv#?04SPcAci$y@SchH7xf{PVDSFN~rE|g3R0yhW+Q{!XxG%{GqX$Mt7A9 zEb>&z?n!KC9-9og{qGUAj%eDNv7CD?pCIZ;;x(|hCf&gMudma$mDPf<3;y@82|*Xh~Hxm@jvtz^y6v)DPW8fHA*f(}i0 z=#dfOaDA2<86CuKQa1|0X3GYQyQ3-oo;pbI@R|Ya-cyJpmjZMjxPg6=uhR|1A2{p7 z5yX_i$ zP3}Dh5lmB1re6m0KNpgS#eZ?j^bC-49Zi&G@jJEANj3{LX^9QZb%ee5ZoABM{&&JW6p0rI>oveG547+ss8edz=a##I&sFhm)nAg>jj~lA-AiJyX z?-G#V^^TJMyD!ub?H75{r<1(kN;}IkcquF1w6?FX^L-HnaegSuXZ!V!pTs`2hemBS z5FEZ6foi>Bba|Kz$ar`XymI9EeGx=i$vP= zG2>dMF^@k7%4ZH{47`cK->*~4+tZnjB!!GzElY1lXF&5PFI@hiiQX9;!$~FOGTq%4 zG&u&|x`a1U^?D+C zZOJ?gm*qfbO@`?BWxn=TI)%aug$49OEW?z3-@yIvuT!njq1-V0n`BE;5LzzG1D!2T zaT3$Qth)bBFvNK&sZUKuxtZ_4l3HP^`EYSR@`O`U+zB$xd{*_c8cPyC>NkzFnN4z+ zUL#868N;x7xm(w(%ac_B0G;Wq}D7AO%&4L{IEU{$@F?-W28t>yf#ssG?lhb zEd!tXkC^9nAO`3cKuN-L5`A8Y<}l3pjCel^p^0uDc$RBz3WuQPeUdk!(99Oo;;rez z#{ zB~D@bbf5JOMDcPMO5J69ciau!GN^{`GOQ3pZ5~3JIm>dKqf`Y=(Ircge|9{CvJ5`7#9d zb;p}4%OJ9&lCS_jjmxUPfcoED^t^*GOoZgb z0KWE{T@*>);5qnveLHkoegxZzuDC|20>->=Al9@RW7oX{ql|Kl>+PmL&7wK47bfIW zqoYLAx9y`5I@sKyqjq}2Rbe%FvEKb}uC846m-s^ubv$VxxOdi@w2w%^&J~|Pkn4l( zvzuw{yF*;%wzDFc++4qamJVxz{&zGS!uXdH4SFEoxsS)ZM2|Eo>MK9hagc55ge5wn`0-FLA$2Xf{SGkm=#RmcL1i1 zFMuc4d@)i#l737*FDUP1{=tk-a&<#4l(*R7TBdD@zjBs4cqEmMqOXgoASS(r&wfq~Ty4K6utg{Cax_mwi~kIA7j0GkQ~E%vpId!#D=ppj`t(JDIuN1T_8%c`(WaBgSWZ0$} zMeN1VwEXdME?K8p)c+B`Uz_%n;^z$o)b)uz_ab~S5reJ-H@n&^M`}7;nrY&xC7lc~9>J-Bx7sZwDN|iRo(u_fan-g^60W&U+u0VJfU+B>_Ysp`)3}gEE!5FZ=C=OydP_-%Wcyyql62+u-X{6vRomJ9iA|^mU&rg z_@Sq`0GQ|sLsEOFikpF8WL7lOw1v~lO0qDzyc2);_ZO?YSuQkN!+iVIQn1PT6J#+z z$PA-q+E{;xJ2LZvC~N;8iDpn}aGumJ(xI)%MXUUX=-qHL)AynqHK zHo+QmFJjI1=rK`wFyUwnMp#r)=~?dt3r4OZev#=IZt@Ns#_zy`zm>$p3votM5y+NZOe?ulujkaHGa_idx4&*izg z)B$kgCcj5(CK!+#52jMZqB3aJ4I|s@18|910a$nVqHI+-RleaMnA^>=(k}DwK<8i= z4FA(Z8}44>#_7j_9^-r-@2ZC-N1u?$)L^T72nrE8A7aH=}P>j`fCm(H}hO1^SsNIF{t`Fjeb7m1FClG zARw9dm|`bIETFOU^1Y*+YW`kw>Vku0wzpdL2=51eqK!IraQF8plIzI757YFwq2{y! z;{C=lg3}wEAbV*cDw+V?CohODK~%q#399LFm}y;2Ylm&%rjL>*x&h13VtWhB>wZA` zY}25LD|11w+y-R=RK&JAwcOK9cVX*jcQn3L2LG+CC2p~Qv7uikd^DLvmKCyFZ&*3Y znbOBiagV7h9Z7!GMZnDa{kkV1RZ$gKu7mQT3DIFdg5l?N+#u|2mwLV~Nuk7 zrOY8=SqHILQ-hS{-Cr8@1C8o?=%ks?IJw-V3-uC#~# z@L=yib}Tkrh@=*8K2fcGix0MafaG^R zhHNtWGUIz6$b>YxKr9GsromD#xxZF*U@?QA2Lk+zq3}fjb~0~6=yQ>rIdUDZ4=#Zz z_!RFqRO`s|RhE|4!i;tk>OQ^& zc2+jv{tcyc*A7|X(j%ocYgvBt*-9OrilK5n$b zzV@{s<9M6Ao#u|m2A6`v`v*AwKqS@6c`165eu_s@mn zQyCw>r<+RYT;c|&CW61bExsM_16tnLL?O3ybYc7-UDPv$Xb zE64%ILVuC|AwJ6^_;)NW3XP;o`?kRAu0|YqRa%@kLQA;B)rHvhhN3*1L)ugVFmgKc z@Ady7Fqt`#;e^?EWo|NTu0`^*IGT2rE$0Gu3@g+^a47iRlWy-W_AT@PaU&HX40~ zM{KSR+r#5;FWj#|t#lz?Q2XH|RE@nvUzYfh%KPHXyZJ!YSQ2 zGl-~I@H_jptB0}rsj~P)Ts7CK^8jSVyJLN18C-PwNrcn8(cCu^R^R@NyLx2A!vd1H zSxVE0M%@L;Jdki}HaaCgrs-uP$zsOw@VMuXVY2yPe`^HMyvf)5iK5Hszvc#2jng3x zSCtHONF{A+2C9gi}iY$uu02>oTc`d+*S=4TOTr>VI&=P zJRhFx?1A+dpJJdmrp~yoVH}CJYO6P6^p@lkpY-Lxx${`NhRtX@WEj{!JJhY5}TW18^7PEolCAA>FI_H=(538|VE_pvQt%hyr#RlhBz_ zIQDW51gEY;(}z;xoem?onvYU&Y&E~*o7hT`AEJeH^~6?q7ut-SZ%b&=1XZ$ISW?BjxEg#|%yGXjB_oc}6qbu=cn&p1G(jY`e0|K7%_?|Yy4a`!e(qQJncrhiC zjCdD-M;r^_)}9A=z%raFjdT#GB_m0grbNrtbHOLa1z)PQ($_8Lxdms$5IM#cAp;E^$)`*S99TR`Xe0kpouC^{>i)mr;~`5Y#eHm3=^vu z@9R%AO;cRKO&+8TE6h&euD8`NPVWsqGJHY}?G-uWWY(Wt`FWsx(@C77;7c2Obck7x zGRcc{!AZx;LCw|KUWTrDO>q{VLS6GF;|JFCzU=!o0BeC zcElSMVhX{nbscVtmlAuIwiugiya{{87h=H_fJN)#$nm#`nwZHlI}#8JnVv3w1Gk9w zClh>^;qFT<&^#uXjF_fD%O~Z+ntp-scm%^?9+a`Su7SL*=*BFAELb%EEB3!GE3U8; zaVnx|M7!vMBztRY_)+wKtt?JW(G)tKjfE!<`F%e&V-(T6rz-KHd^5=vwa<7^y%KHW z6ttY2Qsd`=iF+>N{Fe;09QI2pk{&1!h@Yz>Bns`p&U1o~a>2lrwTAKFkU6AIZ;*1iYl14G*X0;rV~>!*f&4 z_O2$mvtTy9XlMh)S*x*km=7%r8bTZmu3-IyW~y~Mo}03)4sN`@f&q`p!SVQevRXQX zmiIM>X`_0`wNbUWT9^t8Mz1D&Z5^@dRwX=4UWWR1cjz~5@cCjj@<>Yu{9na zIYm-UxxR2&K8So|`epSWpP<(u73cY?h&S8cCRp6t9zgwmNj^%wova zT+F=7cwUX`vsd`ZIh>ZhTrF7tBadvhlchu0TW#EtiVt*D#bw=jTv}!afYuf~oznnY zoOXg#CjSmh_!*DwXCmo^p8MQP*(;=B;dP8>ULW(G_@Jrh8`?2(nJ8t63DFO;Q`Aoc4O(Ibtmu=;B}N?S)#6_U#RIOtC(n%~ zxR?eu+FD?i5F^o^Y%aGXE9Ot5hjPmy<@ZzK?-PLj#|yx@DG+b(4yRW89R%I;Q^;*Q zC2DXl7k03>eA%KF`gqQHt|TuNI`j8Q=7DIIw@^RDiw=3w1b&5Q(e3wMs-dJvCS7U9 z$hf~$y0d}vi89C8rg!O=0h|8V*BUCp{lIr!Y_V zKGR|64t_^4^Gw7gCn9O}AVseD&M1N_`8VP5cZP|r^`_CAwTZ2YCUJ6g!L@tJp^$l` z$7J&O|M|O#xSr`^oNae=iQDanN7)(4j!?eE2Ll@8=qFJo><^nvw3hHYg0*c3%>0kv z3vx#%5O(gzx!J7OClZ`FtC~*Rxq)ks9z?dTUMA5;$FcWz@)`~L&?6TP9Xf|qW=i5& z;gy{Gt*3BSou3&7b}3*p?udE@>7Aw0PD`X;qfQeX}P90S^uOM1MbL)8{bF^hh|w2TUma7m~_7y z;^)NSxWG(U<#&ac+S=n$)f%|e7J^55BdGd+`LN^t5z_Z*1YXbo0w(4z=%Q0aPbZrj zmorVfbaO6#OhFjGKZ87eo`91K|9R~eVg#1cNQ))h4Xt6sM|m~|=e5BF!~NJdA(T$r zKaMPEa>tbnlh1F9=PEOsVN%c)?C(_$=PI(ud+iV^QA~xush)B?=Z6_7=&A)?vAI z#Q^;{tX9_)H@)lR)T`El8`G`)5Tcz%e4O~49Q|x zw82I0K)-INQQ|o~`>l_IXI227nwYq2ku=&iR+N9+gSd`L!{c|-;MUs9IOuUL4KbAFHa3j{^8-BI`02!UVw^dR-CiqT zy7Dt3x0=TpRQ3ho^c~@}-OoWVH8PEe!2LQC9o{4U*fcvE8C=TXFMMGTgl$^rA9_o7jU|DT^SD+XUpd_-MW zGB3D&zwkgq4;|NMsL-hCD$!wh!m{pMFkNyA8@i+E=BTHF8*OvRf_(n1m~gw8yseC; z*Hl+<@j>&UT$cGTdslo9zG$xU>M%0x#;emIg2NZie>&$cJl>1QO^qv=jx zwA72Gxq0b;-qXopUH*1pIORDkox$Uc3K2g#FshQyDEXMqpDjKfD=7)PK#Pi}Z z2{-|VXXPo~=Nqp}}73ZJv625l1N$>>u{==~Hp+M|iNnp3tAM#SM z2iJVgf?H$`36A1-4W;G!xJtv9K6Owc4;(LIlZLW5Ymuh#;+;>Ram^oBY2^cFGnPCo zRz(&6Zg6sNK3T#N~x0k*m5R!5MZi9)ka(IMhzegiIqhvVA)LZVZ}jPbOUC zv4vvWD|ld36+M)1Zd}wfh;--Wq5~jUa@j=vGutn2WW&$L1-MnKm|onukoz%Z1UdY4 zHm>;E4&Eo$u-o2WeZmp-X#-*b?DZpVsJ57f|`>w#k>A? za)DmEVLr=L+8a>~?B&uSw zWR~c+X$jUW(iESU(GgD1aE6Di0a$uC51uvya;GC{KeGp1QMo&ru5umCnIBQLye}U8 z7(<_rTqJVtcMc~rPa$t7C1GRBax##432I>u{E%0Jdvg3-;SfEBl)YR;YfrX;UmJ@e zafqbybJMt^&4GkF$-fWv+Q*3F-E>^}_#HUe1%kJk9sUfe1+v4BwA8wxwnHf#*d2lz zf5Yg}_s>P+Hrygp#-w3lOd5Px>xPk5wRHGsX->L+EFALTXAC*JeZ+IYbehXNG1@k~ zAW2L+@Nd7^Ul4+=$HS>ngM(nbQ#u*!twe1Ge}mdZ9{BxjGdIyx2&Sf=wd znM!!S+k*^Q8HOgzbEf;9kjVAT!4!{VQ0r4m1~o*}brV-`>nAJ&!2$l(P&txd$iqmg zwL_5$Wi#}gL%I@gUiE{_XSdXo9xfe4#weHL{PGdv^M^+WlS;IRp&dUz{3`Z_T*lY^ zcQ^bykbTarNIIcwH@B$x1Sw16-+}x4yfMG(Ic=Zz0nQbj#n#W!lpZPI_GHf>2Q+ye zZ}q;dcwuBSEqGIIyr$qKjMC%h3VUl2IlU7xBR`Yz?kU=IR#5A+>o{W_RpLLF-!HN| zpAl|{2Cb#JuxamBjMr+WcIL?WzKetX()_M*z4s4^tLw%`BnzBGWtcWoPWdaShAPQQyw>DWMqvbVyD7QvCcE_h}Whw5#a@Z^s>S=+}R zO~=%Lf9Gl9w3mM?BE4qeqepjX%jkZ_YNOOie4lUlq6Hy+#250tfXx-3vY~BJA>Ows zqyv;pIFB)-NyP8j_-tPXc&^@zFD`g7tW|>y`g9B9s+wu;>IBZ&N{XxqxSH;|NXbWpT->S{xyj2Ky#&B@Z1O+4re}AITeVL^9)7Z}EaL-&M#lO+V~e@Ex|6 zTHqZsO>x!mje;$~6dP`{S>i-r@bZczm-SPy+9n}?z)O@jkAF9k zCf*~Lf9TK$<4ZtZWPx4NG{q-1yEvB_$Kg>t|8D$U3OF$!oQ^uSMlkMiC5a1`rLZLn zciW;*b-hd4YRua9kG!;iauX@=~uhE+{h!(h{{z9ywuc5_U!b72?Y-L z>s})XjCIBm=51KEz$?AQ#sefRvoU*a4v{(Rg!Y{sH2aen=U_F9$d8VLZEIL2W6K3F zS*l6ZwziVL!LMPD9?NqwKlX+SXSDs~Orj->~O04sw;6)3M zd$ATqeJK`VPJ`+GEMfXy{_11g zy@Bg6cb^Dz6j^6NrqL^E6P87uuUHD=|Gb2rr40WwIQQ-k`g%-!J69dvDA`@j4D_=4NegD`6A|Q>L3#Xc6MV+Mni^G%QY(=?ne>{401r!&ipyBUgQo%Y~ zTwXfUKXt!(l>yVi-(454PWVa8w@biBd(oSS6Z1hgzs#k3TyB$;g_0P=u4o(ME!HO@x1}L-mAC4RJlS2TkMT1u1WL^IHGQM9HU-bX(|f zB3RfVZco^7_~b3Z8LvwR zv8Hvh;G?1jziFZ;xx{cL_h==tGRed>>|Q8&$#6!(74~;Hq0GSsBB9}n>U}TiZWS)w zxqm09NU#iVX$k4PXpRkA`lxJ-JU20P3Yj7h;mqzTU6`Y7K(>4ZU>BcG&arzcmr01jR@b~2M{g-6TMGKVw+DSGT`GZN2h@W)3M4-#4aLS(* zn;!Sd8|M0F!4GQp_!UAB;U2Rn$x=AT_pcKD4sCWqv>jsp$Bget)CreZ>4sBEGm3 zK$p#EBG=`H(sk^2^V;dj{2mjwH=*|o^&V9anYI_W_iG!~-QB{|=-vdkJBzXN3ENM6 zYewX4MLy*JM!rLZ2a)ts>{xEw-dW(hZU#zf{w8I1Hu&4sjix0igUo@?$Zt{>#J^VN zYrdNSJ_~Jy`vO|^airK!gdtB=-eL0HNLu80j1%m<4W33;*nPL1Tz2=xbEl(d(skA~ z?Y;u|gI+={)cWQH)Ia;3o>pnsFB;A~C7dYR8@K!|tkFdLsb0kH+#JlC&_e4b?c}!K zX5Qm78!%n-8#zBa4f=0Qq;V@N$orkP7#}VnSoN!vn{zyutYTfP|9>|bacl^__}PyV z+gR7ogI?w-lN8K9Nx8FGtHJV&=$29JU533bY$NjWXyC2wAU$WKT()e(mCwWk9-)6Y!@GyTQs9n`RduA}z%p!L{mB!hZOA{L5g_50 zfF|2mpS+U`#6G=<-}F0JXNEPb*c2i3QG8U^!+uE*YTi9efB1%JAmLvw+)Q^2tb)^z zn5Uw*m}Kmq0Ve*s7-amDXbpJd?rXhN?QAl)UXA_xHX=@9R3eW9KeB1o@LS~f(Gi#+ z(}gc(a>$5lM_SZ(opM8|y*NIpnXoHfi^bgGpIpQ08U}?n@U^7eO1T zT9pK=`us5?;{UrpQTX~mI2E(H&bx~>uqH%?+R9fE=h{b@R`Z4GUb@MhN$MhDfhSRN z6Vp11>)_yL54t40mxPUeh9}#qXy}%J)UDIB;qm%7lqq2Tno4nUbcaaa@X}7g*6chQe=RYH5SRA|BEe*-Ef}*%uryr6Q>BROWvk zrw$5pM3`_eJdsG#B;-HOC-0=+v$ujs>Xvtm)9$$q^#`p`o^7S(9QDEbTqIpKCWDx~ z(TDg35w9Rd<~Vs#FKwC8tiSO(yA%G_;6FV=OsBsC?|q2BSS~&qbCLI`g^qm6FyZ$k zct2jGZ=C&}4*D|k^r>PcsU3C)V^|02-@`@R(4kLueet6 z5XbsBvi$W_XjkmQjc#IsjnRL&VP?nJ-=;|4P&%fMLF?S<@Ih*RK1k>$M)I64;>M&II)gKyec2#L(NEPxO#c|wA*ZBJwkNLT+o?I z1U0q7&VhjTE%0%`fYz@1NhaRQ#<%R>iJzLoeKd}MpCf|tlt~rYe#95Acs{4W&)j*( zAKZl_A^CV}=6j-k!wxMM3=zD)_JEU`mr7=yw!ppPy2ylFHx3Z- z-$Hspp`GB<6!`MdA19VolktC}ake=dpeVe~`&!!o=e%WT?5ryCL-`9SJ}$an%1hg! z$k>xc9Ax{b+7Z~(R7D+51f)J6xfI%!<8Wte3DH#O(d?@c<|&l3a-eMrq7uvO>!{@8`i6RHZe_%UW>0}3mFtBX=`hFy|DcI< zTucSw?`NNBu7mK6_3%HeEN#+B0T(O7ky{?_g_Gp@qayi~wr$?}NOs5b#2v&{2x*=s` z`^Hu1^TVB*iA(C&jGqUM4x+aeRYT@$S~Op>A~~e(lA%=9@bhm6Qgc5d~2FVKPX$1g&m{OV@4P5 zaLgeqt^R{+l!rlCI4wDx>D$J<3_%}g50j)1v`UG$Ts69%8YO5yUcki{ z$bkQUdxaS*bE1XuOfxxdC5P4&z?BZpSdLDq#gt`V}kmd#_h_h3?f_wArA8%*f{9-skfLgL)JBH!{=U zO|Cz7HB^(;HnCXc7EU+o-QX$Zw8EbSp?Z`Ba-`13jG_28>8^;zbg9CGayyw z)e1=X5{tf`EFU^vhIlR!VTeR?DlV4xr@P7;$i6MUFugYnmnK#a>y=*UU7toLE2Z+z z>^23lxMCa=#d?RdPGGaUjKI7;oYT8!PZA=pqWv}2zf{dM=BP-Tyi|&ND5(i9iE8*w z>^IR~Y=_fdyVCVyli{OmJ&LUxE!bl=n$LIF1f|Y9!ky54p10UL@MM9F|7N~*N-=3l zOG2xRe3Dq3k5k-P2g|nO92b2T%p|PPytbW)&s`5abzXR=iFK&&x5D<)cA9akTL0vX zzhrn(jj$&{`C2~6eFY(&d^`F9r%rF7_n$GX!*V+F46hgVe~ydIhWm>0^uYB>vQUR* zlFJ>0`bKBta4gL1$6?8AQ{zn!PW{qPuY@IX16f-j^RTtBk4Q((01w_`UZ%KFFkMj` zS`LVKNa71kko-GN__p$()dSy!-KTm1Q$Vb?7vuEB1e4AGa6TSqU>570{J(bU9bkYj z4BTnrbQ{wATpq$MCSc^ABH}j811|YpMDZ^jWb4v5$YU6*%e2bHte>MxzT2zK2pN2PouazmTpv0DnRXPyMvl)2FKSx4A2|3^a(hAp~>7w$C^ zuawznc`T1=&$A{vonvv!oi2PLmrF*iJ_qetH?i+T8}VcrxL>nUY59kAGH$*)xO)5G z_>nbaV%8BiKc?$Ko=yIzjvPeu5U#BMK>C(mi3?s)LBx5jB7CJRpUHTae9-jIU|Pw{Q}0W)W8#*s2@(>B)aj|9(M%4q!oYU71BQQUBo7|E#&4?O^le9M`p!eakdTs% zZ7R8>?Mx5`H1yKkgkfB?$4ZuijumF8*Zy;d+TmK%c1#CJl?I59@kh^})kJ+{JnDOd zQ?$In3-axPlP=@vjIL@@ye$(oSwGK2OUX^2o4eUO%p>wTZljqJX&*p`HoAHJYg=L$K!WIy0q z!*Fp~1zCOm80=zMri)b>1n?|Aej+W9FL=h0tFA=OPlOL2dJ0fJKav_Bmf|FTYC_9< zHKC4?wcHNZes!TYmQ8|fo%J~J<0ygR_|g1{9SdPe*Bzl2T6fzTD_BQm{Kw7w#pn8Ka^GsN<41oZIuQAbZ&wrOvdFzygW{lc)DQn`uOcfFv|xLQ2rGWS@xp-r?$c0fmNEbP70`LwWVB&gvEC8( zcN*XbXXZzs`~ET#@pS{f9_K*~S4rxh*}N2Teams^A0*vrtuX3J3ex8##QJ$ME<6)S zO{(O%H5(Uzc$Nq^R<%upO_M|%Bi>UQ=Wp*q{b?)*=9Y~8tbg+4taDtsoduMyzA1cX zDY-HSLTyD@VGz6*!<`0cf0_Ns$m z^M>c?de?sneHyvFiEtoVjsDJWB=>$_!Y~DC!Pn`ZIF+r>i6PtF-n*=kDCDuul60nH zbQ$y3y%WPTLx)}UTLaKEwvrssEXKz+ zk@UyK0M2TX4;*^zgw|cm2mU4w6aGu3T?t##l@!mxYp*E$ucL&R)ZE1(v7f2I9yzYq zOP_3mT995T2Ku_@uwvs{dZdVHLF&agg}uWrdzr({TM+|-%ph#>sv;itPjTDkaQd;u zji+Gj0&61jQQ!7G307y>bEg67VByR)PcI~uvqkqva1ZM#yv{a@p^oUvhJ(ABNZ&ZD znuxD8!>P}-xb!*u!{EnTc1LZ=CAP2E62Dv#f6(6U1D}p+(RYtKNQeUktu%i;&VD=Q z+)u`J|g```{3tfLh5&D#L;Y-6Ep}$MP(;hn+fB5lsGygHP z6WzKb6q6`mT~?(y>{%rB?>x@MYCC}3V@n+Iv7NlD4`JLSlD6K?AO@q`aFf+2foak_ zep-eR^c9M*V&yj*)G=+NgWIe02Ng$w+OS%5zeY%tSt%sTA{q=75j56-uU6~PyM^_K zsDFT&2NYwW5=oY~{AGXK6 zceM$e+G~x=9a@Ok_04#d`5_&OMnPfUNC-OVhg+?yh^CJ=I5>^Nq~rZWo&N~MdmL!= z#3}G^=w(pa=8g$p>xhKW7F0UVZj*C1L_>2rD8wb8dv+123-^X^7cSz6^_}F_?l^pS zHHaFC6_F7$`><}-AU(T4nXfJ90^eswU?JN~`>|^)PMYIE7oU^VXOj)Et-Txzw^0&* zwF4^mq~NlQ5|Xnn4ewlyq+TNxI0IcRs2$Wna`PwoJo`2(-twWFq$fjd^Z%3dG|Zco^`L+b}~PiaU+p3D?(#IIBlN2gSS9;D7sq?rw2!r zllU2ps8B2^s5j5%HcXuaS9JDb!tBq)ck^xZx0eyDpR2^raL6XxnWka?zLK2EF2y}J zBk4E40B+U@w!UpH;v1dQ5^;Hdz4>23>DV}G^sky^vL4jU^Iy@KElasoD~7?wuoJ>8 z>ZG-4_?KZtoKG;+(@}=wizBIRo)mX~feswHp@x%9e-rr&_p#NUbvuk!gu?DF z+@LU8U~W5_KlisD@IKxVX3&~5_TT{Px1VuqDt{5{YH|CLgqt)9h(>-HZV8H{*Hq28 zVd{=>GsO~JS9OqYN+w`f&Q+eJ2aftMthf6>DzEJpwm+$>`hfSDF=l~i0hUW z6Uze)m^7?am`OP`b`ES>yk58=lC`1&o?euviASr5&m$+C$$C-V^&^+C;twf(=79X9 zCbE3uSo~1)4@2FG$xOvQ+%@7K)l5#{%17>naSUf}#*4%x@da6$euf8r2++mcETHH>IOOdY}X}LtNhG5B+NGhItj%yul z1-@%;V#wV#GAzmmhc>^aTdERC&f)8*-xN*D8eVfRM{2|2{UZD+*?$~o-uO!`eroeJ zHRuzU*t1CNrvX_V9nZ)7L(WjggRW)ObDkrr2 z{h7YJc9+|Kzn0vsG8ew*9q#_HvU!UMUyE}3UxMwxNU>6vM)gvp(>FJNqNj8p(b;t1LKD+`k z&Ba)@Jd;fOau(}P4-u%lJ>q8Pgpg@-Eb+y{PSV?4j!t!vw6Rr+tGuiWFRRtCY3Lv3 zp>{<5L1!xOtq9xut1^Zm#q_Rc0^t#^;v;Vfz-IJ>HpHGnm>)sk6 z=P8~riLT!9gKp$6;@=ok0UswIR;?^1Q-?HRMM*2YTDFV3)x|Js?|NZwu2-fC?)J%3 zo!Ql-+t3;BB=pjdEadL#{v)Seh`7-7#Id+;b3catEhc*LdqI1%wQ%R?{Fm*h9_LPL zHAchc#nOZFxZ!dB__`(S@b!$Kf%?KQli+#@99u)S_DjyoTKblizMa zU1g%`E`0oqaiMG*@^kxKwuvLcrKMN4;*h!Wf^RYhIJKpZ;irZOqrzt=V$lYXTlB?8fVg`J~_uMPSq3d9k1#iP@q88T z%#EauJtN4Z>zS~iJQHU+6_D=Cx7atdjUJLc&IwZD(ly+E5aW^)DaTE5mIYwT;Le z5WV}%le`ae=C7lFRDKa%{VFUCiKKz|bGftyZ$SBU5b9tRd$$TlPlij&H@Wj>9QB5b zihTUXwi_yjyCLherOW5u2cC7;8h;Io^EBUuck=rS>q z29bpHRi~oi!oO_H`ISr55_3>z&S=5O=1E-D;hkja`dFcd?a<3`sCueJO*A`+rQ24_ zuUjvXbavvcFT z{71vYr6;iIc{lmDcPp+`kQeN5Qs+;zr}*IiKK4O|QLIN%d29@AzG0o})3FowB*kKI zMG47^)h5eFiuh9W?e{1a^Mq>HHL`9WiZ_{lwN<{58>$%w;nzjDwB7y@W?8?YQn#ad zYBz5{Zb31cto)S2p^RRlkNBkPS26L{Vd=XXo3f`bq52)!uY=}S;Cf^887942p@&G0~7 zFMZFO%0KEp6are4@WQeJqCK+)ce3}&qe*7m>(?&Oy3Z0*4t9`hJuX-t?@YI@3MR<` zreOTa3mZ4q5wA@;xZ$fOeYxF5KjfJbNVn8ryaORWhA7jM@SPr+w}@{rx)zQP0-n29 zOf2MGF`jjH`TiKjjSbO+cjbn{zT5*#nxJW&0yV6wCQ@v_#YFxaebFf3mgh@=grkU4 z$!;Hqb8K?yl@psu^dlMEvg034a4IGT=DK29x-;F}vWZKyJPhiF%-h%9LQ?2nT$<}n zPn{eMuNTO}lihw8{IZJd>RJY?dE+oWp`WPsJi#O99B5cS>j?>WMJd)LwN=WI`yy@) zxw&q_{O_%peV9<`PA`qQL+th~gyh``xF)oS+;jH>Fu8!`gB@h%>?90P4Ww4gL(=T$ zibn;`^n_A0*Y4yA((@wl!$28%nYIn2LPY$^&A%6(|4GK;QKckeY9`y*Vjch&1x|e9 zQjqIhBHW>vcF6~q2fU=8ax|f#bq1Ue*kR0pW-=i}9_PO3#&ovRt*DTRJJ|20^RDyU zsG!?W`|Sp94Pw2%|M}wl#AupT8%sJ&yYX?fvf$5w>3qj)%VCI;2)hbKpF^F@AJlX} zlQ(33En3&Jn@)8kkurG?_h=@ngcgv6FW%$U-7Qqb<0#jB_f2~8@;=d?xF8!QC8*JC z*2m&~?Iz>!Lj-%IsyNj#S!A7@6K>9KB#uUvtQ#<#Zj#u^JFhpA-5SHGo_jet;b@7& z{yNk27dtppdsS#x+KWG|Ka=?#OVG~4gRY%31ctA>jd{&O1*@W^_$N-bk`pW!{C^y~ zJhc}8lt$8(m!5Lp+n>TR*7yB?Jy|x;74N=trV$^M(vNPkh9F)Pwhb#~UG>Zp_`Z{l z9xB5n{@uwiNObFoU2z5T&b8E_wvXKSRD&~KGQFrUmm6o745y5O(6p?I)VRCiwPa_i z$h*ojxZ(>vY}eRfOBNZp=7~#czS4$e_c-O;F4A+{T$uNn_v{0NR(nuQxjORUQ8c`| zV2{^cHj;&28MtnIBrWYuNZ%3UiW$t8>uXWRJ>44%&EK<8PBD*|ecVI#mc_v7p<8T7cL^CQv7Gb{3_+#3exmdz2X|Zh)33d(dq*u3wH`!LDZN6j%qkrA zYzf1AgB3)l!WxRc730_2ndIi4Q#ko+FTFb2nbU2KWtnhGJbJd1WF^$0Npd9put=Ia z>Y@*kr$wA<&%TE^bh-p{a>ob>P4O$VE%8Z7fBB>jX6eKPoszAw?@hYf20yD^AEbD2h@-H4G*)l~1t z7VdrdBFI!(FZ90`xo_a8+Xy=~0!(?OwUm z&UrJb-6@Ng$Na;)cZ-SVgyRstK!i~m&XeKVIuS1IdAu3T9*!1#3AN+xuU!tqB}KaQ z!VynVw!!rait3WgsGU(md(^I=2UED(U5@a@~7<_0eF>!+EG z0ZfaVggeqd;)8<)MDFc7Z1aw!sjtp+AFtTJ{mL6Sklse3<9xAUW)yvL^c4wJ`+~o% zm{)3pDu0(cAB;_WaMm8iUo6g}^palcBr}iq<3l}OYKWxgH;yD3({kYOlT17xRX{Y8 zb8xO?3spFKl+*G`PB-F2T+3*DA*5)|pw$x@W?I^!or#1XKe~onmCX1h+q@ec+(@>4 zt;WyI;dIE_oxImSN8xqN;Z&LRL%R60+$i(C=Vt8S7CO#^@f~}FTx;2#rD(?93T+g` zVgJrgWLK65mppyzu{M_VfZch@MT-T4=@2Je$@=pvcT>E}bf>>NwxwTw!+K7pi*V^f zs3-RL_Ru31vRt;oev&FBy8BjM@Py|_*3l^rzlfAOdy8T3xq74WxW}yD^_NT#1|?LH zS>vNHjb#7_yxn=ecb~w{F$HK~mqmIXcw=-}FAb2j<4T`@A&*a+V@Yu*S!Y-W_ar^( zj$`ci+CK(vAF&tu^olmT!>0L>^pQ?tx(qKKqHD5IXI38B)O(Ojc8?WinU^-iLPx9? zeQMQ7UbyE&b^v?V-&RY^PG{hf#Bka>=N4~^(h!V)I*xXT)soljT@ST7nf88}+q6;^ zZZaOF*4<5%`ZREJZaB>-9|2R|yu&WWqw2SZa1lHoylEFnl?|_@X3RPSNf3)slS|17 zmYe4*{-6ilW^mhQH{gnCFX)8ipTw*99fmS(XY;*6F6KuBh;0kQd5bE^8I}P&#y+du z9}&Fi1-9T?SB!V;Gs(!-Byxsti4SkEo35uG>%T@)Cv$1;Q;t4-Zd4WK5KFY&aMLmu znyo(xipx9jz~&)>tPw-`n`PF4*EP{iH!6N9er09R)<9t{y|%7|!oL!6g_ygy>L9^!wUDZcmQF2D5NFQ=bxx&8---T})7CGmSs^ z^(dUW!rstl)sem(%kXuNJAG#3q_6x!4N`JNJnFm0R2u2`ldj6q=Bs>dfX_>iZ9xUss^Hkfj1y2qgEm$zcj<+F2 zA5_z1gc|sB&!-3)_B8*4G8~Y*3x@aIgt^7M*#TIzDUV9(B#>vpdSGanfE;TuD@fgs zHTu$m(f}jw^ogf%*Y zdh&jf)vQ-`vyltED{+8ZduSe9^c3BIq1rZh>F+;!+a-WlpHadeCwnk&Q6W*^nvG^m zLny5|&jqfrg(oj>pmAOsv3kVr+@0*r;^j*seX|LzWMu_WeiQj&mP|J@^uhFFHRPN5 zWmG=(na+JUmse-sgbp1n*K=(oDU!&CovxYqCcl9EW^dVzi7k}3nRz}>lk~KXpF&Pm zHSYr~w3wNlm@UJ+e+fFy9xa> zBI$pEr(8sL2z>nDh*3iuiDps;o(xT;cgAi@cUfQu#SCj)6ibQTS06MS{6xi$$Z=L$ zN63=I8d&~qko;DE4BM`(qkaj$NcpxVe8+CgvwQP6qp<{}2LgpWD(ZPOu3`SeliBXP zmP=2e@mD@}dS(&-Ft)QK&)(TT+~sB){35?JMLeouWjiz<^Q3N)^`zu(96Z(&;nlt- z_C_|3eg4N1)9W?gKxRoc-ZW%=6!P&X=haC+uNcB*UOqGC zq6O>qR}z?)N%CDw3t@((KZ@_GCC|sa!-33js($wt&t{_pZi;4_)v8)jcxeJ0A0g7o zN8O)?VO~tvN*Mtyg7X;WFj>$VJeO~LGMf=HmJ4_o!VR^2jAOMUY59$=mh z{y#5#v#X9IdGk^A7wZyv>7=hSZvi}hU4xkqShHvQboy%i4|-~ZHa{@472MgIW!kh7 zB60RDDy&MS_NH1K-(43D7OoR^HQ$l%g^)M}dabjDgc-_!wXw*beAYyj;cyd44yw*J&EHRM5|L=5% zCj?>4VtX1Vr2>Jw??HE@8|DqLzEbuZ`*%?u{lZHivr0KI*_eRKYKutY^kZmUEG6id zHR4`M2EnDV7lgX{z>G9Z-sw*lcjc1)_kLi|_8e!Zmy?`juP{foo>uTS=+B#W6v`sY z@vko>3tfM~h_fQRa+A!%6)X>1prFXv9_Is=FA?HZviB3*^frR(Z~IG@1)%_bIxM29rGaF zK(Vei5<0~ny>~Nx?88gaY|@TvFUt!4Da-Rojv*N7F+OKrLwxBKELzq@XLo4uMz3wf z#J)&65IvIkOfQ13iJ7=^b|E=xL(|6?{uFu+FXvXml*1yt@=Umo+f;`N<~3AtJHFPF zlU^ckz%-^sEdRzlHWfR0{r*x|_d$|=W}nZf(RXl?xC@ol*~wY?&IMDaJt%GZne5Bw zxh_fG#+(suw32}{q(JI z_7F5N3hTI1;(5Uzrv&#>>uck=vErwQ=h9l?7K3=lQ*iQHM^}COMRcTFu{@7?iX!s3 zBfFW@SQUsr*iMn<=U6i&N8x$~5rf}weQ0bVZ6B7Ne6qn!g_(HFV zEV!GCJ?wA)jelZ#-}Drimz~Y}-||S1>ubynXrXOW26>Oyo+2%+F+!c{$iGxrAE8BM zLpw>8(h0O+on~j9esj-emB6(_{&?$pEt&T?3(sYQQ_r`zc&)CIxV2~;wGXK!Yupm? z!MP6lSNk$o^h5z3zBLnS=|3;dVjZeaX?DLj{1|10H>)NKYR1gtd;ZGBd!Eb>5EsG? z@cpsy=KrzcTI%Oj|G~{r)|;$bN)*G4$UT;s+7drN@{YHngY*kJUaODjDdgcWrUiKq zE8;wSqQPURh-;}VVZVb5!)YZx=P>%hup+hEab7PWt($7Q>{Z8te;YeexAj7^MzoSSuQkAAx*u-N ztRkB$SAx!E8KIW0a6JU$f83*GpOnGlq66%F;)cH_){}4z1JF8`z_RPbBv?EIA~Y`` z*V9QVJJV4u{|PldpG!t-1i(Kk!XL#Kad`b`JslFTL4VkUQ;=s}j=P*FnX~d7o|2If zG_8o?{uuoQtsTkexvrE$ge^+$(X%^qd)qaDtZ(ktUwA&hMGbRguCU56|y)Xr5pZ|zvr3J+L zaREMOKH*~*&AE+V?m_yc8yF?oPO@$^;-dLu1g@zv{Ce5Va9>S?Mdw|wW2J2eJq7B# z;!o{JzDLrgvXNxJbSdl1&BWU6g(Sj@c}k0$sruWaY#ZWjdelP^kJ=v844Y=pqQ>7k z$OEYkV$3q&4fc&hySo|d{)E%k=_b6C+cKCNFTx_51$XhBv zGuh@O0kc_G?f-QrOF=vOm9o1-E0B9r9S*bI9fkMZ(@}4bui}Z=I?pLG(37v5u@- zWe?s!LKx_-D?m%uL%XJZ2q=#*M@>N|xv^UV52j|*?Puk|;c+57oobI|tT$ePZG1

^LW-?J#Nk~^RZaUsUB}^`J z|D=^*^>>zSW1TbCGUj55Q~5md}V8R|^wsj~8A+e4=_BWZ3s9H+J|@m7;@)({ zfIQpp`TwnVyYLA*8;8@|!^3&g>YQP7bukL6Gs(bh*6qzUwhUc7Ic1iuTFEw-7n^pH z28j-wH0%YvA|}J>Td#o*PF0xIx{~?`V-CB}^W~F3q3;u#HxJOv%VPY2+1nw?K!iVy zMg};O^(E>gm=a<$35Lifm(;--=LTe>)*Tj zmfUmtisF041?#j_`4-GW=%FjZABh!fafXZsEogAkKXX9`zIE5&>2gA@9P5OHZa}iX zgp_}KgX;gip!1zox&AN9VZ4K(aC54n^e32EDAKp{>qx@r3Ghuvl)w1-Y&KrJlSifB zY$5i46tJiDA71@b!m>VZaM$4%^!c7^+__uka3kk7Mi#V?eCt_oSW2Wj+1_6bDPv`X zxh*3S#%?cr>b+Kl`Jq@R1pft1jegE833CLwFgHB9ooybC+5kEl3FzEbL|W^P;KvvV zLB+OJob~ficvNnIr|LRc7aHI%qbGFfh+I-@oPsm-UeHNNAGn<-0^#tj=R!Svwaj_Y zF%{`fW5%$aD03Ns>Dw6Y&A|bvG-n#r^HTC`Vjt#&U zlF#Vb_p{)ypBaum>r78i+|SJn)rG6OMfcs-!l^hTwHw7R6|gKoF#>z5+LmF?$t5^| zpRNdhGFFD*>6}yD9!fhP$t&K{?&E!SIbfLAx3u-)e6qz}! z9L6&I$zi?3m)}?5sIX?Lk$setsLxJUqJ6^6i&=seP`EIY7Vc^#+P!wTSLG|M($D73 zczq^;wvK4dIwU!lHXQnoc?gf0@Xqd*W%~${bnE1DGUL=Dc+B*0lkL5v;lK6h&+>6L z$Jzd&)=21iAAoD-RuQ|aUHG($>8K|HxdZtTu=I=wi<}&jQHpsf&wJ~qAIfru+Zs`* z7F@~}kS~*)hic*WeKB}e_yYP?8&ZWoze)4{E>vVZf2&G9H)88sSkV}W-KN!K94`?= zEyHQlQV*Vc)^kYSQ-F&PWs}!eEbz;JuW0h{HQdwHl5n%@ybzb}ESryJUD;GDKpyrw zCBfvudqQ6Hx2y=I)<@E8g*WLFO8~eV*;r|wN0vk<YzVrNXMoBH%Rho~3rQuX|@oir0lTop2UcPIz^hcC z#JiTQB_qX;0>l?#4+~$7kkcCB{_qKiyK;*){_rfTjAWa z1k`4ox=MRaGj=*m;JJ7;cRuqOj90&aSr%PH?gK@o@lWW7PdVg4K`NeJ#y+2yrJV7{ zU_hJasJpP7v^rh}x<&dyX#FviTosQETyV1g- zfTVvcMFYmWlB6uS;~tKXGwTM%ENmwa%XdN=!y^628q(%{2dnkkD6X2x8&Oq?xAcAK zsrtV3H4;_OkdTR^p^((?sKX&$t<-y^85dZXo4!o&LwKWQnskEZrkPZ2T`QR!<$%U4 z*WkW6i?cH7BcINSZnR|WPP{n4ZnOv!p3{c$xc0gvbNpnKS=Z(N^(CwMJ@|{=YX<@XIgO|n zV4&kD^g+3(rQvPnwV08spMGY?18~%g!nLKPM5^=}(cCD~l$M{1g*^*J7&UE458Ae} zHwc@2j?}*gxo?5^;B_^zWS*KZ=WyzF&V#qG_66KIU4Xsb*@VVj!I2KHXo0~R&NXl( zOvx2t)Wg5Z*gh?mu2&xh@@^^c@Z&vPaJY&5Q~7}JnEx=K?oE17ngCuiO-K5E9@(Xw zjt{4_(Elb6^0=LrWPMzWFax3?Rsb3k7E{5D9^##4jHW%Gss79Yu54Wu?4IwBR|jgz zx~oOFh-q{$58dXOy&r>Z9^>ec54Ge@EMT{8J2f=F#JytOCMtPm!VWG==iAuyRYs7b zGL0Xb5`#WDx2bg96j+{KitiYA;?EA{jNC(Uwl2HttFNV+PP2lst7DPRG*8|Ed%WcJ ziAp$6<2r**kfZ7%jLKmDU7ODP(tg%oJ+iM9-I;D`=EB3o*YzDGaP)pkytInxEST(4pk*GaBPeZ~h&6BvF{)bP`*W=&sLc4_^`u!ZD;$DY5Xnv`?xL}S7 ziBg2V&m*7_P=dTw5ExK>Z01{Q#`diZUh65~msUJmi?^WXd~Uqt`2{$8>mL!Fb&KUt zpo=YAib4!^&dJ(w(qyVGNUA4utZ&W~ICPCYe z-hj>;QJ&uAP-b_RFdSY=ce?sgr1QK2^69&2SMgjXL1s5L_7-5&!~s*Vyz4=J*_~vn z7cltDa>2Z$ue<=>ulf$fHianfO$B69E_bQvO(xdH17}cNnsT)r9Vq93{-0BsS%QGbYhS&Q~%IzyLK8*$K5W98fa02}j2GHM`>%tmUlVqymT z{q+^CU^T+cE3L$>{~{A@RhY)*_VfKFWtY3L@qIP&DZUl$KHv@>4|~X%-WTTP;&CK& zSui`DX#5UxVv(e^{|M`Y?`&{Lo=C*=D$tDo9>K2)4{|d0FmusG3(w3onR{`rTsi51~hVEkVW-1gcY_Nr$O+nsU=q zJi4B0H7Aszy=^vN*%eD{f~#0#U3SP*x|W}z(Wvzix9`y-Xx%XC{?P-(0Z7d0R{U7tZe;V!xGUICr zo`-(M+Kn#Y?AwIW%PQb(GxcCDNKSjS0ouO%^Sf1>L1CtyuUFL^Hfm3i%2i>FR_0edFX{wBFnDD2{pe0Muma)=~6 z+%7}(=y&1tFKSC}rFz13w-~Kw3-MK5V{pv*j^r#KKw6qKZ}PxA_J{Kc;O%BdD$N{EQ ztjxS0Fh#561bCHA--AcI{7K~IS|stV0($9={BvS4GeadAn}>wMSEnlaoQK1EdPn=_ z%whdq{tTa4Tmo!|Oa%Ac;bvJ6Nvd{dyzWzPyq{pEdZyhAp$oX=)L1zTrgz85cP|xouE9Ng zd%%~^jk{kz2&RTUMEkObc4nU*J{>LC`*J7uVVb4}hp7LNSB;<`JeqLyRGIlRw&Tu^ zx_r&~>M&ur+c<~3uAn#8Asg5?7)v$B01V$_VIfxNxqW8{5-o3Pl$dFBNo+Y z6Z;|r1dNayI_50fke%3(BLxz>N0C`YG_>w;Axx1XhA9N)e0vYl8+($` z&)tU07Yn%b*)JBtld>*2ZCr?w=U2mrWIESH-ee9edW?_%wB_U8rQs;JO*KO2+hURC z=O#GvNR(H$R-CLZHgaLV8Y?EO557^(q1k;3IyzO6+}k!t zUaM_puSsmcu2i?sGo=WHa!b>GrvKq*r#m(M#!|}a#3;TEjg)$Uzy5Dx=a$PKt7l`e8!w@@zX~0A-3Nyza!KRDP-d1-9Cj0-o#+aUNaGd2dy0D#UudTZ zt@Xv8^WFkWstl#idw_1=sO9H=T#fyVpBd_r<)?;`nMog9r8D07p#o-2R6aKC2!WGI zwaB|X4Geuar0}y3>*VWqxNisL7EumTST2pzJO%Su$9aU6;$0xlwFxC2s0LlC>o~JN zInD82Hh#Z92VUmnBaycmfKRp(5mObmQ**A?>`I6yL!pc zBI<{&sK*cf1%m~v9^DQuhqe72Vwz;f`tB?ZO3E@s)2 z%X6QQ@-+vn?&%9n6Y5c5;c?jGsj4aQd!f7H&P^w;x@HPwhOj&l}eH)o2DO`MD{Z06N zt_yA4lMSxkLB!}+F8Usj4i71gUA|YwI4V+~#jZ%mu&h8^Sr70t%EPCK^H86r4R~A? z<_SN1$rO8tfm>rT{qB{aSGl#I@tNilFPCFvZW-WMKdQMh7(@XQcVMpr)g#rMWH#R0 zfzdR97W8HBI(RBcGn}I~qsg1q;U3Kp_`l|=>}xHor5?RMLpK?@@h5m+9_=%8X-68g zdv^oX-#$9+g_0!N;Z30^Z^komcF^5(xT)43N|I_(XTo}jf9p#$9V@j*tq0()5|>2f zO+n#QBgZoNLzX3PVw;aO;dza;ki(@2-B|q?&|42Ovq6%1>{6cAnBI@t;x41v>O*)D zQX?(<+fZYhFNEpzllK;RjM=tHm~;LSyuVI$(Y|s}MiWvNyCuo)+#WA1BN0_T7 zEIjA3AvCjlk>1F0SW@Io{8xzJz9c!k%IqafoLY@Cb`QYpv1np%5XyY8euouG-1waQ zs7^X)%SDsU2JN&#qsLHC=|Q;7UCb-DXLv$87t()~qV*%rNb64xU&By3NN~b;UGlHz zFS@;Y0FL~iH!rP51mii{-KAb0NeYzz==@W4=z&&*1ze@9F&}9#LmOcvvR1eG#_2RoCyoh zG?C$?QP!0Yjwnhr9-o~ngs;}r<3yje1TX4F+MRcyqf~?!xx9&q@A`(XCIrKvQa#$p zsscZH%b5Pnj^$T09j0!TAuHPJki?!Z(Bs-dij>Wnw~LnGJR`x5*=W2DG+z3U5ADCu zi;yI^AYn(=I4M)jS1p+2P>tDOIKw&r7|iND$d2^}secOF;f}T#ufl3E`}NHSc*l4= z|5hk7`zcgQc9WH6Donn@J!I7*0$zS&DB?mTEKPYvs@!X6mrX4kr|;kIw~HBbI>#36 z70hquhoYd%i9=3yb69V6gK2*a&5Qn>iR@*3fav`qm#aOPz)8Q*-E)HZO?c@b1Wf0W zCzE6tt1Soc^2w@Tw{w_wsfB?u?T@aY*=9BgPpGDb>V986W**MDg!4um_?+03{`J^@ zatfTMJx%QOgWx61B_BJkFe;6&aM|)ZP@YD8xTYy!KRJXf(fx#4v!B4`91qfs5*R7+ z0N?rO3un!!Ptd~%VBEZqZohm?3VM}*iaS&Q*F2<9|(D;v1tKT7`Iv_pR$&4*D70oL^w zXTk%jx7>W!hUwCE#Q#p)!H!j}C@Fj^j*6$8*w<=wE#I8ZyaQw}$Al#+y%)RqOYyyd zA;)7OGRv9F_EW?Q^s_*b?!3Avl5w2rhoufZg-v-4Xe{zPu9r!I+lPzM4ILZc`HzrI zZdy#aMGT(t_XeLI(~W8X4%IA$E&hhg^s+#P`t=kG%NPfTw^(OsBvjkeKEY*ykTBsb z@iJD@Za(jV{|lmB)th(-KXiZx??rf9R?r*S)QPa+dom~*mZ5K+4d7oAO|neo7`Jr? z@hXaGmQMze&n{co_r!xdQ#4`-2Dve_E3N&RyZ-N4)-nEqe{yumxsNn^ zaC8vv4ATsy;6i5i!(x1?C98V-L#`|Ovg%%Z#EHuaA!8s1iS^FL%_q$G z8qptFYVc$%f@De!qw!-rY-&Zj08*P!`IiP*K>wZR8j{mg{wu_?vN_P+m5;8{PQ25p zP2}p{G1i}x&M0KQU^aXExCM9qTT9$%kI%wMjxc?dC@-e7iD{bDj33{ix)!>7>Nn6n z0?Ie87q@41U6}<5RC9G4>QRJ8E)CO| zFca>Ri+0L*7k#c4(&s8-c?6R_z=f%=Ib@{kPO2_$r+<$K?;=rWXY@N`v(9+_Y^H1F z3##JXWU_+_Gda@%HTH_|H4lfzsz7z=GtxS-22FBmfQi)4buq1&nYj()jH}_0NqgR> z=5gVq4b9b`63I%t_6o z!)P8mh=0-D^Z&EiQg{u6*n_N;kjLP58GBA~gfmlH(8IRpP~wzNA|3}J{X{LS)|brZ z@UJcy0*_f#GbVSH8Qc+qv%XvMIs5~!vY>>%-**&dp}@0F*gaN&S0m>l!A8G-4N)%v*;+Vu<#A1ZBY~%I);ms4^4&?7;_$bfMMuH*%5?ho5if(43!o zwA$t<7{_}OYa?T3eXu6Y@^yu_<4uS&m1f5ojgl?L?5Iy?J`ArIhD@qQJ^dgHvS^Ow zd1Av1r8?rQn|AQ%L@PSy)(h)Alz3qWHQ2Mww&CT$bT*^9EJ(TqKPL{5)$2@H|AzPB zVM8gtA7`^jJUljcCTV9B@v-4-P@*%W^GGCfUe_OI89oJ$_&1uF`5fF=Qa^03Kl)K} z87~u00>#V4DCERl2z&d7>=;|iELs_dr={G0SN2_~a!(V;Q4ZPL_#2XJ&W6Jj(@sn( zXU_J-VyW4YAVPc3pO^(grhODStEHg*;f5P7^PnBvJ9)J8!UFguNjBGuOJO8eQnWKM@?)@0hdrv(V$2IW}wjC4&co2nSMojmF zz4&Om6JNWPaAOOUS$mV5hK%hL184&!v2tA^Dr!Na?iTDL0rfq3`n%1rXzV39Tk}zzYq)w8>+R;acK#1|` zCBMD1868n6e0Pfg>%5cxz=kc6BuoDoYr#S#!22c==dlVjl(rpv8W=(x?eWts3In61&lkibmw>k_~~2sHWl|D^2WS5Ed^M zV4Y=N0(ALxkcFG1nRFcw+ACbc_e2k}3b0C{E?Fx!j9z67!wB84_jVUD+i31bcY6pF z*483Z_e{7O!Xe3Gwl}f-(Ssu8QsC5q`^3*w znfA#y!Rnf5B6BH%Icy#a6)$Mku7XwSm!VFWts%_Q2Q~JNhY#`G@A0sUYEg1xoDo|^ z6n3l_MXHFjIQ{LvU>;gt}Y(HM}QWu6pe?CL`_aNI> zUSK+0S7GG@SAIUW$m<7SG586S2 zb1T9dgF%(vG^?koVo|Lj=w7PC3sTi!Yu?_4Pf^?p?W20s%LniQODRy;JchiJ-a+nS zXCkpl5eGcVgWq(|HJ=y71RW2=S82b(=b7Ko>5yP>Vd!00F#x?0H^qM@B!MjT5H(-5 zhn`IX{A&R&o!_`I-_XH;Jh1enIC-L+u{-|`FPj(%+V3ln z%ZEVFn$4l_Q#oxtD-ZnoHtifV;Guz;523e#cF5|#V)V+zLH|QCxI~tr4_z&Ag+6cT zMRJU-{xQ5|onU?&W#VDv*Bf$|XyVQ19Uzb6LBwAeF|RxJ<1vbL|L+>R<-mr+$Ent? zcq6)YL=)m3bpZQn0n({yf#O2ipWbZF6vz1CS?_GYWMK!o&Ljf&Q#7&mjYBD2-=R@W zh<8z80{iG8GyK3$FxOREZ>9PjAF|h{TpQmT0yX-5e`6<(o=jOt&K1xM{A*j-TNA(I zO|J#GH#IsF7Hm!>mkwz&DzVLJ;wJ{t<&W2pqpc{c`lCiJ&T2shS zS{6y79FDPmxXgpmz=?zvTZuF}baBjohTs#`i|Qr3p)e(db+6WrC8^`@+-6JUIq5Z3W332wdkrwHWWv5h_Q(; ztE@B)TkbCe$*Z~OR8~H$iV)%XJ$cG>#42JT4Ku#adSsO*q^}AkV{?8Z7fu$Izv}`r zhntbRMk|y}=8|JaQqrWH%dpwr9N0|zwsNfV!FqE88Oa)EJzoC^t;&kShRcQU9hz0n z7G6h+6?>4FzD^9M~@aYLdoPvGIYY8)o^GoT+@{yg>Ka6 zvW9krooXT9oy?hp+_iW^HvX4c&mhhCGjU&^sO@KL zf@OKN@aa58eLscZSONos{4OtDLCPZXnbCbGOk{Lmf1o#cro9Obd{_e4yXgKfuK?YA+zx@| zGy`PqEylvrAI}fAg`4|2PXk0#|cL*&#*qU2=H@|-3Q71h!tTDBf-3Mqw9qh|6n;wE!cMhh=T z7x}sihm7rj&Ulj_*LsoZlh4radXEerQ^xtP+QEim$kvhwX1n!!@Cc%Pi=I}gyYhSC z021QezNf~f*Ae{sUpz>DDMe>fJQssAdj=q+LPBnYXRk)pYCN|Yfi+KPb^`9SSOmW zPl#;a$t6W)GECu{<1~L>6VDOXflF9Pe*z+SyzQ!e&G-H`VlPqwRup@N3 zw4g^c?@DiKDv@@3jOt?b@Lj53Rki<$)@cio6RWtyZ_zbocV`5yPPPQM)m_NUs}N4o z?@_he7sNEuJXLRBnu$=4-oNmLB=-~&@AOXF__!&)N;$r6D~we1g~6l~!4IQSG)Vt! zKK--yRtuQ&qQhABoi1pK^rJ{sDX5j2OFqx1xnUR1LlxEB4jwUP%r~sZ*$-X$y^7M! z>fpZQFF!v#m)^$Z=x((p#g-A-`w+M6u!HGT53u0TD_Fy&x6%8m_|DILcIV!*+4TTgiv7)nCcpQ3__X`qfj^&*zV(gc{@8CL90Tut@7L)HuvRWN@sfpoc7pt@Zta3-97W|9M=Gp>(4JCE__ zC3_)X_;n|VeAudjLnT+@GEIS&b-J@K$(TX2aLvM)Q`b}Rsm*S1{8A$tGAaW3lo{sB83!&j=E=mq9g^jD}Zn*6!^X2FQJmIS; zpA*Y@pNq@(xxlQjX7tFr3*u&TNk~~rTAo)8w%n5gGie^X%JfobXBtT9+7Z?p-ec4% z8HfMHjH4}@e{o9ATK zC*coZ9n2x-c~+@Yg$5vcfclHu)!1QrUfAYGJgluLMTse1NLoY`Chi?a4;&j|d%iCT zQ?Ew%_vB!XaX3uOtVR}kDX=(tdIY=_(o+39Gme4N$K7I_sIfWTAe-_|9NN0 z*Mn`c7a?D04nT*@bS7fKY3#f~6=3o|WdHIL>^n$%WDdqKLQU4#h|WvKMlC3FKkaD^ zP9{}V9>|Yst^duWIk_=k5pohC59e`-g#R_>CGEfPTx<#b3%ZbNa|wjeTiC(OFKGPH zWBll@FPx_yy%T-UU~~2dA}brGeOB2T^IB`c{2fMit)f6_YskqcMTdk+A(h_oFK`wx zYge4WJ~_Hz=F*RP=gtHZML8ldPQ7CRSHb7FC;8@U%*-0zf=^or_P!S}?yzR*5Scb+ zgI*lag#B~=g7MB0^mkGzBvB3diE&$|-QOL5R<;A}{8kiq^fj0?N0G;4^RZ>*QM|EXBXOGSqg9E0?CJYIq24tWc)3R z12)CfH@!3zI5ca{`k|cmI+bVid8>e#YU$`oqZ`b;^PBv&@?%cvNq|mjGAKEhqtfvo zFoj|i`;t6!#Q6*kQ50a5{8&8fBO%1KZ6SV`?g}W=gNPWOVsxyHux^DDEbMPa>3+*$ zPiY(IB;+Ftk)P1l9!>5w-(vo548m3hwvb1=7|xrfLJmu?(@k4A1RsKhcn5w=U~6x^ zi@zTChefTmsMKOFXfi&;etCs<+aV!>6FGzp&v2rPM zw&r`9*S&r|f0b}%3dB*(*!}J{q%ClJS` za>NqF01$o6jX*62q8-UTM@X;0Ahc z8qsa~eSbyw@i|+VH0E*yK5fqhLz^TE>erHcCwtJhsBWzPEeJ9wm$F&26Y`ZJNp6!ptJOyd z_9;n|`ZINC%JF&#zu!hWF5G5@JXv_e`XayAASGEJaI!Zs(D{WXbKKzGjNfEU=p^?1 zVGJ^HcZtRpWt=$sCxlY1V9>5NOhs5S+^4_OSxc=`9jWGg_lt2d!*e0~PlGo`l&5+i zT!zMO`J$u3qL6Mfj&#=vkrnP7vNLM{iSzRCDoy<+6IF$6<%6 z5?G=21(`(OrW`5luOHgW45&$9Z*##;r`;e*-Ynx1+AqRfW1q!o?el?KJ%ZvL<3P;V zgXH+h{JgN#wNEBb4oV1dIMmh7&p_fI=5&`WTWQ^pW#M&6xsc*irG-ctcRWtpsI$E{6w+G&|bp zE~9kI6BkR-KKssA^mpn>%)2Pq@0czpD5g26Y1dD&3g;ikoeu>VgyyhiL@`3vp?EmTi_gQ0lzxY^CR2H4HS5_~(NqKDm&oU)4jQ_FYse2$IlhcB z{Pq#AaxjB8)m>x4nV2l6J!N4aK3*%p ztMPA?kJ-{gWP80C^)yM?_Kx=G@ygNS)En6=moi`q&47(Ngy6gz&8ART#t2RRl_n

Tijb{)BFU<+hAagk zbvU(l0x>bHK<)Yn^r=4FyUv06dH)a}$38Cjg{GdcfvoXZq9KHtbM;zS<@XD|-nHYX z7+Jl9OEwIKF?(NP{C$BNOv`UXUoTa_EvkWcoXt*?Asj5Vn+xxZ%g|42fV8X@(rF~g zOfU;V$EFKrt>^2%wp<7#$<(2JAtjJpK>K!A z__54GbMW4#0(c&oi>9^{*nPW=ED5t`3fmWBi9@D*?SwF11#fHpNw#|{DnI`fFY%!L zePJ!AXyOkj-yTV4o{wpV+Zyo;+BIeCT!QLBo^d_}N)eIwIg~ zx{icX-AKb`cc`rHAtyw?GR3og;fk+8@T0LFRsH-9KUYVR-SQ4Bp~v$et51rcLv`q; z**7p+*h>CrSTGKmTXD%=0oMK9$q(DA!w;$KJDSXN^?zvsWwmjEo+TJ z0+=xPSIp0#4z_K+TpK>0^F-RW&;e(YrVhZ2eZre7%u#m41OQJ zBI_$+M0y*S1gtP&l7zXq?Za(2IlBuDd(+=VKg|}P*=P#q(;z=SieyApF@|yPPk_ii1d;T{o#|8op49v4DYcM^C^?18 zqIKcH+kW)^i7Z@5lcU}Z>a~Bo6<^=z3QuoSy{q0*aPt`Ad#hWoRzO!N?GXsP%S04< zV)MxYtXo!c5+ei3z0a&cSvAh!_NI-z>^{W;#gll^6-h{+IEHT0Jaw_Y2jpWm7PD?W%mU=*^q{LXE+enR)Gd+kFh1?wS=nWw71R;#?CbraAaFL zsy_4><^}W+txY~ms)97kqwmX-p>nkRbRVoAjV5U|@{DTjMSNzG0P7xqPJ$P7HnUr= zh6{S#A-TqbSX7^4rX^m$(l2PIcv~}C(Q+81L%qrT)J>@U!7A80&z)J#j=m+lSe$u7->1-S~R2XLm%2qhTabU38q4+N%NOYbNkB14XL= z?EIt2@@bCDqJu~A=hS1MGvgPEba@7fdU0fdiUMw)WCtx&pZ|FxW_BuTW2XHDpOZJ{ zP9R@aPz}S%*UW(^f_Ke#gQ2NS$gsBxm}97d+8B+W9N_{dv<&%FrGte?D`5po zGTW}dL`6~pt;OiaUffE3NzNNaP*yk%d(+?&ZgLT`dvh~x(+&Yy>W`LHDF>Z$`Yt== z$FeZX$IY1qz)H?VX6_mAu(*|27}+x$*Du2srv*Fazp^#3cfm6P`nC za`&h(PoYGe9arp+H|E4ciFz5jIXwu$4S_bSLRgfz0iFG5ewSs=5~8m)Ky)Hx*>6b^ zHaQ;-FD+`2VIRP>82X%_e#>IXCt-)05@?{^97+1wFt&RNZ}+J%=0fTWyrus(d}-}K z6)z@|4Gh&qyqnJ4(J{tu-Sgq*{eMWYE&(bN-Rbiqk3SjlAc%HnY#E4QZvAz@*B?88 zAAP5=VgtajJdPYQb3v*f&fv)z$zU4(6}i&SoWF=m+=LrbLMMXi_ng zBBO_!6a+IK#IA!JAwTk;+Z@#GzXD`055dtpC1@7?Ok3*lAsu&_jr*Tsb#*&9^Pml- z1$jae)ji6FO~M;5U%=rD1sJGexgHEG{Yc@u=`4|5r}5iiNveMuN2eBlhAsF3*&L^U zr|qu=G0FoRJQmFuI7DDEbHRQ(yUP5O;#CQ_|( zG1Bz&f{fUowrV)fg99aA4c|O6m#n1a7Ve zdCC>h);anLJBU|;qkB4PpXm*u^LmMTm=D9gE(4NRsNYYx0%b}M&DGQbI1{ zB;j>n*f@kDXg;kF&4Bf*JH^-~UdCh5PH=y53wo@%2Clqs1#icEBs+Tm0;pc}VVear z?izw$$Jju@`wsLeW$)KwA;!1XE9Qtz3|&Y>1^z_j1gNtl!lcBSf?gG9pvV#lg0Zx(A9;D@wyf_ z81QXGJzvF0%fU!uaQ!$dV8&vAdtxLpvK-0LJiTo`lyhF}$S4^d$J5;f`1a#&0F3&? zlGK;-SVgi6hN2aDr#CENhjO>#;m#Lex|Q~K%TFRb^t&+E`ZdFSn~n!2xWU4OG+#Qb z7Elw_D0;KgdIR2Kl8jJvDEhLfhOg}(;{Cx1rh4S#n-OF> zV-hi2$0Zswi<#p$TJcJ;5OA=mLkANoVMY;$>~->EZQb=1e|}N`*Wz>0i!R!c9oIrS zO6(ZRz?C$E*OY&Ad?~RGtb=?=)AF8Q1PDQ$M~D)L-^ zD({V>5j(uD9j|uFfeSr_NQK^d?oplRx{0q?edz&cb6YH59~;V=2oViyNW{HvG{tuS zH@gSH%sCB+t^NzdH%Ah;8xE{Xj~2j(Pg3NcNgZ1M#}n>T?&4jqEVFj29-gmt5r*#m zK*3Ls!-X!IxhLL-q!(tw#FqlByT5b*Cej=3e`9Z$rH_+f^_`cbNW&!c*03kMqZ-kJ z^FK0O$DiYj5AiU(u?&4qdWn=y3$SjUnZ~hmwbZ$OuSUiO{$smjoz9Nf_Rtvbbc@pAehCY`}>YL8obH9vV zqzLeB=hH+eFmxwde#zkskxY1ZkNOIi#xk{^9^hqX9r&F8Kw}^bZHpy`4m+d2V#YX~ zmkg2ABOE?ioXlU%B~=3^%)WTKJIf08R;R!`xGnvHls-#Fo->3<)cZO@QY6@ZQvUeD zR$pkn)IfWM9^#2>>R`eNK!Zt>K_UTxd{7yRr+IYIba(K(vyj2&##m{UF3=VmB%Ce} zd0*y`@vjYN_dFX|T}`zCH23~t*KWK)Qo#9-@7w_YXs&Yg_1S3c^i^Q|c@Um0Dnajj z>cI>}li6GEF%xF^;HH1~Vb|?8B&i<@Q>flA^5y~@qtgl+#=^X>tSRgrO_y=Gs^Au& zFR~HdP(A#vAJVK>PtIc50ZDL=A4igHY4FVM0a^1*0n11Jm3`$nhoe+K1!AaNWU5_|=z=$ZkI< z{L({?+WRnH7R~^#_++qpRe@rQ2jMDx&wlz(f%z?Z4d01b3tK)6(JbYUpxXI@xCESpBan-R3tk~Dz_-GW95^;yPkc7bXGzyiAovG|jEhb|FWEwnZjk|| zv_siyMiv|op`EHp%a|tyf79-9e)IXaZBJ%`+Cp`*>_G?WB0aG4x)QJN!UQ(2eJL*c zD46TQS4|`n=v-$&j-UD9Er%${Jn^1a>~$=`R|Ak9@}{gN`!x*XVn2v zKj$q`bDN80KKH=2D@wdG3zxD_DD1%hN(8uf&sLlq+(J3|xYx{3Q6^q2L_2uSH=#B9 z4Uk3eZvP6{X&iG$ygHRM3bPjsYz5HGkD1jgGM(4wZ_ zaA`**ne*C#hG@>grLIn3UVJb0bTA#p2hQu7Ogae;e07_Tfte-FjN=!bR^K0}Eaun$9zOhowk zJhOu7&6(aB{+|!#l2VR+sJ`M^aSg&u7M!QrMa|N;th@iE;^?m>F!JRKn)l=@q<)>u za}^0=l#m?$@$EK$KYbE#1s9dg2bs)&s8uHktoFGRw*fi4W_lKEqq&G)r(&7kAj%8_=LQ?d_6?CeoK*Yj+p8;rr%w5cC|7lkgPK@j>v%jXo!5 z8la!fjo1j&I z>CgAgdD|g)F8z#!R?1(M`7FT2H(FuibYb43uF34Y zH&^fzNx|(vy;uuoZ}cG?6={~-oAY=VH~ zrv~m#ct&LQWT7RWGH~{G4sb44qMg1mpg?&!gRSz~4mA;Y;ps}KRLVf}j?JVQz{#-e zZUtKHF${O9Hff`k0&_0$I$q(wmOqbu+L{6-4lhWikt*)laRXO6J3;jJ7L;%C0<3KF ziFtPHn6C>1GPdn{HECj55C7E?ZXf8 zTVa3DURQ_0CUD{P^ae6`X+CRIW(qlG%_T<_B~bMzVfc5JYWr zg0*4OGB`;2l!lEJC?Pf*Ea`0AXXVH+c4zRF4aeaBoLhzXLVV8Zu)lD@2heXBEy(5&|WnOBT)=K{aY!Se*9?F2~iOJJagnJ>?j^`~6s4`*OT8qySoIZ|U5M z0+`v;LS8SnXZm(*!1_bi`7>D7f-Ru$K;N^&l+UlM#NB2tU`X%jray+^n+}(JxSX1n z()W`_z~{i0eP3yo&P&uXCyt-VV|#H5XjrW#qJMs%{mX~(tp9>wvwj0Q-nS5mJVp6N9=2_w*bjJKZ*`~peppi$i8FkDF$%c_{ zHssh6>aR>3hIusGd7CYVaa)oJ|3%PzHUpc~)z@EPWv_V9J5z@K+a(zLMB^qmu++0;NX`C=zEw>j7BuJTK=gGcVfTByDbWI~ zZE5CAaWf3IM3c3Md z{VGGKnlG(TomClzg}_in#o?!vE&>2H#Z(^mT`!)>oat3?@#dBD9l?d zrODQfrdk^RMA$+7o*CBz;eOC}VnSyOTmtx7f+?Jd`i|C>)qPf6uc#=|LeU1^I-oC z{Nu)2xb$ZTg=?q6cl8%UbBQWGQ+^BA9dLq9g%)IG76RQAqa4N^P>P`zNNBY}U~fK} zbYc{gW^&2%{@cvkZxQ(ZFKe(VqWhgg9%#@RxNGA()Z9sTw3!Vg&AyX)`t%WgDnfa) z^OP65HI*E*pt{iA66n+>QJTr00fXEUq<1h6E>c}zs={)nQAilg6dmB-1vYJ*3!fU* z_%l_cxDgcSdyr+i*O}yuwU`wt*d>oom`pa&Yzg13Txo51}tSVeZZ=D})Y1dd( zF-V)Wk_-=frYd+7PA?E(*WNY;HmP}&Q%~wp*{5o}gAriY51&yW)L)|Hzkrzre?_#0#(B)S^6c-AEm0 zo905SuMO#6OZ6D$qi~RBO*~HGFlzZ<;N^P`NsF{e^&1PtZ4cr>^j;Y{Ss#VI9}(gE z!F69wCA=suxl%cb&brm$V>02eX<{uBr&+Rwl*i_5ieb?e7q4+F0r#(85XU_qWQ#<2 z3B7@gwWA7_z9QhkMxD*@?;CO?FGTyqHE*o$Tn83|fYc-< z;nNia?-a^WZfF}+QEk8jWi{sh3Nu{PxC5~A0K!*PU>{eOJkPC1l2MM(M0HRjsm9Fc z#iKZ+f@YvcHzAka^&pl!2$N}6ONSgCBo~vHI=rfNH^rgQ8GT`tp|9D~LCp1{oQ-_Q!0EBh{x-Umq_syFe%0XPxXy3w92a~?jm z#}pnt|Bm)wXn<~cKeGRMCeqB!!TuXLaI>Hi9eSStzqfISO^Cd<@&32?Sx_Zxe4c^Q zY-PdLifS-)E79@ULd25l4L%GjFjmuOKWXS1s8$_9uCi&=uR(JZ>*nLEKX>r|Si0_b zD&O~yPrv+ zzvuk^?e)?hJkR^NuJ`pGRi=(0VbhH7*@i*B_eW|l^DbVdvK+RLZxM8v@uWrQXXcr8 zGP;4T=0}qC&DQWqx*fNw6v8o&wFxsdZsx0cH}?{%O_F)R{*=xn3r?!JY;%#6h5Z)6aRT~38$@4 z1&?#uv_tAE9xe|1-_EbY4yOM~%oj{l&*a&j-zv7Zs_eZ@0Bg800f6wlQlmTDq2es(Mk z9Ee0S%-_R?>`3Y$Zj)th9!@y>lfdj6n?Enc#-Fj>7dc4HAW3Jg3pA^jmYWkL zW#(=6{);=lW6fIhWv_#)HOu4XqEnf82^bv%=rM@#dAoAtQ+41!4VBq0_Bup6&~ zGVA9Zcy74oi5L0H=7zazC{{F;huI8^D&~}9TgNt7uNX_Ec59c_tk{1$*yMrg}sI12-qtoEU zM3zPH+6O;d`~y@^it_vK>2UXmdy$HSRH*SU#b=Cj$j~-Zcr@@0Upd#8 zoZY0HHbpW{y9z(rlm-pE+3ZxVYB<3uk%Y!of_Xs>o^i+=(5XcF^Upz4{Yx1J%`+g) zy%OhHi&72tEG=HFj?NfbkkGjcA*65+zY`&lvmt<51x_WCGG2ox%dMUC&IPScv>~6^ zO!Ys!nmp|pydBDY~L?{6yzoAN#3!UY6aBd*(-fuYgh(7Y&M#+TSpQuXtP}C!BX7j zUkn8dqY9nop{Slwc!2R#vKLLT>Na)g649ntV%l)_wX<-`jCH-0Uq)&tSCZIsLY}I7 zr#$7l#M09-2i?WJ_@++?$T8l2Z@e;@ z`uhtsY+?OPvC7=BQxA|639Mtnvl<_sDNjvz#nOi<;ppk@LNdfMu=*{V@VN;cP|f&? ztdFaBQm-?JoNWxuAfIsB&r+z3tEcV*GU&sDB$h{0CCC{&wOeM_oe_Lyc`q3` z9t`p8{ zK;5dxw0W3i65={?a+EW;_O@VsZ&8*F$@~Iy-td0?`bn%<4$mgG*F0eS@h67Eu5OfL zDft2i>Hj}Bbzu@XJzq-ytR29ApNT+Xi=P0a3RC|<@7^eCefTbCQP*7X*{mSQrpQRm zfN|{IPYzs)!e1O9YvRv9b$us}=w`iY)z*SLqnC{+wPPBUj=51NQltQ)+1;?m$R=z2 zw+J#yUx-(x%}KaiRLHkS9cUm;Wns{0P=nXx6hi~M=gtXWvy;I)(zme`O1j_Sw%KK% zutbc1#oQPDyF81Wn=jn^?)F-cji;wV=d)p)*;)d+$786}Py%{;(w$t|D#WFh_ido_ zT$ay|U&+18`t`ou%z#x=#n@j zMw(``6|SFWz4NJKIg*bqk-bmk!P-QGtl#(+oG0I<<9nG?!M+pJm`8qoYAhm2$;9%p zr(nOc+mr=TcbMN{z!z^V9)$Zugg>WhHg{jDH@VGAg`%=j{9(dda(eKx0GIR=n!xzo z6FMh37f+jAM9!K-!sokHxH2ytuCqNf=7*}GW86#fmEn?Pe-7ifEnqwABhGOYDvszEQI&+L)d;j^L(-A&0NO?IV`j#XO{@E=)^gH z$oJ2p(}vBkT9zR^?`wu>UIjR|N{mio_upP=OEhO=ENR*#oShDzD+7}%rV}Vl#_7|t z;NwB2-K~3xzU+8J#z;SfnSW|=PPh-4HKftY4iX&E+|i)V$$_)G%COwpGO%P``zqc% zRNN?mbsPEx8PUgHYQTlw8Fbm(HXQNd0(jZDQU6J%Nb4e(T)1*i&`su_r9h(@7M;3z zf@5@kG3>h|PE%%A;=y%gAi?;J3UvomI^#0QZru;t5_@s)g)o?38BP6XDwFZ#3yjGa z!=FDekvr4#2x;&ZV$m}{1uA_amMV>eqqJwmq=|7;8)KUAq<5Vx12%?Ul3UFiwK0pt z-HL(rjDL7vR|XC9YpLs9X>|H@3O2h}CD65Y$IHXCRh#MM(IO=IML#*QAsCL&tHT{} zUm_Q>?FV@N24$jZ#^%Zm;Od8 z!xhz~bT944iD{zX_|gxK<<#Sjw<2_+SronCf0v_aqz4fu3UtlxI{fWK7F>PI?zzoN z(ZrO=dIA@KQq$9aAyCOH`1JlX~_GnR_ivz)jg)EQ5!&ESsn# zo^x^2dy=@a6qJ}=w8^Uy&iaV){}b^;J4JMf^|I>%Z}kf`X?pH;7)?l!Lrc!yApYT6 z0?yoIDS^$t_vrVDlgZfNPoQiOLy=)3N?qegrWo2o2@7kU{j(j8Tg&iOj8<@q)b5gq z#Y{i>xd`ueA4`pQ$I`wzW@vO)CUIY20aKQJ!_}h7^nGSu+K69Hb(noy7H z9YeuMmE{BP4l%s--Jeui3TLXc8{kGmDpYc+b2kYbLMGt=+ z%gNU}r@-@lPz;eLjWA&hZpv)^xnxURT_h}?_> zo3bjr^js#4KM_gK&Q&waE=VJ0;gzsyY%Vrob4^Tr0)6j)5Ltgxg+I$OAg8Air>_>L zXBNfMt1;^6{DGUq+G(MHKi?nDhk%3r^oht+BGJqP&Ruqo*y(~U&$A~BmpQ_b=}4$O{02~jq!~L1QSP^A-%HzZ_yX0;%uh!*=dQ8R6M!+&q}ZZnn_oHM|BLfmwbsQ z^LY?+hIwo!rJ%zuUZhFnDSTCDc}L5i!W82aI<;sNXV(rX7-l#&^rQ?celLfcIjra6 z=RB0RXEb)!6V6n<3RB@+)ePEJ(T3Z3mtmHr8!caMiV9WNkUPxFlfp8-l;*H*K#y3u zrs@R8SaK=U>xc_{i{rY=L5Uy3zV8m`#&a_=ZlQ4ROXsw}gNo67p7KPlnAAz~%`p%r z`BmcuVv4luF#F~jyg>V+N=ahAE6aCl!sGAtfQ$_D+wNb@yZ(wt79WZMwLhQm!h03) z_;C##G?Yd!pTEK;LBcsoJ4X>buWzQdD?|vl=?8f^PKaH3`@X^T(NXk#pAV<%Tq~I? zUI^XSKjNw>jo^Hum0CF1BdIUz$x1~bc0JYE37%&jQ|}vfIQse*V(Y^)*_vB$si`Ec$~7c8^#-fT987 zDjX+1n}j%K{o5Mmh$qs2PC4lQjS@JnV@>HY4YF>NI93f@l=ut9C?QV zV!p2w7VgNyKQ>aR=eE+r*ahu7FpoTEyW9UfjE2F|l$RSuJ3h!E$90xu{c|nwul*d^Qst&|$a|X;4DaL8~iuA2dEbV?_h6?nv$Si3KaMAgOp9d?`h5h|h@vj>9-tBM# zNx~WI;g&EkozC9hb0LPOlmba9uNFStr>rA&9C#RDcvV!6x5f5A$TY^u{L@C~f7~FN z|E+~dHT_s><17eVDCDe;#NC7M9d2|+=6Q6XG-Uob~>FNja_rk<-+aM-t% zP_}juHd>b9X{kN%i_I8fM{UvJ#31r;#U1e7(1!K*ra&Kx! zmo!qP>M6)Gd}5yliZo_!EwZLbAAW8b!qy=<5Hi}IDpzWe``hnNd|Rj_oEM zRt_ky`YNf@-4BWfdhs`lv*hAMA-)~68OPrHSh~{n1#*@tCkt7gZ0pu$?9Azd4RXwj zG5}`Hj6E^OlV5rnY9TQa1X012u&LRe`iX-@=R~xCY z3Im4+tn;Oy3S!vZfBWVH&bs(wa{qWK%yG)Y$U7G{?r)>zw_VYl`UOO#(?T$t&Fz+@ zORB@@&BgNQ*Oi+@zw~M9sr<$YbPMCO$SwKnrH@r!<5>|1a(g{{6 zI7&;68eJWrlYG^=(=?;VTURg05^KQ!1xG^ivPc^EI>gY^HIz)FwQw+-;>Q*f;l2un zQS&PBk$D54z;r>Xi)Ny^%zxK3jb$Hf9l#-`x^QW~5)C<7j}I+$hfdaCzvR<-1gA`h z*$HRhW_-a5M7Xdt{3q+_DZ>*s4?qXYo*iv(i_VLMl5_31q5f(cw%Ym+uI?G8yrpBf zk8e8>&Bwm*BjPje={N+Zi@fO36&iV*9-4{*rZp57`|CH}bsklqzT zZ&<~l@*C-7Ta$-?@7iUZ4*Dma(-nq~aH~}yDQ8-&|6$j|7tC%55zC; zGE6P)#A7FmQyJD@Gv-VKPGsFNuEvqD#-JLz-6c?YK9c!#)C?ENydekfRf7HMTs%5v z3MBnX2eI{4_@Vr0TE;X*iJDW8LBkyqmZ1+4r-rbx@mtt_-;Yjq)FS(|vq9O1?Y|K& zXi9}6Ip5;|dOpoq`>HR@W|^_09-PEGcNxLKhGv+5xe%|B7)^iaG0a!7VxEE|V(B5o zD9v~8puyjtn%alrl``3IlI_l74^q(2+NWguCm)t0P={kbKLrz|1iE*M2uD?3o`(2^ z(+BlqFgYa)-b->IpLxfE_SC>iwp0ANG9TUgBaJuyC)_bFOrHsIqqON*tFKsX*$t@m zaifPnnj%B(EhJ@~5U+gICeVd3j9ZI5$uSz8P=& zJ^&-qtWU6XHBaITpX_F{+2V8MI5f{4%u3v7{e)!BhLks0VzY2IGaOa|gO<%SIYxxc zt^G|b27>@X+3(@Y09+Q0r6A(RQ7!5umj4y9zS;u(yucmKu+0Ct|1?nt(;FO`D8#W- z&WB)-b^Ij;*5gebEyPLO3F3TO@Vy12X)5C0AIq3J z&FA#HCt&eo@q%10Ge=Euu3JK1{_SVoz7jC{ksti`xB-v9gS$WLJhC!CqZzi#wVoDmTn=-~!6M0u{yC#T!X}KSUTc_dXnr&*wycC7 zRgqN9;Z_#QQH42abyT8Uk-KsriOeF2urrMPeJyg~@UA8{d#j=!%r1GkKvbZ`dSN3= z1Kx&G($t41D|L_^7sFsSslngPYT!X1^Yz#ya4ta^QQlDsSHkk}>+rXboX|`|#a+*2vQnrD0V6oIJ`&xeKx#b=}P}iRUv=g*Ftv`%Z-svLQkiA z6K4Z^s9V^Ir^J4S$CNE@SwaDNDH=(fj1MYzFKZSB&?xPoVEjV` zt6}q#7i6wmEf}Ox+*~vX#@F%KJ5Yg@{{944_Io#n8-G)zBy@IPVf@o8q3K`tx3C%3`m}C1CP0M#7@&3LL(7?L< zzFLrDLvm0WEJ9>=6dVsf(7G7m(bemtk{uC*JJD<{vlK z)m7Ml=gh4pcm9h6^%>Rpy)+-bosOguQEG;N&JgkpSHd=Sm)yBp6YjFVOLI~cw!1xs z9^4X3JCp4IvS-fa4^Jh-UrN0+bAA}#5;u#N2(j=3(#x6heajCEw$Zj4(< z^@YF<@idur2S44i7Mg~d1wD^rO~=sB2C;OBjTJiO_mb>-U}{3BUZ@sNEND>4|r4+7Wq;$Pkg;LY%J&r=mrGouB@jThzL9hT$Hzh_G1jk*2;QtE z#Iz4c6_Ph?p~0e}Bw+e5p{&z(Uwj=dXFq$5{jAh_KTdH+4>>-q5PTLCu-xEXBtQ2O z98&DSMSt5!L$@PHzGuG3@G(^6PAokc&Eu_<83jEe`JmxfjIUPZ!Ug7?v5Dn#sCP1+ z#Jnr(4vCPxi>JX}hFw>62k;tqNr*V&2mb;Z@VzyXRO3z*U3koaBk|Y(dPghJ<*9Xe zUSTdgV0t-&mjk-RmA-rN*Rk6wvJ$zwmmq{>Ko zD*sm2XKN8Ux4M?@GEwAWlN6%)RES++7xN&w;|opusEUI1vvGR55WCK?9E^$c!{AeD z4Yt#)2M5M==cguc+G{FE_4-oSke`RUpS=f%qs%kq?1Gks8IUMzAzqzrkf#Q}!l&)@3cJG-69tw}-$82_w3#UAujTJf5|1bEH3 z@$$D0IQC~ROxiStA9Q&scazEklE%$|u7kyRtL;R3At;vm=a{2L9+0F**90?IE9(MS z;_X9!552_49>ox2Eg?S^CgK5lL-*knwE8!y~U?PfZ|Qd0d6uo$X43oqS;+ z?=yZ}5(zph>nTA8Ir^t=kc=C0f}OFMbrcVtyG6sZlt{P1Z*XJZ3&rj@l>Q-$41e^1 z;iU~YjbT?g+s8BW{cvt-D9N~-3h72=SjUldPd#s=vVpotd{Ghkr*Rp6H+JHx3Q2n5 zP9zPGZN%2$H6%xYY06huV{T3k1mBOOUw)_=R#@{{E+5mtN9E!(ie<3UON#GtEe0K} z(Sn;(7$>G$jWf;d$%3`Qx$FGTe0b*LOXs&}lCDj8@bv-X(py}RWPvMb>~#=e(MYH- z_?}?1%Ev?a__p=%S*Zmsv2LkPWm0q(+Yx3}SfPB+RI=E`3Jh}E@m6Sr4u(a(-7oRk z4S7Hq7CHY&L1Ov=Bs;q=uR}XYW-!Hen?a%*-Uy%Bel7EP zKDyr`j~{vnvB>0tF1+8PO%LsB$1-kgr)OC7Wq}!bRlJ*sD&7NwH!Ra;loXwo;!h2B zZRNBd;lL)g{|wbt;KLz}u%B^~`@cJ&8KpL)-Yh?07b5wb2e2qG)%u&L8;&|rR?ASXZ07KMIta(W@`GA_W; zjoC2k`y1LhxDWY8?Ir%Lm%xc>tuGu8fJF;F&=q$kliYn%x9(;G9&GS@9%IqeAu4eh2By{-AGg8uJ2V-Wo;s@OckUle#YEH7pwgKN*)`uwH zL2e%Ri=QXCb0h=eQj771awU3%?TkN{UqL7-n>fo|gY$2`;mzr_uyBzN9sK$d+hu7| zTHVL`?9{n;^b&~N;A4SyOKo~0EMfY|e>$Ot_KV_3Q*kYvTg1mXg(|=$Jn&6m8NW7v zL5+QD~rh`RY1}8Y|or=PwL{NTm{5y>K5+>M?>z zY6Aj~_9K_Sz>#A4uF`f$;a(&O*)N=_jwWV8?)E_Ht))VwB|G4Sem$L%@Et8&>qhpv z`-1=U8tms74_hYH(^W?ga^C1zlh9N-C}+Zhf8UG2q1ujGyjCR_WQJigo7p;+#G|ZA z9@!J)A<%9`{&){hpRt?EZ$BKd`33oSAQg`9V_aNL8aQNsrK_LJL8j|UNS486h~M9Z zb5G0AR5q_p3u(o*!*yh7U4#I~G8eytLdJc~8>4P`BRrQ(3a$jFf?S+^Xc{CdX26k? z)!3x;F3~a2hyUeKTzSQ^XVrY^QZG#cjqjm~-OzcGuE@OPKH2cw0ZP`jUaAX_(R8g zu<(qbJ9Sc#`H3Jh-;3$Etm|<2M3!YeI+6}p|1_LmG8V=*XTwJ4Pq^@SGi+p9zDeqO zXh1^|kJBFzXt%D7Vi`VHwCShRcKqKjI|yN(yZ3%(s48ebk?3`WX^D+^-C}9_!pol$ z>#ZEAHwaS1M+q`0st-29N2cqu&~!v!@7*D9M)nH)J6oF)A)0X!;{qpl>focAqN1&Ob>PYnt;Y@Xv`7bo9eCUJQb9lt@JuzR- zw5F})xc*-bWNgWzZzgteW**ALvfC=jR6~|&+@=La3%1hPSd`RNiol0cL14?T!yLU~ z7^Ti~O%we%ZVP{s=M2;2gA4GjfgGq>&9t4X_M%kfgJk&ACCIzofkT!D!<(@mDA-OW z<$F6xGs|I9gmm?>C=w{nIP__ES93 z4G6aYQ>&%X%Oem^a&LXSY%5Nteh&!KcF^`yMN7N z(ziPUT8oOY)*cm>yBSM&Bws;q<8uj7xCT8FI`OAX^{^(wo6f%Z5-aVQMwfrjpk@!L()`cb{gSt^9RX-SNs8yCocJHc#+&n%GI_yD>)@bo($zA8JU9Ad}p7WSq zssc|n7-8SvSXwlD7CNHsKtfln5pZQK;}$_&%OvU&Qjb$|t%;ACaF<-WAp)wVmeAE_ z_u)~AYoVs3AGGI}V*QOH(9iZ$5d%9Evpkx}bl(E4z&70Z&F{!9`8v04lfX3pqgy~SVumi2R3OE7rO!wW%FCx z99MKd&W%)53o+0oDhRkom@Y``FwR@J8T9A0!1-TASRr1P8nIntQm8fBYm`AU=UYL$ zYzN+F&<09O&;RRM3hr=ZS|< z9LQrg!ABBp@QC5nlr4H_3suAwv-<>k3|X!o=q}NwGQREj;baF`oaaVszL+5sr^Dn~ zgR5YE`xYTXV>11zj>tC7+2K{NW$GxppXIIX8Qlhr?A9Q^!4aiRvLg>I_X;u(U3$`B z{C$@B{91+lXVU}k9YpvWU&(RxD{Y9!MByyAg+Eqrd6K4jj3E4_x)WnGF7%|2d2Eodv zIy}UF_5=Ibqrdz(<}8Qs=idTIV*LV^tTUoRFOxd2+=Jd6Izr^1T!NXV9av;hH~A7R z#5!CgO9|U^)h}b7Vb*9!XFKMb-6go?Q2|_HoIIJI&5?`9z#Ej}1zFHTcXZ&R;!^rg z;s;jVSqr_#r1>xA^`YEp(x5QL4?fIp#7{b8>FFoz`9J8)u^NlOr9+-(ZLY`j`2}#F zvW)#R%h24otK^97X^`95g-2Hh!B)0+RHVoe#I%dKowEERxl_2A?`q*po28%|cj8-F z+QIlnvOWeK8q)-EJ&|;{;C7Z@(M(!*PKG~e=Mt{#_e`>NMIy`O`h<~x5u9kPr$#E1 zQSE_3ED|Ov$isJH+Li9lp`fK+izC@{wVORx-_9m-LU%QiBb!QL!ohsJY^)K9nQbBH z^{6u)PxWqu)22iPG%d-VUn-P7V9_b9Erq%E#e8?sUg!P5yp#jho14JVQ1QEGJdskJ=)1 z^--4pb8{B5JH||dBSwOK(_!jjn7c)Z{@K`oXQ$sJk0%PT%lw=-SdGh~qQwYDiF(jY zw>9}D+l#nyHtRra#{g6?ugbEqBD9U&j#bauAYZ%1pTa&eTfIl z>sTpDIZT6;_#z&uDDcU`r`W9E0m%`?W zV*D*vL(swN+7LOOX&lFW#xY06(6U3}w5UND{V;YSP7MoS(}yA4JEs`7vHY3V!>&lr z#e@8LEyS*@QCne?Tnl`gSBz!U<>_dqt0|DViMoHhCff=u1v6VsV>^T}4!kZR1sjPJ zL&X)gZ(d48E{{XWe?~qqe3{KEVnGlg$}$fte;Phim;m`wIdF*S0Ds|jNb68Oom+_P`w6pPip@C^XwmBQ2z<}fA{4U`h`t^+u)E;_Gxtmz`_`2_8;bTWQ z_p}wq9FPKC#e6UeXBizEiou`pW4~;&Ir~yFv8Gp?fZI2|F&DD-E~VTjKd`h%0~9t( z@ni1xqHaAIU_K9);n|3_4$4#2K*lXUa^~DSzY121Dp2~e9@m^LhLK$6=?hqfLZYve zTa$&mr-ft)c<8Zj?p--z{JI6MD9Z8o%4%@ULK(*uZb@VMHAthbJY8{)X%!q|5D9OA zIbD%dU-?c}|MA&WDqDsxH@t)!c7(??42d8IjQ?c0qne`|=6G5Fd=WO+?fS!VFk(Z&VkYajtZ#?zG0bb=oyhUdZ6;GZO5y4Ie7w?T9l7=IngGYf zWlW^Q7U6V)!dUbo&ViixtRa}w=4>f|-@9Gt>B%a@$>kQcY*IlxWVgZT}4c@Y9>Z`Oi%SWzz!v6#*rSQTLR9lWmhJg+8sk57-gVKnqDN@ z%NKfH)nLm7Pa$x9Iu*}e$Wa`)O?H^b3Otg=3o78Ao*jMat4f@r#Aq)2)>!w&qg(TG zh{ib&fba&4{+5C-kIiy^{`kCdJh`Be3K6XDVC_r{Z$ewC#$jD_IeB;MPESm!jW62i`j@y85>pch|e!ou!!7%=>d zQ}m_jrSIWXHdF;U-gG9f&MkoPmP7bcdnv>*|KP?at|&e5A$e8o0NpQI@SfH%*um!W zzi$rXB99JevXkTAJh7U)C3+j=<7RlUvKWu{R-h-?vpv@FCh}~^BAZ@WLg$hW?7;Hs zo=W)A4PDQ1LUbuO+OY1Vs8n>cGo0Mm>jUFR9qxbp9Q;%wsqOqhL;D94;Xzk6<0#AV ziMyTfTZH)zO7)Pe@kIPoxliDc{CQ_FNLXl7wUZtA;L_8?I$nr-u7>h7oZ()*_co50 zFY{SYF@Xl-%)L&SzlU3hDh+0nqEG+wkCH_>x+&7I>Hb@m+I9ZMp_6TwB zV4)cmc{G;)IAJk2=j;%9@*othtgXcxV>&^U^>=LjlE~q`ZzI=CN+Gj4A3I*`gJ+BW z(z%)5X!*yDBsS@qfS3C>Q;Evih0{&D#-eBJj{hoNL!e2UDPII7axT>TpE9v${SLO3 z?Dk}xjPB_?CrU1Mu;gMZwy}K!COa7Zk8#A7r~OFqu?*HyfyB>aO1&D^5Sx0q_q4S%BnW6ub2FDHK#^_s^#upP6|G;J4>e^5B% zDLh#L`;IG7>#>cP_vsDPpJaEp7jEc-%3X4&+zI?AHDUQ>&p^T|jV7@iR5J}v8udh- zZ)*OLt8;KOgkR|g<+sd7Q#p$Mp3QvI#dc_NZ~~by5fzo(};fDte z-|rYtufGeX+xAG}eoZBq(vuA}$>n(d${r{h%{X?&1<32ai5O>gWA#*8$+17-$CSU+BBdM^i=8L$9|(CoU26r}=j~4+e;eoAz4fqyeTV+nA!2RN12ZJp z{8r_NTr(Vrv*cbuCbq+x6bR7|p>uK+$(c7paIWSb9aAUEoxIkO+>s1~?cC2;W7!n? zJ0X^qRz;!_efB-7c7e~+TX4bxaVl!WJkg)m@R|(Ei6q-$gOw_=ehd#B*mp#-xRS&D zQi9)&s}%T~W}&%2{kPJu$HhqeTM3vnHV7vB)Z-V6#A)3+#&1XZbG{uA1s};ma6MIs zmptGxzjh2&s#%RDnw%p;YL~#oy#qHS4UogmjA8+wL;|EG5k^OJxDfO4*D1; zqvq3yCA`w)rm;kXbA2OeQSzfB-xohjaDYR=Ji13F!M~MB%_Ru=Oq7; z9b`Uf#WKn%@Jc#_uHfCoW!L=41-2WUb}GRVN2btm<*`(2-!&wY_kn)hsN!i-Cibecq%;THQ$vU*P)G;yIt* z8VhQ0G}i~l9C%5)$Is^+n_@@)doCl$=Si`Upx4!6=_AVo#4pYx?sgs^afsdibgH0+ z?I16j{ju4Wmt^KpiU8B>+WBC-znQwX%tlXos>xJ(k@=>&@HfYAB-JtkzR7;Z$CrF! zSQSa>FLlG>RpsP0Vx02Ew|MgmmNT%foi6?J5Dg8@hTl!;@T`^jAT;D?-0T!IHAm3VXZPb1-rdkIEyK@R zg}6JNcELqnGqko9W8Tei^c{O{vya-Kd8Y}Pp(ez%m-{-QK`xS3sU~6N&Pq7K=DIfd zG}OwEB7al787EbTPy4)p&(oM+HD=I|43DQ3Qo(dmmjq6*RfY{QLQEUm)e9@xY_@UT z0;H~}fRgNCdEXxUYW_v!m9eSxS|T@>6VB7(fYbXgod6g-OLx&I_K+lBZR zvR#hWoPI&Iax-{l^W~v?Q9f9El;TqdtH7Q4wHI&7;gpJH<6u$YZQ{Jy5*VCrK=-a6 z#6|oLh%Oq#H`V@*2C+Pp9%bL|=Z$zcdp(#_d0Ni;aXy`_g5}jQl)q&;TB2)9);v5V zxJMLUYy|GHQT$r730%GO7O*t2q&kl@iR>MwVZI$p^^U}%C2?JlCK5&WDB5OCDV|LK zdpkhShiY;EPR}J)tqCxsUygU}sl&q$MPVdw1b2NIPs=)k=@tT#xWYxw{xad%e ze@XX&y=pAY-IBynIMq$Wf|+NE^|t8r?;xV7*93Qm9g8N@tySUFeS#tiRdXR9_G&@eo$m%!u+&h+0VWpZX`KLpms&;y;x$Sop_95fK_vyoP>z~1XQwKBPhzsCiWS8Rt3 zd|rYbLp15#c;=(YxrT4ZCYh7y9q$J0+E3vI)2^TT+hl%?Z$5XC`gZVK+YbgS%kY^ek~DTH)3WNbe0aT=Bq-em9yYh(NAB;SKs|tJ z_9>GlDL#l^WV-a$47B2bFL{TA_{NWX1~Dun_j1J?&Ubx#lKVskG~`9dAJ(y16>3ZC z{Z&cZM@g!$%{rvA643VF?@6eG2RMbYjtrZ3@Gah-&fDvOz22vi;Pw<))l`NTf6oE) zG0cxFH5t!4$(% z%_=f5PKbL+k$KR$xsAT6^hERa=)!!G4zI?sTS>4y{eAWY&CZ&PO!wR;1KoN8?rzb$ z&tS}OZ;R4BRJYNG{0MY_YeOwK#Ks+5S@!IL_Qm-3zyPecDa(IxY8Cgvwmo1O-we{a zCAjtdcshgKf_0;8&^uj9LI!WZTJsM4XGae_ILYSB=pPEHoiVd??PNX^if@qksB>to|89tX~!{M0~c!Mvyjk6om{)Y=tuY)S? zpU{u9#V_LxzgNO+7j3FD`y0OH<__CxnAbq!3fh%zN>bz<1C;eIfVT)k7frkBA1*m3bZAj`=3E6^Q3%vBSH4B86w^j9O2S}He6#S zM;pY$X~&&(-nmExaGaSBt+*67_kRYr7RF~j$>GGx<>K@Haf0kJ*Uih|&uIg?p=1!B zyI&99`Xc-VdX31aM*%Ku^@Xl4jd;nojnI-KPd)yZ|JnB$&MF)30}9X>)KaD*f*} zT=*SHMfGj7l-<;5S<(RgMYOom=I_YPlms|4yBu%ybqCpYH+pJTHm5kM5l3DS1#Zj; z_THmFBcqH^WKoiYUmrIL?3Q! z#GS4=&~z<^S=roC(;FA^7jDqP+~m+hF1G*;IUGmVR| zq^=8x9g(Ba2Scd@;}Uf)ekcB0BjEm#&zN(t8lJN3P0sNthQm*4$oL(VurKK?j+Xlf z*SEFN?4O>f1Li=3Pdbzv*5K-yW9i`I7j)HBRWv2&0lAL#;D1@!D}w4EsGa5N9Jzm0*m)Rb$@XQ0+J+sizDn=Dr zv$Mhf1iND{9fWYED>#<108O-2#eZjg7kI23ndL-|aeDvTVV?$jf@GN+b(nhvk=s|v zfxWJ9x}p)U2pdn0s@NTN>JCo&>aB3>u$VyK8^31|hMC@jXY7O~RJ#&`w%r2UJ8?W6 zmfHu>x@-la6Y2^7$I^B9Q~ADstBj27Y#Kz1(k|yYrM-vtl+w~3pOhxivPwk=$ySOo zbKlo>5K_wCdu60T66JS)kKaGw#qpf?b6xN2J?<9W!&_7RxY=@d>8t@i7#&ki0)0ob z<`dSRm>AAIGiav@$6R37iAFLkV>oJUj}U6=_J&l_)5ejY!Z3E(&I~YNcfC7~r9AC1 zOeaxOEXtCrlnc_*ou$5D{?ZzYf3dxQ6X(fCGGf==7=haUOk2pRjEiGsTvc0727 zy(aOgT_Y4>LveZ)%R;swyJql|&qqvD*e?kN6{C#VCHD#NeF1BiPWB+Xf ze%r5X`ip6-@6InGVT&6HZ`}~qS=?8^?aq%eRnSPpB}E}g{Tav?R}zJry%5IkjIy<_ zcm>b8X>)Ks$W(kFEY%)9%O|7hwmn>J{ucWD(HYQ;{7P;<(8dK@LWKR8Z+6_K26cLn zY4?xtmi9uhN)!rC#d4MFLutYEYhe4TiQKcz09kfVJfGl195w}0pS_8oSdvE~b4KH< zt|*j=KFjU2$fLu5o&rr1HlNrHLxV7uljE07p4g?*6|DPNX=)Ae;wQjE+oxz4^TZ-& zUOKhDTm=h?(#V9(Zg^|SC;|8UFhBFrSmxhNh0qP9BqaYX%^qAR%x_e1wSgfMp z9Z@=#0WmE9>fc6J&UV)=`r*w@SbeRYq&s@UtVz+>wSFo&p1U5xy}O{ixq!SsAcc+W z_TA)mo%8c}LwjN`!Km3S#8jmkIu}NvVVe@)049H8CCOUWQ#7!Q~`M zyb|i!XW0K(*W$CFn#wLIf%d}pWRe}r{!(g0vnV$%a`_any_*0$*9xL|OA*x=cEL_9 z?taBRy6x%^cA-WsOk}*xhQqhH4I`h>iH98_K)H!@Y4t$(prl}p{XG8fzgyts=>~Wm zl1F}|sNq%TC=7RZ;C#d~=sh?Oef6y*ZqHY!dlrD!ZQ;aFvKIOh*sj$2mYc~s#oV?% z6l#FQ8CJ;W+`)BcKUtids{`rDX)rmsm`s=c1AMlR92qu^`%87m*R=1#dxX#11yHld z5W5$(k!v&0Q>h6<`>DpD3T~_PMY*f%c*9n%g(YjnkX|Yw^{Q4w-E&q+P^$A3 zU%Dw!!BJOwPSzg+ewLF0gRvN!!?;Ab2yT?=H+o}@3+O#;WF6nq=x)RGfyzr#B~)tY z@xcgaxllrmNM^w;_AG79E#<|yRFU&)#lm~*w*1*pJ$*GUa}=ZXZZc5F^3$xj8q%C8 zjTaBF?f`#3-V=98Sl|2!3MaFUvyM!7_#hIWXIgSb7tYYZX)O1x;TS9Jjne$3s1l9 zB^&28f!O6i-1V-88#ti^uP6FI^6@%iS}KL{fxh@?#(z9L+cl8G_R#N41H5j2Ev&AK z#E(65xs79-DC;x=F0F&aXS6`Ik*MIbr4m17V;dOYdB(fyQ;l>rEMmBHpZTEmU3$Px zG@NzXUQH?O*TabuyHPj8fFBe4kt&D11moL9tYn*I4I7EV^}BlF_Hfsx?4Un4oq>)g zU&-8BUG!WLf&x<|t~K}$9aE|c#fSfronuPitQDKV)JD?Vs3tf$>JVRZ zoDm%9dIz5ZN=e~FH+tjRLSa|t;rUBp_<42wbgGU#F3N_TjAt8l$(8f}a+g+x+=Rb^ zdXg{a3lmh??|;yg?0oEw-^Qp5WP>yKp#m%BzxWAHJ{FMOIWoA3&2?&-*SQe|3Dkmj z2`sHzh(d8CJdO)Ro7^#Uc6~NfUWmjKHaR0f+aHBrw(L;CKz~ELLc~V{vV;Og$NBzisyLVL1 zAr4x43J8tJff@GI_(x#G)rQy7w`Yz(V}A$vp9Zr^JP3!~FDJ^EdRUiADDV@?N%O;M zkO&IH`JiiYU#p%L?kfRxy-f0R5}UyvHsOSK?%cHAD~Tv=hly)M1vXo! z@m&kI!Oe{gFsvbuJ%^*vk!es5N?hiSDP>aIyz{VWDa$vQ-V2}EUCCg{YceaV9v0`Y zj$`w9?#kNNbjkXMLM_}B_ZU!}8-~Wwzb#%o(1k!d#<@KyCQUU1FvxJ;-f9}>E}>66 zcmE($jqJ$arA09Pk|8#HZX?SyFH%GGTS9O9Ozm|r?K9?6Ka6Yq< z@VOCac8U2}&MirO5LZV7`y-$_u7r5K{s0`qWJAp|p2@9Ra=4*Lh-3P?^Woi<)%f6} z7%i$E0jIqDLCUL!7|a=gPtLIX(t1DMjg8Xa&pPQlBR`WzH$FfR+cA53ExBF6=jq+< zBSOvF8kQ4SH9Hb3u8PqqgMX>@bw~KVrJ0OBt^%TCvmx{r(}xe%!}o5c+1`-BJ2B}a z3G9s$`l?L&_>lBv7GiuaS^D@Z>>N3W_P1-e%4}r_G53KH6?H^$vJ8fX`(i-wf4s5J z)`3H+Jo?P6C5L1h;N)MHqq2M+H!PHK@{;@D>9Y=UdR82m#53LRCwZFC*9Kn;L;J2Cmkx*S-y=I%X;xbEd6yw5cf8&6l<9c&;dP+iS` zcSIZ(X9Yo=OcnVi_7^6wo6CtEuX*`u{j@$ZA6!@EkdZ6Wz(+C}trGWe@twO_CgB+v z{PmSo+32ISbqGGXp~Ury-lN71x^Sn4d4#`|!qee5vA9c}=5PN80|QLU)Dz1slVJUE z!1D0ft>NV|mQ~AUl}06IcwZbzC#WUDvaUSxCdd#?7}oXPI>&kF71NI8ry%fJ2T7YK zi(?M6EP~ctBFRgm?VmiM#j%Ej-OqyTBVl;BE7;=Pmya}ZUKPYkrjw>s?s(WuRWRy? zE&qDmc=)523croZ$m&jaDxbX&vZwYCgSE?H#R7FSv#lc&96mxQd-uhMyK;gLuC&1a zCJeUKlS_X7&}I;c+kH$)f1Epx{;Db%*p|+3zqlD3nV;XJpnzO7m&Hr$b5riS&N(L} zQBBQD;BuvfOg5;2krzU-DSZsBx$_ZZoY>twEs5L5c52yHZ}`UahYIyiV6J=^eoY+5 z%ZPKL*DPg(-ApN$>OuL+6-=?$qV%{d>N6hTZFUUjBV9;0UUvi6^g1%qrwIm_1~q%Y zkBI9V;eh4{L8kRwzE~@vZp-7qtG$548-Ir4*lMg-9M63kQ%~>K9~Npzeu4&WVY|GT zZ7Zp5?xi~iL*P(OIjLM$2YIiU=5SEgB3i$RqUjLst*t45>uC)*Kzk zBKsEng9Lvm!Ls1_{N(-}5bM+ctB&TA3DFuT=FPgiPhI9(eq_;#=jUPT={92C-v>+f zGYc&bTu!Ze$6O^c(~O<0!mwYZ|BcMW5uRcM7$^-%^%W@;^JSpMPk#qQHPjEmEmUO{w>jIg^b3j3oXxGA6bn8L!Tyk(4hR+CwGBaUkii z8cUnRs8+KqY~cK1`Pmwh{ahCJvpde*(f+&}88Xnx^4b1}lXGT#f=AC7N4j7UH{qQ< zeSPl;@VQn}cjGCnWBjlsiqXR8L3(JKqmYa1)KX@gG8;r+vpgC9 zCOF0R(2-6Vyt31|rP-hZZ%d`nSv#{FWHwpct0vQTEuv4<0eBL(#x7_nZqq6^a zHr5+p{{EqP?`2dIRQ`&@&ll%$&5K;Hig`vx=QS=TwI z$QK;#gq%m`@$yy!DiN=NO2KUA&yD6zi}%A)^>D22yqYra*%-Y2rwg@)jpmbYdGxZ! zOP0}4L~_zHKq)y1KRJnV9sQj|wM#@e2fk%DFR6=jp&&5hW zRB{l!SX#xbu7j|GV|BJ^ANHTlA*HSvVB?a6$E@~n{tB#rQ*3Bg{i|w# z#ScPoQic*&XL^rLxvvZRuKy)j*UNzGcf#d=)M>8!AgmeBcC?vsT;0Ve>f&`(sJl~S zSx@7C_~XdK|B;K9QS_;PBHWPACzG}rF<){tYK%P3#a<|;cA}@C!m5MiJ<8%8cE4D* z;WNo@N~4#uJR#M+hCI8U4Z|3Z^wspa#q9P^^!ctT(4Lx3=A^oz|8o_=u&D?5QtOT3 zw@E52SXo9+*J92cEm^3*#p-KTGvEp0bEDmD?=?nIa-o-=z`W?7M=zFfIDF zK@P7ijY2E!SDfF(VtSP6Nj`n8Bg%8WLPa(6Y>xFO+#+KY2g>fjfZ?`B}eD|p^5K@uyI9G130`4!{4?BgytwzB~~2jvrOZ7n>&G(~Fpm$~V!AL#9e z=RrETjWj(R0L!gmxL)v@gc^SZVE4YK5%JvR|K8GyJ})r3$vPjOzJYNJ14SnHS^U*e z!^f50ctcu@ytZ{iJ2yQ+eX;}pZh--uc1VLK%S%YnWKk@i$~rxBr*T^xMiVcGAq@06 zyaH6rjBxYX4q`JV2`Wyo8+Y1$Zny6>8m`0qr&H?)Drw-tMqiBcUeEjc$_kbyiwf@% zk7tYGRCec@H^Z4b`O%#Y9I=Aa%y;4TnRQ=>GCYitr^@q^Ad&6qGg##O=p9~kqL@E8 z9jzd?spC_?dYg&o3VGvAY9^v!dV)Rk92pmu!;^K^VGA(o^(*z=>) z$CPZQB`qXrC%%HQ6!WLlWbl$IzL2dBLl~%gYAMLSo{eqW`iRZ7AF$nF5XG0)a#L5U zff&QXl7samCQlZ-nRYSf%mtq4S1WkuA&+}+){6pl`t$LW>dqGi5AcsOHL zA`CD+QgE+4bzl1fVwVkKT=Pi2Y5ot8tUQl`9F{>nOADLhqR_5n)zRe!ep1I6gub zmdVyq?20Elbp>S$SMb+X41*WWK_IrFiY#6(ipMrbVS4>*cGnhx_RxH|7N0|sn19Qb zy{F_}tme+0KR~l{PYb!bsg7gN?O6z>%v0u`{&J1g(NExfhGhX+J-2wHRX|O9D_QqPI_YFP?5#P<0upV*|5`c$ zc(w1Km}NLmS~mjInnQ8bT|-WkbveCrvIHOeMI?`|f#dhov3E~B`APHO@)MRjJ>beM z$?~Lg*==ISvIe5B94ySWOW$n9PBZTK^P;lgLLTzPj%=?XCe7dQvs(~vm3YF z4KDavDpmb>5flnqh_z21WbTPXWwB(gDkYQ_vF_5x=9R>?J^&_bh2bq(Ltgkf7b+Vp zBg|7WU)u~Ya9N0l*{c+A*fO>=?s~;FO)RDQvxo3-Sz9Y)7%?44gdaI=HW4i{SZ4Lh zdHhZ>mg_Da2lECCh^Q>f_Y2@20`deYRVp=RoscnOetN z$)jwE>i1P}$;1d-ojXY4-DH@(i)md3Jh>9v8#I&YfkXb)lHKZRc;wP!G?rS$v$5I? zP0Sb3wXlR3-xI?{W>L6yvokld%9HksZh|D;F4B67Wyx-58Q|HeT<6nA^!Rr_h`C-t z%txD`PH7a*<{~-!f?qUigbNgUG!e9y!&~YRxa#(z)YWrZX<(~Gg) z^LN@JuDbpzmArifUPiYPTYZ)%{3`;NJ{62S2@D-Z{L!#((XQmn0y#jvZ&qkT_KJv!mCv319z=ju9 z+`YT%;M(gA1>yB1ew;jxeC><16&HA%+h*7}ULNfy)RJectK#HH)<+{VpPTyd4wdt> zhN(Rr%s-n9=_`ijK&P}W*xmLQZ}Ud-zrX5&wO;4(eS-o05UY(2@0b?%>9Vg5;oilxWSHm?iHpyE<30QNi@f#|f#GWgNw=9Q zZn^&mH}IRti+)$^@Y4}IYFx&5Fp-1;c^Z}`eI=HA-RYxgx}fs=FPXE9bzAIoLbD2W`e2hdPGVls z^yE0sj%9_3UA)Q!K}|$$X(2>2?kMizO=5H?mP$*p9P&f?Bz)oo^ksUyYjx+jH%wDu zXMGa-lRLH3-_?|UxOoxA)wK{hzYwO|MB>%i$(-}&aC*RgXfHl{>=`7Quucb_AusLr zE&BL|3^?2up^ZPAfX=^!WwSM@ebPvLu#(Np!LPW9v&yL`>+!AcsUyul3L#L}2NlP; z5;Mt3=#eBNaIl}tpV;)CrcH{2FZ&Bg)V3OMFls`pt&_MDGh68G@>o*zZa*dZZV9 zdY0|KPyUec&Lyyo^*2QasZyz^ZxG3D?ylSKaJl<~sbTIA)}2|K3Oa1YNO-%8NQmu& zSl4GRI;-UytMBF21^Kd9@Q(;&~ZYF1yB zFy%}DmTrBMI^qBl-t%%ai%I*rA>6xRy9$(<*6ycj9~oHk z3)-F!;2gthuB2uZ9O?0fH6t2`)nx@7ndpo4tL%BHWGigZl*i%LjPES?2FS4VI&VG~ zVSbO6+F8T(Vc*D%VR2BrAP6PTNYbej{=l(yA_C)9MSkSp9(a{>p7{z!(;X9a(F53R zoxb1>2aBQu>x=QZbuDF3s+@-Vy@a}_#pK&T)+-bciFIk;c(WS*5UUswq5dRPR2_?z z9^;rp&E%hf8_w9MEhu+i%HOtC3Ub#6LEp(|e;okHJ+Ig7W{#nk6>fNS2Kc$7<|1ym>Xuf?JE3339Z-uVVjm1Ho-@qbn3s zRGyGe{+gJs+=J)S$MH?4WK)N>SSVRmNFsIWATYcEpYEK$S@q8q-SA0p^J5Al)&wgS;XY{EO)KJ#uAsRI;=jn;;0B<6SOAeHhjMc-ij`6^r0%z_}Gt*kXumYtGU1Z9S zbTF#+#gt?6bn+_-%8cvCTSB;`(Y~~`!4DREt{~%PO~Pp+(RivqlKb2Ahc3={hHqb+ zh#*c5FOCbv4^azJ`FfpH`d9=kW0|Ejz^h7}zL zfd49=Y_CwpyJ`WbIO9#Kd4x6`J)aFui;9Td@gFcsh4IG0?|ISPB_xh%AJ;7sp$_xb z!0yAduyfOI@@7&WOc?0Lm#I~psfH#TZuSQK%?;$gEH(q6FE*yy^HRQThuh3M{gLI& z6gm8Woy^0fdUrl&k>^S^_gKT}8Q+MY_zhh95{Rd!OH$g<4>HOB@ZZmo{C`TlU?w<+ zlba1_ov$8NYt{d%4iAS;IuT%(GP;vNmZnK|1d1t&z{4OSl+Nl z!@w#vAL7n@BoiwrSUruz%ahk|*{&z3jpfjc*AnDON9E~&vC%)$aH|NE&R@ip4-}}S z>Tp!hW0@*T-*79}zF{58S3yI+nV6h;584I3_-f-hqVstGHcM9H7F`X#__hT4FCYP= zSLc&EVLC{!`l9Qsy`0;sYU(rlgpljg-keKk2YQ04S1nPoF9M0%EYs=dbBpJ9D=B5W zw8y@5GV6;w-g%`UaIxCMpS9Z*fwI#^1%Bs-FI>b_w3F_!pw6_BlN`GNSTZ+#_zSvy<`CB> z$?|%Oma*Uexgl>fxlMI$(uQzO{lJW_ca;IbrA^t8Y>D_7{EntOS-_&LZjwv!SUbUWj#>)3ovOgHSv< zT$i)E`G|Uont?~mAJQsU4n+MfcD_@gT7SD>dtW5pPQ1e{(+H!|{x`soWeU|xB*2u1 zf#_(qo`jJDFpKG{q$d}W#9;=wj_J_aH(%v09L=ZvKj%Pjqn#vni(~nFmh;JSpLVo$ zK?&p7r9u<9QYAviKVf~c->S&26apnXSnl!iKNeqgN3&a803LfNMJ^S%;pNqug2Hd- z`17;atzTpa_vB)RGy zzt0^Jy+w~+brEWhIjx=0IaUzcJJBoE%zF1Vn65)04jQd>m> zEMdB!*IQn4dCMiRpUrruYOkeOkEo$dM_$5~Ql_zV5I`Ekx`suay!<*5dg0K}T|=7P zM@E=E#v6NEi0wuxZ6R2$A~@T4)rkJ_2XaQOvp_}E$+BYHx33%0$%=C^6V_$TE(`NC!cb#G7Lf377`6H7ta zpJ`=hgjoE`siE%CmC$%Io#eMLZSWm=fqv&M{>iUqKs?`pmrpra$UK`%rm*kMM**iffL zM3#BryfS&g3b9nay@xdzulWJG%**^VM+FTW7>}{UksEAGr_1Fp!nZwN$+G4W##ueW zhYM6`_l8PvW}odjtrYIQehjsh8rpwVtK48!ILq9&mF3y9TrBBBmr--2HZ>bi!8^Oz zef-L6?&;oIsvXI)u-Pp}t@0P_QD=Pn%BN)Gd|iB7+>K}Z$MI8LbLs7>SkMS9Bq}@I zVRXtp{32Jxt1oG%8TJQ-x8R$%43M7^i7&0%NWO_U*eHa+u{9OM*XSom=7ymMU*BTG zKp&mV@bKEJERwU%9Y(Uw)}Z#O+&`zekTfy@5=E*>YOoI8c^rzzR_b!0zTWglq8VIM z8z2J?74XIL4p!Ny(5#qWaQQdO0c*U&Idq28#s3Xqt^fD-`Cy5A*$FA$NZambeDs-%2SmslyGIiE9WpFFeavzitdO zbeZ1oTq(I@XF?YEbqMvzF^8BII@A#33p+@4e>(VivL5i1``k%`JGAk!3rtv5NA~U9 z4c}*oqKQ!{>DH1$CFXtjV(h}TtnsGH*e>iU+D$&>WP=&Il{`+DryfmgCcGMn<6jZ3 z4Fl-yLO&>EdVrjDrg&5_8b^mkaRoj9=qzVvs2JZ&YCGgGa(Xbn$mgZ5R_~?{#z(-> z3#Ej|H1&&XnYN^>oOf?bFA1DbB=n%kc&&${WHpXX7N^`%6_EVk2a|s?Yz$I?Q*&}b z zM4UHhviyY5Gwh}y@I`6Qi@Ynd_ds~390m`oBQ{;Xpu>>y9kHO`Z6U11F&Vc$sM z?|4u@_7soW52Ll$SXOq;Jse2_x$1;&@S1)C|BlzCD<6!;s$!N=6aA8#5;Y8W%?-yn z%GXm=F4s}d*+bZl7?O@@;{KB|r>+Zu?sX%!r9j6{ujGESMkfcW^jW9tt&!P%-5{+niNXqq#Gfq5%cF+YWQ%&$9gj?NkM(&meB zhGkA(lP?AFwU1C=S(RQ_s)Es<*zRwY!nHWY&=kW^SmHeo$%w5h<2o`zgl@HZ+w@1T$aoUb$nPqW`gBd?7# z-jaaNqe5V81e;q-|56_7npZ2zB6~FE!}ehb@M{a}b`0^MWVRVB!+tXMbRRqrVZBru zce&xok#y(sp*>gHHxtNXrb~?2P3#Y_JF`{;C_E`7TgAuX1@=yt`FNFUcw0n870v-{ zX(#-M;V3Ey!-D5=WYhINkY~KmNQ*?S>7;-L9r1#7^s>`>|GC&iAuX5Bg2?wdjBMw?q>?~);87N=PpU# zquv+(AIH|a<0ZLKf;~n}e17O&P+cjCDo;zv&b!hmvWNNc_q%ZZ=tHL*wF2$$UF7T6 z8W_XyRwG24?)1!r3ru%6rH616ih^jGhaX(~Q9*Y7Fhg0BXiQaz=9=6@pzf42WZ5aCv_(06uwV>iu9W4Y@m@`&WTQ5du@0P*D8)DM64p_gU}u}&_v59XLh zVU$ZIZ|}GoQomzp=lzwp3HHNG%r^T?`YLrGGQb*ZL-XFj z+oJeV?-FjB0OYc}8=CXg1>UO{@?F= zHJssJdzx8wN{D0qEf48fMO~=+G)S_(wZPfuj`+xU6rHhJ2GvZXutf7M$Ja@wnc73x zrE;$h4zTx8?MY|y-(^ZeZn2J)w0t6Ho{E#1Ud4B>J-2^-18tKzF5F@57s<2TE)ehf zrju2wMfCEOAsp+lu7XKV*(~=s#Ddy3)4&&%kXn~czQ|68E$81sgLwsUnWuuzjGNNQ z8P8qf`_YxmJN7^9dOC3@fTcQ~3}_&35p|%)xQ;AEcTRP-Kb<2zw9jg96TlO(Wb9hA zfDHcUflIw*1y5fj^KI50fIF?$DP>cALqygkI$wrR$YV*3tEZW%?ena z`Vc3SsZc>&9VoHSZLW6;cj|T=9a-`i7Obcw$2wlZ^%X1|LDPumv(uIC+#xOOhFDhh z1OB^nN$4HB-Kvh1Vb^-SSnk%J2KrCR6%r~Lh8O&T_U&QVG0&Iy@eJ@|WEW<;kK^+S z3aE2@EbM71BxFqnh)j5g3p5qDGi9B$@`$ZayRwLAV3^`ouTh<)qxBY4(^QOgppw1MG{5#2oQG#KiU}%lT-4vn;=2-1TvI@-xe19)69B z@hYJ<?(y3Xv5y2MjZ)c`TPO!mt~m}mlC-Sk92xzi5E0YV|h6C?_tVGmIpPV z-=dhu-dTQXf`zkB@s(dpgjk6*2o^6RVS|!rp1^cCrDohx%}M0Y*dcr~(AxnI)*0fy zrVb)v`TX*k&V&t98nV(GMB?w~OgEAG&ZkJYO1X zID~0Z*XrRed*8i(&oFJw2MBOs&$BM&bfuruF?K_kW_olQp4N#*kqyzDVyq~&0*p0e>vxTVi; z)BT1+Gh5WA7+A{qoR_AeR8#90(@WTa)a^X->y8GhZ3w`asJE$+j-%n3e-;?J7LlbV z*?*ROf2XBq^47=Hkp*Ll zoD$w6W-_gEc%wHS43p*-H$S3wF*@+!DeKe@ZG~&Q9C4J&D7p+s-~)EU(mei_oA@(@ z7I$BPH3`jRnOP%@W4DQjht5PvR6t!0hu zB{X%HC)lm8BaOpqA@Erk%6$s42yAbqHnq(EV39$R6x?xxwv6Dj$yR=u`wWQP`i|)a zDoC)iD#kM&ucl)>ms##l^Sl?rtgc?7?7thLSE}Rv-Uf1UPb2JLoW=@EcW&XZ04i7H z1iQT(NZ9)~P{`iD@pe;*S)d1sx{eUo1|;#nsT_n|-rpf+VG+4&tbq!yERVg@ky{|2 zLoM_#!lR?DL~dIZWbJs!^dTyAKg%QMC9@o)@)Yh`)LZKCatPC!&b)>z>^8A=kr8i& zp&M=ZAtltG@YH)?c#s3ydu!9Vr!}yaWdI(#9?SXIG*f>KSFm4RPki}(&|}7Q+RJ>2 zlGzwsPPCBNqCn7Lj!EOeoY&!L!HZx!~CE^n>LAVYk=AIa>JeSpdq< ztt4*-heP70=kTPdf@rP%0}d@=nEFfK!n$7+&NE*7$iZw9^F#o(z41bP`=!jmbCxZ5 zxuBXv*!fW{Ni*>02FS+ob#S-tHaag=p*_9-AcbMk*UNXg85dqsOW7Nca;k~^==cb^ zZ1+#J*h9viI0gqb8z6E|5vd$*g!)XU(Pnv#yU8n~JCB?NyR+@2?Yt~rycvairX~_U z(LvzY{CSWja^aufQ^h%K4`rEeb^TfJhH03W?(DbFiP1;RL~k^u;v{dWJ5F4yDkyb6 z!9S`o8Kz_iV5v$OX^WR;y}04H`QB9Sy4_^5+O|!2r;th71@@Z^(bW7K(JlQ5r^eCb`%I<)sQ)5f#Ae~UHc9?T7;l1qm$@Z@iE z+@l|j{vpwvlZzNkX1TJr@3H(P#gUjO5`-bT7ODEJ{nX@dI7FzGk@inB@+5IDQRo-6lbczqw;bh>YN4q#56S<0$ZZ<_AB@>PV>82%N_7 z@WUn#o)+sVh`pZ+<`Mbi+2|%{u3~)FYZ$N`-dT9Ya2Og{T37$ZcnQer^OS0 z(~(E)psqfTIB!tJN@pKDwJRp|h{;$u8JNYoJ&K4H%l&@M^gl-wvv_{iO#8cLXrG;S zY6s|K&qO)+O(rka2f+q!*nhK;Oj~jQwjGwkA7koB3(NX`V;O~=Ef(C|yN~Fv?baZB zuan%k{tmVb`eE5i37TKr3C5na81qeppOBaaMN{YDgo%A*j-e5H^+jP(OboZ+k}T%l zVfvrRPAOaaztYvIL)fVJ=OeVUz13#RcV4}%B;ES@A641s*-Z^yh@{8~@xRpE| z-vqmvRxMTO9rsKlo~{cW!ozVQv9OV8apgA~@#2=a)8!RX!Wr)Z`2{g*4!GD^n-0`! z;)dI->p3Hq6KwcO$5-7G@^x#*4uB%dOc?ppmxOc};@$s#p=N~<-|#>geVh{u3(pi0 zJey59O+CcHxHZsLd8|R#2{MDvPQfMRv<2;A((B#(uOsr$OyrF@G zGxPOOYnIu*BAfUR&wveK@%T9HAh$e>4@IxzA!%X_x%0)J(sonGyfQ#`)YL=bz1yfh zR)xB>iQw-sQ5Z|_a*0P@QHg=;aOFu8N$~j$8yQdd@Xj9MclZQ6l4}4iv4{k^jK}p% zdpY6iHO_uy1vN!C?oGoM_}Uu*4NxI zm3x*tg+O>KX^J^SRQK$Mb(@SaGxH}oDFQ=LG8UCYD(c!|`Z(c_W zT`P*Aew| zvgmTb7dQEOu>NQ*2wgpdd!ZFAu#oM@PcxQq>Z4uh@!^Nz(ug+ldE*=KpBRRxZAIxm zu|HJV$PV_&*g=?;yNmT8c|-t`25Dr;z=e z8WSG($HbeiFtUc7ex1bPDuFnr_wKtTK_9Z+r)6CYZrCKkk6)b*(~ak19`~DM293wD zzoSroAcixOl0$RGi)y+%rbypur~Lshz*@V6Y!Ckod)eH3Df&C_Ub__Q`}<3^tNxOy z3es32b{%`^+|&P%1dXQ| z?meGMzT|tL$9`!6J)FQ#@i_vwyE{SQND=v`tBnZ(Y@Rvj#5FhO(y%Y~V4lk|6>DnY znzI+i&S5js$5tp5Fi+*Ccif7`B&uWe7&>^BX`dx&o zdH)8L)Jxd@K$|Y#u8rm%QLN7>j?*J;)VJdv)0EVcW#)r0n(_7*6#Urt$QVu6_2T!S z@%*>_6?9x=EVSM%BCUIqVU8{9Zjcn?`ZRyg=uB%sjaHJ>sf%*#mTIJGy=I|GX>-Y|H?x~gxz&n5$Vl40)wrt>_pm9t{+jrGp)EL*>Z6l(_1 z`EjOD^k9IzbZLMAuUqK3PMLPi6~i4P8Q)uTm)oxvOEEfdNap|@Wix1%@70lJHAk$;SMHB$Rc<^wb(+>fKH-)8ejS;}`;~qWWX_1-xVxof>|6!xI?KGk7Pq)g5{ zZ;pmIwVG5&71*p7zSbJ#B-UW&bqTuWk0!ix^Ml!r^`yR74!!UCVquF1&#O-xQfzWT zn&k;xv2TMQwsU>&S;9@xbf=fsABHK9S;pz9WQbxqgaZl^)c+l{WQ+62qfa_G z>O=t3@5QH{-em+UZ)U-t-NmG1zZiaDnw*O8EMDUUmKi-dl8%iPq2`HuLEtnKueALp zZR}@evY(mZ@|c^RJ{r_CyLhkMlRq{R#vQ&G3L!2!XutUji83+44yNaEU;m0*HIe;|{o%Ou!HtwD+d8S; zs~6yTs)Q_N9b)DMte0@`JFhHXhJ7x7skhcY^0ZG1X%Wj?tI8lC?T%MYC<*TDvf#@d zQi4AZ10k0^x2sr|OL;*)OrMrZDyHXyG@B3iwNd*Db28X_$0gL_)UY0^@~;w% zTQbP@19RcnqIVEtUrA*5YNDNaI1bvFa4|kX^xW13!uidZ?IZUC)zG=Dfjl_X0rv_S z_wvb|`;_*aj&yNi`(6WaRDB2LQzO~4GL^_ydf<~KQUcut@qF=}cF-8m36$OFlb`C~ zS>}DC;ZB^KdLH%dw}-#0+Q{7N^{__D3kBblY3%(D2xg!8>u2w{jR)RQ#S4#_-l>u- zZBK-`v%)Yw)QG3<N4k%hVC$bAoY`T-U-F@ver0@})0ZN0Sv(cCoQXswGcj(O=nq<( zy$4p?w-ATfdbsUe0N&TDA~oeQ@XPHvR5@3Y<~gFM#&GOOuz^L?`{CfiI)lqTWs?y< z-a#yT-gX9UHk=|?zo!U_upQGCPfrVY1lH)xsSab zd++Q`_9zW1D;nBG2u)FmNcVkRM=23fTH1T4R1_M&`+NHR^*pcF<2f(#Iq%Q=x~})g z`A4l+S3%CQtGIfm1}l6Zi_du0+@V3P~5?hXoXeLf}(8T={FeD$BL%$ZeFXh za(KTvhpzK9#nc*}m(KH1GY=QDu`5qXc6ZHpWzkKG>mM$@A{#O?Sl$dTNaT4qw#8pS zn(r&htU3ip49swhYcNjPszSrP-EdF5n)rLuLDA%t@$kr244cyPY1^27SmhFiH(pO5 zc~8gDBg?o3{MTMOFMAKTdKzKw?k2k7b2gZA{&xD^ZE~>Ho5@V-#j!5F^ItBbE`C>5 zBpPUS0Nxu)NwmjL!Uo{Q3z0bF^i`5;f1fQsxf+BAc)xj2HheeoN2A%QY@SCptaRkx z@ft=Z@*MPYm4OmWTl{1y#*U4`u}_|mlB2C`)#_7Fzy2#tT&sak^zPyEKYWk(Oq%yD zg~5W|`E=dhMi{EXH5hS)LMd-KcBCasf^TzX?}3-e%kb3C6p z-2NyK7tHVw?tL^ALJxd`scW-nEop?ETobM`e*xK(;?Cw99DvV{>uFRe_b)HIj~8eE zrBB9nvEwF(;AL|r^*?Wd#p&VPe_ZtxHi@;G1Z^@*KkKyaoAsE*6iGGbY z#p`{e@N48VVmDhAJN}pV>+YBsRQ!|aUw;A#yssgrI~yGH_&#>wPvNCAeVNV0Uj7!j zJRNpFn28zpJm?cmH{3TtO`M=LQ{*0@0mskZgHt@`A+TH>N_xJ6anL7vrZ^jx@%Qh) zek(|`sxy;ou!bum>*%8Kfy`jP9&A}5#g_kWhH>;3R;KRE@8e6Q3a+|_%cF<@tci{up5Isw>>x=xfhkuSX z#x3QY%lvukR_61yf;(|N^oYegbb@_q+#7D11jG0}u}yjcJu=B1KOR#Q$BvH|4Qe|K z_doKia6Xq+Xbi>b0^VVf<3w(FXR=DI3m`gM&o#Fd(53B##}qZ$@ePeINGcL{7QZ1c ztN2`R?+bPO_f~P8_l5m0VxvG71>xVd8A`_KlMge(mmq^ zOJlqjSgD$h^yOUxnOsA=!-_Tvem%+&iw@ zvf&{hl#f1CWI ziLZHfg!cgP38w?1_dXLLJVFd#))&x`Py3@FGz^0bCKBxPp3 z-uHvKpvw1<(G9oBlX_qFcK8+8E>}*^wJ4$UI$KnDVJ@`PJ_KeTdO-2NJlZl?9n~)L z_u$j3#GB6o(}t{ukL%m0{l08aUf_$_FZ!_k6LUfBQUu-~2IPm*Q|25WDADGvSv?&; z%#Gq%<8)J4_f0OmX^OzNkw1lJJ^Hc8+%A@Nrkn4#)8W_C8R%=~L03(5!(IIch}C{f z7d@5Hf~zO)!JwKFn(U_und(`vulW-dc;`ao=LkHvWd*7BcVQaV*6^jemNw2;MyqEw zn59=CTv{2#j@1nTU#`>ME7JzM&s@UvX@gixwmNF^``7fM7sSLqg^ikF2XS6CbeZfA zFz9)V%T_s2l@){W+r2itd&NYQwDvPQ)b#=;tjVG``RBj$vcbMdQ^+FiMi%36NP>-1 zFKc3--*<6=Y%*Q2tBlP(=MIAo@SD-nM!5ea6uVPwZo4Ps4#20y+9>{6L92hXKy(l9 zbYA36ly8PH{jE-*E>}sLuOJNb;Ir!d33OH;4?G}H5HB9{T-4@h4HmIYFn&=EO>p76 z_awg0G;k)1T(g<_%JZPLxt?Y&uYsldUTAValMSqDfhc~7!>X&%f1tP8whRWMB8V!v0U?^uCoW zM)ADptfN76_lF7=cZlnge|)3QhKZq@Yh^Fk%8&|?r8PkiC zkAQ$qH(E*!EbLbPX0KnfgvvZ&s%ww zB)B|edFrdd_f8vC8JYubWj=WLav%09Egz=yJM#D4Kw>Ro*rVV;VBDuOI#d~Z9@^kf z?$Of~x3RGf$Ki1B7pm}#Yd+)eVo%MCB=Zq+5V9x?NN_%_eA)`L`TjF=R*~?xNRize zktNZzTv%%jej`_7jfE1k4p7F2H*K(L`2+GNb|{Eu2Eo876_oMJXTzL8d|vD!%#AVt z@rY007nnt3AGboX694{|EFd{{UM&CI0f=&JpclMffRfccRQvA_{jyRD;x8YB{v*HA zvBQVsHhxDltbLhOF~kfGY)XT0gIxOQssaw;IPli(z3_(OPdd(`cL%6G)Ect1X5!U{ zQmmQtzzf`~_&~*vOuK0WvRvnoSzkqUe;x(7O?^?URz^Gh?y^DKt)Qu~iGJvx20J5z zFo*NuaoS>dz@N#qj<@8=zc85AH5eO@eWsxi7C4h@LOv{tA#?3iQRCV}w2HA$T%P@# zO`ZP)0=Uk6{N-NJ7lKYt4U^&P-Ug}pQK7@t18*U=v1zoyWn#oDm&=skEfjeCc; zDq`K%JGf%UW8ssT+8{8_g2%Hz(^j(r_+G+y*I_G2$%U(Icbqi{t?KApleeY+H%{r)!UBz8oPIu;{@Yf; zN(7uY@;gX=Wixp2*;#jFs36v?hXu|og8t9n(bQr$JU&cL?4`a^^iGC=n#>#cy_|dT zz7560C&KX8NmJ6N>JiJy6G`@gQ#Kp|tC`xEXIe?~+t-L$#Q_H}(bLuR=O#55Pg5WfwNWSUA(viy5J!gexkZmco=xHaP6C z9vf^ioO{Z7Z_(oCVzm2HUK0-3n zd0K4PNRFy51kvAkxM@{N!}|=y?im4CTc%0;YeE=v9wWJZ3<|A>@h(>|K}CZpeNn{u z(|B%%*p;jdf5pr;IKt6l?g8Ka0bDlU!7CQasY>TLh~+zlZucOZP!HNVrWSR32P)f zz)4<*Abesk9y+}$gn3-M7`f4lynGhOWSU&Sb!a*L=4XiR@!q)L?f9g zmoIuh<0xo{bi*R;HJ z{=Im(_tbCD<$DP~pCTbqQD(3;OQMHK<~PXzm6h1PLxGL7bw|2SPJGnER3xXQ4=ct7 z!E5d}|I0nvm&yY%!Pryye&z_6Dg6naiLW9(|5LXd+`(_+(~92< z&+l!eS{-4Mn~1mK32<9B1GmqXVuN|kUV~EvzA^VB-=BTGgF|qYt6gHn(m%{$;1d`_bLpEBp08WacV*@+!pCiD zZ0(FL$zAw{Z6DlUWsC6#lWF{RHyrm_Rs8baR8gV*KjCcY>}oC21Ny7W7Q)e zG!2B*aapjMhx6;qn7*oa32@wy0(?8nTk=u_h97wsfYTuu(5{6q zvnpuo$={Hs!*dS(-O2S|5v+Zt6C@3-q)|VUp^!h@FGDBL%v0{DwL?xkS1VRjL{EUt z!6t~gm_rv_8jdZ0xQ5NsnS?&fVKT+%B)l=$`Zt{6{)?)xB(mZ7TejNL7X$-~=!-rG z`uxr-z1Uc2Ztl%ixhjI$Hz~ILgfvd#`pj9k^w)bLg9Ssj$kH_mRDlAzQ`2n0wY1P&TZlp1eo(mzoV8 zijJmpTKdDVi4WoOrXo6+d%oNTgyHJD!v%TXs_^D(E}T{VK-bJpg?;CF=cE5dGCN`s zq&3C^Pvf92JM?kq82)elwTa28N9^qFF)*~dlfJt31JuV*9Fxy;8F>=)I^}6a0ea3v%X|5mV;_gE^Uk-hj;nA-e2kxu~e>Nb|J?lT=AY- zKXmN-0B>eKrCDRS)`jbA&)$Dc+QV~L=C9jup`?VS%>NFL!b348x=Y}YB|uYQB$~Ku z(IM4t2!mC{4H|ny3MNw_VW}8|Jq5JcKok4PgyYx$CXs1FrqbD)Y9w80o@%FH_Z$;^ zcCwAawi3|b8mhmSy~swNJ1jlD7boR(jkrG1i+jnJ3adr#XnImr9DgiNbS(22sK|H2 zknCLg?gZB%L~!1F=o$%{7|L`;tb*!EZFFB!KE!JIps_(8_Gw`W%;UH6LRlnb&*ItM zqk*8o?`60963ky8h4YP{60vOulj^jV;ABI90Zu*>j=vTyN(yjSfcbTykoYE_ZkzN6 zcIrpsj_M-ew-GAr()F*B`8s*R83>J7g{wv>u_ilrj9e`%jwQnxgKE!}}|j^}mU zDbhp>#UNaN#Zx$-Wh7kZy}GeF*)&J}4_xEC@zM5$L^j!%Wwh*<@WxLm3DBs17ma89 zro*eHVW-0Z$*jH1Z!DhYHy!ivl%&piW8goNGvy>MW^Ac*9@HN zE5%Ybrh?5)u65tyM-~h<0n10eaPm?$T{eR!HOmI^ccHy7cEt%W3GTz+H>JFnPzn3@ zgroC3A+e9W&)&1`lHKFPXC+|GZ)eS3YAk+LDjel{o|=QnH- zY7&L7m14=1x4c6k_C7`?*(N4wb+VozPq^Qid!_G|fLV70=DW5CjUH>TQQtecpS+vO zw%5Wsi&ePEDTEr^xS@Y+U-3SNDWZ?!K_ENg9&C0kr3SB+QBM61YI!^s-iXqH{DoOy zSofJmT`z&>e1Cgm!b;*#Z!mLZYlxpvM?12oV>#FR%^0df%HIaF^-l*&?#NENxQ1Np zDA`F48aoin_&vQf^(CR#Kd?1wb}(mmEiLb?1^;uw7!_ehpRUqJ`-iQ#?2w7*qkS&Z z&wc@>=^Qf+MEG=N6dFm}kwd4N*-P99U*qfO{*5}A`iB3%ttnJDqlVdQx~;?ihF!Q1&69-V5@NvUGIBP&{hSETxOe_J=YIWOgyFkI zW~A0Hj9r}F%PljPaL;k1mSpZOlKTe=+`~2Tvpcbv9L;ojPk{tK54?w)k9a>q%>wLD`;GE<}qZFZnLqfU6;JO)W z8vYNG+qhQ0C5fEyPGuf^?yj~jqBjFlpn>ZTKX@7o>w3JIw1pzrzm{UT8s~X`7j)yAfljkZpm-|&Gm))Z=u?_6l&{zPz2hjfc9wuMs z^If$J$-L9f&P8p3X-D}@b35-yl!xUaXI`1H^5Ddcy%nzS*X^{6GkJ&@BF(94Q zNrzZ8L3XPPjw@1UvG-LldQK#M9($AQ2uNa=r}biK2E^OLc3c~caWe8&tUvnq(x2px#Kj|zT%N@cZn7!PXjf97)CDQ9>9lM zIC@w(R>V#s^OL93jFq(#FG=9OGjLVe1cx7Oqw7`6p&!r6*cj(UZ0`lL1Mgg*awWg* z9x%b~a39R{Tp`@M)*U-m_7y)Im@C@+`Z(_p=z<8IA26z9ASOTNbMf74#PePlyOFvQ zPL6D&u}bmPiDS-7c1aKj-4hCF#yt_9;aKWo_mt$F{mZ1X zt)XyqCLL`s0uQ=`j|2M#k&{ zR4iMKd2veYl+AGPE)9g%dXArd+PLFL5H2>pEll$_f)DbaKx2D0UCgrxA~=7T6~B6CUqj)|J81dz7hRak``zXqfW(8zzj80OA>C7B6HYRzNel3^Nb zD9@$qLOLi9BbVHx|5P7`HJ>fthtCHRV#B zg*;=N9eZ&R3Ek*k>bYO34Fl;|k zN_}Me;0vWYn348aXnJTc$XR8S$n_V{x6&Yx}Bqbtck&zo$Gk~JJYR!6s8nu))7 zzMPq}4taa@KAYA)STdVWeKZJj&hm~qodj~!Era!ywu6)5wRH21V))CSvE&wOx_#Ji zTirE3&Du;PcbSo!@j(T?A9z@aS>4xcQh<3$e%4+FHm{O?mH!A6I8Ig# zoJgOo@<7XxGUDSh&qU=}XThB3I(g>jQ2Wb9I4g@kW7;kxz~ejXUw9Tw57g5Y&3*U{ zmiKc7o3UfLU7*2tBWf1hUmx+Fy=(RXk3B^+a84S?>0oJo0#Iy7|>ju zL+u`Xgf(|~Rcg0mpIOkrzS8f|;f@*);Xkuz5XcqB)@CGkpWObiuU+(3c z;m6!jdwL(S)rW7QG%eoUTGk0t-nn%4avf}Y#CbyYHF9Bm1atIX2^;3O(fw9Myf45T z|GrgWd&9Zc{vGGrmyozle9hEn1j62fh4j^`*=Tqy3a2$cC1xi(S$Cv0r1Lz4nNPUC zKqCMzKb(>@X{<6#e#>(=ObV#n>uyLl<2u!=#lr4As?5^47aQ|mUWEGFt1&@dnRynt zqs1j@vEv70Q7eo9)3uq7{Y-6zO$$;aJvgw@QZg|0G{G2}v z$&GP=?AoJVoK)WT2G(*;b!_Y}daPC!1UzT*Pzd)^+}6hwu7}s27L&9fcsy)0PJ>}H z@~DOEKYA>z7biD9J_RomE%B=HKdN}=BfRzFx|f%JJffFn@a%s9*g;SJqcTOM3(wyk1FGt#)HatB*k{?>i2>D!`*-c)y99 zF7E_+z|uuSU@_-HW5YW6?%EL-JsQMh59na4I1-&MB@jiO&+JT(9c+45N3ZgkV!t)- zUO(VWXI1e|w6uZ?kTUw0K_ZQc?f?bK%^-M0n|4 zOmC2pc*!gr6NZ|TCW{Cbom6V$Np@8%kuBq_czle1UhP(U96SnD5B_dY#6?J#Kz1 zQm6=%mP)fNn*8?BF@txx@?2<XE^H4H7Da`iOcDKEc)ygm~X(f2WCnr7CE4t$#ZHJuK`Qmhrp?< zA`0%Rco~&WplUkDtp)=4 zyJL&?P8uCJ06bsu&-`ZxY7E_S@;8qslyH29n< z_p0!B(~U$D(_F~14)k)%#Ca7klIPWEzv&iO_)o^1%wRlmwlCcvaK{lv%3=rk9ir;5 zGhtLCg4C1mbXD>o9Dg(%`}$8Ne`n3)9=R%db=N*x`{)#moHr6ROd4tK@fyhg9)V*A zc@y!{5VmKp3p_9_rv|R>SZAyv-g`A$bnDtF7|Zqa9?Ns7@T)HVNQlI{L#~sc?UC$O z>k5gV#eZuJl>cwue~V<4-5YkyBoH3mD5S?b=HTA*Q8;n+Gg4F4#dKw?;e=%-?XK6t zkXAqZ7i5`q+Dio@-iN|M#{ycHB!%64uO-MU7IwAuW7l_mmFz7`4m-e+m20pmM42^J zxZ}=?QsQMFM~Nm*GK3Rf0%1=$@7>s|gHkR*c!S;++GLo(pD!7ZketnZrczipls}WA zMPx-`5X(5aA96o8(3Y(fvf_epZD|{gcrOQ=Yxcvyq_5OKcQmro_wequ*GWEudH-f( zDy&_dM@4a+^k7%0#K)(gaTX39u*6*)J5LKfgKc00k_taEc!wH{?qd&iYsK_*mmCf} zXM@G#mI>9joC7JHKG@0kKVxq6#XlS;M=v3yc;jQXGHaVe>v-&J4RrAv%I8)!RygD{ ze6;7YiBt+%J7fS{%(aD6B2#+GdIUZk8Gy&<-y<4J)bRBn-Y5RYHgR#QG#ul6^2NnG zdgWmatdZf|;83eDGkp+ynf;IDcXrW?`D!RtV}}J-Q>k3G8;&}!ES8%+NmQFO1TOyy zhQMRI^CDXnM^C?l<(ET+aWcbTNkkTWACyVIgx5&Aq^0_pvF+4dhV;Il_Ieb_k{19wE>%m3`jnbkkpgoK@N zqOywqnXHX3miXbKxFkAvRujV*H}D%=PH)`mhSwdT`0hZMV2-yU9ChNktOHXijPk%! zWj#3R(0`)Sh4W$cY-!eVBV*G^**` zXlcBn&S$-|9wf0Tj)mR33yBLCQR2G!6BE?=!1VGW>b*Mybhv+Q z%s3O_@LB%MM6AGn{?hDW++&E%(?h$&6dIFkf~_BT7Kh9WvZK744gG!t0+cIh&+azX z`XB~&oXg?4>zS}Mi0@jr$&!NDF1Gi<7O;C;L*LI)#@7=ZQ1Re%>SUw^)p;SXYIZRl zo~DY&yTVa@zoB6MHBIu<&aTJ!LczmvEnH z`rwgdr+EbHH{AkSlRD{Hhc=iq%muGLR%c_X`{BX0k$9`%CfRKNmYK*q!u}MVA3vrJ z`kV92sI@z&;+p|5vcd)mVvf^GEtWWKL=-B>UnT;_1}1oQ4E79bpuT1Ou$1GWUuGgH zlqq4dQ+x3+x3vmdcz(|Jfjt6$;S^l{I~a!+_oe-;+_5WLN$i`nUF4e~gfr8`ptie^ zHgD9$+y3D=T-}lcJA9)v*E_IAFBw*_;Vjgw8i|8l8|mOF^{|TXod&P*CYH+{@&DF4 zYtMb?j$^fz#VT{NL?U(uyiGgde>q)wONL-Ii^RDbuagn!QOwe31x)_fN~v5KD7$*0 z-Vqfxe`q}%=ROyo{$lbejk3AgflwJ$NXZjLj2m#6cXb^nt|2`v`VQZL&dH>Hp`&p8 zqi__IE>1f9sSkJtghI1d0X=OZgI#<#+ih7Qw8#MMN z@fLXHo-bOxd`B*yFaqm{K=`k?l75fZ#f|5JFs}8s@W^gc(231}`)%1&T3ZGMT$6C+ z<{~op;$2p4+>4Fdrve-h1!3~BHmdnS9%iQOhrxZasDj^UboU6xZ+Wkh7Jr=tmhGuv z{ydKw*7Z=`HDOFQO^W^Adme@;S)xMPU%ICv6E586Iw%c)k}yvl5;8_|~a7l5RVMXD{+W`gO7({2T>q(s^#=zIv!s<9|mVT7{ai zy6pGIf0F&=EHia{x4Rb)JDT0l_K=d;W8y^7dYPe6`ZX9tA>463wLjkf?+%{$9x7aQ zSs&aFX2D_oOj^Qc^LYyVhP7lB893lJyCl_%ha=rA&^^`%3$j#5R^LY~;Mibrik4zc zf2C0GiX#es3}T)-df4W}`)G7tkypi8Y=xE`OrUktPauUVH~Idp!h6g`T@QPrd+jHCC9?yXyeg@i!7x1cCm3)0rqTnv%XmV7 z8#HrYaOPbp)NSW}|NCKr`6rcO&BsE}a!aL&e1G^xwHxg>FA)W;UI?j66T!Nnm=>=v z#*d{+=H?xEiUC^`e3y^(Z8>c5$Q@Me%I9!kCb;Nj(D{1je>0B=!j&IF^ zTCOX;@oFN^!S=wzSGsZb@F$|N+81Gl>koLSl}oSw9gVTv18BrEJf8_lS+w36SX5X? zSMtw1$bX*Ow0ePPPNVk)EbMZ%>g9WoK#mkD6&S1U;TFWtW$!>PAJFz8J( z^;u?$4c~a)@|G9G%|QyLCfwjzSKL!C*Un~Mj)6^HIdtTOY-s2HL<>h*a!pwZq-wXo zPN!O`$8{_PXY6rtLLALHq7BB0ArOD6nDY}={BS-D^~a7B^sLv070dGA+p~}K^SNxO z;xkc6?IvQpK^=}fw1s|Zcj(^SktqM&539#$k&$a7+2>+&s0iz%E4K_l*WEl*QSTPn zzd40Pl{i4p*J^5G$F+is{n2995;|K=9ljdd!ei?bbmFzCh-Oi^c=2WOz@U)@ijGNg z_^Vb8!2dQz;-V36NQ6=u8`k3~x!oAvs)eiE<2ih5k6^9~*WqL-iu*Wj6HPP~!I=t_ z;NGy>!94ps94Fgbk~dtB@~W=`n{i%-wOu$52c$>h#6694Wa$sc;vTDgcHSgud?>p( zu^0D>zgl3Ty$}ABT_wB{?T(6n6~(qcGe!IPTu|Wfk82!r`3_$XHTivQr|WgH$vB!V zFkKX#j%st3B(0jH3Sq&aT+dxV)x2dT+<3ZQiEu%u8k;HoRpN1W%DfEw zuCBr1nkr1S!~z#y_ra+#DP(KzD98v61f7Mv-^64Hmb(UF#R4zkib>|MJ|_bj_J5-u zHnNyz!GHgSi%8dmdrU!!V_kCt_16$X@TWi|vTZc%qXP7Mupfr4=iQ6CW@vgp7|rIs zPAb1_2{s%9TUGPv!BQz^m>ep}=~{Qn2Kt?tjL{4K(j#0O9~~8e^B4G&!CV)%LgWiE z6Kg4)wSm+bDw2-iKH~m7TZ{Xt_lw9`r*P)JWSithbB#Z@V;A^i>`GZSaAP*l#^<`q z!zn~gMIGi0u>~7zQ#wC-DsEmDg{QOQ2+C<-XLm5F_O(sia8nMJc=cl7xJixR!Eyff z#5Q4*)exp~;Ge_`<1k+XooCtMgzQw>)9r?{)+mYUtVJc;&;3Q;)1 zvxwLBVqoG{X`JQkh)FU!Off|d}8NGCapYG*U z%}g3Ajl%F-d6;115#DR$S_FAZ(`d+RcRYN%6OHFD7Cr1*2v=Pa;mx8F`e&#KF1Z(u z&(B#9p;R<;c_5T{XSREvhr@TZFk)5}RlO~XSN`L7?HUhKuU*e2eM7oG)l$&P${IFjuD-c<_z;<_6?K9p|X}F|q`PNy7*2t>9-| zM`zl8fCn39;`BpKbY<>97?d3Xp^e3~zXIb@rq7$G2H%n}}4(ASi{cj`|zV*e1U3{;2B#O1Vm`l8Vjxp_^VC{_ITh&=JRYNC! zk2|*U77^}EWr6h$FnB@@eWcm|QGA~L^lTdqSg(tvbAI8S&*q}8aT<_fY70vnPS6n= z)6sis6uP@#Ca$hc?Bdg-(66eVUiHvG7{~R=8=~pQI5k|y^(3{{Z^$m~3O2gPQ=(ONw;;U17V zxt8Q{P9BXavX|iGHFaBH14iP^_l@+aLov?|RVzjiB# z?b5%9HaeY$%CNt%Yb5VZvKWS2I9I=!d7ZRdKV=EH91gm)QUzfZ9GT;Vjm|3Uf?YGr zT4a{%mYE~Ktoq~W~hQJ6n8lTKKxkKTua@%wU;w8FU`Jmq*OJM%j= zuav`c%OdewX^F67ga+d~NJ&27qHR1!(`5}_vQ%NpnHKnZoj3loOD1(nCNRe-5Tq_v zQTuCpc;Q|U2Kajk&%CmLSFbYQn=jAg=bAA(DH30gT1-~d-Dfc!`yj;P2lf2-7IGZ} z(e^_tO;1#Wr7eSUxksMgnos$YpvtjOqVEe&PSw(L5lVPM*A|BtEEjrY+QN{x%4qVagiaf$ zhLNfKKK@Ze`uB}w${PRA36Exjbf7N=_LX6~%W~i%*ZJ@pI&mJZ0j6rUJWJY?J~x|= zv$$?bd-QX%^Qs1Bjta(~gKZL}qUFJ4O%yQ5qxxyhP+`KKPlq<)=|6g`R;hPh4oK%% zI^iOw?ntHmxyJR&3I%b!`gl>zd3{*!5e%+<%IRbib#w{4ga0Lm2`AW%;9Z6FSdF|sF7e~P zKJFDcayyrubG#^-kx7aSx~~bvWyUTv>`x7Iy7mIrWM_{XMr@>V$S`?DZEU!Jj{cZBetP6w5D zw}ZL7ufpYYHMK00$6Lmcc*ek!m}b6W^1CiWT2du7nfeYgF%UI38`3XH9+>dtFU}qx zDbnk*hgsu(z#6V|cy4Ne%ALIXX8RSAf4_nan$wGowoUR_Fr44A!x*vM^^MKT^^ss> z_||Xm&XZ^UG@1x&g9F(EcX`R3TB9coaQ{^N2z69(s|EHg<=?x$FNw8ShG!4ofV7xO z+OoZqX>E*wg|#{KV;;}S=DrWj@3Lftfec*wxdnn9>S($>_q-pr!DCZnsGWiijCKxz z+ZDw$a7I6@;5~zm1qOoLTpbWv=fTI78T4>QKHTT`reUWylY)DiP;X}o)9>7&yWDsW z_%$2U`0z_O_TUpXsL>4EOgri0&wpU>VrOhTsm|6C4P1MY=l*%!BE`1vSyH|OoZMeS z^KyQ`aqcb6R^3L=!eF%D-iEVwn2Va1Yx2Hj8_*D(q}Q%0W0kE9h6ahq&pXX*g8LDW znpRJ{-)o}a&s`k7FPd6U(7+j-f1XNuLxx zJ1~hDA(@>MwztBot_aj_@+N00xb7?084{+HQ@d7o)aZ~GTLyg=JqWUa=u>}T+?HGl zG5n6eIlx$z8^k2|8SAUad)!r9=@ma&?32d-ehY`NHH%yM{w)Hd3dBS+JcV7$3xIoS zMYMjd4D^gTD!E555t$=Ri9pvSOOuW_-9o~2#b#1hMP}do!|e;9uwvJDTD?vIOZmHd z)woijho2^kSICrfIR$OwoyqNMaAuea8y-If@8x)5*z9DIFmyC*7!}AfZL6rxfMIx( z?+NF%dI>GJj)flA3}~d^ct)H89_07^Jcq?(+T9TLJ)##UGeoJdM<)oer;UEUs|0HD z`(ebxELx#rh|@0mVE+Zrk`A49L-CCM;=+F?MDJ^-!Mb0maFOQI6Na+Pm}{Pd*4#tg z>|(IZfh?1h=(XM|;s>|o0gWqfm? zgl-I0$BviWTcI?I?06EznqjMCj&@j<1FFWpcqdDmT~E)4Z6Oi(O5q(*i_!!YPg}@4 zX-0QHR7Pd)ZJDt8GHK1z#8upvbYz1~qRR+H=(8#cw)V@X8vBnsgDa|E{CqrgFIYT&N@?@s?XXYd-S=?*GoFCtZ23riVRV`y?c8 z!d8~4(TkaZ9lUpbi5m?0SWcbdOy`{zJR^D(5lx%^Ju)`8E~MTkacI6&H$1~`2;mktgZ!?S^T zhIs(T#>rKz?dvHR%JFS4QN%2cjb~~Z3BQxedOrKWk#N`P(n9P;kkT$9^!2u zeZi^J!H`yx2U`C!==3Fp@QLq#ETcA)L9cml>Fs#f(a3e_QPJ!XGn05^9zFdB#lxLZ z_mVoZzORX$Hj!xiLZNm0Yy@spXHctQL|QMTGVFi1vF+FL|jo%K;!Hv*5O zOd;1vA)Rey&pkadte)A!Czlae!LyX*{{4a=S&j(?K12_r*e9{GM5|*;oglGBU&@2<<92Uh+JNzJAtVEC8|F|`a(O7&Td$y*H66p!f}zc)eK1F zS*y9#oHrIKVdGbRzh3i3IK@nkT`7Jnxw(X0y9|4`O~ngSdg$$wg`kT(!?wVm=uVyh zijh7L5noH)&fCM4pGxSbR6>_)YvR`Y2%K_i7CAg5nx*dBDw(Nc)$*Vu-3JFoNwd5Y z{5gjR6mNY;9_|g?<#4Xci$ukvugUyx`Ap@PEfnY1(QBIW=%)~d#%(Ut@J<8s z=YHNMU7opG6bC~!bkN+fLfAf`jcwh%6%H-s@93LScrnWc#fR_E?{jbA#`rPpN{AnkA1{NEk*(gbN<#^#`pH#SnJ!J+=542d;8DSe<%?sK8RVz9toorLA`ibtL*@%GPLk5&#$`@r--_nc_z|zPx7EUk+qv#h7->!>9V(l@RREV zY@;SoHDeEq*~RZcYr{q7EgfN{`42dwlt-Q44Z+&c{&>Ul1R1xxiVgET1^M1}boJri z@UinIF4{SOWko5X_bRU8F$W@w&1G3veZci}F?D^N2Q7RaEVLdiw5qtn3iioMZYy=~ z!eKAb#Ym;MRQ>oklw~x_-FI%^qW?#MAE%gJJ2c5Lh7Oy@8wiVcz`* zc~)yRr{UD&!f%EbngMsYN)1JTL+<5OE9`9KcnID+IZzyB;MPQM9!tvvHRYh zFyKrneJgB(^yW}(Iw&Q~7!nUZs|Vp#bC;y+sqVNhQdT_czm1~Ut@GjC7KEK^i>P_u z;g~-<0_}{ZlHIhB%9dSZVS&;t=!FCP)f|CW)-+P9)DF1C^BYfY_aPDdU2rAD89KL> zQ!|Zt$S)p*n;(A@Y|!?==oVSA^Nb9Ut)3n1kMDr%e%xF7nD^WAJTw`%8^mC592>oP z8D#xyp-v$k0Dn2>+4+_%dX>}2X98fm2t;UpB26M3GtqB5G!ke&JaMS_hjq1QpEu@>hl_hBFN zpM%rWK|EW2AsL%x22DDFP&BTZ)@lz&NBKK=KiONj;mQQi*_;7;%ya0B?@IWSzrSKW zFDA{8A2Z`0dnGveaZw38sfxg!H45CHtOC(aTyNYbn=WSp>{`fk*SEb-D(Bgf9j$%E z)eXl)?Slo-l#vQg7ZlK<JijXMhF$co(+#)#&v9tk!aKaF0O(*Qo#EEyey3%f&w6PFspao?|y_9By({pbKY zt~oiJvYG^z2C}ZR$DpFVo{r_&S;LHUFxJaeShR-s$^6g(_CSi&@;-~RIu7{LV-S;Z z9*MW#M&h#c*JQ<~LUzl_Rx)@0s8GNb&LNLwy3nD&n_1;-p2Icy8=X2{2i>yxzBE`! z40gA(n$cU~#g}rL&HI$koR2Yz0~2Z|(dgeExPIC%tUVtl8vpqc zJiE~Vdnf17Gl}D|yI&N_j=D-F*VQu1rKjMgVm)na>HwR6yt_o)pRH0;!ASn|jJ^n@ zv-vyoz32la)y4GD$|AVKZw)WwM+?=<@3Q@4dby?l(FoY!se|ua#kAztcue@qXLkJr zvQS0=mMpjdWy`8)6YqgaYJ4Wa%(JOwFpAG>hqua+mYwo2cG_0p#FQQxz=To>4&vbo-UiQAhgWH=Rw}whUy&5qN3c7NTRYiDyG` z%=}tOhZ)AOma)BH(v7sWe`Z}uTn8RqOH0Kl<;&oJdjSo;F2Z=8Rr2Jy6ImP4%q)ZV!C%iRy8o08 zUJ41u^*v8%=tchdJSWHbX%eyh(7>!VdcygGToup(SanBCxx?Js4-`wcgU zE=*krId%y7{OIe)P7lF5IrV_oXV)|eGMb?kcXhWR;!Rw|U!#h~XJadEgBD z@0HW-W4X8VmyFn1`=jXoP5b{N={g*#e80GrO=OeZFp4%B?t9x)yS@#Y+IuNvgbLZK zj3^CpwTvdubIwgfG$KNa6SQr)cZjU#6?ySL$P6SZrLF) zj(tz0GgP3)JPDrlekLpUT6AURKMXv#HULhu`A|4bj=E^Fd+FzM=)ESD+rQWXq>WV?T^oFHZjdyWeTA6!%mX+#hBJRR721wRfzbw* zX>-UFy>r-tsxF}8d$;n0&YHYI0g5I^uTBb@Z>tk%Zs03O>HC= z*@)8I!mlun;i`FME|>f}8FCLO;$Rb!3%B{0&h$>Vo@R0*ei`8;rZ*@wx$rzkS`IR# zQ{ia%CsO;MAFS9uSd#yfCvGsBz902_h>x~?sE(4uU9iDFmjoOLLHYS&!a*4e{@0Ar zpgAr9bT#Wpf1w7>Zn}yAV^ern8cd<`STQ72z9+GX{cw!UkWw;hIlm)U=~#&)uqm5i z;0SGeV(*Tt!&`W7ZVPBGyIYmK7omp-hv9)j4~%lxqz2++a2>nD1nEBK)*Ps&8{WAN z@zGQMlN)*mE!6NQ`H9_BX7nT2zVaifzRS8VjXf~Lp5rzg{Y9h4I}GtJCv3%0a*8XK z7G5QTlY=o$H+36;S4NC>Met0-% z<$?5th&Q~Q));@JmdcH$k#)nu&~0ZoJ`GOdJEnL;;iwk4Fo*SD%$N;~5>Mi*ECPb#9|b@7XD6%P?@*sV7{GxD;GcxdgqN8i>+Lad;?v z0GH-7U&e`gNMgF;FXtsVi3^hOX_Eu|{?bBz>$iY>;Yyr3CxV3b=)$S5iNJ_n;v!-Q zn%(6P@$n65KU~kWJWR71W6woD+YH+eWP;4N2I6@tjncp7L;TAD=Wh5J?TY<3WU2X} zCK?3_5HALEe`Xic%cGeN$Euk)v3cn*>rl9OVk=pfXN<}-ezKfl3%+XlMY#Io3&i(U zkf5=1u*oqMfAsrsRW~}QRKhMeFIG=}{?Np$=h)3qob@ZowbQe6!r;x7FXU7HFL*HG z4rY~$@WgUv)GHHw9>THBj!>WnJ_|dq;Aq8*#vEj~D zej#RAZbNs)`^UUt^aNwp@6%46&K-b-?3V8EDvCRBIgRR{I1j7CYss?3p=i@DDopuN zz_$Nk~&<^0vJ3gWtOYMfbk|&GHqYnF-FHSL}|CtYfHq&2) z{&>Nikbg^;Kn%=nuOgFL^w4^}7cM(_k^9^;3=D=Jf-^<$N&9I7jL5%&>0;Bfce4(c z9naK+-3NU58Zv6IUp)!ZCRLIzkF=@x(SJBOg#<#!v$g1NBu7u2)<@$4FEnYt%UPeX zWVy025c>8TSwaj@TrnD}yu)~=HPfJjD}qr^OUca==0RA<^t88@atUS0^!ohWLwxks z>-8|3d54XYB&p&?dD!x2H+UWUK&pHBsK&B%Y^N7wOTP-n8juwhNgd+fILn7K*?C~r z#ok|I6;NSvJZ9X?=2d@|qSlVLhj?m@I~O5(&>E+u4w7o$dT1_X&!kff_jj%pEI1Vf zIu*^t?$tzG-y4VfV!e1KY2FYkkQvIP{Z*og{toQc(LRSupP5cWl^sCn*+GP+Rbaa% z6906G(4Q{#;K6jETSn$_F19J4be?$#)sgt|=AgApDi)|e;!bT;!)M*m__Xch^P1;@ zsPo4_crn|a&$-BhgnBAW`SFR!og08x?AGcyp@-*dIhLMV{hKb&7$C|e8W{e=8TWq8 zB`=+rpOh07riqQ`U$Pj>G9eORM0g$RYh$_7Y);njVVD_Z4)6CB!*j!8a^Tbed}rQ- zeLL22g)0)Mx$F_(WLXDpxdE28d85|Z9$rM5fX0Ps4c#7JtY$f%&poi-OOs|i8H4wK zF|EwR59eZU46gk z8f^yn-3L3-LG7+yW8Bk{`eSRE!nIk;0g$pX@3 z5X%0KJMrhMx%^UPrkxY>fXgz`WS{Y5)V-U6C3`1w66u-D2mKE-_2Ru@QJ5Nj;5QQa zemNY@JU(UoaBj7+ke*ic2Gau#WKC&3d}I2kxUJJj@6k|vuGocRGH>&b{T>b(pWGq& z?0(|jG6l_drlQ6pUry=4cUp7)#Lyj5&FdE|OTUC|&lKsJ7CCHXT*FIc!ZtQT+J3g@PWd{3 z!I?~$_N0Nl{Fp|&>dZjtP(QItXM&Y2K0}&DpEKIn#`A9fKi3Z2vtso%7jMN75&_58WqMmHNQ+xyHDc-EI$63@UAGL;_7&m(ImVUR~f4I=r)!9DMDY2^MejW8%&lHp?0>7;Kn>h7X&d} z(*bKxwuyr1{$`T4b227rUB&QzFWyvz^I%*igJvvKZrdttoXohkqs!)UeP1$YZk0Xk zyxu{~CNzRn3FFST=5e1(QkceB9(N`JnOip(eSA{U#_bX3eNPSVeZPWxGfq5D{t$>k zk@~_I)6M+NZxkT+j{r1ARgm695&X&S2K|0Lyki=sGNwhU*K&}BK^ z+7_sMW%l@u;+b=hqg98z1Tm7pX_^w`q)r9ixkx zFTI$YV|v2B42Kt|ujQ6kU87A*pYVT<=81wX3kCB)g*|P&gx7be@2r1wrozVCAZwzB z!5z=YVg*yQWI8=vrsM4h|4I!LTwuLJGdWP2 zEIo^V+ikgsC4Z?@uRWapSw~_ErE$#+Pi$D9NDAGVW+_EQ7}&Omzbsr7Vm}1IiFb8m z_C`hYW!+DI;T<4aE((l zv1}suTl@(P{X27L<~;QCJZyQchFeB8k-+7On8o%H1GjK4dfrRA=(jKDhHX?U@AwdYo?(6> zBdtqV?X5@?*C^r$wjasvMy{N7?O{zM_*fXU%-dol%v6m5=Ggd~J(PG0_%`<@5>O|np_(GOlRK=LR zH}Lf|L)&?CN5Rg!|ma|>zB@RY2!NSByI<+Is26?U9FBAt*+oa!5y-zO9!uC zWj!O$2&d}bP1RM|4&L*Hbj})tFugn2Xf4X?oUsNYn1|i6Q;T?Nhobh;L0rCnEq|}2 z9mp<3aIa*YgXc`Jj^&<}NYCId#nh9^v2OI3oEW{$JcXC;8e>OD2XSi>#kY(L$eMnc zn-cJd#w_}WrQ&--(f;=!?o4>aU*PTqL2r8D+>SD`jhLc>cq-nx7Qk(s{*-Ptwj1KR z4eCWvig9^4;W=EO!Uy`JDh9$6s>yVPkr>;27N0qJb0<5b;8n^&Si7{CY>76*ddl)q zN6*O??g+-qW-7wc2rvHS*BY=~DhWE@RFeEBx^%zzJG%3<2z|3U6jF88p?-!OdvEKb z#w$-85J}~R8I1s*n>);SkWJo7Nn$p`)eU%zXLooy4A>XJ5tb|avPconGMqo_yo|Hp z?$X^&yM}Oe-Ml7109p1AnO>znZ_wh({dFX7JBnW-?;#y^JKA2yN+e=>)JL6dngMc?fDG19q z=?VLl!})S=EMT#5G4!8c9b~^n@dvx_o%^wt+x9Av#@;>*udG_g-3_{U@R=LaDYf#X z?lPTij^@x@dg9q_xNWJ6=0?wmcZeCvRWL29Sr+&3N*#M%UBD-ib*yCe)03|=!9ehl z)TZg+-d-0xy55$X<2*=jv);-L7wU=1H5u&u?tzm0L_&ju@jS~#x4gWNzyFRHym$}< zKYrAaw1VNdgMH4e>+abOh-t&a;A+U7@tTC z5#u$!ZJ5Ln>!;K&U?x23?;#cr7ucSwih&A^L??YX?pZ9r>-WRCJ>GeABfD36ziJ>0 z_m#k7wP=(mHzxnB2xEI&8%~wJ#Sg!s3|9wSVVB81qBqP2$C{_&Po5vQeRl^vYpEtyh#26-T31h3N*A$Z3Zve91^ z*EU|qPk;4orCUbBIi|O~wd5_C;?xR%*^b}u=)f&ySz<`rc*l#5?G8T$DHR&05r8-#1~ZHYu1Kir#^Lv19HU{^iHZ zp+X(u!0;L(XKscO>|NRHH-me-zL99XaU1gByqIvn5fET8aI`*vzs^@a?`e z)*6V=z~`-C(#tX{jAFSP>t;YLn_c|}zmu)R0)JnK!T>Qhp2x?FV8N5cl9P3$cdagl zToRzM@;uIX-V^#M+#cpjbdn7V>cBrG0vCM}p`CH9AkH#fbDQ$Gs#5~cx0b`7V<~xm z-U2(;Md7T}1g_mzjr9RCeYp71=W{iJkl#8|$bta*qui9B;f-JjW1Dx0<0(7VacR}d z3(p=$S2z9|!dMNV4jPz%Dhu>zf3FAS`vY!0N)*2=|jo^=cI9K~?~yB{{#t>fPAyGifb9fnww7Gj^Hi+diq z;hmILoml0PbeZV!iW6h`Bh^fVn9P5AR;U z_f-~$wyYpn%=&FF>{G&{j~O1`zGqA7wc)0E4XD3*O}6d~Md$xoFz+>=zjEgYNcnme zmZV%ElFS3OL`;AyvLt_ zS}*uK&_Is6et^IO(Ku}ODAJb_ib}6r&_@3zzf^1lT(vn1W1aSqz(l60Jduin7yP(s z8#?Io_s3vA`+YIE0c2UW@Yf0vx_`P7esdFGzJ!qbG_`>W+asZR8RHXQHbIis9n7yb z=Y4s3gF5$%4`J+U;RyJ6))h=P8?3k3BLq#w zrG$p*R{X7dj3M?`B1}mCLd-MR*YrrhzAw7AOCF4czcJ-t82gs2n9%`?i0wL~ z+pl*}uF1HMUg!)3JC^4xdRPpPvmUMxfhbQZa6P)*X7lP5ZPLz#Vp?oJ&Q@N{FLhrD z&Uy$fUNvO)OLM%(bU}lEW^hyfYa+@)XX)s%V$|VK04($ThpX-x61Z*}<2CMG=Co5nJNvx>=Y+ws`PdU<|dnUj5Ck2VzN-3BYxbzhrkK+R9S9hzMwLRc5~kG1%+ zlVt@9roh&HF)*{OkzAf-j`LHl;#}n`ys=rc;Mce!@E0p5Bd#f zFYkgP*H)r%?mO5YW1Y645>#=K5;z*Oj2e%R#MfmZ$};`!^*^t(aZU(czalBjird2v z+`JH~l2{I)eI?mnF#`GF@pxl7<>{Z7r?Z%+W$FbsPx1nxCdwN3&k&)Wr#c{kXm4osBAxEIW;!k(W;X)G%#a31%v=PA8& z$ewXRoka7eC~`Mgw*NL|TDQ3a?AW_L7k*YjsoD+3AzaQbZpQ7VzZL3;uAUhieM3kwP?Q|A9Os);_s@H7|vFeRS^ zhg+cWxJbO7kk5Uw9|w+^@$k#Po_I{uN25dW_{SoZN0}B#^PY~-OFEQa!J7mpMi#?* z`4aM|oIOkI))(|>9hYu?o9Y=KhMxH?WQ;5GDHOP)v2Q!?+tLSA?6JmBXM`Q&)@EOD z#e%QuwB^QlJn~(DKkBkL+pcf)gr75rJ2#X6o``^RQ6})Fl#=WzqwqKL_&jl+&sj-| z!Mr05Q2DWe{7iTaaUL@<_R3+hrC0)d_prHiMm@>AI|4iXnQo`~o^4B-E)0CA2LIo$ ziJCzeR<3Nuxz!whr;I98jX4WqIakPZI~iP1$@10TigSkhvuMGonL}9_T4MZm!4LWh?Q;dh3Rc-)W`8WAKs)lAN<42^mf+SamE$Y?-~)A^D?+O%N3pBBIgwH zmyXSLft|13lAJ(QwEGc{KFL?e)?yhLCiVbyUX_s^scz6@I+LsWhHa^U#c9+oz> zk=kCSNt@}0VGlD&(M1_N&eEy;7792iItum#CqmZmFC;Qn6)nXRaL;XBTl@W{usWg~ z`YYd(b8_7f)5tQ5^tW&=GLCRqCKHOx8_DDeS}6AT9A0x1<%}hs&`dEiI4=5!jA|c% zm0D-fO;?^y-_7pc83G*5GVTt({Y=lf|C>?Is*B@`jY*g%xt-*b02s0A3v7H+Ny?bt zA$OrCzAswDb*gt!pA!zC)Kf+176aUn%DB`=lZ>R( zeBB1jea`+D#B|7Y`%vTxe&N)Ei4}~i?W(=Z&5FvRL0aeG>VI`4!qXT(bbI2Ul?|`_K`8#(_#5LKU-I=Po`;$^ z)=$Yg2*Ng6AjftGlcRy$uLs#warH7t;CGYSX&+$?-vygJT1cOgBuZGYOyEN=xyQFF zsDu4K%-pzB7vn6Qv2cqQH?mq5hKU}83xA5qlmZaU*)-`dj*eiqPvT zqTr>%Iy__{PtBIGUfRhXSRg9k`n#t>>YNyOJidt(Fm3p)P*+saJHb1$lLu27FR#fj zCo9xcP|sU{m-gFnxprxE=fZ!O`Bk$N6h~dgu{rHz{{f`in944CDR| z6=o0LCxczSjPt$riOXbux)Z*6P#afCHnV(hod@yw3n*`(SAjZu-x}iOg&si=xzrj@ zP8OkiCU(PKaW>-x#d@8gl_6X@=x|1k5h z5#t0MT+n4(KAG1Tf>-jacWcn~U53MDu^0Voh2{VUg%dU1mxD=*} z3dO9~Y=kPNvYYlECx(-vZ|I?KUM%D98(BK%Cw!F^U}~HdF?9{Y&cBVg$SILuTrdmo z@lw%C%bzRV-$B>P9)vX&^&~W06e~RaFuq8EF49oNhnra*U8;~fJF$h1JQxYSJ8Q@e zg--a&GRdEB8pn%^yG8fx{)deVRc&#Nbt;~G`;7Y9b$;sIn zFyW{cu3mYW_ioiwYW&)C$or#lfblN{uK0YSJU!86h^qNa!>>?b@Sgo0EY%U?ElJpbYp$oD&t`2BaXJ*o{^`Z*H7oeG57$6; z34pT97ZNbh5|1(tWrD^m?yO2HpIAC zJkE+w#6DYXTH+>!qBGfhR``;;BU44su8M&%%!^unobd*2XE6VQ7dKBR2iFn~z(chX z;(BZ}7Ux8w%|7ew;`Wgce)KkoIaQImZ!#!4IRWLimhhfx8q@rhZ-zWRFS{;7d;eNo zxLlrQL>gjyjT?@zPvJftumX?yF>qJVM63&#hl%+yxA_P2@(uVve67V>Z2R;pzWUWncFN}&iN`>LeBYkXdc5fil#=`%Ch2r^{4V| zE(YQBQCh;iy21P|x2Z7r;XRDqT|&;XuiwM8YWFs+=l+XIruE7HFtcA?AGK?o@lnEe z-tngo>9wW*X3M$}$zb_c8y)UHA+HB4@dU$x(9~=$a#S-7e|KhRH@DuQfCpJ$fMN;j z+&L=-89|w_Ykn!QWV;Dp&j|%mGr1eA)4AHi0lxcuW4By+EYbUS3tfI|8wP4rVeel} z{@oRl@W?I*3IglNiP@?sKb`65+V0ujR51X#pVbhxzmU9748_!?-*8HkE&u5cdx)xg z23N{h-f8ztoI6o~uev64YrC@PjrJKs*&5Gh`h#JRD!SA)5)I~m8FNQ~Q=dj~KG|>R zW*KjYnb=6OruV>eTc&BRwIV;ih2rSP-%$VNb^fgHeo!;%JIIf$Am3bU5m=_2>Op_* zzF#}76z&JNv^w(DNtEfK{BXh<1?m%_ivH08wrjuO8q!0 ze_2M>&!c@XkG0k%`dAN8iM9fNrqiesC4|6op zndKEIkJ7h|%NqxOca_6FmS6hmY#$t8zQ2%+E!^(rJ-}a>$@bhPa`syW%OKLkbv;qM zp8L>#bLgJ6s57Z`iG zip zH-^ni@w1qJxsBX>;4-A`oM_52q$S4U!==3>s974{%oAX){S}T;9aOB#2aIpmk<*EW zI85X$%4tpIy}(dR^6bF_V_)zsxr-pPxCi{S%SqhviRjI;1>6S$Iop>&)xItr@|e&0 zCXLB_#)T>6a_6Sh(3=MTaP{_keRMW)M(a*5E;vsfjx*2Hv~4BC&uJ_QHbr5Ut4((L z20gfQ@HU)!Q$-xN$>DMbmVN!bgcqPbnofB9hI;sk(6MdN;JR}iih?|~3O2&>3 z9N|}fE8{UgLF|$!yeQpHg2$`CBl}(OlJ)<(ZOw#{X3V!@X_Y<7Ed+PEiwk=Lck<6) zTLw>W17EktWAr`XrB76%;~Q@dW&aMF9}1On))=%^gf4j42WcZ1FDw$r z)hKe{Z5IjR*IURt=C|;$(ZWn;QQmg3P;Ba9%Hr zIrBNqE<#t9Z-)K1JISr6KA11U_6zxZ&cHd9^*BpmvTPQ?SdJEN@R4qqldzt9 zuv9=}4juxJ6D>q6$P`^=yzx(aA1^UKoo-do7|Lp!UXcRE?*H&}uk9oZ{>d<^JDXeZ zUn?EwdS-|}nh>Oj>%|k%(Zq-R&XRz$J2M$hmXiL*#;9KFhU-$9$I5URRBUm8zA24F z=8+;w^E~iGcOo&C3c;Vr@(e%?bzU_bPy*aBHHcMBK8dW|{ zu}{UCr~VuiFE(i_4aY1^rLS&>^h*1>lKB>Wd=#p_BDQJFV-7UJ0fN5trm-&MAWX27B1{qn!l0s^i-i&S~zL~Ti%>i zmI6$hcmM*!7=8}paGaq4M{Hc3EezEM$EmkLmudSyypl(=6A4(e=>t#o*ce)~;?2-) z^O9FA+?%zI<$lZ4{_)e{wtfs4>~AJ6hbE$|LOk>JNAvWq&xLf^BIsQFiTH$Q;F>J9 z6D2I?cHDnVdu4XPZtFJEcla}WtBOSHM16iKYs_mY1?v0yOswp8mmYz%LuhoV>fn7 z{qR;^fUy>FoZ1FHc$-8*Noxyf(GSI^f5e1>uwVR5-veR8Tv;6M(?HgbW*r2qpD~nM zz$HWi{hP2EBsaEL26WDM?VBAu-(=npA%_%1jZ$b_+V8oF-i?W*#LE6 zm%=K3_;C%G5+i_|_Rr*6>{NR3avy!cJWWOujM$ye1%HfxO}-aSgvjmj;Kgo(ttS|M z&WOPo#dmns1&mipRTtiw6UY}8v4J_I@8PDx2Xgf&`5-sIvmNoYBk2~nlY^EFkU>1I#jp+z&fFH0q%G{^xY*^E~p*8-!q zuR{N<^Msoag01m#!Z%C#e8urHU{M+f1t03kU!EE+_?3j>t5R)`92f=1wp2rZL?IbS zz7GofrSVe4cJ9Q2?GV5J8BAvRZ(DBhG2uMZ5YC>;B|b*lJ$}Z}o}Sqp05X{>`0{Ea z`Fu(fr7tob+%}Tiz2*a5Sm6aLSSF;BVjo!VPC{Lr2+beBRLjI5Vvo z+MJjUoC&t0n9q7guRrJ6+d;*Acf-r4U&!D|O`LX2fK|yaxXFSp+S42XRUtLxvC%Ie za(D2l(s-V3+8yfsN(`o76{Y=EvvK$ARP5<~&dH(}n16DHEWdX|fA?_Kn{yu;UX&AA z(E+&0e0;mcN^&nz_wq?V zjoc4Bfr<$YrYHdI3CV8WDTkTi0$f$3My*B- zz$rGnp1PIKZA(aj)OivpCH90=>5jxL3ZA&&u^*>4-2l%$xPo0pPS2|`2>&io6E3~I zf}i?K6H*Qez(c;0M9j9LdjEfCvz^^+&{An#Ef3(|D4Gr~_3uII$Oqz4C5Q7)3$SI$f83a{_vwGWhv0@;E6HOy z1~q@q;HIrDJk19gG-RUsP_J40F(s%y=m8opv`JRt6jYnfy!I~$w`x*5ow(;8mP&SL z;tR%ydael|Kd(!|Og0~Q7nKq(mV>*d&;g7WH<8)nT0pgbB^CsoCjobY@r01+y{B<} zi8vX!*u?H-N)5zDUkeqgSl+(l1KTn==AUw}h9kL!q@rp&Eb@B>x#jib)4|#JzEXhg z=~KB03x)LV${9nsMsALQVDd!;Gy5CK8AUDDZ@@Uy3z6KU{tq;$)eDk-HIj!qzd)9C zW<8-(h_gu;PAvI~GK&)U?&$$wv7j03;wwnSe{)cHHx(bPxWwhYYp0uJcR}RF8gk1| z0>|C-#bW{mYWzzR6&Vk>OCpCmu&|rj4@9tT^%^4R_yxAp@373W@w~HVl4;_0F$nMy zrJUDXtXZ0hWe!UsT?9MzgjLT}Nrw>CthVGo}Y!z^j-5Xcw?gf20{lzpA#fRO@zU&^vcWuv(%cXR1>^Z^YkrkC3} z8ZQjE;+s{|c#_?rxKgeY-G%}Gaun+|kaUL&2HQ!F;WV_Eo{Hx_1aYQ2Ueb}1m%_-7 zZgOvzGV_^T$BDDF=_O+YTx=)6k3G4ZiB|)S-5U+>p_-_SF+@AhQz+hWj{A0LILMyf z56+pcOoLT5VWfb;eP2S60=Pkli2@YwfPFp zMfN$p9qb6pcDE7IQ4R58kr>$AN(@ER;o)&dC@L%^3CJ|Vej>u8=Ue$*Iji7{6Uzkl zt0sy!bkLFAW4HGs@AWAaI=SV>5O3Z+|1xa)W`lXwV)Vf=mU*krIMAzcoYk#4P?Y!& zCnW;-I4=7tzWIBerxFzc<)_(f$vQu>^x16BX3MIU1zh>N7t~mPGyLuABrQu6Fv6Yr zGP>00)1x8?sscRRlF$8qk^*dT#l;4X$>gAsxNElumap*RGMbncH|821@HzK9u`UR! zbX0`}>zDKUthHgPivUVbRuXkp8+z|Y@6gOC>pTj5FT0>c*=th2n`wr}cHmNlQT*g< z%23ZR&H4FLGIgT~s_Q3U@|%0S_X9!rZkno4Zto@jvl}yE+VA)9yZi%jSge5e&a$8L z+J9Wrr3ds?)j(Vj1AL-S|rVI>&8_bk*|Y7z6UX{f?} z_j{TQ1_nE+X_6C+)oLb-mg*q6#%8dT074~YAc<)O&(19)FHDTk=h-Qo`+OF6VxKhZ z^>YC6&rKxWW&}RA_P`spH^}*2A((JRMtE}=kNoum-n|oWZv(c7&}vp22iB^BeTeMUk6K`=LFJJ8&j;+pi;>*t$a3oU!3#F*Y$B?s{(|ee(3dySoL&w4z zyyqFuH)GtN#E~XAB&Z;he$PYYQ>pmz`X%n%gH9T@dM9Y_XWWOSB%3vSF*!nkX713z zKK9w}S)0T4uIr_;uOeWA_!pvlc>umL4N_R>c;3gP6k4`K3>qGbQY*J?cq^`h`HS<( z=T8vz6Bj;@f)%_jhb)^>W*zb(9W@M7E?-ux8>mRJ@C zq1z^X;r-87`Ob!u!RbO7OpAR-B63CXqqG1=iEQJhm>z-ai!?>xU?Y1y3Ao&|jTmNrft(FLfwdpkwuUA7H z_vm1Bt1HTVTfp5_9-#6(haqj}rrXk3R^x#^k|Ct{h$;SH??kgIb&fXGLYtL!ZVn0Qk zw~WoGygcqhStC8TCVGfVQfV>5k!zfAc%m1#I#dZ>EZz?Tx*y1fQY*alHUXzyo1Yyw zI|Q=_q=mU1r}^SZ#xS|}7PviN?;~wxe8BLwDfc69VXhgiJXAEazw<_1g9lz~vAIE> z#_HLEcxE)LSoED-pD+z`nf`EHSqx9)#v*wCs1Ob)R*+@oIw*6O`J{YSaMM0!(cPyV z;ls@~;?nsAWFP{q-?Q22mpW{l=m`A^OnX0W4aPAXHsjuA$Gr)`Gn#`~bz}?QC1?%U zF^tvdt|rN5y2$^JX*13WdCNztQ9AABkVi@DXf*iUn~tM?iqTiqqWIl}d86v%I7_j4 z;N=?uOM+X8&Gb2_S#=d#wqM|x?+k_a!)0;z(QoAFL)KYfkcuvw7IJAPUsAWaO+&Nj zs!CD3J(}^Aa|^ijsscF5dI2w=e?&aq>Y~X34}5gZkGs3c45ue2;6#yg&sY2jLP7lq z;ljaX{40SvFlUnhp5Ck^hw7)(y`-0(yEI5fJC8=WsV>M3z9yTa^^w$gV&wY=oV(fx z$O?6bD)XmgtSswq6<$HDQFnM+TEUE;R}u2g`SYvi*}|&#?_r13M-rZ`h$a4PzYyQR zW$Z|!e+v%6BKcNg;%$z7{+{^hOb>7T)5kO^=pU}G*vK;ES&pKcwHD#|TBDLW(>J`X`C+JAahT%uIKI2 z!u_9T@k8C^LGNTB6z*ssG3_I<64?AN{m}M|y(!$Ss2al0lpA3f^SKJUH%{jhr`^!T ze+EB3HIPN}x%9B#blAVDk94gLVcmc#L!P73&m-~iWj4=JJ&iE%u!1PYF2ME7V>_w+5+|P0NvH4F4$s>v ziNRtioUG`J7qb*-b?r#}%RaZY897|#nqTznxd^z>QbR&gMDV>K({+Cs&+9xWpw@Mw zL;L&lCj?#NuTWca2~t1CQTvW0)!Nd-oq zyAQ8cd?KzB#PK(KFIx*Gxzv#(K+b40biMB&85`NVrrH@V|Hve#^ei#3I|?@szT+Cr zEFj^_b%<)LB@yG)@o!}m&e*A8d$1`8CHr-SW?6B3pQb6G>sJO3Ti%hNG2-}>X&~n< z*~XRKI11mSGNG-4c}4<9qVhY|!(uwX%gO*cSmB|Rf_ZSEv9 zM3q=qJmY-*qB*NX*0mJq1Lse(T)}B(sA$99?{{o?8Kz;l_GT;2)+79Vf0V)gzq6p= zyN!s=v%$bQsaW9{%mpUAq9+@c0B_$9GDl1a9UTOCH7<{fviMH#+D5|}?HV$`?)*!V zPvP1~FYa@cGVB?-A3XPdAd%-nFhf;Z$YnY4UmK2wEd#gUif#?rp2oTrWUt{Nmr~v~ zsd3bxv2duzM?(JwY+A4$NAne_!nQG3lkALMACtM?hj?%>BpSAaeJ6XaTHsOdD3&W5 z&UI$c=%plhaY_uNa**UmU#{Z|iS#l^dr&A3obgz>k})EY5vW=;~vc`VCi+vx&sM^_4rz95R$`!mVm zbvpQ>%o*eEUEt;IcT)^!`5_w&x_Ng@ zp3q|+tTSeh2#seRpDWDU_~3*VxxUE;AF-a$RV<5gTWtr8iayS|pBqR=>j)gacl_&igS>ADMj0M%w6Ka$SFug3R{;|-dcindA_p==7B=P}YCyDd_7 zwlW$j^0if`NqZPAt5DMYT-Py*N+s<CBxKXAN`&T~EY{kcA$_ve#~CMG?j zJPNTFOv3OWHylmRrTQPp%dx_kyXH1}%Nz10&(7eiy@f~a_-a`kNV}@xVY^qPjxoY1 zHQ{)=B87>w5repCCtx_Uj2QG>MTsB{!BcBz*0M+mRGja^IL})0Fm@E4raIf?zhcbt zK1G<5OW)nybjF_3z`(MTD75wwW#<~x1^{e|hTnkUJ1Md4%nmVOd1`G?w6g%6_zUnvN$5XjfVdpBb3>nfvwT)X0qWrCHtB z+*{bGzMZ_3rhWv+_fSah`vo5~khj$f?ar@cP+S;ZOmGJ4$<5?}bP=psv;J-g#^u!;6$9Z_`K>g^KOkI95}cKxMlB%|73GiHK*S78=LYy4o-si)i>a&^?RaGJr;vX=y^4u zil=pK2G?`#-|X$4m;z>-ZBVF6hC3HG3Dfncw`x`@(-h6X{CvDfI?W3d?b;GqiG+PT37wwi2+v&CdO zpCy)+<+lt5W4YB3$_Q;{qZ@6(V|D?Ud%q{==V+r;WITEwf5zK1e>~@M{NKFI*ck&k z!6rC%sVHZiItqj4QD(JMEc3@^B}htyfku57SyOI?6&7)5wdovh()kcPxb!#Peca1_ z%Ls+gX3Fdq=^%lRrsMmG8E7GI!L(Nuayu^ko4wQADku-$3&RTQ$ex%{_)agKYCf-- zq)qf3TP1|wnzG5eqZ0T$#Q|5#>|?I&kw6I?rwv&9PpT7u?@r#cIsag1-vs z@Oh|#v@JE|bO(Qo=mVE>CZpr4lX&iWF}eR=2=*3!LdShN?8JzLz;BKPC(86*$(O)_ zbv~$9bCI{jA_!ZOZ+*U%)%NIrClF9TaS*RI%g|cVc z$WvJ*?54iQlkO>|YPr*)GQ4qQ-oAgx$B4K(w4r_OkL313mdO*iLVIoUpA~X#ea7H> z{3og3#fS6~Mf_vbNmkWPz#r*Ulerqf49{-j8rGf$u~VHSX;1_M?%%?7UGvBssZcZ( ztH=5CV%R4N^xk=`1N_$3law)Pc!Qiq{jWC6+Mhk#aECJ_*wvAOTatKI@;pi|kmX)C zPrweUfqXgmg6W+-%&qnc1H+3S$hgCzxOl;B%6c&5O<9u3ZLs)vj(v0pp^C4D-z8s@ zPkW5;YC#yi`z13+R*A#R#^bVnEgPVBuIV%l$6EaO zLe~A5fbkoB@zxF@#@X~4_bG_#G8MncmN~^Bp0gMy?5!Z`;|(!VC39Xn((dh$)ovvws!nC>Z5-ow|iA4u~nn(O><5}iX=GRs&I_&{?O65Y)tK)e|4 z1TDtPeY97MR!T9<(*i!(VT7f zRRXsNA9#Kxj2LW}ME4wTyc0WyL9bs#{PXdVbL^C!Ft{3}GjfhK|D=dzN9f#8y3T-p zDfi?-ApEvzBRnmd6FKUK#~V#}?hbtPF#m*?7C&X>=PE(ycprFSyp8B@l|-Yv-e|jR z1LH|qb}`FW!Sn2Xa)#;^y(9|hHlB;_RHT}AIvTDnWVW?^<5X3z!F=EMBx>hmwAgi5B?WEFBLk+2mIqm&9ug-qEcdC+VPk0XlVh_EajB-@rmbM$%Ua2OQTkLVDn09a!mgSquQZ|eGASxC+ zvbRg^L1;q(T$1@fEK)bU*rYt4#NKee@~1IXYlwHO<_Xsu_HTY}tyBV^Iyyg9)JUwX6prE3 zT$1T!W@36bmsq|J+-ZKKNmv;JlH+hi?P<~;EDJlRe{pEAn&^L?hJOluQ2ozxCaiG` z$?D2Dlpcr6>{CoP zoi~K>F^w?yYzdkBk}^XSYf&n30bBRN9aic+fqf>_zeM|m^%ex6>Mr>^`W$_FmcbxJF=DpGf&SKJOaJtkwpX$SpcGM9GXB~QGr&-a07mU1> z5Ue~91~cA#AQ?1MHeh-i2X7kke$KnYU6c@ppfq95)%Y2le5Hm#&t4NDO9{}5Jr3cb za9?Di^SC>c`?0+({)utglt>(K9RyN#J)a112G z9)joTF7nrR0@fvZp;PiOZ&liJF5}>2FrM;yQak8H0qdHc(`RfU1@ ztf-CD$oms@{Z`s zWy5P{+Uf8s|LJGyBf3LFzVoz?ut5V;K*jS0oa4VIyYt84`akjb{Ae{VI&LO+U{mow zkErr3(8<|^Ek!b1+}35_J>eQ$IrN3BVza^QJms=Ejpr@)T?-F)6oWIbo~T#o;K#Sr zQ!TxoIVb*{3y|FoKjOX-#dD+Z`I%cd>zo)ja9IuZCcDCn>(ylE7)Q)~osQm1%Jb6{ zv*Cq{D!Lt_U8_Eh&^n9mp=>^o&r>I&S3cd#*gfZ!zER~gmM3$6rG&YiJ#nDcV~lU+ z(lh6Aaa_jIz0A8oYb9`~jpabtF&<@%7pGf9*v+payAu~jh zb~<#B3)x0^QjKO$axIu8hl;t@osN*A)kj)$$Kbf@Nw{N~92c=$94{Nvj>4TqOhS4( zq-`9AR);K7a83ftciCb_@E+#F5f>a(Z^Wc>4c4_)8+s`RYU%byqWh8M8qfXU*tEaI zf$}}Jns}j5cL}+4Ya;$u^+#Xp`^-1(MKBN$3%5!;$Y__zcr-N@OYsXrStn{l zlsv~iokqLDL&{-bQWcr}pAuH3(Yx3Y2j+K7F6Usm52DMui2ggO-^O}jBCm(nVwcA~ z=PQlmk^;76!>$xn9N6)MEYUH=>^&LC8;4BKu5X-l{a#2&dQVDywdsD1^2bsxljAGo z;K}rdP`tT@962Ndo|Cu0j_fal|2zv$XscpOk{MA@4n}6ApJw&tFW%vb%RpQ^btGjCQxJxLiUmGJO2eT#YC5=d-5@_dy%~3A}IZAcxztz<@IT zL?n`U2UizyzidrlZ1^Cl`Vk6iK@lBeJIVew9rSFc`x=EvW}43jZh_*z^Jm2OQHZj) z@j(21GWIeb?`){SfXCO_g!z0BTG|2HA@yW$a~5f+{S0!hP-hlRfJ*paOi|yR>hhj$AC2z%#Sc z@npC-b3R=ec9u9mdSVZmTB1!|R9<*yK@NHTgLYVaQo+sgn;5OgIS}QM2n}OeiCL2o z22tK}`=RNkHHYcFqe(^ZJ0Xf~k6#4erK`d8emR+4B!OdQ&>8h`8)N~>wip4}m$Z;CH+fj>oPon>ER#cfBkIjgjPOQY9E*ftCml?* z?R@?Hj>Nu6Zd(_FF+yNI#h+Cr23%5tuYA&ncEFV*~Xk+yA6F?rq;W zi`P+bKJ`7>Y&!-0R6Nn_>>1|WA!R5W*bSb%N@6yY4TD`Om{*?v)V?_wjRr&o-D3~4 z%w7Z9DR~1*`ri{fFBP=knt;_xnave~-q;iMR0X8!>J;O&t{YuJAy%h6Jq4hIShjlqo*Tt9POgbdd@RnuFf^BPv%-y33Ew@5@2_$F)rOA%57|wz)b3?SgaDqWZ7H6{G?F$ z_=z$c>ZsPT(+4ZpJMeB*hTyE%Kk!A@S2jI20th3C{wrt~jNL4pOFh;73oMz*yWVj2 z{*Evup^qG?k-#TQXjT`B7}-mAAZ9J)5>kCt?!FY>nrM%wez`LimxFMVk&GZWXC?dV zur8E;Ndx%MNPgU3#vNJngZo?fmq_MNXJU~hEPk5H+gaiL3m@Sj9{zDe{Af485GhPTi{B3DRItQiA?rOL3Pj5f_!4ErNm&=|JyJ1D<(_GC%q-CT*+BCE zB{a9f$MQdw_^5pz%R71ya_PBr#&X)RqVNb7epSJ9R!Ka?<`QoDurVy}A0*Co;SjZ5 zk$&G!^2&z#892%z+!DzwYH8tCR|Sk{s@HlXaWCD^x`mmLNwY)I#Gwiue_mrFAQX;x zwvTkvJY7V)N`zH0W9krZlJfv(v&tDVgzL!(B@tZUfG86no zV4Tjs*}FDOoO;@CW7$+Ap0(0FZtHQOkzK!x&r9(9p@#MCMI`#vBe+6;|KTB1nThkH zz<2lvy7yX@G(Eoxw^co(khsw0;!j)SuY9bo30 z9`d(Z2kj1fA@0l}^W7f7L+Ujg@Y=+5(4AE0nnbX%XeC+mW}(HkG)xbjZu*~p5E=!I z7cjw*tXs$u&|Ods35IV;=zJ-ZoJ+gviw^MvMwHA4uwF&l6GrM`FN z=gd?uDey53hMzlIh?>iIyi2o?^3TP1KU1Yq`<5kY_2uTv)BWBR4M{9K?amCH-3gxJ z083O`$&fpXDd#COcJWdseTxv68h3oe4-o$-3Jw|T;EjvD#N2#5&0NyoLj!fJzpdo# zDgxoxX{y_&OQS}rCAJ?^;{6HYAjx4S`nSrJK!PNIy z&KdKqpws9FnJJ@ysk)Jv^G$)PW5#1g0NveKykeT4{opp`MnUg~_ryC-8ZXjkkk{(K zOx-*VM6d6L1=}mhzAP3yeG@R}t3`fJe=xr66A{?lImjL;od!8uZ_v(8dhc#kr5=X_ zY<*h8YyUNeJ8$-H_Ilk)gTSUu$XLm8sSo(LWo;!kzaGopZ(IS9SyA9r_k}#t-w3M@ z6oZ#y11TufLlK%;8zAeM85;_?(vxmrLcS3-+81VZ>K1x_6yuUIHDIcpD?D8h|e!r!jz>sis_wdY{9~XouJx1Vo+>AAE zok)8L)98$CB6lXP;Cf^GNAy+WpEEF-b~1K+ruXRII{4!j^{fVEGSBLlK$&GMbkY9M zYv<=+#n=RNT=0PR>246VYm5=pI-g}FADY9q)8*hny=t4>$K$CidiR{-$arh!b7vdf zVT0^fvOnDrHI2Pd!MTrj)`@T{I>(N5g_!Ft#mQ_2Hn$;jF0z|5qMZeMX>awj>#BHc zdOUKyXUNUBitv~&mUrB!A&#_bl~4_kn5|%XW#u6&nld)2*Ftr8JUU8wW5xDl5;qi# zON>PXInE2%CgIUgDDDSjSsCd#IT7XDQgPAxd#1iFbKuUG2FT4Xp^UXq>L}Dk&`}&6axXTzcZx529IgwCvND<$deIm-``uLpA-pL7(OwO}5ZckbO zWI-pHPjh@%?Wvcb)r5FhhoWrfJ1k#)jUCe)2BzoQVg0fOa^%7wcYd!kT)t9IZ2yR$ z<_|Bl&Jg8pH|V2G4)uf8y<~P2i^7~)VKDVXGx7K>f#WD=Bl@rrPwL%0E=yKu#3!(y zGIUQ=so~;z#YBg4!!jlYP`+yr6JQ_>D>9CO-NAD5=x7i=o-$6*^V5bEOHhZa6?fpn zp*m6+IUeFSIzY>cUUJ!pX6_=qaO2k;@~k8Tg&TYEUB^_`I)VD(ANYao)Q4nPO9yA% zzlLM#)lGAwgK*9IaRTL#2zJgP9+X&CgM8Rq;+-IkmNcvTXpbwy-|G!ep3(bE%U6=r zsg3Nosu)ppP@gif%twnS3i8Re{?FeI9xjxQ!EA2ks zM|m~zlok2^UXPVK2}8SvjEvty@8*x>7}dIG9QDM#r7IYX17eU#JGQ15w$MISd2H(S zLv2|;iDBpB5rqtVappNAeODUl<^+Qb<$ep(cSy!ls{c!i^Uj}`hqE&S@a>(R{2#-2 zLGh3Tinr`#M%(O$TfzWOFSims*NA?HFf2@LObXEr@y<*rOKe@9PqCmXsJ+a?U_uZ|Y$VCP+UE9XP)*ZVc z_iiN-O7tV)j=^g8~VpB-{)xW3UBH&=S|=A~_dKK)|&Hno97Y?y?} zE$OH>eFG!aSjZ_VxD?hXj!Dz7hM~Qokn#8%`EqGFO3}UZU+vR8ufR|&c+ii6#;>f2tvnn# zM9`Lk^gRo6Z znm$K?Y{V8z_~BFz2SlpL<_{_uMCX8Ypd+*TG2ygNy2GTuT_jo22xauV@uF`ZPraUS zj%{PX>WL7iU;6}BZBs}2hxw#XXc=BPn}Lfc?=R&AaBb*-lhIa1o zaguihzS=OCo&5bU9I$u--fEvnfj#9b-19+~B5`K(`%-S8(HQ)8{-PPoNNB&Nh=lS~ z@1B^1rqqke`yRb(s3hmlQDP#*KpFMPXoYy_v)`OHLVGL+E9)qaRa&nAj z6=h1I&}&Nsxe`X1uKh}a)iImcdy<+kh<9MhgF3Qdy$YNp_8_yMmt;^+`%+mSG&}f& zeEAT9lH+=C$LOi7`967w@AHL-f-LggTnD=@L}AY_HPh}VL8zdqELd_qoSh=eLWyEE zY`p)Lh|0_0wPoqpTlh$||9 zv9up3o>d@?o3t??DU$xXXBace8m*Y&1M112h|?N1bfNhpa?_op4@JYy-S6S4MhmH! zqk}J#Ju!ce8M7>196IkfLtAhwNp0+c$i8)WxcvZ8Dw&5L#%5sON9ql(90Ogd^i12^ zLcUwm`~p1>%rp__DOk+Ib9{gFGU?7Y7}^8fRU9N#x02H9%hBsx2AT{nW$v68;Y2SU z=SFvmaF13+!+voc6jSIU?F-eAM|TkVyP_Gn-de8VP9UVxemy5gXMFxO7LN_@=9N9- zqo!yxu8e-n{=6IpuaEb`i-!$_pS&FB2W8+~n!VLK`Hssmv4SzFKgjz>inwJ;1fKF% z;I0~};j3Wka~OKXT(KMC4jzw!gL)rGp2$%g+?9#u^PV#5D^x)8*Dh!;tRyj$mt(;% z+S@zPGJiD9X(s;^62Ra-c777wJFqw4)aMW6Y}I_uJ-KK^Hz@YJ1CC}ks5T(W-T%PH z#2s&Oz*mu-PdRu7E2CiQiY{{d8O>$j8I+|=dy!OIc(kS%{PG*fugb}&{5c&LUERP; zj(N=~wYX9y{x|Y~Cxew#yIyosiqp>00_mo0K>8`KAaDg*t4Cl#Ku&(K56$Nu>c&iU z8ietlHe^g)Fyj=Vi4@=y`w3qSAK5zA{8+(b!7h}rm^q*FfX zuAD^VHp_8K)MRiR&C2Cw7c(c0-h-7Hf8bO?Hu?TV3YT2nh*PiZW?ov-?)uhv+&TM9 z-j%8#jQA)ikk($#N{38>btDsi7p8!xipJs-A%n%Lz05Jk~8dreXAfhx*VJms!8HbHR?%D$GSmBCfOOd z@p}Jeti$=)l=0w$%`1NJ#NC0jU-IvasyO%*hBWAm9YaXNt`)d{eFk180_Mo19`4{; zH^{fBBNZn#Fx?`a_6P)$_k~wcynljVQpQep;R|J`$jOFOrj|tL&!pXFCsF71a>ntD zBHS8shEvishptb#2!BqXHYAbU86n783JK0R&13zw#NkK&DfslfjF=yrgrbL1anImA z(>m(^9NjfR(4C*g7K$tY*PaG2aCk$MriJ2>#BvM@oWq{FeJ>(h$E>y&*7oW)bk5h1EHSGv6iDFvkeBz$b4x|6?xz6gz zViLW}Ox?1G$nOuul&*5>rbWa>q9^21X`SDE}VGEg<>3D45YiEyt0u5(U6IgL2-jNU=2xv_%Lyp3$Gtrj$g z+<}R2>d3cMs!)H{9+ZN5$>gW{c!0i_-QMLA3vC5Z(Da1~m$HcWCj;6;lz=#CqUivA zzt1ihE08!7#vX283VNE=a9E*&>^>=rr|6#gyp9{AN$(IIso9{}^^H8M(#NVYFKn$7 zVv^|ds8ggrqS?y((=4-?4@4`-6TaI5+^m&>k43_nF-HfuzjwVMkoKrv4^YOemnnGu zj4K&CFBX>hyoZ%s3(2mcdzpL>tkE}PRuo8pIyl2hoi?(ZvN4@P{IFy$pU7@rfXl~c z;LH^-nEf3xu&*-+bfsE}&=F7^!3eU$HZGT+$`&<6#(|lb1y9rV<6E)2lo{8kue$S*cn5a3Adsd zEkQju|5zY|Hno!>b}QWg-HkD?DAvA=1Tg6PA3`W|m2Q`VZ{ggCk* z>kVP{i&k+t1D4QRM0JBpW09nV^#5wY|cbbQT3zWl?j*%t+0cTiq8=YhQr znKV=Sl=(YJ6)G?70>zJ&WW9z48Z7cf+5QRn%Ckez>-S%LpXAQ=4;q1{)(!BS)J%Sy z(!!?N1YCTWk~9?-a(`5cM%aC;P3}RZr42qXl;b9M@=^Fh8Ez<2VBegw0I8u!*x=Ab zR^L>|C~qHZIPc9XcejVLro|AT)JQetsVGLh88uxS7@kuxw>aAs++@1ROuBP7Ji86X zPpu`^GpFDqms9xPgqZw{b0HX(_?3FBH?osx|BmS?ACOlFB8NLhW6K+F%#4cW^*@=w zUD5of8$4fq1G0B4#PA8C9R5e2H5s{ z_p)U^FzvT3iOpDm>s&K1snv>kVpPfPdh7sS-M$m^*NXV?St71TkmI)b%HnGJ{ALXm zGke6dA?1J&K5>3bOl9a9c;W_ZKD&#lY*>IR2IH|V@Jycm*B}gfBOzGQx0IEsoeW7k z)8KGc6A2=g-2O@ZBff%fjU<7}Lm1C9bNa=tt4*!`7w zh9k!p{&&6=&Q!xkaVPOmx*Dg_XowFiBhknP-yE0qgN7^^?!blyf?7VRN z-(=z@Y=jy1kvOlUiaDzz0eerK0;a!=lv<2Km$Q-h?R=bRjYtsQO3@O`Pflf{GZ%vR z^9Jzoc|$5qLNVQ-3_G)Dvv>23fjiX@`e=SrbDjoPw|S%FbO}b}ZUyI{WDGYS{31vH zUWeR`ig>{FGr6+U0L>fHao9hKSylg;8>;mm$!+7wWx5bSz;a{ZV z!R`X)o|-s#+z$nxf@UI>A&0&6{odj-hgbEO_KRH{=9at=<_v_yaqU4XT$3lxeaO&6 zk3z~F+I@wYsVfWH8a=^Ln4Uj3O~dr9@i>R}S+9B#gpV#L3N#znv%4wh(CNQBkgr-# zz)b>|uTDZUKVjyRjv6Sb*aKwrlJU1Eq0l7Sf&l2a@ zY$9qu4fndmqnod;X$ti!d!#7}Oj1JG!gtG|VsSMDoUI_sTjem7>R>ZZxG@X5{UHB( zHXJ|HO_V5GU|i`*Y)cYi1_z3{-Mc2yZ1XVDj#dDb4sWoulqa)(EW~HJ8Q8HpoS9et zlY3t0HR4a0Z4n169p1z08MKpR*+kTq@Wh3cX3U~`Nti~xC~Fhjh)W37f%v}YD;`2v z`Z?wFbDrOQ!88cT0U<%~VR|cxU8RY`)L$g=M4VUgA0JiLH{wTsmd(1b9|CeX_;a_7 zgq}CVMf?a96`IEMNsQ*&WKVEysiItlN*vTm>L7IXk%ZZrc$oT6QU{|M|L2Vy>l6r; zVst02v<;Uph{GAddwE(_G|yGoh&M_fvS*7UAjz^HXn34_xoC(h!Xj|WWj|(uPc?Tt z#S*qR{ve#a6534-$K25hT&*A>*j zbvo@$mZ%~NlQtor^3C?8+UK{-3qgavKe)wYFZ*=uEI9Tn1@^f#lj^|<_^c}dcYmql zSt%QH1sh(EY`FMR5u=x#W*&7aK<$1Xh+7v#{! zhK-GJ(Y6e9TCs{5d$Ed3neG6;=X@v1zvXbqmGXJEmoS&65)g|Q!(C5+?42f!(T~?* z^r@Xpn{+T1Jr@^*RWes^q z`%PTv{_$+C6O&T+jBB~K7wQ*%B~MC_TUwwvqQ~A_Ye?Ve5qM&M8gq=Yn6_=qzYI{D>WwXSh0Fvu>fy|zGxk$6Nu4E+y2&(`lskuar!AY4TR+T&4+(QW<_jpZ zLIHO&0&M8k9Z26tyM7uavCkt34aL4p?GYq(KVH%T|x#Y6a>b1`E1^QX24gehTNPA^4mrMZ>*#9 zq1KIY9~A(vUS`AM6+PrrxdD23okC?>QD$M$8_p(d5;VvCCC@q(AzRZ2EUPg5EPS&{5+hBWffMhtq<<r1$K`85GCD2TF+VF zix{dipW`!Et7^E7^Z%W7Jx?j4w@^4<)KcK;vDZ5x%&>|mo7>`in&XbwaL5m$ofKWhzwx-*9=1AeHuRRHKyXMi zDfZIAY2t}^^aqf6|&RIMR-JD9%%Ts~%pSlWa(jq~8 zu#5N{HOKw;<5B2UJn!g`6I|3T2K$0WQnPP5-WH*(Ho-p*as3%tBqOEx9gVa9L*o>*Ftujfa(k$wtzbY}n)-l7Qp<9wiUcM!?2 zl)zim=kLERhS%{*hr3{tIHEI5@3{>pe$jVlpC~7?Ujh5vY1czoJaf8zJsdf}ha|6V zGWN3pM#i1OtQA{$_iGiwbF>fCrr41^)h2j`_LLbvUd7y=QNyWp+K*@szfQ^Gef8^T zXD!KDxhvqOJ?R+yq=b2Tivx>HG4!)S!dEcILk{#_<9Q{oK_wUq?uZG#Br)ucXah(# zN`s!6G@E(Zn$vCl&Y7@6T#D{ol&$r`9MQK#V8F*-)p~riUyU6ISq?wKVxX||6Dgk) zj3otPf_p~;*rB|2Fnp*S{^Qq>_+l-LtEKlx#mx+~zTnQ5?FEbMuO#wT7(QE4iY|Mt zn8@GHxZCvHGx3KIcd;Zo z3tpCPW2Y;s!S6HKVDO`sq~wL6xLGMiR3$TupDBa#8)tZVwwt&M)7{YKljx?9LcFIK z;j%H|cz5SJX8tQl&|Bv_qAg5+Jr1|J&|FegjOjw!D?QMsF8H?c7Msjl4CxsSkSAJ7 zoHD{tPqP#iAIxUUmwN$InG2N~Ux+R3l8bXci0oINjR|;iLW#$z2l*29h+J z@cJ_uI5`6c=pE{e>NTdP_8S+J>_4(E%VuP;bN@|T-#njOITeNtg>P^biC`bByACF; zZJ;v0i5z>Pg^pjmao&pcOvzXgu%q5EZ;2+d_1Fy5tfITNhlPyYW=TkP4~4SvAIa=s zMLe~SzPpF!@VZw$;?`~-=6WbEXibO!y7U!LC=yBHRtY>lV2AqGjxb-H<>0!s$A~{+ z-CRk`qZ#@8$4`>yLqT|Yp1h!S(OT9$PZw;@+<~vOBTsy}G;Rn?!f06$#xqkLj?3FY zL|!jBQZWS=Tsw*T?4OViR($lg`Gm_J>9guT7QxXQ4GBC!)YN?eNCF{ zw2>F|z6xQh4w^%iVKtnX{EnQU+2^Fq^f$w9XEq1|K+`K5W}NIH%9BgE9=<*pCk>Nx zAIHLhXWmftTAnEG?%}>`9fVa%@5#N5O8EO%9A!Q_kw2aZuz37?FpzB{9{w}~p5}pX zj<00iHcP|4OU@v*x1Ibwp^TI13_qjCC;q!6vGkWWzRL<`>}DxI(Vl;E^`{H%JCKaW zAM<{js%7!f&a@7TAM@C6Qioy1c@DCUx0BJ7b;EZFz%O^kGWoYhbGMW|M?7Fl3ll)> zi#AGx(>v)TZJd)!&u;-S%)^7toNMaU-eZdq{np=11!;#eJ}Xq@G_*;qxU3ftpZsy{>|I^@sr55bo^exYRZ zE>=l)E_jg?5dGXtRA|5aVzopx>8j^7ZCuRln(%r=PdFU;5K^{NURJXlm!%qxm)4bz z=m}{%X-MdBBz&Fmm3%&+i+=O{u_@S}XK;&lkN+rwcCjX6@O1{Rr(V7#+MAfaKIPmv zF;{qdl6D<#p}y#8^jY{L#!2nbg{!+7-1CLDo6uwGh>X{I*LpAsEF0a(^0q~ zo~iTM2zE#Lpr+MB$}$XbPqII*6>{Y*lv4tAIUkUnU{6%7C2{U6>ajnr%*^Vl<;uYx zn!>&l3R=L`(NQ>djs$mvYE#As(s7*J8^)&RF>JFD!kp_lL}tSj)T=##`WG)SwRbHr z%PAfCcqMPNxg?4bZ`?FKn>p}#8rTV?0nhe5sXDrrs(9bI0qS9yp)?PBsjjs-uBPr!hsF2+qxXamevqCYi(3*rOa5b&CKrP0&Yq8Ubyl0 zD_JHKhTbK`XmQDcxoY`>D>}PXP_|U!@C{JGTlJ^_Nuql1dFEJ zWUr1kg%8mUuwhv#c~>5eIIWca-_Bu|82Z4|>RbrP{6db&8KAfCS$tQZz%WZ|IJ+wg zK{;@UWGIOEro`$MM)(Yv!?rD9EHzw%!TKe%UIGKihn+%RR9seh0`;VYnM~_4 zE_43B87q2260dIXLI-z8X0d1wck1Rom^Q7E=-g4pZG&;>@WY8*q`BT9-h22#^8#{f zWZ;C-7C7qFL9C`_!=(sSOg5iIymOb}mU$Vd(f*RzY@rC}c~rBdJju!j)Y~u|hi@+b zHl0J6c70Uqp3>i)zlHE|U1|;9cxB2OAici zY%NyJ%3^;u$G|*h5ZXgOlKW=aP>`vLi*-bq>3KC=!3(ny#x-9_2wft)@r+47IS{Xd z^?B*|xTJ{DyC4d)1|ngKOfyMb7J<9Bm*Ucn7Us)$4LGxCCmcwxBDwJns2D=o{<4nw zvN0i;6Y&!p(|58?m*zqE(-hFM{YXSk=%F>`!MeFO@XjAt!Z~}q8p$=R415fHz75JP zl;`%DM&M%SQVgD>$o}%PhCdpS5J0)Cts=TORd5QopYh`jUEB&VTm&<{o5*)BBm7A_ z3SBO3ViHDIaD9>6U>0Quebtb`8LG)RH+vMf)odc1=-CSWZ)(ZFg<1IYWdLd%NX*|5 zn+=hUayWI2KXc4?FO;Obgv#eFMAwaSm<_@(d1fxpOH!YEmY2w7mI`y5oie~`r7>DZ zj^Zrrlu(s=;pR+CU`Azcf_c>AzI0;`dGL7#W@-50q}r{#hjOMk<8%fd3R}%=aINR2 zuCs?Lf#1o`c-n=1AQG2v73Z!Tehlw4hQWH_V-h1Y1?~Kgp=9uRM(%KhBzJnB_$o{yFNUU*?z1vx{XmvZ{N z+_AaGMA@%|YYs86E$TC|=*a@-9jd6QJcD=0IT*DbjuQO(=EojhxCv@_<*V#0#eO`ne+2)MN;}@K|iz57)Da@_pYvBc(lXxLP zoij|&g2HL4*m}m0vAEgC8PNQr$M!0s)}f2P6XVgo=qwouy^7UGR0Tgvwy;x_HE8xK z8)RMUh|Q4*)V)c6S9emFnycfX#e557z3d^O?h`OP!wUm<-5}d@vf$5rRrK_6VAg0$ zgPE8wd>&IyG#46T%BwU?$;~p|lX?}o3#x*1;y2j*kERee)IhzmrNnJl1jm#wV7>o{KcSJ6p*l@6j&++$W|>6bPP8?jlqt)dBlD(?V0**gLwEbBWk7qe>NW-@hSv{ z$>JB4fAjY9ykKnlE+g2Oy_)qpuMf@Z?tsB^+86&*2Jh4J?cc*9Oxs~iXxL~ANA>zh zZMzg|Ygl1kP$W6j%7Y!-6F~cJJDEa%hY`}Uf4b6NDAu9r|xN~p)rhVI-SKXfM7T9QCo|2;&nr1$zL13Y^41TG4&V*cA8 z3*G(BP}bBz{ED(+O*`#GsGUiU(a-Fme(y>f>iwY1oC{NfAhEWUT$WP77h(z68#Qb? zNq-T3>N$ndmEHN9N~u3ew;F5Omat)A9w6gHcW34uq`4s*y82b{!mkXT{xxyV__D`{ zAM9{IGTbTGM)%eIH4J7RXN7Nwt`2%HPNasU#INzIcTx zzBC_>n5V#y{zqang)&hOB;v=ZjXZ8DkE@}x_y1j2uibOu+hZI2dQP4@WD|)lwxuY2 zMUh=ry9RdBz3-&UUrFD49W;pWLD9XZc*a57KvTCEIQjRaQDGL2p;@i}gl!nvhm?VA zyA6(Bpgc@38O;Bli19;o&!wUVTiv(9>-t(UOr)^tgC)9#d*|QLz5|P=({pFQF~;n( zJFH&z5;}@oi0@2&3=9fGn=wy#OLyvX&i4~WJhxE;nUH2}jO*Wx;`C_7#N!h6WbRF1 zrfArLs|p{2xgO%wD1|&(E1ViTo3}bO0XF;;$7u6UBrKMPvA!8-(7&4bGpdnWEo~1* zH@=g$PRiAHioi3;V%%j#X}scKg*zg)G43>FrMA_5cnQNi~XX_RAHg53OnD zX9}vQt1yFi%R3mK<%kLd#(r#Yy$$q8mqRXPI@MZC#Klzi7FtGoGZz(cQi~|>*YF!z zH7<;1f?ng^S1Xx6@&(++7zOAQ7UqDShZhWrNcG{=x>jQ_#O&2b*l z5IS!N;})7NI%l$x=&cDtMNt*OeM@I{qlFfb719{uMUlWo|~JsI^+Lnuj>Mau2RHL`Qay}n3XB3X(*6{1*{ zG9ki8x5JY5_arPx3&VeUqIQ}!ldV4*dXt<-II;3_WAKn1j!!4p&|{G;*eWx-1XwrAnan>BnSpoD{b5ZShOO5oYuxMX(+|GIFN< zCLxE@Px)c2t{=%a3dZv<#|ZA)uVSq=CWGY3J20lSfpi^|!`z%Cn%NX#-c8VgBCvs2 zY;q^Y}t~3r7%0+8f$7CPq-R|up8Y7p zf2tJ0N;NJAbK^z`H>oEXTI$$A-*gvtdofPaPQbSJ1<(;XNK{Tqqg1p5?zO4rjSH>i z_%=rH|G68H-D)T|-XGH+DsT#48LV^6#;NaPnFHzr-0#Ob!FPER5!Rc484j7Kv2hOx z?@ognnkf^y*+aC?NaHX1Z_~YD#N_Reho_=$V7af4n9>Z+b(f=Pq!>w{lffs8vvG0R zQ|8l66+puXST?Jh$gD6xi@h1>GbqL@@t%i*bjEt@9w@VJipIo@di0jEVFTQKA#Vc* z;g5TX(*jK#Z4JV>mx|2E%BKHhl!OQ@mHfX(Ocu&Yv&;lIjJ=vIACwif8%z^hO+(syU% zt!S6c&L!|9cZ9r`6v7u%>8_jmji_HTMAz4p>l^-(`Q9c9KCj~7r+){@IT4R}Ayrsq z+Rd07j)xyI+hJ>HBl$0l=GU)LV#vD-jIYdWIOUuUrRkld_ThNE)NutTTh;PbCNkVx z<~cV|Ex>Jk{1Aj3o$!&L0ylqOJkF(`wO0d5tl`qtaQkyC=*oN{7N)dwhYQ3$`C#7l zrCY&E{Uu!5+fIbt8@N>yJz!(eSE47PLYb_$Fit{}E1YEnvRmE3cykj;nvw@beFQ%b|Madvd0FI-Wa_iW^V8;7y4&;&w$Ok1=BoGe+fD-sh@h4_Ew&tscsTR=ct22`zoM~-_q zaq)MD$L8nrA#0p{ApjGL>xj(JXgsA`kE-eFY}G0Us9SXv9B9stp}hT=)5kE=EP^LS zbJHEqg!qRvg4ng33kXlC29MWo$uLkBmS8r%xZ_H5QZKoB!QG&;{0oV1P{cVC?6BrI z@^0>b#{D><2slrWn{iGbf6@7wN3$IU6UX6q=P(pI9K*aS`N8=wbcH*s8cF>@W1Jb9 zjQOiikt@D5ga2BMf23~{YxQtEs9Dh-rj903-X(|cRA|;^lNQssOA8dl+~B&z5E*Yt zKVSO-@J#njqFN{mgOu?Vv%8v{q#2D%eQNyQ-PhTeQwv~yK?~hCsJGVo3Qncp>D4*Y z*=>#?(0#ucoGd<*&+#VcMZJ`YJS(8e$V+v!st4^F19ud#R&x;b6 zGNTdhRcA01_Vp37x71hAoq~1mr;#_xS1?Jc3T2PP)A;i>i0tczmo(G;nQ9tq*B{2h z#1)L&YB3P4b%pDc^{U=2gA(+6?O&!S_deJP&0A^Tgy{>0N4u!}@}uFXcPELXZ0Zey zS2421koP07n3F&7i;JHi#BJ6qg>!baTj9S#5*#6oW}eQtXT*oOv`HBTRSrV_v>IX> zA&>LxsU~?fhzMDQV|Jz_U(jkXTe@i?9GaO6Zf{!1sDL7B3|&Y2sltqd*myX+!wE)L z4Uv(rQ&B)G06p0)R*7tYQoT?y*b z8sYDSdU}7PLSLj0&9HI^9`gPmm| za5uJ+MDr)$wmlhm-c+3T>7^u2uCPXjd%0!*y^qEcy*kXDFptgC^ne7;2`>caw+Uz97TOf0ZvMtt(klkv==uN$UkJ6JEpCx^qZAaKxMr`Gh zJ$UB(HFRCLpXWK{5(=EE!$}4Ctku~RuwFh2Ck@^cZ`8o&qJh{ydp)yu?mKQMcQL5h zj}XHY9aOqZ`;LNY(_1z0@ z4K)%=q5B|HqK5g-7nuG73b3dk7z)nk6JKXNyk~p`W20+$0iyFc|NduVv-Cz;DPX__xHf5U#rlPw3Ip!ejt%S@VGNJXEK7rYvG6Yh9_^4QG_8ty>axH-7; zjVQMygJwMvv+%{Y6owbE9-d`H!P)sVk3&848u^`=@bDe`?#Xp1NEOGZ+x^71aXywO zX5*rFD;Slec20888I~;^CNsM);y|Q6f4|uRcEITY{ID2-;_w0@*KL8?A1TWy{~{B0 zc0NwfO~IVACriqXN21AXL4Nn_xh$774QBB(;BDeN;xNsHJHLOJ%NZ5mVlU3cl=c8D zxL8kKL`S1mW-a#oQe)3~Q{VKTL`X{bNUlX`;uY$#_wtP3txAo=5WXOPR%{?!62Ac^ zPpXDTR!u~2fiaHKol05LjZwQ?$!#du1?;9T#O0;}+Da_I#H$?d=8I?CKCl1HUJDBY z^juDLgX=on`3K{0;6NB!<;5^Jd`G#7i(O&*(MGa$f*z&~$74Wy2-(~ajv4u?e9LVc zS&1Eb;JlggDXf}_=9eoN(N%?-1~-}BTrCiwI_(_wA;Qy`fG21-_u-Q_Nsd7jipmaR z#0@i6tX38tl?A|m7S-fYvL2f4xq^GvT(@lzq*?wJRle1mRQAZ)g|Lb02C-?ciD}Ih z>@BOppQba|dzm3%*isDgCqEN!HAAeP8;B}%rI;7k!b#kk1*=DXkwP2FLp~7zTnvVi08Q2D?Mwk-+&1AbK_!vhpOz^KIKO4L0yn=HIa z``=7%{v?GjRIZ}%KSQ3I>qAcD`OmSLyeOg+I-|r<`_luG@=PCJKJ~@jH_kJA>{WoD z{`lO#j6`jofIe17abeFLMzwbVy!??2Pr`c1@vHN38|^#T9BW~_J2DcjXvc*4 zmWyoi$<=V0`fn#T)RTO1Ewn$Gh22)$nP)SB6QXgG6kC3Hl zCith1=2m_tF}K!z;PPLD!Ro>ua)0GM96vD`mCX}JC!*jxDl2{MnP`TAUXKW9bGz;aow4VJky+L zEHI;8BxUWaVpAF{J|vE^v{QJAAN_s1o{b`FRx+0qI=I1O&SM_1m_+JBu!zC+3&gnd z2H|M4Mvp)32g^>~aSv=O2O+3BpVSH;#1+SLaK#%wvqWwoPSZ%iz{-;)lT#wmr$B%| zXT}`XyW0|$oyma9Mej&w{(5eE-4HkMR)9-bG!L5u0&sy_J?Xs}jgzL=pvg)#_Rxc6 zp!O&c7Siqmvprh)`$-_~-x$H$^Dq)`zYyS;ObcM${Wn24-IE_&Z6Y0yOfZ3FFgFId zF_P}Dx$3Z8@a)VNQs1C}0mBTQ^B}zaW-qwqi3*S-E68a}8KV4OKa7#kLpjOtCAOC|(%e(_a3;!kTi8b2j>PyJN&d%E7uW?x zjxgHX0DFe($?_xGxaoKn%3s{hsMel>pnw7pY#Jg4udT3Rc@RGJ5oJu98@V~J454X{ z04Kgk6Gi&{&~aFS>wjg37q(|(c5@tKl{dic^WIAPLK=vCwGK)-CL@2b8|fV-QMMKYgG zrJwJ3{C)loQ#ei%B4`Hru0a)1Dl(@2#ti!A73b~y8IB+L` zM9isX+sIVo+0Z%c+nWKfScn7tfj%R5()^nAT}k}>VljwH)BByEc)PNM$giItnnG%43;IlW!o&OgT} z^(g>RI0l1Xa>?(ygxYv# zn|;aLh@K!PU;F^R*3QL}GvZuPoHja9ubo9`D)Uug6O_(~g0M$}q(;aS^Gs6k`1o+% z(c)-abfz6OueGt;Ufc#T+QGRi^eahIScIl2w12R0CDUu%$%)=`f@d&9PPJ1{&cqnp zeprlawF}3KzsB(&-e6eQqz7Q}X9z+}?h*mYqYx{2jj#JYFu$%kV)6;vv6T~1@^{fx zeDx#_b^ThHMDOYFC_Do~rgRYfr5m|Iry(xtg#cIPA&GM@&cy7y2_&m98dXYO)4mK< zRz+_Gl&2@c+$o<(o1r$Af2SD`s|eo7*O9pF)<0w_jTF)@0>p4^$o6E| zuKXB*Q&%bTBVQ!bF7L(QpWXu9)2c~U{#876w2F2Z&14flhQTtYVmPtq3z;Nmgjr|( z@VA^KbKK<}Cvtx#Y}NfuoM_)ffL9=NIIkp5^Jh~YQ8p^fPGqXfe{-_C|2Mb8x|C3A zAO$TRS&~`juHvTY^n0QF3j5mSI-E`IhLk(>mVMsnS({b`$kmGmzx(utP8qPz`xCMFv=L9=rx}6<<=9NHV);tBx6vK8&0)6qrp&Sg9h+u3Qlp#^w4K^ozAYW3o@pz{{mRLlSv!AJNd`cYpW#%)MwUS_F z69P|rD~X*B?X8#^hjXtE+P+qZK!ro&_;;2UvEL~FYR9eV_|-J4OwHgDE@-58fqZNB z-@#+>=Qn{N%9mi4jYAF1U~HJB%M&WBH3O^z%Mi9gG8%E&MJl0$+zJ@ptSuXQ!`{0vG)_xZl=6_M|9a zVzVv2YFo=_3Qqv{>TPiR0PXcInuIsxf^k`iVOg5oeb97N#)TrZk6us-a_Q|m!Zwf0 zvtPuqBLCaB<&N_~PR1Fdo2U<2K8f1ls_;~T3M)kW)4eDa>co<-WZk{VSX>c|y=GxN znH!40+a3t^CFf}7Yc_tHOYgAiE{t433)jVWhii>rNpjsJm_Obf;#^zE?9y$>A56h` zsfsdTyJ#Gq(~80+4y?HBVNlU2hZ>vxH74O=lpxT*m-f4Q1Jto_RCsSJ4O@D4e z%U5yC&iY7#XH3Q6bFpZiK7-+H>*5wna)QQ)Au>)}1^tv_F!hQUC%TcoVY7AlA2#sV zYwL<2IeHj)k_F@ny+L#xtio*h4@~j&b=Z9>3$=eolIGRig`6N_3bl2^jrqm zo$nwnLYujzYX954*G}f)QM&*vzS}^$TB33Mkt*D;tjabmUkOWhCc=evpUA=SM))J? z1P)|c8<;Mp(J@c ze#!<5Qc8GFKUQ$h4l2O1wSpX3f-p0d_B7ltBsl@P$aEaTwW86?>sSA{##644{^t!5 zTp)>(_kyu?-3D@#^3@NSEAhS7IHqW{hC znCHg0GS46LZrmc*_D7+W;3xb~%ao1&PPq^>0w8X*n(%2pt1mMdU%kn&?OYy#D$A7k z@Q8MbeOv;98m(YhSWQuVNeEPjIZ-f^UBCM{)X;lhwfI+3wcQB6#rfelQ%OcI;~iI< z_`ezc;GrT6o)3i4$d$ypcQ&fhOpQ=jBGY9%$Zd)}1geVdM1Hw4N{gi8$`6+0mtGQ< zW>NicMgl9YkOrrg_du9$CwW(6h($$5utjGLllWc|(#_l;v7>|R;1ogoav(Td6DJco z=)Uw;oWCeekKJge2qTN4p+dBaJXDs)JFZvJPr;Zs)vt`3d2W;&4i@4nj{>-Qh$EqW zpojYn(eu|~%rU;eG=e%<6!^f(Teak;yDFOX1moLRA%veBi3@$j`A+*5v3FKYg*#@s z;I*QSd>v53YUjX19bAKQ&*WU=cwTtNAa{hN0% zGaS#roxZzp#%Y-NwNS><+A6euyMeJXZQ?jxL-05v!0o=TgPUnSdi7-`&V8jhrcmZy z+`AKui|-IeJUqZ*RXx%D6pkiuboe7Hcd`?UGGJO}8_2l!6KuVNoKqDp+?&OW>Zrow zRc@fZ{UiCWmU4#I1!EQM(tShwhEO*azdg%ijH;zzSS18bNmH+*ts1WW6NAxu1GYc( zBM_8y`5r$XuoWnUi(kw@xd+*0F840sbDb(Q39)7?)Pv!99f81S{Uqp~5%$ZTz;0Vj zrlnbitI+lt(@eCM-GUQ=I=FVp00|p61t0#%LYMk$%(%q^T+fj(FrV8?4#iRb+i)eC zKo0xQJ{^vn8Ueja?@3BC?H*c6JCX`qn8owDIn(S#5cKdnd0QcgfAxb=YVa4?^J_CU ztF+;z7ozMtH)&YW89O$swImJUTlh8*FMUI-@~BrcIS5-{8kU`&e;))~l<=G9S;oLw z8H$%21LLQ8#OAp@ceeZ~H)%wG8@TxxK6*K0$66&$V&gT+5v@Yr1XcFW9cQ@oIRAX#!j5i{J(9k=SceqFi608GZ+J|$r7iJFT(R*v_MHl9PbQ@=F>^`Pl%egC~YeF*W zFBawwOPRtwRd;y$p@j@PM&sJFW^CY=u*ds+K|sD7Dt&s0jjk!DsB>-X4k&uO1jKx7 zkT+S9i#R+Ei}EPpUHUpR^wSkO6ryN%{17>I#|x+LNx?q32p+F98b2Ow!9~$6?4lXB zVM>cQrpbOH85@?M2xMbR&MHQ3{d-Py{yGr(OFMctsA7zI47R=%6@dG>g1NLktGUOrs5QuA6Hq_#FV(s0-ul! zko?#|7F)Y<9~KO8FH8iv_4(3RB|Hmnb|;eKKQCciAoXS+R%PvjSHUa2L^yNs6WMWQ z94?JLhWVwDyhhri(fj!q%IO|q&;Q&4qI%WP{HU31UNr@4CuifYXYS0Dqax`x5?Z-W{CbQ8wO0eXiKkQvrL!MtT!}tC)lWUo2 zJ328ESN&1oH@`|^<;#{qVtxz6_f?bmYRTwD-)?u8&0?4Koq%7i#c(&{D+yU-hDjnJ zc-}*fNfPVg{)o+lBMW|$Z}G}tGb0cT#a5A~U2}2v)NFj%kjO}C4|4M!9Dqox7V_eq zGH#VkMn&E<64G-Gr!S$}dqx7=`8*x;Zgs=AH=U$G#t3Wj4^htkD#kNa8p^2WEnr_K zSw-_`yJZ5wr&gRyNsq+flVbdV@bRp*yE4ctN5hNVUF7jZMZ6?&6^G4@c^5m%IHAQq zxGxq$-2Pky>p9|hWPTBuwQe#_H4DUt;*m_yYEAH1aS&8*)Dg`SYPjT0Fm4eEC0CwP z?Q5SHfAumuw*H1WebDAWfe-CbJ)(g(uBYM3M7~f0r9P60r0;k?I zz#%Ex+tN86Pu!q6_nIAy>z1>?{<#acG``V0AnhbvR)vQ*Z)D6?HFHr9CydQxn|NK^ zu19-$VwE_-dk)l(myHGO@yvrI-?;v%9&r6+J*kt5zPccKSeKoOQ5yydTahmuEya$#Pl3-eaDPx#&K~g|3;gu_5T%rw{+bQs#+_{X2-zw3`GMBx&<_6f$8X4QAcRbX_f5t~>$B#2p zG_Qwi9__?+U zA4jXQH%DD)zA^?TCsEB=VHzgJhT+N^Cwaktl_A0{5X6?8C&p%yIPxn1Rkn;{RO;I~ z_up<~J9BQe9GY5R!Kl-}$u|EfVCUiv{~ouJ$Gf62Ot%SBY8F#YpdW-zC`pRR<<9lsAh$KGrF;0z%Fu4_;n_n&n} zGmWFnp)*3T+tC#YX>N{-ltg>Vlbo&POa>()Q722DzcpbkYrkkBc%~G9F!jWmzgNVY zujXOzI!$KfjqxCqz6p{AhDj4|GIkaEBfs=EX)%sQ&zXJrZQ~?X;uPfuP4b6$riSDf zN@80wTsO?v+(nKwPDH;$e)w2-E#vxD z1~TO6@2YVZS&>b<3Hk#dQBs1;e<6wU_6K16-^+|8Q3211(eP}ji)e?_Y@gOu%Iz}d zjpqm_eRX7PCQs`rf}K+Z@TE*1xjQroH$OOv559#n!ZunE-R=WySsjU$mO?lhfI8QT znA+bKF!4nW2*tONo$6Ys`z{SF%tRTvwh5HiNW>h7gfUHnZ6AlPXkV)TcO`Di+z}4cJYZ5|J@F4Q zz(;|}l-;(4$QVc91sg5CikTNXO(7e0__smg-VdZoLmh5(yMm$eClVv1hiw9Zs8Dr@ ztl1rf|FVBzt(+3OE=LA--3T7joNrW^p+nV-5{!!NI z$E>m=lCfyCnC^tJbJ%-*G}Ci~z~qb%q)S&93-%mA>wI}8Axn;;Hs>kqMsljkB8ezj?diuQXbfPsbA?;z$bmOkG_jaVQ_oEtSEi z%n2r?nT0pWY0zKyo}5&efRW=aL49Lg!X&~*VX&}}OB?a;L`?s{Q5fm3!i=zUz010Q|#px*DlDc70nj$2?u!2jlR z@rGSk6qABOpCWi+BQy=S_$_kVo7iomH^HGo1k($9$?dlVAVzP@MKg+cOCx%@imbI@ z#~UJ5CE++!p~;uNIG0VH5sOkMsxYtTBQp}c0sl}9-_$g!#G$bOgrYUkYnMASPInHR zx6FWH*G>|)%!Au#I5_6($S_gG@&pERg>R4pi(~Om5`A0ITcOYzN3dv10N<&fiAV*D z7iPxeH1j;(H_EjWocaT|?mEQIE7%4u^3{-hriF;FGRG{cSKK_ig-QDSh6}aW30_KH z$zeOXyZZ8QzXr$CvwY2UQQw1yju0pEP7E7I7vb)}-$ZS?1n$}7jFVN4GRuAl0Y~#7 zy>pw$$rBOSSuDq|adu=ENKJx{Hrff1*FswQ=x!;SI2<1&yzwT&gh-{&C!keIs0w4`n4DdI$|G1W+q0k30;M#wu*t>+Z$&r6_$KENz*Hc=+?$~b$;`ejlYG)e}*rSa?uhKAm zohTzAWdtU%j^GtLOw2ydLVV_rVQYZ|bVXy!*+wk;r^BwZTn5~Pb3jWG2^oZ2hGm)?1XO?KG?+GPz;dZ&@RX*9r~ESgzJ+Q}F@pNHCycVUGSohOUp zP=)GmIcb|1W~i0(p8dZ$-2H1j-VpJ}31-TiH@Qc144SyYS%O*k_Xk&6y#+o9G>{F| z6VSvf8TUDEAxq~+V8wS0{?hcVtoDQ)FlF1IruGAw!o*=Ao$~^f*-XVk4VX#y;pV(g zL+k$y2`5%uoA7SqH%defOn=Vf80doYYsuOj}o=4f#_6AwL<w>cATQ&njm2=BxnZ)4*`rZ*!n#-PP4F$m@0xQfv65H$YT%U;dSVqtE{Vgap z)5QK$wA1#!1qM+cdwFp(WAgVq*Dx3gr}y=eqPoTStTY&>k1piR`5TJ|6sz!@Sst5D z_qU|z?{H*wHwmAki{J7OW4M4b)6w0}1-!Q#^V-dJlf{Fxf^o%#KV;n#PgE6YLmJp* z#Y*Ksa>M^-^3iBzOtG@T)@AD$>)9r7x^FA2dHj~xv`gVc=cVW)CQ_DnE+1Aek;dCG z#~C}j1z<`uEoTh7$(LVCxle`VV|v9gxfif(r8DOIQsQJjrsC4}Dm=Ygjhz!gxsQuu z;GW3;PrdSIRfy&5=cHe0m@#|9JvZJ-y^Q zWzXyr)x`6!=JUK<%{i30Hs|XyLzJHuT`-vlY^3t@!i{FS-w!LLVy>5g0dlB^9K|PuA_aKt?$XstPgpnzanWV|!zHe`iMF*-hW^%eaH=_sH!KAX*JVA6v+!4;Hw_ zIvf3DJ(!A&CeG^PjxOO$?xA|c)kf6)S?O{I{uKL zT1&Xowz#G;6Ghe)+6sF|;@k_ee5N&lwXt6VgW)Ye11Q8g#CCR)`%tH`(MY5tyMTGe3jMNdK)TEb;C~I_ausP-A^<-;QZBQ zOog621Wt2E+T+bU?Wwr()ft>>{zJoVl;ZRA+yvQOz+f@-QVs*bH4`a zEzl4XIDVAtJ9eW)%_SSOvqm>M6EBeU_u?H~vLj!{yuG!>RL}5k{%^wwztQ4u#$|NKF#*SsZj+qv0a3_t}1 zxCl=J6lek^{x;;;WJ5BH^A4FG3cp%nd~3F4^s4J6689a8JH#q zyDEdgySS1F$I?ELuj+ih-d$E~x;!S?&%|p=d1bxJ<8jIJlPb=L>=XReGUbK z7rkV*zAC=1w!!#BMV^dGJRTFP!kXATR=DRDd_MGTOs{Bj`N&N=YX_%YMo7D_99}gJ z#=yQmWaiVYSg6{H2Mxtouix^Jv^*A?j&_oZj4IyyX@ib@C#Fe#B8cwYN*TXz$9@jV<3;mfU!^2U91UZXa~1;Ukp?C{-DIT71TPK6;J0PfyoU>xbN+1knAfg= zX7Ub)J7e`WWp0W|8qOP}JM%j=_O=UC!Kj%lp2Iv zRIiu$CP!oH*?K%6wTN|d34)E!or?P)S0wL@>LvQFZNM0pH|)Kx z+n~2V1UqOi+a*0s{5%qb*1xnEE7gzOsf}yLx-+D|gyUtNI{%l9H9KzdL&%)>85Wa# z0+g}+ip~>1yU$F`-oJ2zLsBEuT-5@xGQ=V3UpSk9sioyjnPwn>#>f@NArD0o5@|uYYO{$3|$j9 z5HXsydF&>`KhUs>9e6zj?wu~SiNue4W%%p+udu@l z*20~eE%0(dEy-y~L&4%Iyu8br?b>h#wqGv--zkG+{sK$<`6`%dK=RDp-#wf{q!qkT z`bC(Q+n{0~i>cLp z&@PZ_DRCK;k<$%x1S#w0h8adR9Yu`>Cq`CR0oDoAcVFszA|xG!Bt(e6|Bp8N?Scj< zsYHW@d^fRoRKujYM6^^g;azS=F2(*k=WtPoD;-w`uWSU+FEF36~34&7S5zT z)q&eQ?=c;tn0m;q-G%rYUNfxk;TaHoBM0=7+KFxcI1E~tj$S5W%(uP9;Jj`P6#ESm z(lrN{>IdMj7$kLc-;lgehnu6d*$V5G@JBrv*020PE-#G2J;#Lj3ZG7~RU6zP^>YJ+ zWWFKK-y5Od<1E~AY8SI!=pqF8-i3Ji5fViin7_x*ryROhyuYFExJ~H>V9+4IHR>B6 z8+H_#v&!7;XByb*5r{*P9!$FDZ|<(?7OzIN;u_Ux5B$S`jMJGoEf zhmbrvd}fd-)Ms?+wP2r%8?2oFg>1{6K>d;d=!BQa#1A@{KQ0t|UdA)*RC&la8Z_pA z9=a2O<@sv-ec$rg-*Ix-JYzZ*U&twQ*nb5d&@8;0+B|mR&~eyGJu&{rKape36EJ@Z z?T7uQ#I$`^;52saA7j7!e7FUl?y6ySJY^=ou)<90O~th-443wk%MAP9&b-uG1E;t% z*fXlk)3v7=JN+t}>B?t~>M~&S?(dL9v*8DF$K%$Aw2w)^h1n+inJeFBHDvv`Mg#*$Pt@G?9C4 zd0?C_fj4i3GFRmm!R5JWF!+EnKvtOGxCNKdenS;6?%fK`MYo(=Bq_)RdsV`YzjO|N zRpyQ!NykRr*VwsRo&6Q)3eS{dz)xY2Y(IGzHvLxtBfKu6w{1S!@1@L;+6_#WVh{Iy zE9C=F--W_k1q^!|gQe*|h+pJCKY#J!f^NB6$=LTbaVp`dQ{AiSsuEP#}JN83y zFlhBW0i!p4Wa~UlY@_`SgZoo?-s`7vmexsQ+VX`{kKnnn4PG{t;sOPXX}*N=ha=J$ z<-Oa$a5MtWE%-(}I>pg+%`9Z{jCi#(FQNR4IxN`V$Z`@Huz!;#H|d(iZZs(Yucx1&;C(*n$)OoH zy6dX;eP+C9ugBuXSd3mCQZjcz6fTV%#P?2??7=VvDESl&CvCDxnz|m!t6o9xC%wEi zIor9%_5)+Lzdk3b?Q~cnS(8X+lPfrlUxgx3>TIB!GkC2_fcuJHh$Q9d-6=`pySzJK7u3Je_ivm7To`s^~YK%jc0h~Ix5f+vWlgrlTxCR0+;aMh; z@236KqaA1_W6Wx6sY7S%QP8%oCGY(wqSvYzjLS~36}lRZFK0{f6~p7$1@G6w!3Qm1 zxwn?+oJvP0i`RH=*qU{Jc?K-0J}XNZyh>$LaT3iw9}kvc&ban+506`oaoYrz+=g~H z8MMsnB|j49qgFEQUObb;$Xxr%or&2FO6Tgxe?yw+u{Ih1tFRRpFwUgVAD-5Pg1A5|53~=73UhaMdJMjf_y)1 zZFXX>2Bc1o2DI-cOtl({DqY1ccN3nQ3!lr<{>CLN72+c4KC^DKBpyjDBR|wHVZTHz zZh7;KiG8RGmdytsq@#|+Qzos?7D0X+Wt4e!&V-s%Ik2Oxo#e^u;o+I-_-36LlX1WV zc51GH*muLEJ!lRddF+Swc0lsRQzor)EjG4mv1LW8V3$}j%qsgpoL!>OGFXsrH1QOh zujc`FFB)Lur#FOiF~JMevn0{Bi*c&D2o2Njf{5D)(KAp$3ken_dSCKdn>#qY9R~1# z^8HxWkn&gk@j<2vw|FhhPdNl&2<@ORR{hJ3)VsrhH4P-?d<4c@sq%#l-Pw`)e7J4c z2LCcXkpKspdAvLytxrv0qoU1ir;7$}L-1#1JhRtQ z0VY`mjd?AC{Pd|NcLggR{;>6^kHF#}RlZ4M9{VsN0kh~`AUSFt>qR?@!h8wry#I+b zG)%-o?+`qpq0VeoQRHqs*vmD}7vkm@E5H-QVEVGKCzji0pt^Q8?$1eK`bvLu#`{Cz z8~vRT992a(vw0|NtjP29PCzMh`kqS5XOB(34KdRP;d*-~aTw6Yyj4eV^}F?q^0F`7 z=C+0K?)(T5Rs96)i`A%kvx>;hio_Y0r1(FDC$e=1mEgE(EPRmaB9$?!IPuP0+_`Zb zGr@2&{A>1v6Nj3}heEm=vl1wFIh48MYY(|vX%H#aLvBf};$EMAGPVy-7JLoU9y(*F zkP27tdjr3=Q7>GEI%`UO6Ezw!05t0{-~R~Q+fxCGrCns($O6>gnT@4$H!^I0FSo~z z&THcVV)BN5uFq0G@P!|w`St?%7;*?$!x3UdJy)k|XW_a>yUVthMPv5q8k{|IAv?7u z1RQ7%g&);VY{t{>i8z`=q;oiYoh4WQ>gpJ)?ODnr*qc5VrPfGtyuBt^N_B(kr)kU# z^n!rL5isq_H21QLuSust`2u$mKa%is|Vmx^L`cZkDO+Pyf}r-fW?R-%7T2+l}!CBK+(3=o#! zPgP#ZYQ8dujGzKI`MH%mx}%8WM`qx}m#R$5>j{ue?+PJNv@7a|1x}n4fUlIYi1d+Y zG!=Y@0oF!r;1dl9)jSFV=W2=niAc=Wmg47h#j(fgogpl^1$185k{=6iVmZAXTOOao zKC(Cm8oou4W;R3;mRjL|?m?(AAjcdQ>gP@$w1lMOpM(?600V7l?Az5tiiX9}pSKU? zEjBV1LxbE4KQDM-R!3IT?^Cgr$tdh#MI?=GViomrv>ZxeZF;kyXhk=e3HA{AI19Y6 zk238yxiA+Ts4rB~4bpSEsn<~h8zhe+&7N=_)1z>CtN=gKL5ofJss#ogqhL2>o9`Xg zz#X-T`0lC+&vDfw?$piUvFwS~?U#`9NCNkd5yxuboB+U+t?ZbKT znkYc;bQZ?JM3C;W#`^^L7qV^Hdg0knWSIl1_3h+Jl0M$sosK1iVobmLL@;Vt4M~(O zwtBt|KA^YMv;}&@T>v+ zmc1nn6%%nP-Hol6?`9Ovhr?*s9Vky6A!_4P@Q{EVe!N}HYfA6r@~ibBp+bP0&}oS8 z1pRSRpbBT=tA+X0!?`5XgGs9S$L+gLxiqI6h%04*Ug!wHGmmGH-O&-)JF3i2yXDI6 z{&olA#oFM|l+WZ@xB?d0F=+HhpGhCp0W@_3>6u>%&sGPArUc==eX-01M@0~u9RyE( zs)+bZ4-?Vpa21|6wqX|@JPF1o z1Vm}4?frvxsI-*ksb85htvX8F!IZsYUgZKe1t>ok2(8+S$l{MPQI&d@N<>nb^43c0RC!%iiRcEDvs#$XYCGPBZN*d}`)cuVdsPREH<5Wyq7R`IG<`TYYt;Wcpde&?2EeN&}z?i9>#3fS; zKVJ#JyWN^hUCLLkd8y-A58V|aj+r6B*iqR>HqMDaE=if6A3B3ARQo@Y&cmO||NY~o zVTFu@%rvE_j1ta$(^g4aONFLFeI$Fdm$F4x!g1MmB~PMU;dB~(J$n^67UKi_{K zr}H@Xb-&-Q>-BoR2;7|2L3hMYh}FNlIH9Bj$=WVvVuJ?$mh{DsKKpam9S^`pl}gsCBa&!)g6dRV+*;f5+~uWHF*$1~T26{25fYIY(MTC14sxtdwI#&X z(EdV~PBQu5JPeNU#;Sl|o*A9VN0)VC|0H|%>4~ZEJ=z0=MJ^M@coxogi$L2w8~^03R1&#SGg;5IH3hq?0vxIfK=Za}FwJ1Uj5WzRwrUl)|g3Sg>! z2*Fjl@0FCg=P~3`IGzBu_3+M;31s}%iqQnx}veB|sx|3&ahqy@Qv8cs_OWw^pFrB z&r@UCMa?+MPY!d3K3qj&e3s$PB`LVmGL~t)Jq~(K`GN`U(j7^khVyA}gycgB-ad## z_l+g!obZ^vQk@7o8J*x5_MM1FQ2ubD6ZOLGVoHR2xQjDZj%BxpX`U;y%>$QR`a>Ld z`{NBqAwEu;!%B3@K$RTjvt`iEzSYyPBx@N8C~al@D;L1R=0i~Xu!aPR+oB!Kq}v|f zmVbXj7W|hhgzIC@Gg|iRp>E=RcwN^_Zc+`f213zax}3K)Zwq(uW5L+@d0NaT$jYG{ zS5Fyk^PdDd&#`3hw)}oEDp1YJhMbMIN$spniLudf5{rW z=beJLmhNS|J6pMhF8jvL(kZHx%ep26i@Jx%$duLaO2P>?hz=325D`51R}Tf6PUP>c z55#L!A87V4VO65e!;Y#~aB*)d`PMmu_W95|^3_;g%Mx8~0iD|)&yDB0tsjDsni4Mf z&_q<6G_b298OAn%ycz9HTUCm2w&m>SV~L>G z^A8#}P(I$j**Med5>^||Vvb+!=F|>u0ey#FqCJy(#-4lQXnYG9cj7kwJuk(VIjh48 zo__^ZG5sLD{uxO)BZVOcSe&G2#VmO~9}9K8G3L{rTpQXC6?mo{LsPU^gHcJy*yIV? zHIGQ9%{ zaOPj>9HX9%G#^a6BM1#qr#fvA>G0$~rRhrMg-RQDbKer^ST;hG-4Y?qLKr`YHxln7G>5gv9*ryZFwzeF+XGzNfUI@{MYtGXB6a8aZYInvq(q=a_(Ef z!=7g1^+f>#dt7m9t`PTf&v*DFXreeZu2_=6Aq4Oz=Z z16cSw1qKg(BO8)uA%w@H*bYIabBzYPU1|ZJYWvA9BT@WzNe`QM_>rYIg3wI11n*19 zv*X`wgL{|mK{sW&xVrAZE0mdEc}CZG>rz6l>SP2hRYsi`(3s8%8 zRK*+FFtc=Kk6bZ}DWLN(Y4#UFUWOPaW51GO=&L(q2~ZcK2;)$?SzEi#Ju zug?_)Hy&c%y%-Osiw=NCeQ|8ue2#y2fm&?G-SR zBoIy6wuffUMX@`sSjCfOCdJBdjU%VVyd1l9q`>>WJIF0rO}70z; RB^(930nG_A*?=sp81ht21EIAU^3cFA~#WPt#c^) z$(8d4oVRi6uM5V`R^c1>mwmIk7De% zSe(_I$ZPEP0J8;!u%xMx%rnr!`?jIzeT8B6Tx;j@mG+J0yGxU%;kEN2n9cu9CK#-N zF#dn=$8m^M>WJbCH$4ogJ&~`U6NG+SN-*)h2^)Ov0#rSJ1@;B4Cnn5z0LdNsDj8P{II7%aX)70z3?` zU&Nc`8-zMSl%UKO-|(BBn{EaVxt(QfK9v;gfBJ!JItd+1Cz z!b;r~B3Qo<%~k8^oEK)lpMDL_!u_yr-!l?!D2aB~#(39wFLNqMgR+Laa8<*eT)Vpg znE0XSGr2 zYt(b* zeVPF(cquR<5_8~E@UF3W-sq!){WodnbyqTRN~gV(tH0pOuQS=Uni-&G>;jRC%Zb{? zwfIk#dLutRH(v46A0JN^;!hPs-YWpdsf^(IYb)5^D~9k#I2A7a z_(m#L%|RQC$DYT6Opw|Fkf3k(T_UunnEFHhJ<`RMVt%B7cE?mH(BJbpdDcL52OKxK z2PQAuh?n3l4BVEC_4&HSM-u|D*meZhuDHNf;W5adI*IJ%8j^8rA%=gY9_dGR%(V0X z_|o|plHU9#dKV;c+G_)h-};u9W7EvFe^muz%97odG#`_wPh0SaEa#M@h$g)*===R3 zGn6afoJUCovS1#FzPo z_+p(ZBa)*ED_pJM>y92GUp5a98PINV=MZxGf(kZ!d1CU!Fy?TQ41BNf9Gl_!6NNEw zkiJJA6&X*WnWmLlQ~AqxC9|JoBysVuHj0;}>^YrV6F8*M9n?ZrlWplMaI#4X8c&R43U_yN{~{cq zS-OhMlv2jq9~qkemE|QX(0A0n5)4dw!d_K<1POiZ&?NnxNQ`QuTiSVitb2@+itgnU zcbPz@(*S9nERF93-SP8-QL^beWw-90%pWH=i(MT&9UPTH;mP?%Lbl7{Zpz!#yR)4M z%2){V#SX#1zZ&ACl>;GkZtwqio)I+N2pM^CFp*|t_6HsGeiRailF-s$}F=#o`112 z7&GX*Y@CKEYvp|r8WLZDyKx&aXxNDEM)$E_=M!)CeSI$6Hj?A+kLR-c5Fof?e@^po^z(;YBRrc6!6^T;7;jB2XRAjNVYqh` ziqgLkUX&ufu6M!12J+04jvj7UZ!@I)>?ZuJbYB{2h@WpJ6S24hc&@u1pV^487Zqy3 zq-HXzMi!DQ1)4birZ;*!?#tDT4?y36Uzl3Gkgd^_fwX@fkiIjSc#RjvkZyO(`pEGn z={j(#&YfeLw)s(cTr+b83N_y+6>-rxeJZ_czm{ibc zr{9Tnlo_6Iq0gFrG&56wnA5*z3-&+D$@-6K*taSgD?N3{Mm0LaUYDTh(P-ADECXWX zn&64aFJjmmgtE;=c)Is7lkis-&QVW7;JjbtWuh|12e@JDFJW#+6+MS=!KkmE#YicO zLyv_o=qP?51$D1E{b@a8Ic|ZNa#%7!1S!s*n9;tK_C+Ola(^H5U&Bl|ALsyeI&=qj zhw98`zwwoy0V^tQ4BCHE;0;SZfBIa!`z#*6{}g0WBs9VQ@MgHYZGadCO~G4nx|nj* zk4!BL!7X!2FtD=FPbWBJ#q+Fj>^J-_++O9-%i_- z-FGbqer~LTMx`!dO7C%h)p+=Uo5_^rsDbTrD`-ycA(xhEVA&BjjBF1fyV#j{)}G#B z3+^yQucv`RrY9&qEhQIPgt3k0n`UMd89z7k$LV1b{8)=e?1kq_=qkcP%Z0i5?@!0z z&F~W3xQWN^Tz?IIe9wnfZJp%Eq{Zm{%onFyDlkLqrgNUY_FTIBMDFKZns3T+2kWV8 zh?SEtI?%2MUFIY+oZQ7()trR=Bjsd?#dP#tt&cr>C3w4c#9$HCXS`QrvK@DmVXbKg zeCYa4-sR50cP3{sFJLzly0MQ-JjjCn>weOAS_VC6rs;6dA7a=fjI!?Z*>nwOvMc1^ z?37SgRoX~4S<0hx?sA;2xP#g1xCqj14uVy04JkagiTbtUAot-6AbP3bSATQctt!8XLTp>R(zuT^WOK6 zoJe;r`CVMR&0a{`-c3%#%OR-=!LNEFU~<5XUgv1aS0rbzJe)UZRCBJIeKlqk1cOL@osxA+IVAr+#M6)CYb!lE>r;Y-P<4SaiM` zowup6(esqxP|-PfYgbMbzGcFa_q1!^$Xw&>Q@3%}@`?OUw*uKzy8}@8z83s4D#&V@ zr7)aD`=BL^Si9Y~sE76$*x&0XZ%son_&v?MFSlb(t95aPbPoT2S5))%1PJ0yLjJRQ z@;5FMjA%d6(>5{YP3tg+S+<}^XS>|VnJ9lL8a--sNPb~5-Zm@6`Hj)+)ANtv>cb{z z?EOW;45{}MsK5PU7Gw8dI&2=cf)DM#NM(aEPPy)eoBM^iDH)ltGgcnce=cYKC~rqR67Nr&&x4z9xF6cxW4cFSZ3R3p5yt5CNb-9_v0AqTZ%*oGawp7! zBPSi;MsOuL8JGn<^W<@7rY*B;FArSuQULdTCkpPAc_sb;U)TvTqMtNDpxPX)tOtnw zhLu=R?1pOx3dpRcP}EbW|K=(M_VdqO5H=D8NiLL8K%duoZ`x)2LeDsqzPmfZ2k~`* zFMA{LBrJbj39I&eA@)An_^UG+jYCf|+95%Zp79taH4M{Twk-OGvglY;%KKyTiz_cy z8Jo#s2ZYhHb8C;GDRUMJZHeTs9 zW3Mi{4kp?8pt8A(v~aQjQi~-}Vaj*nG-!JotL{B>i-;KYJ?QRCR z=o0M!jhLTrL|Hww6b&~;Zee@oZH9F|anPdqiwK8hL4~F~UMSneqb5UcF8}4&O#Zm0 z4y@l=V)BqIcTFG_3s;un%JG2|j47a5Lop{^ zY;my5Z;fr8T@a$F)m5l#~e%(!6_Tea9xL1u5nQSo{MTi7Zpu5l(M~j z)+9nEeP^9aIK%CJ(ZT)NKAt<2Jp<31uE2{!@uX5D4)4q<#V;ue?201?;p)k7P%7yr zW!WM)xWf#cm)r9s#RBn#Kr^~n9%F?K&cT+0rEqt}H{z(w!;WgtEbuB2MFDqCHo48}9hLI1;Y@@-Q#q_oN5 z4bi#AQi}pGwr>JIDnF3Tv9bmm2YOHYS3yp{O~$VoA27FY1$&x$DhGz10-^Urz2Pvt zM)MBXY{vxK_i+0j(=0UYJvr={1f?@3;nBTcNvLHus5Z&r%tA3{!m~e=EpIb6s~w)s zLbct|xWqu04Bbyfu9BXatz+2a&6zNBq!A_`Zz0it!%*mW3Fe7sGqnfgLCw<&LhV|J zm9QG(N!m?wT7-K?KmW}lIZO*(&g?9ffUqnd_}WoK!WcCS{z-Sw=jQW9|GeQW1iHp} z(aWBRU~P&vvQ*Q1AaMuhEiJ*p*nZ}fFTN8qM-{yHEgVVLUtWdEA{c5j2Zg1BWSg2ehECK)^T&P!)$ic> zO(j_VPJwM(vKwS`qd+3LooLhdyYZ`j+$HVHR%F=2%8E*OK$(QYzRIXNdarTkrILq}d@70_ZZZ)Gami4~Qr+k3X)%cCyK^8iz;-5LLSRG)^ zEZ;c^-e_3CdZ;3Ueqz|!>50>i=@D(3dwMA*#&34p!CH$whqVjpVBY?25@;if!Pj{B z?2kIb{Za?f0m|Tt?j;k}h*Fm7dXzZ#A32$b@NAs zEwqPAH<6Y1Q^pJ1>8>Q`MgH4{IGp!_dh?tawp!{2#9qmV5&B;6qrdZt^!2E7wu?7I zXF8XWePWE~@A@$j_=@7Vv-m4Hf0jY}O)0o<9QBXw@8)iuJq~WEW#rRwWjwsV2;Y{= z@c1v{Q2R;=u3nSHKAM~gVL5F8QQwK-X;Cz5SdZDAI!yW0L9Qf_fuyQ_a;_~K+@&c? z`ban#Mt}UqOyG;GP-C~6%>bd#A;9ivA{yptxM*i720iOxYLBe~%ad+Un=wH4Q-5*~ zWzs68Yv$LKQNHE0N=)&#V8gCiz}#(dkmdM`T>Fy^1#0rh>Ra;O-?ij^^zz4cj+;-^ zgQB1%4ra@8QR~vsZ*wWKf-~5z@5kU~R}lQz-%nf=9k63#9J)y-^RkcPwwHeJ1t@B?M|}b`FLC*STK9XgZ%)nac3>>)eo9Gva;i_9Y zsNZrTzit!d3STY3;*TrY2Q#mLywod5TGmcvx2U6CxF>oC#`9)$E$8&_M2z|OJaZFZ zv}-ylZvI9dXf44k*%W*t_K^8bpNS~jTOc-Th|KMqii;wbVaQ1h-fjA9w$7khN^=GK ztu+Y>Q-@%lb3IYBrTHn!9v5Gu$k^l#a*CVH;p^@mB7UR=wo7frqq<14j@sZreJ#GK z5@t8&6+*pRAIzKnf^a2LxM5m@i3cW&DM&fA}ND`ID+0lw&uC)K?Bc#QgoPpZvei%%BrP^I8%_Vh}tw-O*_B?Clbm(0zjFX11F%dql5FS$s#Y5jnAYpJh)tcI#9cCVN zw{rQE!Ser}>I0V3abnX_eC7U}M_zy7wsnb)Y1E(13L#`2)o_C|iRceebfK9+?_fvf zr@I6^r1_)LpI?dN91|3Xi@|M5H;Kcv0IaSQ;L8uJVq?pf!`ur`;KhGm$z7T=`l_yr zrL*K1{^$9y-1vX<{8kNRaMtMKfrDP;eoG*Jm#x6=5*0T4g9;SAa|W}@a$>dB1Vx|5 z;QmP&#y%SY&~8M4f1@jamA`5W|6*(5K_F$UO-jY(Pd?zlZbO#)>koq6Pa#@vketfv zK3eapt=TdD8Ih?14Nnx&d ze}f1&<*p*0HSk4!pD5fGUE0C}8KqKFOa7#jAY4`0@p^E^a9*QZCS=8>bkJqaiS~{V~XV9wBd3CDHr5 zJ}&(Ing{N!+~L2U+6ybWdsd?$VK3sI5w(d3@9Vmu>< zIMGcEOb{C&H{Qx(4%PQi<_}4&r`@1y1o#4$s_fGvitsBo1nlgZNWOnM>hCGV5C8Qt zCh@BwP0J0`)dxw$1_x9$jzvF@UHKIwl>41kj@C(=*{aD~p}`;yM#_GX2?KJNHR^%- z7czN9Pxf#I`Y*X03+gd5Er9k>BmAOCJ5?W~W7?Tg>IIy{y4tL>WzLdZ#h! zN*v9sCG+|xT%dl>LWsTelgNn6a4L+yqhbJ>=VoR!C&G;P-MM->G-# z#Y0j4gsO$?y~{=LDx()Tp%>)YZ~#^vXuws@8tm*iGfm!zHg2G;UL7>~<5pbt?tsG>XEm6Pe>;|+y0HR77!Pcmluqut z(=P8npU_fKg-u_e3c_!l;r(zqnIvO^$JJu6(>>jI0X z=o%J|vfJnK8iU?(8a^GIsjL8(j#F^yQ*CTtIzl?^BT%1qY7Ea9WMYM=K7Z04o*P$@ zGga!yyXJ-u-}n-24nU2GJ(v@%$12{Q3QHxt!M5xnaS&C**|hIKVCr9Tp%LLby0+7oNcDqGixt}!h4&?P@OVL3M3S_A+eq z!P7|ycU-wovZkuxtyRwGFm#YHHW7rav?Gk$QBBHEnBe>6v@h7snJkXEje1HV{CBUm zusP1Tu&SXJcDeVEiw2ab9;}a-rzkTOA7;Z6nypBstZ8eWE^=cLk>6Zp7H{nQJmt%D3|UC;7sn{0qr)E^SB>X4A6H@3VwGUgl@Rzv z{rR<38MyIKDZ1Ytz@F#kZq|?mzNqYCcJZCWPyj&1&So;Ylyf$Zv)iyXb zDGqwYTS)C81=QT>iR`UQ=id=*wULhQm{zatb&cLJLUU$GZL!^OQKJ3eZ(2)#=W}pVgD0AbD>M7| z4s&0Y|8G`@O1DF&z!p6A2S~GwKW1GQ;eUUn$b6_{K zs`3nK@>9`idsuFYKp^rnzTxJO`RuFNbSFEK0M%K|MC$7~t~#-ud-&gYPWGY_^3N>C zGo|q)FY5tr+)#?sq!igr-)+HUS~!f-4rQ};TU`6@K8mj4^J3Hkaqo|BIQ5w=+kBI9 zVN**%X_)pk{5D1RaC&A=J;IpFbaE2rHef~>u=;iKcw&nViU{ZO)~eKVvd2WnG!SLM zV#uE%f(7fcNPAx(MoN_7sew_Zuv-$0DC;I<^LG*zB!`*PT(OzmLrl#BP_1noKkuU{ z+ni_!=QW>zU)5J~kLEXnUN6Or#_5dKp9PRwwF9L62T1lZL(CO&Lk%{Kluix8t?Fgy zaZs79>{Wx)=FYIewt`$cwi4}{qOq$k-FUNa0H%wM=iBV?XZJZBgV~gE=W1C+3PRKI z*@qA45MabA31KLyeDMo2bq zBQyTep2q+a3|YT`iEB}WkD*rJYSczN?$1I=>OC-8Bgz$SQ^CR$z8G-q9`h|g5>%DF zp((tOgz8f6#OFJdRW+BVmiL}px3FXE{4DZZ44V?Q(V%REm^k0XLFyqn8ZyZIRiPb) zy7piZSVe9M1>*SaUAQb?m;GWn71AGhz`q+0$o*<{{5v~>cI%E~j@m4xyFUx)xK3GW z{t{@`zXZh?KXO##E@qS!qx=0CtVbHnFrA2kz>W?QtQd&IsS6FIyjcgDsWe^U3A_?t zBKA@bSI`+Q>tWA)ei;U*Lm$Jf>_4PHNgDGHQWkFa8(ywV2N!jM>Q>a(G5IzJYiT#= z)xdaiv_Ri@f`4#ZsD2gw7ylMjv>J*22h8~@|n@Q9r(Gr>=Rd*E_{E8aPQ>tC7#Qz^fu-?5hD9)s{*G^=$+f%1}dP;#pT&-lngbb3UyZ@;qHgQ4l*EYJ#@X=lo; zRZeK`o{Gov?=t#5!`ufA9{tSyMC1_VOJupCt><4diSh(aZyCpTx~0rcE?0&-wjp5A z)I`Qleu8OhOR>1Lk69+P4x&R`!KZDIBx;GEd6Pa~e>9M%A{m4?9(}~6nVZ-{joZPt zI~K&;T8Pts3g~jy9Xl6i@?o5v>3&g>rG$0R zD+;1rNVIQpmNaUXn&QPCbDoyiB}g?agpFZzUt==^|NiyB`Z{%H>5l=fr(+l8igXf{ zD=Mfh5sC{x{UKG;&0&uGX;@Pfu_g6ik*#V6MD51H{u0 zF1#8dW`AbjGDj2q@K1;5vgj@Yo^nRi8JCU` z?pWhSFgEBRwnrsV;j$NQ@NOd(bN%s)qcDHM(*>-US1}a%_ki}A7v$qq8O*x93}?nz zG7a0EaQT%~Jm?dayH_a?3)H{j>!NwAYyT$Dnw1D2PW&VeS6sQZ2LGGkx|9_#CB*<6 zk3J+FzaHY=O{HjhUXi{1>y5kt zB1>VaO#?ZSxC#%Yq+p!UQRZkT-cK^MhrVk;Je!?C3pSU#*B<@fEM*jGR7SB!C zS=)`_uOVeY?EFR&_9$ZRcU_#KuE4x+)P&uRJK*Gd>UIBRh*M{}(sw`_F`q~MkXfbJ zlA*+UOQ=J#k~643tsu$@Yw+%;7+kaZvGLs-0r*sS9N)_0HmkAv1o%4Fg5;elvbsG3 zXEuMpl?Ig8T^0lfE>&U-6DQv%=t!T(GR-*F$?O?KJZuD| z$8BU|t0b0BW%1K74d%11GB_1j!4rXYVwF7`v%6hUz)_S-j!?uEhdl9UVFc5^S_)p- zctP`yLb6|MGM=92j)n__c@O;yxzA_Y$7c93s#jdn(Z=szM@aG0NK`vmf(z}27_a_$ zP#tw@Y=#?31fsfk2SUCMyTwovHfa2BhOf!g0VzK1Y2GtRt}mU6&6MF1V&X^K(j!ro zdSK4lE3$a}02H5#qP<0(#42q8$`|_JdI?eE5Y0f$OY6WJg`VvGtCA3r?lCsQS6VK^ zd(%_UeAu2bo)`{xZytjw`AdY1Wbr}Qa+Kau$ZIa@;4X4XV;YEx4uHWaAPz_DNY$-_K`a?I(?`;oi8+b2$kL^2hFUA->`P3pVp-J_JY9!tR(} zGAt&Izy9gsh1*JuzQtVd5Z?#8D7V2fU@3l%@W5D?aB}OzEPS=t1z+oiGW@rSV7kT= zK2QEcx^;AMT4yA>Y6$RjKlx)?n-Kra?09z1i%eYqz7z$vZz0q56VP0{1a*~6SlQpV zphGVo>Pvda9yfYlar3|jpQbZ6^duP`Cr-K5?61?LV5>Vha4@EFvOCR0#4&>D<2jNSqi^}6h_LRp?nB5W!CBrSGI@yX# z?ZL6R%}jp(gDyf2;5xM{*61sz4!|wfl9a{Vfz^Sc+h~1utq4l1qvGO7BL!&WwsxX|Z zIW(Rtw3Y-Vdk+w?H6n^$%Wxj;eCarz!0fkh0)az*ux0CS;`dnz9ru~y)BSq9_eqf$ zN%u1Cd#c$y*+BE7JS_5wUw z>5so`h4@m>HCX-f3g|lU8-6MRF}*Bk!p0fxAE#pExi#vv%Blqd=8ztxP9Sl`8sL>`30$2y40KqmS~e8i%TJ{*>lVQwp&YV? zGKz^m^?-dCX4L(p;r9$H7@=I;GY$S2v+*ykf5@_XMR=fe;0dfs{6_4yEQC$IJ7B-e zAo-Qe!^P`8aEpBg>84#^#nC1BiSjmcc@FMT^WNBtp+BGn`kGcmiY6r&_qcD8OXh$lUT^r0b=R7CR><~)2_R>NESWPlUb zT{M7GV#up zQXK7xV}Eo$109tnh%#>{POeh8@e+$sKQ)*ekCmZV^#Hj0v=bHaIXEcehBCpT+;nXv zT-NT1&zIa~Z1ZG5AkGJ>E)|m^kI6XxmOIKh2=jt&6>;iaZDanBpGze0$)FZGGoxhR zXcTUxd#eW1-^}I-8n9^RDJY{|lfhCNsHg9RGLaX_Dtfp2ThNA6%9gScJSoWf>JA$p zKOoa3X5-ehI~cd|AMcfoE)2?8z{d@vBzyi0Jn+aEj z838W_AH(n0|A^^$MPxF0c$6vQE!*G8-5ODZ7TkuQYm@(;+(5p_(HK8qgq zhnTCEL|_(u?`xHPCO0*w;f^71EVeNqr@d~W@ZCxLFyW2tSsf0Puh&ARSsyv9L+`B( zI%qUSiTP_Z4^AcTg^Ue-WT%TLp4wo6VWFPPcL8PCx5^XJTt5*NJuOso3&n^f!^X)} zi?H}A$amMi&)%7yjnf-SX&2H~@^V=MI^=wy89A2SR(Bi5P0WYqI=uwOyP(UpRD6He zf>~uZgR@?7Y>e~odLjvKQ=YyuW%(|cpoP-rp-3WbGu;WpoRal1P#fpDsgN*?UOU zX(7+u74b?bWg2LxGp~>Q<~Bv|gp&t5$rlvH2P?ht<@PF)t!M$FLXI#%wZY7r7Fb4e zNlhV1`PK{W;kZ{N$i=N;=a%1qcc%)#aUab?4a~&}Q{3_T`*>c7GmjfD9zNzFxqDd( z=I{4_&SysC@gxIOrMaZo%mij$!C9EF%nzL3{U(k?0pHCt#)}h{@QzeR;kn%%4nd^a>~%#tHQXR`^QP$+z8gSJw&=h8kIu4a2b7;7hCva`bI(i zw&eLN&*L-vs~CaI2tHA~B!ktydicz47jsmfp0``RV8HCT?B%x>u;YCKeCz&6-fh&v z&|9InE~ka}yU&9g{jZIid|^CSw0I9HJ#@#%-3{a>?N7EiQi|#4l-Mot$07Io9hi@O zWcTS4s3RPYl@kki!n^1>YDO(CJAR10r{W7gZA!sZ?FW(jEQ^`+F0U-F#oXA?#d+pg z0aw>XO5bK<%d=9-tJ%wxt^Ce;9u$Gi^gb2*@)L-D7r{EnA)W@o_;hIrF0~zDR+>(O z=7#+s_^E;D&9+3_@)Vjyx1|al};2|G|joZb7@RTP|*Zqye?@-3h2wiL}S700r zwIJPe2Ne7nBzvE-SV{eUtC}*19o75ytCir#bxLgC%-OKU`z*LDswBI1?8F=k+Nb<5 z-`M3T&4#QVMXgppwoTR^qBheEyGb=+an zSVzFrP6^sap@q|&N681JX!Q1`^S1Ff6Dzm?RK}kIMy{IdnY;jFvpq2&@gkXS5QsCT zwPH*A61M2NG-yoofGZ0gk|-HHSVukBqei3TM6(oX7%jzR>9xU=pF(y)KE2fR={PbRspz(Lyio73pP zh$==xM(Go%Zy3ipY>>g1U37-@zvdN2c5wnpiZB#9juVxB2@xlSaE00f;ubU;Q^U{V zg)`R7g!`hPGPEDW_tcPkoon&_|7UYx6bJ2FYW> zp%wUQjym&Fc0L4Y?FFl2eME$^j+F2CqTG*rImF1!80B(bAB8VopNM6t3e|h{u=0WwZ>d%y9=7{{ zXWX;d?<+GQJii4x%zluRx51d^Sc0ALxs03lKkkmHG3;RnNCDlIoECJ$48w6;;w&vp z(+$BJ&!01L7iYpdi4b^~(oC{8<3>avDN$_z35MySWzekiZ~ zaxiMs>}r0-Mpkv(ZjcV9nn_qIIk8Cv^Y(jUW^OhwC+-mU*9y5Z>+xKvIL&d(E8+(I z8e+OQ2W65=F;8BZ{h@URy!He^0A)AL^NPk*|7Zt9PCc(N@d}Wu@8S4~7P8@nD$ZT# zjV{h}n9IT=T>OTe@YuVPY~8j6%wITw`@<3P&0z~3Ip~e=f|By*?2pFvl=CyoU@bf8 z>rHr1XZ7oWPBMG>eA-9kj@=6$@T?0N?nc|4F|LSdgf!i~dO-MZBVrxC0zWTH!Dx|0 zW|sIl@b9|`Yh{Ot?D-k^JLy6$75*HA6mvIZAf&S4E_ZiT^H3BXtTMSP!madT*P`u}r_W!n4j8TF<3$~Tfv z8IRD_oqnGqO6-Q^cJR6A4mhsuCyjw8anGiBEGaMGaYq7C_bTm6+IEnAta~25_>_V+ z_k*0#oQ{GIebDv9A|@cKi~Gv%hdq?BwpmsUgD&f1Zzk{-_BC)Cb|PTZCBR+zDum?7 zVzl4WN}_j$V1#}NW{Zw84yR-(OnE;T+5I5*(s$#N9ICfO-yuzb0T`t;j9MN%Hg}RK z)XG1B7KiUdTKp*n-J>0yE1xhsrfNeY*$&+bLxiV11-D<*#pvnYWTABk{{H{@pQps` zQJ4ciWX{5Gi%P?#m*O$;|0C%<{IUAqFm7d2s1O+; zWM)LdbB-vZp`|6Hy*J7p4ee~9NTtwHq>RtGZ=&7vNJgosG$;~@jDDY=?>}%}z4Dy< z+~d05*Cp0|Wf?5F*9tSAc90`Y3h38hk3HfB%$6!`sD0)ONiS)>xzZFoQcZmmA7#1l z92F2B9|d~b1>}946lJi7;O^1VJk#Fi+$fuN&c#uLTljbkF4{=F!Jh_6(CRE4yuiob z_y01EM~va&5~@S(Y9xM?gDSc$6d%nwNM^I~IL`AM4)slChu%qHTUZD-#nkX>I;O$5 zFY_UM^B|dHrjAaZ)jVWQ#)!EAIInOG^CL$V_P+6fDfi!yL|axG69pltv{;qZeO!#1Vl{X( zcrl4PmrM1z&yihC_aSfMpz2K-T$$fP{5q2Gbr>IwF9$O-&rIaHzHS`Jb4iNJg+46_ zEE;Yg8cou8mDcA6W&X^5m0>P1e6I8IQNG@Y*)yV#3bn7%YC5O(-e^ z=kIOsd0Z=*P5IE72dPebY8lh#Cj9-F?yMC|S;He7A<1^&Uq0>Z5v;9r{ddq(1i^lBbzj+PFh< zAM@(iUKrF$fN3B4$lg0N=S5zCHLII>{byo3}!2jYQ3R3SOtPz;NG0Cd5)0 zn8GD)JR@7W#r@KTjBHFoeazejMZ)W35d z_`=*BC0{H%9E#^BeJ093DPJ&BfC_sx*y>Q~sftO3@gcv7>fs&Oweu48hgIGghTn68ESz=aq2T2!8#?#cRJChq^dM%Y9F2WajOc@4dOrjnCt zly#rchh7I9S*7(eVc>fK)$)EI`t8M-ZCHajpKdchj!uP+aZ6#!`+ico%nA3g!6>!u z7V)CbpGu#9+DL<)n?4!3W(5HMVm*;@h{HE^efV$L33j^LZcr|G3y+On6TzEeoTgHP zUzBFD6K15q$1TNhw)!vOZI(wF4O=vx`HI)^`Y+cw(`1AnQgAC5EIkKdoJ|8M|E5O$ z^ns{;eIpY@`P)@lYrtNnfjIcLd-# zV^MEEL;pQSjKu0m;6St7vO_w_ibGO(!PNtM=`1W`M?FNdLuhmDXzNS6+8@!J>Ny~MVWo%Rk?z`Dg|cs_cF7zAHHQQ8CN%o||xRZZZJ&o(g5 zXe8EOSE7<<7JgC9C2v0ifGUfzLLv_Jp zUcOm3_f$cBWY-;7N3)E@98hJ+7xGk1AMK{>!~0X$FsI8X+n~`0c3U+O{g^@!w^pV4 znRn$bJI~;(v0@d)4IZr5rwS-ldv6S94#V)C^gEIGVV=tXg$1Ned zny8n0k^qAoT-f>t@h~pG3|^J=kSiJ~SeDAid7DF+O_G|N(Sl9f=Uh?F@=7jz(ig`@ zs%s)q)VD(4?Z^d6%=f$hxEpr=)$_NC_i@Uw09zfd@``R;!?^GC?^tnp^Kt zB6PZbB@0{bAzLNDtjYaMYxF#Lu_*{z=k(KT1v&Jynua&8|0%QkoQx~yP-eofc`TVl zGe{TEJ;}oFWYBgUr@#Nd8oos*7t*38;0}HxDUOrJsLxucsJE9%9^41Bf5n3+eP;FB z3z#ZHcP4+Ec~yx=Vf%t7uwqs_nI5Wvi%s{V*`Y~{@7E!&e;&P6(cMTyh%A0H498I$ zsb*m5Vu;P&0VeW;LGAIbPO%;tG<9~om3mS*^RyPDJpg|5PqONq3G(iS z;lt7^ylBOl-16nABRW9y!K<)q|7biiwSjoGIAS%;1v7ndl{w-c496Q!K=aN45|}j+ zx2HRxt&}BCgT6bx$EmjS_Z#-BpC2k$f)G zE!3N)sfqs8?PNzVaYuxRJ z!*fFMA7yn`PP>lcrv!MsTZ8?1cROYNq|!X8-{f%cE}R>833Uysc~Non8xhffVlKX{ zis(TYqa}c2OIrz0f0I1TR8p&b&QqJy!|i-Sd0aN%$>ERpF|1pFDt~;KsaBu4@d7DW zs42>oH_76r-u%D{#%&WFI}LY zdgZP@`9P9p-or>aK5i1f%`}Ht!D)$Q;AA~W5ae)ylr^5%9zp))rQlXK%Kb>wVE?%q zKuGF7;J4S4UEkvH;Q3x`NjT1KaoPv3cfW-%*{_LN`F(s&cYRVtGg*a?sUW3Q4560? zh?1cq)+XEGKZ8bINA4h(>~1`Ai|kvS2QS3`g3{!Avf9HCV;96=_KX9}9&HH-1Aq8D zR8Q2V>!aF_BwV)7gzP(dAHRB04xa60c4j+)=;N(WB=nP1ZC0cVb~_wvsLw1h)TKSR zFGNZGBqi&p{@vFVcg}Aa(E)}D4&a4(Y0QV73DEPK-W618h@zeWjxR_?{q)Jap$a~C zwENo#(@!OjYEVtgFhgRPnEWw;(SohubhVM}F_Xb3`R+7>!Ha~`d8)g=6+NxZ*|7=p zU_7nW*E(BCzWj6$^Pdl2mJX4$SL#@}U9}XQLPG;a^s3u!9pe!q|Zf2>8%N z`ew+WByq=&58pVDBk}msF0Y76KLFjc{LtvL(4ryyGQa zp){?Lr@f;X#!9w>_^!{S$ut#H4)L+cu$*Sx3&Zsn_9OM#R!kf3O$){oX2RUY14U5( zR0S7m@tB37li_GjBK&LkO42P$(D;!6*Z=Hib{?A#tserxA-tcsU6jMta4VFQ>Mfg2 z{UiR)eC*yepDh{X3upW;Kx6-Ra$~I%KE9ZYo{Qh`HpQ*yb}If?tB34!;R|Jsi^Me$ zQXr3SziHyD^?R6xqCkl2h==BX{iN-~I6O|X_L8;c@wOd4249SyfKYxr>1(6;GDA@) z%^ERMssA`tiU0a-HAWWeE{5R8>vg2){t`GHy#r(l2T9V+8~C$MfG5t&Qod+5o*m?4 zjHo+%wf-~=7(IZ=2fD}tPZ`XinMw|Yhj?x4ow-iy)Df@x;VHS0K=VuN4eE(Rq7<&I z3&g9uJ&d(!D3mpwfLzBxVwb0mDw;EJh2>OU=EZE>K)-{xjy18DJFfx1>N`x0qq8dY zUS+><$47bpc4_y~NCK55Buh zy#y82JomJCl=xXk^EG|g>-vX4Yn}j%N?J77R8-b=vOc=|6Ue0cC6~w*xP7dmq zQXPl@BU61Dy(wQf(arzW>et`paig0xW*zuNjtEk*V;$AWTMjetnpHt+&fp-MPz-pmnmkCoOW6igCw*lL6YoD8ax)8HZ)RTw9ad?m4L$kta$r#Cn=H%t_wKHn!}8H2DPZbpg`B%Jt58g}GS z|4tv=(5j=H8BJU@DhMrQw=l29NrJ;ke@I{&$Ob0{ohIbtOw(B;_G1aU`w0*$FSC-y z082Nwg36hnWE|bYyxKm4YJd!wZ`<|Y&_~L|=6(`03n|=@Gz*W`zbE_X4r=G4{U|P$ z#;842gToghAxOA}IEM?kDy?rLJ+|u^nxiLdhVqAp$)dj(k)s~Hg0FOzaWsSUnyuhs z_nMrHj>o7qpYWW&8Jnc%2}j!V!HN3g+Q0xeLlXKl4Dw1e?7(v3d`NpfMD{vpV9nJT z_{buKIH_EszDPcbY}8~mk~YEP+6-W3{~~iz;xRM&6Xu!)vgrwt@M}&zEPvEYQae~Y z?|6;QR=b&ZU$bDk@f}#kiE#DXlu*k@ zSqw{XNBIl(%z*wF$T#-|%_DD#8`b0&&B($jJGPLm+Hv^us7M8{?rcb66*LVrK_cZv z?C94-?_vl1qOQ-_3XGxc@(NH}^_x_NIN*KB2sB)Ij;u46MVWK%=(S-#)4Nay+TVsi z1NF=vUmAxdB_b6Sq379LuMPCh7=fF1i_$#Vo2X?X!2BJvShf3!Ah)v&G^&1+9k)i~ zYf~rOYx12Zbykxr%U{neekQ_wtIq{>Rt%p|#+TA{H8ffhiLwv&Ge2$#gJMyK`ZRvkLX>*AvzE@_1)Z10R#!47*`J9Q_y%23P+QgYydL<7kV4ezSS4 zp~pdv<}wDVekZDnbx~q#7(Tf%nJKv_1pehqMl{>&D%wFIV9boS? zL=^jPqFxKVnU0Yo8>}y3xH$Ejq`9*La0WE`D`EI`7ul6;ib6CaJL*pkZ^6=jb#h`UlTf?U3f-$NkqG`xl(;28$w5ulu6`HX97=(U zIlW}d%zb#i_!4G#Kje8{i^r6muTa5g75i`0VQ7&Rz+Jb`WI%TUo|TWlMR!aXk%fI+ zW$h{mRQo|f#mlg9Sq(Zb_G3DXzi`LLN{#Halh4Vaf~h5L|I|tNL1*y=;bZ%oVP^b! z>NlZmG^J;s$+FkZn6M@VO{xx))@76{XwZ$d`)06DY{$UDx(IOpl})OKOVQc02Al2_ zGOa4s;Qqji_S^&HjFCKUZ??pWF%iTijArXlo|1Vq^*N#;99g*!^eGqU-{4HND^5nc zpsS82B4`%F=59QpeT>a783PU;G_Rs3oE&c{rFy3tG#GMboxY^OhEK)doH;}a7AfGT zcQ)v8zm8{XG|b7B8IAPVJD=u4@|#|`Hu@C_iqk^#v>-Gr-NMLimW1m${_ta8195xH zV1Ro*o(!8s!f%wKOrHP`EX!f9T?f!EXoV|6UF2xl7;MwB!5|-9ri^A9rfK_uvrZTJ zc0>yQR?k93qh_LIri~>h_G8`8vy79BIwa6q{r?_&!GRj?LBiJ&-N?)1V^Q$K6u(aS zN5)dN@ZN?P7zm)*-_ce$d>|5)4#koWr{Zz+y$`4vValdlUI3Gx<%4iR`O_4jQr#B>J#WcH`qDqV{S|R8I&|Nqf@aPZ_?LPr(3xAGLG1-?yoa4yTyFFF|MGBu z<$}*5QA~MQOI*fI#Kl38sB-!MQ=cgU4Ivv~vCk{ww@@1w&9uNzqZD||v0Lb>NWbZ^ zC9IfQ34D}l2itpJNZf=mcxNGtJEl!#ObtcB-_U-9zxM=nFg=~>F8YPJ_f)qwN<9jH zY|CcS7AwKv(I_|?{)B9AD?^ng0dlDW%xsl~Ah#h9ejWHryaMJRY>B{WV&>(CywmXC zRz6<2=E=^n@Q3HT3vjga2ibo~7hC%%fBwN;p5moVTz@>r$s7^p4&5FDsna6B;F&d9 z`%WI&_Y*Pd`7UPR^8@fXFCP3Q2S{nn1l%3sgmYyU@yWJjwe+PK?e0kL%)d4jKtG$*s}NpXtxZKeTyiMy~G-itDEqij=PL1be3HD?k!uKcmqODwvY7K zPO?rU_#7yJ6jW zj_4{C;Jg9>Mo0`XZ{>F3nOj+CWqi7{>~cKD30|VjnMtgQ^hzjqxdM;8+KGhE1hfeX zLqS9}Pkej~XQcRFk9}i~4$WP)!k3Mgh=_IpUO)j}iPB;V0`@?CTM96?f5=~vKuoxK z356RT@}5)n-Kvh4=%M4y_DdXrIAH-i!_P!rSPf+lQifHo2_qBsm$U3%1?=q~g!}cC zI}|So$CX66GnMlAGR^`!bbpfaiZt|)=i^w#f6RfU>NJy_vi&2zkU0fw@$|>*Xt^ex zy!stSZ(m&)LGxdhgpGmaFT&u+g$tzeT{-UQ5#W!dMNIX%X`nF13&yJqk|$r>@x$#< zEZkd22HMhaz8Uppmus?>Mn+)fw|As&H^$Dws>);(Gt70&QHw_x=Pumrf0T_pJ_epV z3j=S7P%;4J*auXbchQBtv^)cL_!WbY#W2aMQotK@zi0dS6_3vdfrgpU$WB`;Di3Tb zdmu);mZY!O!Sdq$XkWOEd3aL_QcG3?yRw0>8)nixL)v2t%_iol<>(P5z%^fT*hP0L zpw_+>jy>oi^*ajvOO?Y1dOpZZ6v6K6q)TMSH> z{!J2BOvA%1k@(N~D9NEUylz|zUdS+E*QzXn%LVzMG5ne2KXJrbE(ZlRa*UXkJ!nMC zgC*yNiTy8aT(Qjof5x084a;+Aju~YDT5GXo_qKvrK?b2xGaY+}`Mf*F{&2gu(M+9s zA#QE70HV*x;2+9e+~#49yR?I`ubb*BXDY%gstZ-!@s4;^J0m-oiTh->5||!GS?@v> zV|!<_0>wvgyQm2yZuSwq#0j{XZ#BZfP8XQMwTUYrT)CGV3vtBQN1?c`JcF=837GV< z1|@t&SRWfbP!J1&ik4U8ry+}G66dgUy%>*6k-~+)ci|?(vFwo@Iyh@R)y#Mmmuqb* z!2LJ)Xsa=sopOt2Z8?>JY)db3x*&^IJ~Pltww1U2j5epHzkcK{DLkA@?-(Muq2eXM zCRH@2ew^v5dzl&AMB$m*2CAcYMe?3Z!VLu$7{XWJ`CKi)bAS1`aIl1xK2!=)HnfIB zeEZgD!T4^*UEaILo4KpwIIeS_Feh!&J>H zus*w;1khXV=kH-yIP)Rz+0z(K{LnY9@&fgmt<}Lx%PsM$*CleumwKaK2(U{?n{9u! z7qUxJz$WnznfW~(yA=djC_l{eei)B`qHFNI@k%zX-MLJfXvU(JM$Y2$9rl!Wm{qMVTFXcXa3#jMAjByna29;Z8^ z*eOEno0N%=wAmLLtiFnb{rj#SB=31+uw2O!>vu+wXYLtT63)jR8?;!JNybpuu?KPvHjpy? zc)YN$6P+){vR_)q!1EQMpsO50PR-=7zEgmYcg;c+=`*Oc9=ZMQpA~k)>y7y z$4hDy0>{!RBlX!kDGyMg8%~(KB(E1u!XuUesM5NbiMl2YG4ZQmc3uOSIp~a&_40B2 zn%Tr(g2TmhKDrxog+1P030I|B;i>B{qViY)<(sUqGC_wCo@@x~<^15oBl_DjkwO>7 z2?a-*h={B%{wxZ@o;7Jq+*D0ixiu0V{;eS^( zk-!LS{F%;7IW`+c|A~hA=BjoED%7DIMwKKQNtLaaB?tbk`ZIQ^&` z!#=Zzf+uq!{M0b157ENq>+LW+GKHMJa0P#Trk;*6Ep~_7c36>=0rpkhq_mo5#}~av z<;*>7;jS2v7ORJX&n-m#!7L14aSdw^?WNrBi%{-y8PTZr$K0JQMGjt(cXnO|;7@aK;YOnd&0WSm)y!^iSb>S!pj zoEwL>=KnCJVHUe-!DEnLr(LI7As$)0?TEdJPZv=}`s< zW)NTM*OsALR{IyiteeYZ(7Y22*VXEXPm~i{e$2qNXT*4d0BOpy*oCcTV_B_Ly1384 z5|>;nE-&yczzE|P_`rDOQICn!+&b4GUy8hlqiW@&-_=rTt#A9=g*VvJxoqylxlZr4ujEXJ!c- z|F#UuE!)9e{~NhPJ+rP8SbWxYUyom`~5eZ}e9S7d)Aree^>EgZC zSiRJgx9-j@SS`~I0_)eL5-ji?grM3REoMpCD44kKznZ))X##%gJ%H+TZ*Zm56uGr2 zI9U;yWIZW-7&?ynVLQm>8+TBG&MZ!MhMD|>Qn;tp8vVp{N_|V?v4?6}+?BOipD{i# zdfXLg)%;F2cuhpy7LH2Fk9fVM2RU}uw~@WarygDW@XQkTxLqc>*YDuR*8(&!b2f12oWA4GA(1!dA}uwzKS3(eqCkWH$_ z7&tQu*^oHLr*|l?+o%J@hmNpwq7^`v9}4jWA;d`(u*AOxwIyb=w$N4lk4MBaWA0*m!6V*qOXtjyO zwbXZ@e28YLObkcwfb)!5ye0?^M?$sZOR}kt^8D{5qm76GPfPL@_a*W3NY7m8rHof& zP4P0VbyKy+VaHY*RKDxS@Xooy<-5^van^6Lo6bQZzuuz7pb;DF=LI{i=0noYFJ!%v z87c=PW09y3lfTRXYN#$mckwU@f2583lkD)jMk>t$yNVN^@ew9!vmYpbFT*zjn#T8# z>Xvv^HF<|iqIa{Zs}I7X#yT*y`9NM%CPv1-WUN;7V$@78LGa^(k)GM5z7TEi(w!S` z8xx(-$ECejp++zvPWq!1?dz=ZwOkA7JsyN!+pc5szieiE)>x39>kDUd-jkhfUidzV z=J8DqBQMv-A#eT=`c~6k-2L`4?-!1Ou# z^#ZRgV|Q;SaBgoqycp9)Vwa3T;lmC%X}lR@yLA+(IM0AG#XsbOfbx6y3`wGrQF)!_Vj!%X|?C2&bO076#{5aCZ_(0G~!wz>C~ zU3qa1&(MA;dGkUxoU8}Y&MbIs*-4hCnb0inD0HkS=d}!OAN@({1Lq;AsSunp5fFQekK_q>VDZd|5$@`%>jJv0w;G^BBDMGYyKFNrmcTd)x~ zF@rNG8~)F6u*?`HKKIoyF4YomryBDXek*`29c?h`#%tpE$`Z>rgkY6~HluPy975)~ z!{!g&ivb-gK0aY{y4QD8P7m%?_M&0|{sgCzbd#KKkq3LX5%OcqF? zO`jEh%$QV~OY>+Ps7`*et~NWP(ic*cufVYz-^q_`T?{%KgN%cK_pRv=H+$JP&PQH^ zdyuJ%;Zx~1W6>o74`uPts!3>Z>j3k|CkU>UrvMqIc{&$HRsbQhU0W?-JVulw`t+==k+%xSYUz^*xL+d0)G#=aD)4pOA z)s!FqNhEU4W7HKsYJC@Cm%h;iM-S?wnemP6xi$rHN;ul#I`W0~xAz;`QTV(K>$*z` z(yK$kvgZP6ldC{0s;N6}SIo@6G@Y_xmH=xqM2gbXaA>C^D*40`iL2-FA-xOypM4$r z&IEo{?S{}Z4P-Qb3O;lRM^n|)j-QvtqptjSY;-xo3Jog4osS`~`(g+Y5v#zve+B4X zIh*}9Clh|R-UYe3f8?U*c+8+0a?ZGsSEVEZ*kTBOJO+ruU+Phn`3b+01f*3&4|hZb z{O5)7mxYr8zmfXfI?EML+vel>*{(z^xElUce1e++-Q?b<@u+{)7E9mgGv~yNK;Ol8 zq&{!lDTT3>JWP1{noL`yk2*A;;(c8@Q!k+nHlHG3qWDXaAY_jAZpnC4+kkhg{S}wn z(aO1>6yZi&s-VFfQ#uz2aThD7CgPMGp0r-axWv1G>)L3zzwkFX|2Q7~eVQ=R(1?Zc z%fRDSKJ2GCAirlhLTk*Nkv)caoHr(=gy5<67lhT_1!qk&;LNTb@~kZ$eNHyvv3a{# zhIa^_#nr*O%^%2*eag6&>NY#Z+cGi_FG0F_0T}s;a&oG7F`asoMLV`J-XZkY0vGIr-T1G>jYzrJ1DL z2XK0kGrOSjDYPm#f%e+JF|kCL6&uorhTsFBI;M_vQ$GB=X8KH{G*-h~57SGh;)8X?2lP}HIn&K6`u!>Uj2i^1_ENTRTCxnVQ7#a z#4szwAtiM^Jh87M@rioq^LHwSTu`J;k|J!LBft%VWo%z52U@G!!R<;L5xcI04-Yb^ zvDkvyEF=z73+zVr74<7cd8N`%?=saQQ)QsD3_0ioc=*_yGI#E$4|#+nI1fMzcZk9>@l=bUWe^C zL%cLG1oOt|Gi@Km;NphGF!=B%@wXU@*Sy2%-|IEmyWAVn>bJtBtHY!}I0k3Y+mPY# z^YS6TJlyO-zoCV5*@e6$xc06B{$1`S_nmg&`uxl2nbyoRzvs^R>m-lpH>TdpgG_rV zba*cyzq6&#&2cOCo!`uCe;fs|3CE$JjB1>Ms2^>K6?W8`@HTtgfgtI2K%X~c`He*U zb&U2Es}C}#+$Es?z8gG(ZlXJBA}-Sp#u8831OGI|673|+>m`hezcgMiqxq5k9VB?c zU9_h&^$Q~*R;-Km%rrCc{HRH#E*BFqI)sk{@!IUGpw*zGdIcGl02W0W$Qv^b-r z{x06k)I>Dd#>a$nE7;KZW3XF;534`WJ}N~Gg$si4bkGzg(Lfkh-&h4>=Ti3U-b&Q8 ztifH=*D}s!-?`_V;v>6doU4e<4Yc;sY&#ErCZ4~_#|OGgXVa9qpVo~njhNAc-zat${l{-KF~lc+T76AF(026xsvhU9>T*%pCE2V582(NOnEJo z$2iY`QQBfm(F?vXsMbTgq@{4^xdYx)Yb2^}2B^MeKbn6}XQU-3!K0hB-Wt3lmCx(A zle1d6tTYiWbc!mjGd9IbT|(TQG^wl!0*i5=LVyJmN*N<9YZ#lg5*lfa{C4{M7xekwlh=|j$w@e77M+8}im)!y zhBQOr0EoEPkr}Vz@V>}jbXszjz5jGFmP=ZU^t3-+i!u0=00Y*zvx(2rVEgw{h+_K5 zD_dP|k>;8aulMKXJecJ@3_82`B&%K%-$aF?_^&`l+f4#CE?*D2yXuItb}>%z7vPhN z>;>rOI3&k%Dw58#^4yF6~@PVUp;@{ya}gzaPD>-`XT-)BWu zH&x<2jT)RAuEX9{jD#Ciad3C$5UHD^h6_9?SI}-g?>gmA$|pPq70FI=_n$eA>5Ibc z115~)yHU{Mxp*Y^u;lbueET~DW4arOeflc!jNJ-C^akDjvKSAU)SxbZG-;sUO#Vu` z^Yos_Dz8t5wcQnPePa*VEV>J;u3pCD1}!|71#`Go(`1TZ66W|-d0=TPiIP=(a{G}q z4$j|--o{&~mN**v{fc+t*RR|obDz& z4``s&@?gs3>?Gwzaj5g54LPeB-8s{FmR!wyVWxIV8XjDMGCEcPU&DWr3@l zwM(s@B%v7f6#SN)#Oj!?forsuHa!19LRRVE+2fIz?D>r6seXhTB@l;Qr!Y5_Mc`rNsu7;jx!B!Uxg!#n6v#5!3O_h_{9i3?Oj5#v zUJK03=_b+fSs0~B{TJ7S*?OA6x8KOF(47F!`paj^PYt+lo=0z@aQO98KS4b`twyrVC8kbOct{(fKQS)PsYw!0a(v%W$u^C!P_T(uxL*sS-j~Eq|)4$t%|qH3)LT> z|C$;U{+i3~I`;_DTw1~MGxZTaAB#0RsYbLwmubFf48~Euz?;=W-i?yN4UrDm|E__I z-(`TjS^M$(mvm;-v`H}M!hiMiXWShaRicW%&UucWY4x1Lp-&^Vbf4@5n(srs;>N;U z1N9?J(hy+1CGFGH=YX|NG|dOs04jQs;^oAR-Dj#kr zd?VX#6vFA)>=C%IvkpGFd?e0i3PE|fDvnlq&5O>w3>N7(0Y}rG_T@eF zuBCp@(>oa9n*-d-Xl1aSF2s2k%3|PiE8KVT135DC=MHD^QKhM+Q<&#qAf7VYM^K-2Ff(W)2`(z@A@oum>GIr*6R6fjf%D=;1l_}l+Xd)0i?FQ; z6%coT@{85KlOZ~@?xai@u_+cz+93&WA7eL?Me8L@Gdpg(qls57F_=c*UEL52+?2^k z2bn{$bRzXBv=gbYDh#B%GKEt@?85eC(DQRIbcYR+@rNeT{9gw&F&8V>_r5@TQktE%I$)b@=!;e!7 z;Rw})PtuAZy)P*j++-^p%=kyjE$`zowg&glA4BfGrZaOG%AYg} zMos@tVjf)xmUC5cQ;jq8R9zY;tx?2plfRR+!F%W?T7y$Xgjwb3GWfF90yoM}D(&b` zM)AvhynJvHTa~>QI=|(>KD7>FGZWCW zka*4qQp0-4)K^mYOVb`zW;c-Y|BP@x)!0aqbIhM%9f)Hipvvzh=~OF%_*xbG*_!L< z8rr~xHGSm%ToK{SMysLfTN8ATre2|6*YOr*dbFkpv!)Z~LQZWIY;o=-=Tq!)WlRJ< z{dknD7>>t9Ts@jRFkqWHyrDNHA1t1JBMp8<;6nWlr){Hnt1W1|yUYVNU;Rh^l&;3f z6GQRc>>4ugn)2181n4{qK10f%8fctL|?v_ajRy5PO-g_tW$!>@{y-FGU zgM_$swsQE`&n9t8;OyMku-MTm-j@ zRWM-pPUgZ%KA1+ofe_0Noj-m8q^LZ^Yulocbph*BA6>i<1}JNh$7#>W&) zqm1sm&qP@Fhf~0{KWL<9KEJ^g7lfu`UcDIaW?LMFS@xoDdJ5~cS04=+bF|GZF8@1l zAH}Z<@NAg}n_iMZwZx^MZ}*op{?y|<4g5!R%U5mlVZP!3Or*^4*jhb&5*mrFTf-RN zQBpAV+`5svUHK^hw{%3}S({}%-pl*Ag6=wE+XyS%S_w-2?Vxk#JK^DkbNfsSk-p2sHGasSJ&Y5 z0U`GK#uc!zbuX067$V#BHLzB}0h0~I$|VxAv6^Z^Y8w}`3A}A^H7^V9+EX1Stv{}P z?x^@Ck!NMLhm&nB8>!oiZsx(NH>1(D`8na&RAbwM8XPRqW#i{Xfs}e29K1F}W;kk~ zvI+Hau35ly+MEEHE{{R-V<*||B!lZ;W~V~{-DBa_#Fewx{iUKtPpqRObK#S zTbrNpl&7_;7)s~1L&t`<2ET^7e!7Y7*;RL z39&bEvMrriMv1W18|Oi7aTLrf>m`P)0~U)%p!waS#BNjqN}1JR$S-|XDv2_pgY#j# zOBElz?(pE#KeDympY9k#XpT$`v2Fu6nHd9t;0b@@kKsjaLw7NgSK|1$|Z4qYmZ>|KDw7rmYZ-`v$$z;pCtVZ zRc@kVXgv=N>^bFMabtbrBUdv(Wmp7N^gocQMird6=mgdsKEXr;o`h-PXW`#u0q)@) zRs3FWfEMxdc-j@u;RAhFX3!pxfwplNwuMEz`T?HWDJgh*WI3Ea*+VAfsbR%Ue{`a} zCjV~A`SU%Fsm8aM70r@3PD>8sCO4DyZ}Vslg^!Ed1ZgLZ7naUVLVw4|ydMn?iy9pI<+KGpf29~})h9zl*JVEO-TxNaaSVur2)u{HqTaLP0UXVM=vXn2O zf}fndDM&6DvYuapsP=zEy+jcY*)aG+=^*d4St8z|dx6JOH?v-;QPBIT7@oiWO>SPB ziQ61QFzUp7=2M6W6s+6?p|Agt2b6a={*5T?TqVpsF`bO&s}1Nqp@+n5n+em9a_?8S zlHaZdSRoUN#l?Hcxrs6Otg{{~^bA?^Oa}!L8rQ9Z zm&Zm(_g@usKW>2+x=xd7-83{cEycda8tl%%Iz5zQl)_ zY)i-o7%6UmgzUehcG^@d%{N9p$5~8Ju^tprp8lv?FX_;f!l^&akrzR8-@ep8ysaE- zmWi_#b!Lz$c>%h`sJC!JH8*SHkFj%g#wgXG;^v~%bRlj@Xg2MHq8Y|rLagN`dw9F; zIBcX{_Evp|@ispd8w>A|DQdA;Pd=fVIi1fMTR>z}CfvVH&j2UX(8~BEJ{qj&osnG( zQl2)@I9-5yymSW^Z99hdM)>6F>1;g6l%kTYCM)OW2P;2Z0Xf=@*jINLU0WZ2yGEa3A|t|16{{RKSJ34J55m3420<$7Xfo+*=TK{x0mU5aOPFp?QZE%KdKf zV2!a0113o*?^}XmXNB2k^xbsR?JO*w&`IhhF2ygAm$2MIke5!MpZx4D>Ic2V zDhV;Y4!kjhe@kPbY-bBu_30h1Jo*2uVCpS_P4GqGD1`M7licsBSa8*n=E6kt z!^WlKa>|Z7th<4|OnF7|wyBWZ)=6p>>rrk@0RAI6yy*|TIIWJnvE85PqYRKrmPIb~ zJ*i85hduO+T3bGoecpKjs_HJn#_uCU?J{M4(9eANg%vyqjEB3b@8Dri2iZuusixa# zmq)BN!}dx*+Ksi)bF`DVl_}!zA%8TA`%G-4wn5^Ry-;f*z$rf0#2YhA(97jmKCdJj zYhp{$QfLhuIzI_IXBU8<@?Y{hT@G89FT&jTFy4)=tGOHh#c@w_sAqdP0}d<_!L{M< ziSt$!%B>8=W$bZgNH-i#EItcQmkDrBSLD+k3_e~R_`q8-B^Q>jXo2A?wPa<6G+w=A zf#;;UdFvNTL$C01_!ieg)b%v**nmI2DDEJ>^Jmb0>JuoPdYgG)A%zJv3p9oH+iseg zkDBxN20aRbI}Nr~gmT0;+yq;}Kjez`EYv+qcQ@xg z(DK={obU6-F`Z;_j|^V2Rlp&SGepEt7Wb+sV{@bzvnL@0x-MRV6MJbt`)fJeAa8<7 z3fp*p_9o$_{1SXsu$g_Hb^$U-F%X&Cj1gWJ z3&p38_mK&d;jr>e9rCmc*afs>{O!4H;C*W%N*8?4_dzheeX@hOw1Wqu(QCn{bA+ty znt@LAvwiX)g3PE+$7fWBS*NMVDu>Y>nf)nvPw!0!UQ=$5+z<3!9L9b(3k;c1dR%tULY$HaQA%?}TYKw%G*PC0}?Jt)ieFHVdp921(S6`=GX@ z1vXzQA%A1_@bqhctgiHAjOHo;|Fj#ppRFdl%NAqv`4l`k-jWP?6yf8+QVd?3#mdo6 zhjg_DFyGWi%v`3ULxLHy@8>Y@Bn(0Js~d>?>LUVHQrMJ0cZJ`|NiFr+PVp$i^y^~m zDX;+L&?rb&X(tD}tGS+xI?nEi5a&hnSo_z{#XlQ_IH8IMsA5OEN~?rehjXhT*x)$) zQR$=Kmjph(V}k14*5ulpSPZf#!<&b-*p>IULbpXGbdENYJ3`aY`FN#2G3>V-I+%>*N-@^NO< z5vD_40A|!r8rvsMTQD9)%M8XeZF5Tn{4=}=-EWvPVVTPC!oSUODa6kfh!`c*n!`lV4PPtL-Ari=KS#Ne*B4wSTsXJMf%CPvGntz2UMGgX4~ zD@!r#vmL7`&W5xPPgIc4GY@ zysz>YqH2PF0_QOEFG_)0!2)R3=_flEN#S0lr6}k}=QgK-|Jwb~>PQL$%Eq8%6bn)B zTF8gXvKZPWk0S*}OzzLka5dEvl2?zARyS2_&9*>WSCRbvCO6ULZ3(J8-@vvfdw}hv zRIpgsMP47E{*lgOD5H|cI~M7~d9>tlmwyOydJP%ibxQ^{qKatlRTjTWDB#rzyO^zE zVZaZ(2$KXx$=hF3(3Exn-LF{2o3Z;6e6A~mCpNUROnN@;K{$pdGjy2tPm( z>?FE0$MM#}9~b;Tf3j&Cbbs9gD;5cGp7S)&mwL$OOZw#tDnG#eo+T(4vYHi8xdLZe z5!M9$CG)N1@!M?{&mRxtWj8c zAz=*~sITRZvnYpQhu#c)yy!Rvrr%=x>AkqZd>nS1`bD_&1O@23>^@(Jtsjy@SK5>E z`Qywy$!k}zsJsL}J8QD{diKI}|C_LzW;#|{XyMdnfhfMVh<8~199QAkIJR@#NOhIk zQ}QUJN9VSsEXv4F!;Y+@OhH5_^d(+`sb)i@GIk=0oixMR(Ve{0iC3_&xCA%vb!9K7 zU4*df#jrlRnfQ&h^fHj+d0<0dxWaqrgoZ0%Dgc*10Z z@4qGzeODIa*U*lW{X)zkM+WX|tcBg?qoh~W8BN54uv|2kr0L(n%{?W!{)HwxIc6o8 zNt}X})W@6lAqH!9d`Bk!1p98zDF_w%0=DAc2n+ zl`%()o@WHU@FE|Hfy2sK;JbK;#Lmx#b%V|D{YMGuZ}h?rySq5jbeoBoJpoQQy20L> zYLeDvjXG7S7(Zx5z7D=eYdVX{1@E%Ut4rX8NCSKk>!+RL4{@z8%?$tJ>Yb zDyyG(?~=kaKU36HFDG7lu{bQi$IUWgY!YS_-?nRzP)z0OuO7iJ^xL@lRhoIc@R?uN^2w&wVpl zWtU@cZT}UxKGa7tbR@Czf-&B3EV4}57KsQUV=l_>2pP*wVa?!IyC8sTy1=PZwZofGrnIEP(zr5Ji{728#t3MI;UkbHTF zlwMHAJ5y-CJgqRD#e%XvH3zNx3H1!mls@iWV^0;f)J19P^NcN9mxReduZ09GM6Wr z=gYC%^0;HvcM`v^8qL|N6PNGwkA+;!G* z=Xb?%XS9VlM}uZ*OIb0%k?MK;W=Dn$47yM!tBY5$`~<~cF68BN+GbfAcx&kQ6RtOi_2}6Um_cH9CVOIKf+#{orT`QoEwSIE16$JcNd?7vDfJf@9I%&;6Gjg(ticG6|~#y)GkBJ+kc5{ z$dW-v2X%a&6v6}u1;Li}S0FE)7JCANL9e? z-bTV-rHnn50k~k3F=OO%2M%dv!HBXjcV(6!oRpk2rhzyvr&-Q~`53qK2Pt!#fWDb5 zI=YxMNA+jGjYKz4t!W^eU374KLJ-ba#v=+!F~|wEAzoa_dc{>j%=8*?5fR|jXCfBs zQI>2L#|+)GfE%$JVPMq|*_9%P8lnbRBe{cUb5}9{S_zW7B5abeH8dNYh0u##^&IeP`&zc2PyTKfHP=DNxNnavw4OLywzL) zT&5&0-^OCwxesJ*#7unk*%wU%Q<&w+rV!E+1J|5e$zF*qV0-om_<;p^yWv@!05?Q=CXI_|kK0zieA8!-@h)Wn zeHUEE?%Hw{>N^nv=zX(wryPdAw8Z99$9aCO>$uE{SnkRYJ==?A!csdyG;=5Q@0Z`nkMpvK;^z3WwTt)k zoh;UmugPG)|4(AR3elEku_LmD zS=9;3l-0ptLzjNuraxEl&DRpj&6~*@tvd*QTW>;SMF%;O8_D&$G>n~-gADz#+b#$< z(Rbe!>RGy^Hx*&AC-Yn31WW&si}k5i3j3K!4Q01Fpk+8-ophK2t&#uVb1e3 z<>|WUwMi7_#cd${Go&&j=?7Ch%c$yXt z>fd{b4E65rviXX)T#vJPnh`KuPy?g+--sJig7>2M_}OC>yMEy<$es5XPW(sxmhn$e zA-)u+Wdb~c(?!@fh3mj*A7$?4_K}aa(x^i<@FORe5r>6w*fg;OCFar3=lV|Q zmdS**+gi!FcFGOD7mPLczwk1mmchdPE1+b7AUE=2KenC-!joZ@B+gqF1*fRv#NrSp z{ZTM@u~*=?>HrDXh(r6XVpIv=%}O{%f$5iW@Um+n_NvM_Bhe3aHH;V!9m<@+Oxjx` z%w5V9gu1wiW3zXnt32A=o{y!YKS=3i1-!n5hi6YOV21XnLgyW-KL<4u&!E{D=N5!t z&hyAV1Iiy**Mie-Sg>0Es=!X527v0=YmXOT5uLsHcEG$&UkDvK8{u~R5c&7f8pq99RDy(uIo-jKSg7l^|FE27(AORKH@s&g^pX21rsiH!t$?$q~*#?T&3uPmQ%bL z(dKbb=)VIt(2l3cZ^W=mLIO{U{;_{-<$IQ5&ca z>hU@@Yt1!S_XNRxO+SgzrW*Uig?Qj;C{KsKp1b23JEleSC1!$9fdD?~eM=eyX}`8m z0Jg~mQR*o5e@dKzmkqS*Az>!|5HrBa2z}njXAUy6TVQK=9r4PN!^OA|oo4p&8WYBW zQ<*iyo#`bJ!?V!ohCiA=?ING%t74LD2!_|DGj1QG(VX_pn9<&Im4X8F^y1^Cc_Qp_ zpXr#L!Q#CJgS_;4DOfT@yDST5vK|W$!-;^KFggDJxn%P&(C|1;RO9m|-agO$RcILF z?VFA}h8nwr&}Cc?IT0pHbynIRzx@dF^bzet`5g~yorj5pAkAnTwnUx!1H2E)DHz^Z zg7M3?uy@j9!E{M6)X_7Nyrn+Y_@2NEou-VYq$K>B=mM;0C&^wUi3|Tq;(ND59KgF|mN-=FW&8)pM zfwRW0aJ;ggEL<=j(Vji+fmK{Un&aN(|^cP_gXG!sFq7_5#pK} z)ljEN7o+bAb64j*!|T^+FL0^|d&tBAmh1@y(;fXJ(p?JIt*7^Hx22@dJ{}j%pt^d} zOjg}`H(Zm}_Z{>{xuhzdyT)=jma!cE=?HRGks9Y^~&4fn9o#us4WwQ{hJY9bp# zlxcp`7d@^TGC{Q&uxVZ9SiaAp|0UjarkP)RZ|0(n5Qy7O9MdAYR26XJ_W9IXRZnEH zq`gsmR2~5)e7PkEdpN?d-w+X>HH~&1FT|TkN67I>si=@sf@U6~?C+sv5b1da z@L(6weLoKae5n7;@tf5TpBStbZ^m-V820&_m-tGHk8MS(*?qnLffM9{&Gr$pS!N3U ziC%zGAAa*Do}9xK@mx94-$L9(-z>1#>wqJ33Q5mxEe!qPjb?|vnVMJQ;l%76kZ`Pu zq>vEQRSd+yNSlQmoo$q7Xco#_ zv(Fm6V5T6qmeIzk_YAQq z*MN6#I)ZUp3zRATASd_9qr$<3xN~D4PttWfoDH>xaO&&Wy-f%8n(6*7yqma1sNsFu zv2|qYO=dmigDs1Y!f$bnq}S*b9!TQj?t3Dv&G{KPa*xGucf-8Pj;Z*V<}a=;(PAHh z2WY$AgoC4<9=T@2KveurS!zx_r1X?5zL}|r>mxmw zk|klV@LW8s@*5^gEtIh>-4X>p9^}<7O2sOwuRd2SsWNFe6j$s;5>lX_6;J2YF1HO->lgLC0feDW{(e9j%qny;enpQlz+ zLt@Z2xEiM`g|gy1&cN?$HK1(zoh(k{Q+7oe9`3Mb)B0~gx91};PZ8uY9?=dI3qBq; z2w_^QBtT|{7UaJjBKIylhM~nRaI1|^WOL*3)I-X<8~=exnxF`NMQ-q;gLX9YoX~$; zCJtBFl4d$%dVce9Q~Z6_q^KNB);2&x<3G~#@EPtj=i~ZuubAiNrck|~cAA?H5Hn>N zB>=^g`iTW^Y;)|CgM zjN}(yrojp@TfZFExeIa?^AF3(6Z z9B40h)p1<;WGXZ3r4TGCnlR>PHu0W-<6g{1399#MWXj=M6?6O)YQ!ulQU_gdgN!Fl zZtx^ME3f0l!VJ`n-+98EAi)bEiLu~#u&DXeCjgOMvYuIIy>7a5e7oJLv(w+Du)TexesYe@l z(Kd6rBkitZ{U#TOvfuz^i1ojJOD=oN!h(6;_-c(e!z9YV(Wl$tZbTJ%xFZCEvVyTG z)|uDV@(S<%KPQ2G#a6_YK+6ltWG?C=X_R06FU$nfZRatGYsZ0~qAC2RH$a4*NaD6- zmMC`b9U0#;8v|_uFhKtXbHJ4{icZJC#>MozZY;z0e|!x8DZ&Qt*bbbQ2h4ppN@l%# zjy`n1+_)}2--l$;J~GNIJ><;#zw(3Mw^HEl#~w1663C?<$rW_j=^lW^3H(WTi3moWszv<^&tQ%jB^}dtIC+<16cTm>)90zvi-c-1I z9ziZ_fSj(g!SvwcIKJl*uVaxTxA;%YnBKd5MJDXD8-_D6uZcZO$6f({^j8mJbm@1y z;$8$qdkAuA&tBuZd_GpK;qzRR3&7+}3w-?cgOIfoa80-+-ak6PQ(r3wTAQumIrZ)T zjgzA1^OdM*_L}U^QbYNqApDq^&PWDR4eF-^_Gi#Na@1=artF>DQ$<Eur0UGxbPn(1?U=Kzy%tB-4aE(HF8 z!kpwo6|CDgAH^I7NUif-Jf%mwX;MVlh)eTe?Rmk!T{xf7Ry(U3h<(Y?Qf_Sifs) zz*d`fx_A5~inf&RP8rbwHL+GZRAX_$e^pp`GK8&@KL^`))IcQvJMnw|38y~fW8~A- ztmeEs5O(?@+Xp)3S>u1878p@!%_!K(pnn5|fj5zJ0yr^|0 zc=7TF#ye*UyrDeO7#GS1_Wp!Qu6zu#%4TJ$t_y| zkta4oRLB6iwMrKGFO1N%;1dx(oPgddOK{s&F*fJ$VwhfX9)2(HAe)-h@Y(i2+;&io zXCnEXGYR|34fhLiqJo;J{Ztp{?GfSD7w2H#P0IH15oOcQI)eRR2&@(yAYyK^XmY^_ zx0fsXwTQ{r zj(>w%`h47AvX&j}Oos=Xav|oxD3MfGLM5LC$cVP^GH=Y~x?gYRiXDZy(bBsReX4zI zR|4Pwe@D*FE#D{|S zEwCY}n^fMIjDMCJVfr0iW}Lxzc-CM74haKvS4Fvza~I-gk#{8KNenthR$}048FtT& zh2XX$23jt(5tpsyv`daYpKhY;?58_`{dySeXA5v&cg?`lO$NyN3FMc&yh}fG%4&Y^ z%xdqV{Je81;IXQgh!_WReMUKBTJh!FO!)R!486a-BKo{?WIpq8c=>Gh*}>D$krf5z zt^(ZtdAXRaz{iGf?Y!{pWKh{t2y-s=5EWDESC?9Zu{%YWU-{!8&2BX$XLXUp^{Qxa z&L15|zK}T=_dreu&1S3+sALdyuLFqdshV5Q)Z^r zE??aH{y1*#JI-qpr~Nn|TOcy3o=lFF$J#$;cynhjPghtTYHOB`&F$cRDco6PgU9g| z>B?6}KgtO=ewWTnqg^@P9g^s3)I_W$-{RKWd`w6XW!ao5c=D|YzFamt&n5Q;2GM+U z&4O9%^_-)i(whzouXhnqCHlM#+2H%m|9DbMFLJ8F^p>zlJ{I+aD$)0lF8fMy2h6d_ zhCa%_%6G273G|E#JYY<;twHdPJs42^f0n!&zN5_ii(kWu?7e%qlKOkM70zP$-D}~D zR5;w+N%@Bsv3O)&C4OxUW`}>AgAjWE&HwqGT;WyVxm-T-0@twh4R@ea{2_dJEy$&G z(Px9sZ3XF2X7XJrSgtq|2F!2;5|fci{y>vn$6u`Gn$I#aL;oyB9p0g3DOEg#Mi)TCBPH0WiN|m1-vcgI!xJ~jkRF5rWz*G?=D=$7cnms&w~fkv4w$= z9UI_9!Z3+lxdC%-2BCpx8tJ87G}UY}>OOzRgaoXF_>U1VS-YD|?vTcf_iS*+#QRqF zZpEO*U;`$IUu1t!f7C5ADg0CumoM1=7WdELgLAp?Yn#ThCujHHgTACTSaIepvHL5HPS0#m|Km!=!Ce8~i~es`ckh;>2CCSHM4_>n*qzooLZUJs-52@)>#P)b2)byFl9PAzsIcH2D>pjhw>q_C( zSr*uNsF28ij=|NM6}UK8nw5WL2?sS}K<7al(U@3?8uQ9faX^&)a?c&U8Xg9HO95_G zrUq`^MLm-{h4bAN?&DR9QtUn9!VdNvgWKCu;9O2G>Gh${WNk5ytX5%Kl|wlG`R8M2 zY-BQFUz8|4|Gy+|l@;jM#m8Cwv)QW#5pdN%3Z5hjaN9nrqOY+b`t7ylT`Il`&$ktV zt3@xVdOIGaU=cc*i!xF-$HN1;)$n?-i`d;&!xGA$&q(`9uH4@XR}SrjjoyM>>%&5t zSK{N&zmrI}e;yXe@X__k1~%rv4VY()usZx7QKP=Z{P$+493ILW=i|hcTE}pqv>#b+ zE7e0X2ViH$OET`YD&Ah>hwq|;m^~?H;pCJExc)(qBgx)4sV4*@&xP{-9DfZHnp(hj zO#>NlqkguDv}1B*7f5TH{-y3?Fiv$=5DDk4-Xl6 z@)Fwq!?ScJTljYyYf2Izx8Wmf8fYUUUHZ6rW(dChXT<0y$iOo(XPDmKN#a8(15H>Q zmwrv)>7ME5qI(6$vM1A?&A^SL^Kq@gAo=ZoANfy9F(g=wJ-o*VB;V|S?jwDqv&Rw> z(n9d&rbFZqWlG6ZKG_o+3?PFaA9jW+_vZ^-|}fTaHJfUJqThQyd%NLtp>(< z)e(&imDqW(47a{^Ex(TTou0YYf8=42EKV+_?7>Z+NRLt?=I55+(KX_1 z``#t+#OgdWi*%4{Rdw7|<1d^5^;#6~lEFL0@@OSrN8WnAKp{G-U)zbXJ9*CV9z#G^ z`X7na8ixTi)1f$X8SPI@#9CXbZy%k-PH8>}4tW_6$hDJu@6>TlxIg-&R`Zk!SAy(A zYxwg-kki_D6g{{=?Ak-U*$Ly&ood$IbO(Ci)d{EwNP?8WK_Xj~h{q^1bKdKHtk=<4 z@ZVn!zEQu3&L$0%*%^Ro9;VFszPoV!@*U{-Da^(1@xt9-f>6mwk#TbpffR3rG5vXh zvm%Da8(>`EPZBX(0UwGj!0H}DCU2`2s8CLel+Q2HWoCpq=R%Qxa4C7=Pc@3(A9$$W zgkApc8<=jdhV#pWIQggVaQsO=Zu#(%DcQintX>D$PctdX)NAVY$pV84kCK|UGz|Jx zf_Y-%?C54&*t9bOTIITlOI{47IoG55x(n=1Sy`Mz^SYmI#O3>)c!&P>RI|!o$3Fdi z3k=(G;FYNW7x+jKjRg&H$?is;mG?aEZo12u|Ly1I`(UBf2B{fuNk3)6baV!w?XN(l zEqDT?4{w8icAv@lxiZ+CC4sNzw^})@e~00eHMGs+4V&8c2`aK$KvB4t9CT1Z-ZT?* zI;_VWOp$}I$tIv$J3wkYr0}4&Ija76OXmED!P$wQP*F~rJ|)Bj7X zkI3OB^F_GGErxgUQwY~+{CrHKp5~MZCz3^IMz4T;^QgiLR{@e!x!aG5ka{i6G#c`INESm3Ikq&9mFmyI&0UL`>@W+w^%iY&&+ zO+dlf2N@^YGj(oX9GrYULJn!sS*>M-H!Y9wTr|^h+FYs$q-*N0Z z0iwC|0bbr#iq#!rY-y`8JRjT+8qfO3t5Hk*zBCA{E*v12sdv{!=o5<6%x079cR_|y zHr)H(O!R|4BTAGZp_G;c=jGrhYY+3~1-aR@pXE`RA?9YCA||{Cl&42`b>-Tuq3i~z zQ3!{S@_rJvPXaSSOmJh7gVoM;vAA9B6Q-UFq#E^k2&Ot`MPVIze&{ncHu2F}XC14b zlnGZ?KY$WdA?|2iKI-(-3~yH`Q_?LB`xa}0;?ZI9Cp#COQRcQ(P&v8wDT#WdDW88y zG1KUv44ENruzB7$I(wI5-MUNI_rjQLRr!pDVSEg=e#q`O`2q=h>%p#dm|WrV@yG8{ zyqEKaIVimlvQsxfz>|MuaNl^8K4XZHO6A1kTN3_qquHOQ;_T+#%i#X8^H5JaE~{f^ zV&@?gKun7Cl*IH(dCZVfk z2`22{&l+rwgV!46u&(qM@jE&jJ#~)bi|tlS>Cby$xAqRG%ogFkM95<2UwJHklg0B< z5QTON1&Dkqz#XORzT4F2cF5x=>B*AELM0Qdh&EtyUd@76J#KJ#^>6a;j4}G23dQL^ zmXd#wF&OSthx(IESa+*BXjiO;6VXDPMxih6SRR5tw+=H=>>{xAb$~ZhN65*^s+f4e z0vF8jB5`Ur@nj3_N!%mOmh7~ntkM6Sz17NMP`#iIC;k`3HoA_-x1~~;9Cs=I%}5b` zaiiTR;p^Gp3%8-);eYcyM_L&TKbas;u!XK>=251x^B7A%Z&o(U4rqn2l()oFQ6JAP z3&4WvK*oFBL{K}m4dh%tlP_DOQNM@wC&@Njttc$QY;8Wq&U(wvO{xI(@)l_8>Lo6Q zN(gt1u=L_QM$S$iGE zWA-g1dXF@4x3E9jPE2Du;-x8XPaLlf*OM9hWzo7y95XXbGe zC)iW|TY)xfkxw(Z_tU{nt%t~OHpJqtU{nn*<%v9w;k4rFD4&CJY;Mb<*KB&8-x^L@ z0%b9^nf5g*9bi=7oB}1|IG8zSltg`=f{BwTriMS>XS3ar zyWz*H`%vE1Oh$UE@qtVkrX4I`CQGe=Dce_#&GYqH8n{Wu5C?-#krNXiVhhzOQ~I>o zL$@7Zb!!-uI`3pgV4$oTy4WAYq^%lVJ8AZ_ zZ5^w*A`2FkXG8CNAx=S#!)!6?^W1Wrk*$>hWeZI>JcIT%On3p?=d^&GZUr%`p*)ps z4E3(?m^=O|U_y0!Irv7-J#a=Tm2{l^XBl~Mvl=faQB9`*A!`-#6}l|yp*UiMOw{7A zS(tI||qQG;#QqKjnRdYg=^EsZ*Ta9YDu`{^_!=dC?$`e~E&XQl7VB~BFh))_M z3&?nE^EJSSnahaQf@I`VW`)2WZFcqcBQQND1LEuc5Z7}$7#~4*1Wt84xixn1Gk~5$ zsFspZFN;+!^5|C|K#2B9*x#QBb<>B)QOaK}6F0+4t3FwFO-e?89zExa9bgyQQyp&b z6CBq6O#*$@vBS}udgqLo9jW(WN5gFxT`t14bF#RI&WKXaEM5%FrT%;%55d<3xbncM zIOVzlHa7kuwl@`!n`nZZm?3lik2cKcb%XlG-(>Y=IxZ>|olIL~{56jS;b+tGfoxKWf3(|8q z)sXL%$577Mcl2yK&w785!iG>$oVg-8e}>NoTolO1|JFIM%R=vfu4)d<^A_NS>F$1U znK5c?ZRQD2pU)lq=`yx|%v5{;kEgVbY1;L3ywPDd?P5#1 x2?j1~gVwK~NqVR? z3jDFcOBz}{b)ye>eE}cczr1A|C92>`Sqm(=|Cd;H%EJ=_V-OSkM@~mdVOf?bW-fR` z&iA!y}eOwFVOl~r^#II7TkQaJ3jap#Z9ND{E8M|XUx+)ho%V?k88lP1 z$(Kpxu*{l|(KQ>{eTUN_@gV@n50U8A@@TQo2-jQ<Xvc$*1-%X%Q$ z3W-FQI-1G(pi6%sQ(RDXF199HimVb`Qly>cn079z=(nu+a}{%Ce7jajcCgRVJZC@#}L@@O7M zXv_a*wVVGVw4#2Sy8c&rdNkwXy{Qy^SshmROaOT1ro-J2J!A#lw}*ZXK)-7rdAv2T z9Q)(@*e-HNX&h?blfXr;;Y4lnI6M<2k770lnAFv$;r54E_`n+_Kc1b2hyZAZKmr0p79)_kkK~q#0*?DXn*2qZW zJ^mG5n#TY);p`|UxLt_bNB3wUx%z0v4U*fAkFb*Ft-=b$*;491lI6C8o-6g(mrLPA z*#-FftS-r=XPa^K`BB`c!+M?A1AOsp==N_R7Ztyt@`EzmZ}pPN6QWtlS(e5|yY&`oRw}y{(4&bILI8>3X*7b{2^K&IbM_>c_b1f!n^Hz@8cnW{UyIuA#z-ZzX}W$y+p87it%x$i=QdU++Ip{Qh+mWbc|^Zf^;*Lm;rJlB0)pKC#+3m2m_1Wa2! zV9Ug67Jp_WUL_B}nIF1rY+4l-OqEct!Cn6CiFe?vL>_74G&VK}c=QCZXa+y!x@DZ< z?w=)ax#Tai)6&4-@2&7pH~B`+oW{mqVq6@mz|SR5M-x4BwRYdw?5dHtOg0D&XKIVM zoEqV5ctwww?{2FSzFnw_mp$IFLFWM(ah!%ekms${mV@r}AUH@}7)u;9@al6*%<-MX zE^ki8Lm^^JYovSJfSvHy%GsczRa9CEDWxfwzPo&Ob zZaa6idpyJ+o(FXW-AwwGKGw)O;*O8ISWfg+yeVId?e+@1&+wUWv^@fXt$wh3t#PQ8 z{0@~SMe(-enVE1>0gdgC=YIYA0z(5!utQ@$Z#bRaX}9jd^f)P@%iB`en!C7X=eTa# z9XQz007IOfvbU;xu3k%LULC#8?OHrH`qzgrCy%*+_3?4LbpJLinK5w#t5&jvciG-GP#SU zWME`4?K;;k=R58M!~2>P5N`fvm$ztQ=~@wfUlJ>FEea8~wrBP1AGcDT>2stshV~QK z41>40e~bj9E|~H`{|>{<4YWmAAuYI%I}h2ev~w){&HgB;p?!-3KCzMJzV^}v%V*Q! zLRlM&PZ*A)Z~9_-@_SY=VJomht6{pcjPQG(0&I<=Pxn>no?$+o`>|r5Yd38g)nkdBXmss!gMsX@z4}oOiTDK8ri!qNEwU=!Rj|N zZ&bp)UgPjcmB9XNAjbP9U##hWiPK0`!G247;~S1xH19I-G3_{(+{%Aw`|c{5uO$}N z<5B$Xe*RE(_!4Y4{mBA6j|qMS)q=699g{umS9QT`xY zJQxpoN!@If-azbhwZ`+S*NFT-T&4F>F{VH9;y+zXf(+vq)aB5^W@{4Pcf3Ca$J=n* z25W%Nn}twV^_~5tPWI;^@)*^9N;J!~Ly-6A5@v?W2!7KI(P*p%_FB@(zKzbrvr&{u z;S~63-^aq^mX+Xnp7P5V<8e882`uVH^0nrhfP0k=Q-(CM?)ta5qPYZip;WQx=yU`w5&W-mjz#~&6#l?H5I>JsZcBq^m0PeTR7P;p+K%@_L(r(N zA$LPY4d%HR_MDS_iWmf#HNYRQ*NmsTl|!yG4zP6L9BcGo?gbBc*;dWMMaFpiVE`)0 z4q#?AZ_x>eNxmV2pB-2Y{NNfmt1TsruR%=LrcQw;Pr24m7uepo7#ceNvR^?FGlP_4~Fy((Ii-3mhIrfb3#6??S(juyGF(}7S0*0MD8EIclSlXn z(zmn^lwj7Y`Mg!%>oCIU9!$6{CHTF|#Hp`|<*pIIS=m|%5qkg4;blqWv8Vg8O2Je1 z=|?=){(gyb&P%u*9%S=3%M;z>+LT+ieHY|>@fuzX4Z1X0{)0mLQ;CwziY;ugUm10zjR^($1$Ah*{ zELco!Ve1Ruq4FFF#_m(#LxVShal>YqL7v9QEh8}4!3IM=$>th_Wl|1~SXj~?e8|!e zSbQ`EYO8;<6>l~0$Yf`9*NYMPc!vt(!v34XfmPQbN?RIfUBg=P-r;9DSA;Dx<3;I_ zV6PtqYB99qP~VM*|Ae7xzmuZC@fRRi{V8Rc{xIpq+PE@;L*p&IxML@@AwhF`&zX6X z@<`PFO>EfJ)$IF$ZSc%!HSF`35n?|nVZ|)+hJJR>wO;rLr_h->i(kxldR&16wgA~} zolJj9UyOKQhgQbHqQ6g<3D-VF_srx|t~X%Y=WnpNT3{NHJS&2}!y4hsYaSW2wa zW$Aj@>O2O=*>4i%^-IP2b;WpS^BUgy`Dt)7eF6QsRyJnqF-$!t#`i;yag$Uu;aBoP zxHY1Ug&3>jDpPr!WRWED^!!WOQ-_d#Nm@8yX@uBnj{EaFnRZ|nPERaGhuaE#fVu;S(t_1}XUQ%k1MIGP4raXVXWrvFDG4ggozI(;-Gr(P(ocvrgnfK)k`RjG zQNy^~SJkK+&H%zDbg>+FfX#ErQ$4Jlm6HZM<)jmuMLBbQl=NXqBIVuoeqaMOjmAgO z0oXWx0J{?O9;dyeosNDc@1^h&E@;<4eV~*OmbVMF4uxV}s6Y2}p9ls7E{4V9I#^P+ zCYCL<#KO0wtk3Z?n0i`_Z>K5p9h;}XXwxI`G3gsK$}vOt+rjwAzMp7Q$0tFQTrMn} zFDvYysD!Jsi8)?S!K{29<0;C)DW@s$M;3ZQ?U_J`Y$oQ_g~6C`OoUCQ3z^>2GguN! zna~fT_$`ZfL)Y3=IOp(HVI0+8>W@2|%fwcg(7Y zc5QL}@!O$2T-NpjaDU!O@LECsirItlrlkmL__xma*UzBp7BP0}Z{_zNN`z<6OX1*y zdRBMB1Qkmub1HG-K55;7Ua420^@*I2>@E-YPiufhqm%%v24nX;YvkJ+SZ#A(%(An? zl5`s`Okx6yEj?j5<*MLC947Xy!Y!Arc&+PSK(MU@I3y?Z^QN2=w-4oCZ{^~yOa!)Q zE}WH;62|RVj?KIManQxfOrepw;zLehN#%3SByBbfx)cGg8YpXEz8XL4C1bFcvdBd- z9;a-o!o=E0esQBFrg#%iWZa3|uC`*z_m$8&ZvpRFcAXlIvO$}8<9}_kF{t+c-iZiq zu%nfba&lqMZt>mE47jb-2)fIjF}0b;(POq49~~&=O#bwTXWR-{qF2d|rBB2hSg=ompL7)Y_fIy#o5P#Id84#2dipS| zxNU*`9!lrdS7zY{x))dFdhmy=L!o(l3ixjL!?+z9sI-ze?W)nDYa_x0jgeVB`bLTI z4H!9J3T4e0JGihKZD!D!S<0N>vgHVT{&)mL&!vS2lI=L?NigpGa9p%`-bLus`~+-Y z{9$`ZqupxhjCs3dxe=H8z(Bd_P-OIjJysos+v9vuE4G^HJtHnt&MLT;BO~Z9Q$+5C zBA)y)DR&QLi+mT*tX5pYtFF5WoIF7NzJIJ^NFQvX`|@nNK+*619)jpjbdSEFH~$9c zIJUya-U7QFGaN4xn_DI>klSb&4bG1a!0&~!LVQ2~j+hyUaqmM!3m3nnPR2$keOAZj zI}M@zJcrM{q&bgc{XjB*9Lx!$_tz{XymDKFuSevvZ^S98Q0Ud;uO7CDxH!EfSlvsJ zkEVVf5At&wG!{HmopBw9(_C%OG3G1!2SFd>OVH8ylliZxNC?a zZgz`cj$7#LJWzrWRi=F0A=38y$Ab(fCCsTFit;nYptHhe(Tus*@et*O#e>%Jy5-5x zN9_gV2(7Fr@;Js&r@-;hW1L=xCir+RgyTEfn9xAIMGxe#;b@}BZ(F-i>-<;vDlIKo zRvF>Of_-SD7ij51A2`{y;LFM2;R8sCET0G#3pfa*txJCE(_o<5LIzkbxw91)mTOMkWm%zYAk$1~o0e3e9 zLUdp!YnVC+%}+UD{g!#mR_+{rqI`{Ly)pm8buT>gNrjSzZ*0U=V_bT`7h|r!6*at` z38U!wd@x%^V48ubI*9tC9pAGjbe7&1(GN8)?&h53Bj9FTB1G=`$9}G*&i8OftU6!e z-1oy-yh3Mni`QFu%abSJ{_Rp|7}LOlCm3U#KV=hU+jDGlA9R z&^N6FT>}>K+K+EQ?DlLJ^;=3<@KTMKQs7WVKremiEt`cCo~ym`h_ z0us=MH2+VdUvXJ)bfE7CPdGiXk`*^h#QACtcz24CNRH;;-cZV|v_9wm^?L{3C<{|u z+|Ha9-NOZ$#GAcc#0_!i3xl+5AaZI4OV*>mi(re7MFp&S8+FYrqPx;`CH|%`5$Y^s zA@E-dGwS;hf9;Z>V}c@oxoI=(QP>Rb3DSaI$#9&bZHc3|$>i>KxQ7Sgig9DOC-2ZV z4En50foysDcTZ>$1KSB@BVt6lm%@aH0hv8J#3e_rLtyzo@ZO)p;NJ)A=SgSm40Had zTNDHdbO+Rv5mvt5fwMLQIZvbV~p*qeQ{-LH4FQ(9sWA60_kru!sb{-{Hm&m$Bs_QeIv@pi(5;uchwSpvH3Ny ziV|S_#eXb#QeSj6u)zoFL83oip2Fau=$?$sMBOx)zrO{peq&67?i3qm{5QAl3ZtQH z%K>l?lNB`XQ7@8>B5og{D%!)u&}rTX+qZmWbq5DwL9G*>Xzdc6TG1bTf4RcAjNk0A zgwEJqE?Ci$!^X<1B3~zqYmR+ne<^eHR#$=(jwtfW3h&`5+9@21dGgRc@doDmk`H9c zXnuTM5ImQ=1YbNTH@!a|SI;ZN!E;7&8kZAN_Nu?p?rb%$Ww8eouiz1=7OmN!~d8O#ohzf6SigspD27eH^wtjGIYaps9ny zAY@fL8#jyYU-?d$cEi&pLjDAL_M^V|b^CaJ=`pw!R|)5@)Uw6hAJN}Nf_DrT@}i_$ zkSLc9cL&P~c2)(*=8;Z#H;nUE(Ezuh1|Vd0vCShNLmqLi%t9(y60s&kb`IEW?8JT9 zWeDO+)F+YpkyYe>M46@%>Qc?(#TuXBN%Kc&nk6mlP~DA7SB2oKwtbw#eIEAxS_H4H zI$87G{&=ys9Ufy<%%=MsZqE|q-N8zH{Ksi9tS}O6iHDH?%@o_{onJ^q7s0Bm zOt|hSD~LiB@tKkW&d`3%R(ciS71I*jahpEptd;OBI{+Rebh0Ve2BS%x6At&9&#u{@ zM~@6KPN_HMThn|Y!z>jF48Jqgi6;2-5S>#8ycgN~&Vmuqt}t_ojIhg@a#eZqXuf(Y zGorce=GPae-1p(OK?D?DOaxc)KbBQ87*FXq<9gjU&W>8=v5oZY%J6Och}u(-@}(38 zsx-2?&v)T^uPd-;d@rGTv?4CKE04VzFNlOa3h<*s9j5h@7IOOz!J|o*#HVOr*Pi#s z!uPfqvBs9`~(mB56SCW_xC9` zjC#rE?VdxPPhz0itwO&^l;^Fv%0?!n;VJWC;?5}YjW`cVu13JTNx#_UQSsP+emO3W zJ|yh2VI{4vjlSX*f!`Qv@mCy&sO^#{47^K1kI z&Hv`}kGt8RYT5|XfME?1k_i;>aF@~>M z!TEds43%|mKwM5ItQ(fYvI}ZRYmrdK z&w^KzISNO7kHE9JGD4z*AF-6eu;Tkk(at%S!OQOn{77$SXD?~s+@E97&0d-d-_;M+ z?wbaNKw8sRC0tzUjx`rD+4}7};kVK%m^4dP7()B~@a6JoSu`QnKC=Mdhfpr^>QX*# zOe$PhCV-Dw7pv;-i|@0ovCc3^)OKfu;5s#0*h9aA;r*NNsH+7+!~%P0tBhaAO~In| zbGT=bG4O>l@DuZ71(PSr7)-tn@nbcS_WTmipVbISlk1sUfF7pkh%kSyGF_Z3Q6N^q-=5^q)g z6z{+Mh*qe~T{rlEg@ zS@V7gYShJS95w>2^3AcAGO<~rAK)j_+-CMw;;rkQ;NkQYFeJO3`O|q|f$~b4QJKh-iJ9o^=S{&0_f)A!< z^U7tPVYf~V$iJ5s9v$0>`Q|~W8?u+{b;lL5_Ai3T#GnZ4)WxGa$DoehJBC&l@CGBj zH%y72J$eR&T!@6XhrY84KV@{@;f|+G8eKj+)d|?e=g+sfEdx79E^ zJplR;Z*A0vA?POOjFrO{u%YWNU{dvG1z*i&(US)P1;bhY!O1orz%O*2T~RvPA1Z~}qDHppkuruHaYwnheq8ml40xV;nK;6|gb}_STyjV<`<5@NpvSHP@Oy#zyX86G6vZ|sw2oGNvcCw0w+xjV@B>#mQ#zgc51ej7X6 zaua3AAGLm!5 z>ir43lO^)16J~zAMb}jMx<8{ zpuNdIZLEFgh(Axoh{pTv7kvKQ6|(4z;UIehHst(;{kjj?S^g8=+D>;29ZO#R>QOjh za0E*B$_T0@{y6V-7%p!=C3;TUa{G)Y@WJ*k`*OQ4K2dVPV#8is`I`P6F($nEG#q4mYl9)Gpy+)X$(q#5=XGFH^0jLk*v)H6DV^E8hI&(d%( zZ;%yMMk(W_0gAX)MNK5rCV}xjjqqw@1Dp0z7o9up@cOzxBA<30m}~6{!~6eXHuF{R z(Kr{}VwTH1?#E%AP8r&ytMku~DdOqp{~$1>itW>WO?M*+F21b9dp79fii%D$<%>Mbdtjx+GhqgtHrlq9NrbPQ|YmDHx^W;v>a)dHi~Qsnj`;zFI_? z5aM5{sN;oiJjN@jaE0gkz{d3pAd<5GE0o=E*JgVRXe$@}NNyMIJN^{7h;F7qSuh7* zEfhT|WxaeJQeLbC(~cLk@VYlVsy#%w}kB0Am_#EApRl{-{zk(0$6qjhX>#_fLVm{xU*K`3`h)3B+9{d2D#4D$2SJ!Nl+o zZgllBFzW~fIqKN0xjvQHAi?NsddelZG7*gu#OU(YpEe%H;oja#&>H`VU4l>exK4uZ z9~bd8S-0VC+)e0SCM*0)+DScBL0CM-fV=oX1FX;M!@JflHg!rqtf*^%iU*Z!;}s1I zyFjckTVl>H7zX={J)ygyhDCW<3-Uv#7|f|1ENkug3a;o z%&oRgFqrnL$Af1Yri6P8kNmK~>Iy`!1r!F)?mv@#cln(;(Vh3U?kfvgq5U zc<0StTyE*W)#hhH)0)d5dD2VRvRxI|5d(em=PRPJi;D1A`@dOz1@$oep9N;;H?aKo z{c+qnYvj7DIq#A7u-9`v7_Iul`uC5gF0faqzS5je9o7UNtSX>iQ!nAm;&RN?l3>uG z=bY9@cewX)HiV0%gs20nv9GB=-a34h&2YJe7M{g8;k6R~{lP*wbUXsI$y0HCW;`BV z^a{t%IK(dzPr^{?F?i)=QSO;x<(TuX1YM+-@WVHzL#$^O><*F^V)AmZ7x@sT?Ks4R zyV(i;^A-p;M~QuX>;Xt^ZG<RR zWhgRhc};!yCAe|i3;xc*8uE-a!rNj0*r%I0C_AhKr>l#(yNmim%~LCI%IILG5o);Q zk~J#D=CcmUH;oD+uB@*zpVaIQc0Xf4VIJvPI$!YaWeGl-tjvFZWay?0;I(bj@sVx_ez$)ny6GD(OzFPclU1xF z9XNksJJbe0V5?NWV8v+(PWo!em(7TVuTLYPGMT!8PVdH|^dR&-l_0t_^(s{SD}b8A ze_1GKpu$c&v^16Cj2v~~Va-%{HSH(+^udf~vLCjl)UY89KJazeN*McGRv4N%4zHEC zVClNZ+#@N^F#a_0c|^bA<3cKo3F889u*ESTuzv^Q3=N?$4_k0ef2*hu=??qOqbnA9tl31D2EiW2MYb zkvGEbEL$8XZT|3U*ey)BLw!A+Cj8~}P#Dm85q2;6!@hme#N1`$QTTgaWTSdgkUROd z$NTZrd>XnmIbzJ|9CjqN9KBYMb{%EG*VEnQka`@PP?HuGTj!wCsbciCQ{)^1ZsG0J zVm#Y#1Ao@wJoqFR!PyVrS;-<5T>04vBLxLcV-@X2Yv=dOXPGUN(4@u|zYZ)Def0h- zXwPU91LhJN_OdZc zqn%IPD#`!~qxsAiKCt{=I`m)I!Y1E}Mw^CE%)RW#y+1hNgZG34n}c72q#VXw#N~nl;8f#CiKu@61-`EU9jG>;3y$}fIgK6%`H%@)Dnv;WxS$^FsnktOcjQ_dd8UqZf2j4x&@ z^G`0#0@18UsIqBe>FV`@W?N~GUj5XQ7zG2#ug{mUMVFrA6yn7(ePw>>oi$+n(I2)B z=weri`G87}xKMvSTPePTUZr9TSZ~5tD+EEbK`K0KY-1-3E%BzDKTekWDDupi3;mAp zkV4+$1>`+8TdhdE@tth@GgZ8>P79+{cXA7d9fta$iQqh=oAr4%6wh39!u-&;&KqxC z!gDvon0a$MAKjh|C;UsHa~0_oo6Jz!XfKxZb>OZRWkH1fWl-1eE%e`|jHV;x$)j^o zlw_*}-!jx-_dID~!-S!@&C>!`Tx($Qu>;WB!xqQ-+Hn_U9AM*{bv@_m1%u=9^ic_h z#+&g=Q<`CuZUqcl+*|PcP=PN-NU&jMAs0;9`Kh(DU}3V9p!UuH-#J?2>Vj=7;o$9_ zo!W#M%KWx9i$J$e1jIZ1W*yfQ@XB>NyrOg7Wf1kqL{&&I@A5&ued{DF-)@VWiwbj} zUai1p^4RA~mhfRSZ$WLpEQq3vXNe5Mb2gNHE2;G54aQKZMS+f}8mrEHPglhyJt1fIS6F{mCh;9V^D6=aqS7%c-!e zGzMlc+3-a1AM;amLb|d@tTo?6xY_QJjmni!F0GM}&hoonJ*gZuRl$g>kSotA? z$~X+Nkl>efYJ7B~GP<7Xf_J~)vd$ru7`BSMH#e2}(f$VLQfx)sPLqcwcW&dgv|`+_ z%ak9N90p5!U4l)T?M%0?CUwX0m^c5NXhjvxZOgYpCFzYT9#2Q9Ax@YSn9H0EEAjkV z37VQ&^1~KJ!H>VO;I)PrWkU_|O_(*l&)F!Nm2(?o?~`^R-oSJG1>nyV!H|eHHfDKMWpx}vS>5{uqZuYA;jkrQR5vlS@7_S8q9ncgbZmA@5Ftpv=qmp981(NGN~U#-6&=3y01~dUR=ysJdnCz0rO%@jA$xv1^Sc z&Q#~Q4`}jy$}idxV%6dZE#j@7=tenb53Wv`iD98SLQhC`Uq`QX<6t?Pha* zhhjpz1A3UhafT+!TiqAqtW7)kk4k62d3h-;t8QYw-&jx=q%TG@N6srT8y4hWg2$74 z3sZH}P+w5M)~G9@1<6XFZm8Cydz>@Y$Gv(McwW1a?fx+UCmph(-dsB_yq6=)*|iQh z{KL-WD&gvZV=>59gUL}IYS(b;seEn9&l=SVul|(7;b*-CiGLM(J4tYZ0oc+U24^YBfehl7HzTo1y zA)fLa)cc@ukk@=LfxMqq7{2aV?%Q!ycvVhNs)dH5gl;F;p zhp7u=jIi|Ryq?{n*S{QiL4L5|&x@FWH}w}#Z}QcsiCk*TV8AsVaB@c#yHXv6U-|^& zg(>Sq+lN%)rRoxFYrP*iY^wmg7Q#~C3tCDG1q)j2R0R1_RQ+xF2p2s zv+mg~Ubj0W zqxVAp*o~qYT6eLas2GzHH}d)J7h%wjBCwPG!Iqm*=4*i?b)_qC2j%;NiT;0cTkn87 z*8U;3PjI>DZbG{dVACoL|Jli;_9&syp^7_ZidoTd0f+gN;LA=rZ{OiyNf`ZI+&b9B z7t|@)Nx8~e6Xv`AG+wJF@8}~F-ri*|xTL4Um42=4x=I5^E-uBz(a$+U>V$f8-wpK0 zx6tUl7xVK2(f()wd$>=)tK_FSG}xS9XR`ucT86^@{J*U4*uIE+?9q3LhfCXx)A*cN z>MNv!_{6V?kT|9i7F_(yMBnN$k1xdwSxb4j4H+;lAq__Lk`s`!Li(AS_+#&VQC7Sb zD4P$3FS6aNLU;yhj*T$z=NoqBy*8dM9D^~R9k~(eqrhsOC+w{F#AJNz@ZrK>+%r^< z4YX~5wM##OZljCBPkyy9agtG`Hh=3kD)(IQCQ(x;!W!5lwpXY-$O> z2DWZw2HrVVjHC5Sxlk=9DAHXA`NS)(B2Th~?O0rrs=>_N;?XBvjQiA0`31+mLB;)Y z;{MAENz@&&eVPO}elOxmx~G!9Iun*Wl@i{+F+#sDR=B9zn~gKbz~i)+d19f$kNCR; z9z8q&0o}jZnsvngkhR5AyU)4o*b$H4DP!)qDT05TF#*|fOAHsD<}QEzhR($j9C&yc zUq0*(+}Mx_vD6E^b=3~kRS!cku_!$Y#|mGc&+F-;-4n*ZVR0i|KJtR?lGViL3L?sX zPUQTuhJgQa5AgX_#iR|7;<)uec&u}+sNm`wjQv=G4Y$O+{MtG=bAj&Wuew?JW5CP_ z#HAlz!o}O`Lc#d|W_2okU(_LzF-{6}2Dg>}^S21xwym))^n-8{6rml+)7NDwy z`^j6?=02vwiq%^=G!apD#2m@q`=~ zIU#8=F&+(iD5hum$~4nDkY>YGbCNg8RJ-l=y%W>A<;3a zN3Yg=c?aCyH^S#UfqiJ*jRW@(m-A{CcmGE`+&{Y?R^^hPf0-(V>B{5rzp5fd^5*B! z=Pa4t%%UC-LapWW4Cu9seoh<&xo^0h`J8+~9Zx$r4nL|*ew}YO<6O|n`Zn8J{+#xya=wp+u4FG zeKEF@_(4}Mip=&T3FS8b&F2X-XJXd}2kJz~WuYtI;*dBA4moYb*CZW<2ad5|n<6b- zTa!T@Qlx>e*u+ahE2T**E4vgMi_Nyw=MzF!fx^!ah&a{3J{t@~`ydy*6}HC3RVoEvt`Xy}NWiNTa2{{D*O}5$!#q^48}9*-PgZSXqiaA?huB8>@!a zbk6rVep$4vR2iC9se&rqm+f>7aK;TYy2~`Mc}Fv`lg=KgUrRYP8)sNiwifn~|EJFe zWt=k44*SKcGmD?`nAM-MbzLU>`|)k?CbJxh)8r|<{|;pqN^nu`3+{-?bhx#5CMau? zug`NBz9C=V*(`6?x-XMFgOo{0RpIp?EroXO0E{gD&A9eS81py;pDb-~ner+gM>f1f zi-8e*^YY1fGtdeTmOjr7+W8LO50>D!jm!Ds);rMsoxIVGGQ#77yYSAGFl^sx!Hx1A zE0j||Q?{I}@R@QLD_A2W?|aFX-Pgns2`-r9Kasm7OYiN29&qEv8#ZvxJ2dMe20~0R z|KR0UsMy#@mGV-;0sBXoM$C|y<`OQu{{ZSMvjk7`PPWWJ6I8+mai-KApS z`Rq1U)!c+Xeo8R>tSUcaxDSM$To0?r!0As}hSTn1WQIHFzKHK1tASrIn?tu_T`Lx3JpDcd4 z20lx3!?X$6EYsQ#WS@AzwT*JZ>O?X6kPm8H!U{g+dOA#4nG2Uqr3CG!p?LQl@nem{ zMfWV$3XvC%2yt36!aJo5c#_`;vu%N0Fg%7y3&rU9zKYvkbPT5L*bhp5dkOaX6R}&~ z317~gC=x%a0-xeWaNt{5*{e+KAUJBs_`9c3U#*?S1DmtLJ=GG@evLfT7q%ERQNtK$3d?}9x(YIy%V?5 zGr5|&bZ?GkTgRNigeb~!Wts8|z5HRz@O0SG+RC!s`aGR{mh)a2Sz=BH4m*3(EURFeImLMUWC<3ISLOTe+X&w~{ouo% zZf5S{fl*fiaLA!J)?So~uDy$K!9g=V#XA(9q+WyWO8PEn9z(W%zLSa% zNMlL5yNeGSaUSNBOQ6M~h5Z_G9B-S7(M#zx=X2%(#I#=osWI|G*hqDBuJ4W84X%j% zW~%^xR_U3;zZV(e4eCU(Jl4n*%Ck@M5oUkgj#ICPw}GhT=X*S=Awl~M zCH#5)2GAYQ2rGzvRFd=e}7L2ytE*c@tOTko~tZuL^!$E)!&R=dIA*E*=wkQK_66!FR_MV!Eka|$;< z#vhg?2(4@QdQs?1=!j3W;zjeW9uz`zZ};dG$tr2Ea_Kh+e3-?Q zo8w^1`oqwAOIEmBrhwC^Kc@FNBhlPZX>cGl9}-eJ*@eNnxZRD;bs2KpuDOGtro$cP zjQz!KmTBPj%E_40p2hBH?*nn?atNmH~>Uv>*Z zrscx!LzHzIFcgoRqh0FvFwvm%>xAQBM|!+=3R5#-)}2OBy+-qS!f~8Wdn>g)Z@A^V zjzh4{eptr!5(Z9CNAq6txbd5s=%d?PP%UhP5wfjp@yKjU)hfYHBVxD-C4)g(mIGmP zJDn?3aGkduCOF??+T)MYPD+e{^{PB%Q67BbPk1o1g55b=jazR^@X2>o{^ZW#D5YnG zXC|9Hyh1v8@I88$#D;U`)d!$z#zhF1{AJEvYA9T@$DF>WMJu$Eg*4kL;lu_R!6>B~ zd(%9bCU3)^9~}dVc`-0*pp0;$VLLYep`BOFb&;$_HrD+r#@Ob~eDs4W;OABZQJ;RY zhxhuRjyj9*)AMTXb^H<|7Ex7ow;Qn`MKSTSjD@?*nEw+ zK>JjA%@5&Vl(H2wyB zzAGoJBJJeKTnW0Kjo^|`^nsHydN77E@}|x&L3%Ci2n^mc$le3;S5!g6^YB@p5SnZ(7mY( zR)~0`j^EDqMlbCuc8`Q|GL?D)f-r-LirbUbG{cJ23r2t zAfErlR4k5R^ztGcE!cD8l^4T-10pCKCnpSDtA+vNd*R0lZ?=N`;1!AVtj1dLgGU?% zl_4iUt(q7?)9#@r-MOS}d|f{OypGYWVniPwzJARGuy2-taZ3y9a!J7N)?zH(d77IQ z_7EN=T!batr#y2(ClQbU!w`q-yz5$8~`9NbTagSPS?mNY~K zpPjKm;ugCs>6d^q#0}6di{Rs@Pr;;PR%mm$D0fua2duG{;B{k4zdX-?WfL=?`m&6W zTeK66G(+%GvKhCv&|YxgHM^%jYa2WQS>Hx5^cJ(oZVh~1?|^Dq<2a|u24LXj0kbZ> zWsCf#VDm#OJh0qQ6qWP=HyD!kJ3+#)P-=p2OB@)Q*bso1P4WWqj?>vivV(KTYQ|0?x&w;jOG0@u7#xjn6!}sQ;`0|Sy?@+i0 zW|XaiQa@SY`cK%L%sQ$jc!kkKdH1Ad5y{@y=syX}#NtWs%5vcvs;NBOj+ZKS=UU0QY-g)}rYNof#T z)_u-(NeRiSkkwETl`Zpke!l;K3$A3|a@AwXy!@Q;c%Mwi700J#?CVj)s3bj<&^yUpyd4CE%6H(|#2!)+u7dfh zmiT%gS}61JI#s_{F*t|&$1TMMwlDn~NXRw&FPKExGt8!!&yTY}j-7>qMG|y(xEJbP z3PAI=$HL?-sc0z4vKY@jc*Rfg;BNF5eje)}9t%}*nzR)b7YH~F`;jo&br~cTwvj7- z-E`{Odiq7On@q@-Lv0XXSX~|&pZN+UtQbF}U5Q_NU^eR)TLWUGm$7_xQ0<2eYJIXG zYwq60pk$`&y_&}7mifR+rt4|3?uJK?TJVW(DfW$e$7w{a0M!x)NMSimzb*y*@l_uC z99+q)2d~gUgY{LNpUz)0+X7b>`N7i%y`;TzI2wkUp~KrXwoMVY@f7nfB^>eP?=QFk zK8&A}=u}TmFKfZ%%o5aDww6zeN(K4X4`F({6m483hf8e)_}Df{7#T5?bp+`S&g9yI zMKDXM5$^q~A&*xN$Er$GY(8Mk#gtBi`U$KfIr=B*Q=f_BSw~FVPNw%6wP0@u>zKGH z;wMV9fP%$mNVq6PN8TvKneU77a(OXlFn&JVeXs)T+03_RSqv-20_rHNBs(<{SU(SY zCw^Dr)52G?9;#3{dZwL7v~NMz7uPZ6qqQ(#_;332!Mj19GmcZiG+Aj(b|@zjIi={4 z%yc65T{2Sl03Y+CU~4Ewn^i}lxx5J~|6D>6mnL8|`}~M#L*7?45cVy+4-@aP4l?Tt z*#0LE8yYP*sX%AAaM>30nAgZ=$ZV!*nB&iaI5I1#6n|c2*;LaR{O%{=P!tozv?MY5 zP{^_#;zc-q)*(J*`yDWQS^}4s|0UbDvs{KlAqF*EAy#?(CV}2*IG)YtOTXEC4&cDy*JfDvfO!U7FJXsC zA+Fgvjc@nvgj=;AVfrfpoe=w#b(ECgdHW*n0d)l9r;7$>ax?Q-w%_%^O3TO0tD}N4 ze@CHH&uT8I&mGE_pM-wbkGkw}>%vb=UFq!ZY}u_XNb)4mM`WVchW758Kxmappl*^iRQ(!I@mKHXFXN-9_!( zA`;9r1x8fBuPJjlAFnZRWTQLSnN^d_8DFt_YzcO%mGTN-o4`Np7f9-eQxnhE=(@KU zHw=5vJ(SjltmB3-+o_kN&mN8&m_Ov+nS65CC7D#Q^>mHD!{%OFVcER2+DBdcs$ z(Uo~kqYkL>Kd*Yh_0BDWb9kegJWhTtz?&|GnbtF2qs9!DwK=qvpY$yh+E-nJi}U)( z@oFusZMQ<>8Rvz;r6KfmLeijj?%TCQn9}_)!gaSHs3&Vq0KX0 zyz(@Vvs=zM)@iXYWkU~nqNa)p8!T{jd9;wFOX-Y-6?8?g1ii|%`?@uqFnp#DscZO( zL*JF4#8Fe;kFl>Rrk;g)j9cm4`ReHmjR(@K-r(xmiy(jcP-UuO+M#WgS1|b{g1TdI$~k zr0H;@4`|PH94i{k866!44U)Q$GluQEs)`wly%Dr;*OCQGG;tc^i7gv%%YAh)g8CzC z!S!@KnRwe8=d-RE71>c_k766%5wYD=FySrTS|OpkmieEh=w*WssNBLl&kstte*SzN8&B8> zyE=bUABA^=dyhNCDtJ0u3R7>Fle;TEU=Mp2#MLSDhZcCkoR3G~#wONDcOntfhZUjh za3j8-b=PQbxDR4GJBgd!1)Lb3i*b4u++}eWC?Pgbr6NU7(Ajt{%nZj>$B`?-54eaF z)?U-Bg6 zGG29KjD5H3-1ikC@UD-A1%GAf293EWamx~2f7A<~X(+=|Q~;4koO*OgA zI%cKg?KiB`=i)~$>?{vouWyFq@;#)B<)}ht7vi|D)A;f0yWrW3kDyR3pvULdv3_`_ z@#zh?AupowcE=Nex zm}3X9Dc%PIDyDKB2d$|~q|>0rXMnFD?`=_MFqFv2fyrJEUvW zkhSBLQM9xJ(iuWel<23oF^x+2_ zGl^xK`!@1#GoFCo{!HjHXZgns>>WE}24igb3)Mn)P&vo{&1db(G+27F35Nd2A{7rW zV{0huFJDm2b;VqQ_rd@;-X%@nu=DxARB8M#Tv<4)^D}r>HG;#g7E(1P1N}^kG5LHX z_g!ZcNWQcMyT7cfOJ4o@7y zu5zkzk8u@PF8jvEcKA{5P0F3WVQT?n&(1dGtyv%1?Vbqmpc2${*&!Tu%NGlD5`^P4 zGcb4}<0P-x%|~}WfSq6RAt$htEY=x{5ur9n#wv0-U0P5OzZ9CS+R1wM_gc;VUW=_S z2#fZ2(@ADO=+^o!a-Z=r*0b&j{zX2C8}SB3j7Kr1U74p+4xs9`2EOj?BRfK3(PMlO zo_%e|S84izX4qr+&boTfGghIyZU^WDHw%CJuY$%}2RJAuMRR=>vCmW|y(pch-LVyZW1Ol4S1uxke8RHumGe`CKaLH95kv%>=H1!)(H9Q zJ`>w-BXHpaGrY9RhKp~pg1+0kpkYfVc~)eN*L8icq+gGC8nvUfXDLoxLiyD3Z6Lkr zGeogmbCvc-Y`au~-Cm{K>6y%fI&=l3d>J780zJ&{nT|XBtB9@IWBm8B2%X+5^Gif7 z5D*^<2S^9G5x*VtEN@`8n5{5=%O6_R@pdqWVxg*r>wBb7_gw|aq90M4GJou975?AZ z-O#lC2#B%#epbn2>}9#;5lKe;i^7wTGWI_FCY@xW+XcLD@dn-3nR7;!E-=r)212Gv zQSE|-XvuuboYo^UA3x$%#_QXE-h{up>?{O3M8Wu7;uPCPv##VBSU#!DW^?9a3}W;7 z%FDxi)!w@xyQ~C8Om8OQkFVfE#))gpyUr~$A)w%8jN7n(7VMSZ4EM+NkQo*#$Vgncc$O-e zcIOHXTfyeiMnj%^*aZrISugoD0oCgGj)Th%d8Rl)cHu&}cvqZi{q@3YL;bLM zWeS;Nl!-6duBKi}g&*m)9S@+b(~a1$<6HSv?k8>Kkq9jV4mcZA zq8)x#hl!-_e8&*a60~nz&)?Yf0)84iffc5b^x3&%XnVjP|FbmaLei}%ziA2e-6u({ z*W|zoxh60Zv3~g_YFM_(98E6rT(yz`ynDhl!Ppui5w48U^V(rT%@!j=_rmRcNy3z`#be$KzZV#p3Za*HJ+rg@j!DM<9p#C+uZDseiabSF(8dU}xOe_u5Ns#mcc$o!XN1?vwIzgmdJf2z45w=aX+ zlmNKxDMJ@}IpCH`GweEQFMJ-7iQ4Qu8LN4YyV5%fp6#`T4}3S-U!jcgb4~E8AeBhJ zyMp`KtQH(m;hm%vF{AM>l%>$V2o8PgsJqBssqE3{W>tiD@JHL^A-&y{IYaTkEg_9hGM4`*VmSuuVx*u&rIdkA`Q`LM9FlN=tUfqR;*u0xC!<}yGwFY=gdSDu7%Do# z>5bX}`|^C@n?ye;%h$!4-&S~S>}Ffj$#GZ}Ux+TZ{P@b#w?V6>9LBwAAh*~vRjtql zo+W;q$L0(uc>4g}BuUdLQ8TUHv24knM{w`_>>VUDC%q^BDO;^q>XXmsMG+q3j zJD9f+R?94hNDaodi(q>x1tUDTvXUsbB(a~Hb%)JW;TM>@!Ir!b7`?lLyp9s!sunYx zy6lr}z0Y6Tx$o_u|IK8bD$eqd#9KqlNztBiOld5}(>*G@!S6i~s&NDkRf|!p#rh~y zY>XpzI*}Xt$(SiDV)y;&{Khw@VDY&7pu4AwyknZnzZbLc=&vMUjF=ni?6!uqLsB&7 z<|4e#^6&Y!kH}Q#a@J$R_WAQoc^8dH7%Rru&CHWic3U3}rp-VDn=+etm1I0Lu?U5i zz4(h)?tzni35Zz7<=fMWDEn_FHe6NVE~!y?G9(tJISc5k!*g+9vpKG>`YANmRDqlV zd6@l%alEG~V&M-}9PR#^m@Qy@rmdTRo6$oabSY#1xEWZsR)yTny^5QeR&HKx$nX8} z4_+UA5Boj~=(@8%F_!HBm2*nCqGijVwPPW4nn_R#PbF+IR>ze#^N7JY5lS-+Mb}@2 z&(GKZ^$-ZX&i}|rDNP)nA;fcQ5^WbhxH{O?>*XH8|GBpqoi|O#`}^LBj=KHCO(#om z!PgCZv~wyH=cT}|9n8B@l!wn*4#HqTIA{9GhR)PjGRWsQ`|t*Ihd06T?Iq;Hv|;FI zXwCSv4&3!I3+s8JFmh^rLJUK$_N-5+(yQIJ_brNHp7Ni zN!rPB_by3t=&V|r85@v?+05gysFUT$_J+ZXztJ$z-A@{KYhtyH33};92)CR&O;3;e z-;Ax|pMr3E3z*cUk&#hRaHT&OuD+9^DY?mz+Wit{yY-XuRhk$z+JyaF5}fzwQQ#i; zA8dHqK}L3~;EFH~FWpQgZ7+Rbv$!ifcao;JZ_U9WMJBjjDnu0Zt{meXSZ)zE^Up6n zgVmWCP%o_F2QVkS<*zlrcU>o{vWca95=8x3J!YzAj+ z-Er1ckv{_s6;sKy`&Y5cun>JOsqo0Yw_T(Eg8Gj#a^mk#v`{R?9hItl=tL#_)xbFX zW7IN!Ix3-9k``L858$+!Kcz_{7H(eX9rQUYu{C4w)M()p)!X#8sBF-Wv0d{bx>@?5 zUXToJocSGJGS6rJB~#w=<$0L9C<4@mNYZJ{cj_@#9fw_?Exh+xgaHeRk(1oZPo94M_P)Ki%jg zXLIFILs|x1?&cCf2+K|1QNz`a4%~+ubD>ht4YFC@!J$MCU6}{(zPtr-K6V#fzA>+C zg%O{k9ROJsiLlYSjTC(OhvM5yF%^rs@}th6*DxCt*`0d-EhVJS1X%yWg}5_sSaXpY z(zjk*vinZh7U>J&>-x#?U!yQ!xHbCC+G_iG(_J)qT8KZS{rTXdF|a1695MyJi2Flj zd~&!2a{c`{xBoIhZp#C(sFS9XOq5Wa7hv4$6yf@lBjC#iZ8+e?_O#v~VI*VPA$r z8zV!HeyKoDrtdh7|G=mUi@-N%8RVLa(P<^4@X~Z6oHMhE9Mn!>_bJx#9izhcOAj$a6OPcW|I zBPDFy#rUD0=92jh1gqPNP_j#fUpZo}MPY?008$Iwhn+AE;`iNO1V+QUw#juV7@_67bs!0@KW1kAY zvwamjlZ}9Ld2OV6OE-pZDaE(VYWym#6EHSq6Ua}e?fm-8ackL8~`bpgc9po4@^Vklp^D1T-s~`3t>TM%qEKN?QXA}?+5;ghD^$FI;=Ogn_?s<3o3ZBoN+BKydXQqUqb=oK(^0U%BWJ@>!rp^7O>gH zI#9CbsAVj3R>I=gk+`|up9_yW4arKeaA7|CJHAmvZvaLNdc)x~FG)+8w`zZ=8rmJ1Eu1imV&C#&JYKSw z|1&WWrZ3J1!q|g}&(!hHNi&=~RKTr1rVB|sonXzAc5-)44~C3=k7pD8IEx$I^vUTj z^dQ@p=4UJ5+!z_WSC&T%9x7qqPR3T|9Jm(gc~C0l26G+z$*_HT*xPN1HLJ`CZ+#E9 zFDycpwbOa2qXBTUE)n_y+Q?$d9<D=ke_GXE1NT9)I3;RV?V6Fh6ti zFS7EbGRDkkffgS>Zd7+ByiI!m1r9P)E?*fn&dA~0yH6R@UK8dr9eVUTG1}`>1|F46 zkI4E;jw(FCyJC!)zr2!LY-tN;?(KxQyQFNT_H%Rs_Kj5=Hyg`=Msvh8Ih@n}!M-|P`6tw~h8HY#w1@oG^0-j;oeT0uHzu#*!%svzdGZ%Fe z>naW0{>2!!SQ6XB63+2T$SK=3z$(OzMUSvNh0u{IV;vR2BeuGImxH8W5 z)sK=?WAq7Z3-rY?o2GLO>xJ~tuf>D==j)mI5Iw31nx2=EWxq7Aq}3crfgR`GG!bNa z-C@k*&t%!TUwGgE%P{UK;~(5;1BHQlm>DKP^^}gF=<5lbYv#|@jvNKI{!E2qGX3Pt zULD-xY=#G;3yI0Rc=Xm`tl-0{eDZW>hSKP(pkwMU{su4;e;g^$Ah?Uu-2xFF0CgwdG2 ziGy7#rs}CMp`{g!)G~?K?@ORDCm4idrRn^QDr^@jhmi*-2tyK{fXlp>@OuQ~q4{Xz z(pjcBI!}^I>KqLc%*XG%u9HZ_u+FqjA@)n9kaH!zkeB2P={KZlSlk@k>}ZU>6N5!^ z9hG?AwFHlz+{z!JFCcbl1{fGi&{=d0-l=20T;~Ac_c@-_G9qN~ye*?m;mX1$fck7w z@=z83CEMchtqZwJu~%W^aDUj{D?{gG|A%4btYhMvo$y9|FPQxh!;PuZ)VF;P+IaY* z>1|8SUvdm&=Uan;Q#Z-r)$snV894b#D!Jo)9dlXkH6l%wAAMN`W4<-R)&)${SC7D0 zCtvhdP38=TGxo1Y0c~3pGR%)E;m9YN`1F)NwwW)7%%x7rU_myZUOX@pht_Vj)%y~U5pNk6x7eSLD7^zgj6WG_(MTq*>_dGaJ7a9v z%>P+Lz`FQ8*dAqbSX~)4jbw4-qZDC&mnPg9tqsxHVsu3!+f^@X1k>PeWP1Hm)MC8c z0);BhuSE!ZKI{PT!Y;CLha%bzv%qCpKSg>5eV8v%%D6^ZytQ=?cyYDRry@(IjjU!q zW!BYI@sT_1>j*Y3OF@ZcI_f6qqpqPL3fEPU#_uefcDx8nlU4Z^qqT75Q845&4Q0+} zIW$XRzOq#nwhLlgsB>fP;2bU&s$-Um1m>2OlLGTGe+*%GEy+~88&ZW`3`Z`OENbEzF&!lGWw4+?3;rY<-WLi${(R%t2-EcumT^( zRo<|~2`3+#iCqZ^ByvhMK9euO{)6WHuvzC}(U6O9bv)yac8$S<-;9_B`qAdYz*9_E zRD^2;$9R3O2N1rf7^Y{mkbl-g(Ph3JdTtoT4Lm`3`TjPPip$YkW6oiofj=4@p1{#% zV!*#`r5*dfli3OK=($c2$LME~L$BsQ(&dd1aK4v3a#qC;3e&NwPMK7*4w{nSLJZt7 zo!=wb4;^eK=l+nRoN*-HS?q_#pZz&{d?iFDEr5hl3999D3_UJ+O4NO?b^uf?jKB#vkUbtm~uGQ~FlOmh2 z7D{kY!DfEFN(N}hB!juQ6qWjT6z!W%Aemyw<=AsHamQjhpK$s9k*L*GVITDhmsLr*t6e+8zM^Z!KQM4mv#r7d|eNuUV?tye+0?N<9NH> zk5hOy3g)l<-+ca2p^c3j*m$MIR=yjx%;odnEQDGhrmlSlngvIb|3Bt0@9rua1T>HjFuGHVU;l z3tWHiyzthxFlu!_VQ|l^=KBIJ?P&({o9V=SY(KiQ`TtwbnpY^i4Cgh2VcH34s<}-G zO_s{w&I{v&AM>BW=}|9X$v7c*6ybB{6eVPMG5L$0+95A?fFYykvT6}A2PMYMu|n-nBplFT_a`*_rvEDkk4-2FHJuM0VBGDB&AU|4fId3s?0!?Q{;tInS*Zs?}`?P_Y;-bVC)G8UPk48oYV5MP}L;z!yUqhi&v9u1yCXc45dN6{0E>SW z;(<8M!lwtL854g=}lE+s`+y~8d!v5 z*xy~%aUC37A3W&U_?68VM`uj%5?0ur>S&>s@McgGd?z^sx9LgX==l|-wV?)AvTit= zh3fn`auCi44zrmfPTluC$J7%=D1K`OKi@4Bu0M;1dpEmDiWKYhd%}8-rX>npyw^hE z4l9_=`1vZ=m!MUUB`QWdB3~10@a8}s5mOY9Ei)zgdpH?UT)D z=jT|rj`fUxJH~%H^$-k37K7dNReQjVbdLOt0iV6+3|a^o=0*y_Zy;&_?rf zwphiFB$>fC(fcgZ1bzEopLVO#G7zDyu*&gycT^lb}+2Y9X$F>{R-$eH{tV^OJ zlwaYo3guE~;N!&iqM?iapcwN$t;pWO&#%sayW^9=TVINr#T`TM&f}P=Ysfu!;b@K8 zqCrjY3QPAKd#DR7YGQxdO!A!7am_;E@pny$zZT4i;D z^V528c9Ept1im=_sV_PlI>{*>9}V9IrhvnOesbub4lXX5F}Ulvn*RWG&5BUoO^r{_ zbOml>IGDw^lMOmzS$nff(OjUxU(oV}51|_&LRp$dzOcg`*DX+gma5486w``t6yuF! z9{hh7&cc`WtMGKW7~M8%6sj}5Y*p_$pr}CW&O%1 zMakhd{H)|F(C{k=w9BNaqxT#vv!01z@mqw?qn^Qot68wEa)7v{KgU0XMd)?xGN)HI z2F9OsfL84;a`NgBYj;^a1s4;WV3ONw;>UO)dn6hA zB4Gg+JC^#hFFh+R^d*K4%0Lac0Lmdejs%Nwh>u33)`BY0TDt;_z z%3DKxX*Zd=c?jWMzp;Jop|JX<0|KN%hrD(Z)2)|uN z4iA>fp+m2HhFH)`Toh7_PAg3Lm8-*HW=aesDh&`%ekA@Xn~9>P+d|&p4%>}=81!;1 zJaPs9&GA8(4@^TJ*Mxm_Y*xRp;CmlL!Ev>4I9|zEhzkTLl#oNO;+aB;CogedYBAo6 zIl!lFO@{J}JotF2n<#D7#2JN*OMgg_OKKej23kwtx^4$qy6TuF#tj%*6w>tO(SL){m<5lc|_)F2P9ZLA~r!=-pIJ5mE^E)tYE~w0m zKQVa^7*6wrc@xE`aqDwTV)t3`0SV!^2KFv+DME?+0sMc@?t<^vatJ%#MBXnD%d*jU zkBPop`F%$z+;O`P8*^l6nVbU#Fy6@P#BSzk(SjL2nP+7z+xL#If`80Ec|q`%;Cwc# ze@r#uRTzik?Dcr4G3_B2{Z(**wk2-e{6M%gWG>c@o{n*@apX?o1vs(e0?c9FOT#6;lufI!NlSczw!2twNa}H3bny`!|5gOc;#$dU^I>QQJZ6ax;~t-R$u#QQ@XA+? zjvamhiv|8zA2*ScaTABbt6Qkyo9{%!MIMJ~GoPd*5XmnGaP1pEEZrN-Jv#RvjM}>a z_LcRLJHvFa=dTSm8M00>atqhpD#Q)@jrq+YF*ILT3Ryk!bhUdkc8)2X`+bSl)ceuvCovT!fp%uW)v3rU^71plp5@`MpR1FEDS9 z;;(z8R8IhZ4%bqjuOZ~Vh<(Qvvo21F5Ydr}&urgbf=id};3eDBVb6_p7|ODZ73N+T z93FtiQ(p^XJNDA$5KNanWZ%QxFJV?-6I{%HP0p}BLDS_zd`K5_ul)p|sr{K=OWRId zwU*+N5KH`_wm=w|)DICh{b0m0gE{{l!Kb4FQK80$yB$4_J$Eyqa!wB!#&Qiq#mreJ zJs|@>Z(+)ZLVVw)#s@xZ#$2|~Z|xYuyImCE)Kvn!-zk@|??*On31a7mMpORC$_Vg$ z6ayA-S(c$dhrPRP(ed9Mp+)f>s{7^r;O^pRxd4Vd_)OD8dqn)ZX4Y>|ijX~%Z;W7^ z%%5Q}&xFmfdIiSPP(Yc{obbTgYy`H)XdHf!x80rsJ$v&YSE7gAk+m`St2Nr~R_1sd z4XLq?&|}>}-o}e(m6n!br*a@iXZFw&`Jbq9Rx2r7se%Ldr15U$Tk=7#6pP-lPHK@l z|4eHU46}EJWgY$GK%^eJ>zUw$ktSpVJVN29BD@ndgI}x{1YwW>iY#|8cqE=BdR2;6 z=Rb1KD%Zg6pR=IxrWEx_RK*QdGWfCGmA$V^aZe)KX`T7q)`C>f0*OaC4*$#MroE09K(k*;e zuLXCCM}klwPW?h^;8i$de@XlxBRf)YHoJ>C&aL6buD1i1zU?qvmGP)qKFFiW1c!xw z7o~Gzcz;SQEV(J5+WlYfC-YfN*;B#YF|`>i2}ZfK(F~=W!LzaY{2}-?R1Ej8DJK)vzhaqL z2@c&fgb%yo1!H#|g4{_G)cfcJRPLRQheDT=$f2y8CWz&@vrYIXL(V{|dpwLf$9iLH z)NsXHD=hGQBs3Z)0ON*gs=M|kIZPw5NuB8tLCs_-e8GFaST1RsCBJIJMerVS0WRK= zpx^t(xk{Nn_ekX8gTliJ9`{i@i~YcaS(zOOETn!IYd zqs)f17@bGoWxi;vGl8?cAO@37|4?%08}S+~0L z8(7CyAK9p;i&fb+=DWxrVuaR*8$TnW`p9rL5l3*{}4`|MpN4sHi zxP6^Sc&C-8zrQXRoX@)wi=ljG6GVA@BwM!)#}PTExF^kyo1QfdHs`wo>oXw+ljT4s zs+PX0d~dVnP769`mEhJHmHe|wJrHxV9t`J8(W_mhD5g__pEg!WlAj#ou?zLHS>d||80OZ zYo#e4GaGe2m}A-tRZ$X~4H^&Gvv0nepFQOqO!B%4sjtN7%EJ-#;@(Gtd*=NgQ{hN& z6SVDSUXH19;CQ8$u3kP@=shDE)SQCg%@W3^y2Y4mm!+{d$UwN_M=jqquy7`63G z!!=Ee6&!GdTe)c*42zrt#~9x@u~8l88CavbOA?8HB?}<7(UR2>E9>7p>zAF>6+^ zDB{Fdd~~%0W9)bGiA@=h?T`-V{*$EJqYmSOMgFMOoGm=4w~uLRL4!NzheKaMVBOe3C|)gMG|HetC~NKjOFm^pDigh1~_B=p(JT|9B~`yQaZUWx4pV zWwQ9LSuSIY%WK@nGPb%G%=pwDEb}LdfuPl5)XZZ9nlVoJn>#mz3tq(0ci!*mzUQpV z+gkt?Cu(S!=Wdade=Ft&l;YX|YsLk=45hc(9%Qc+O>UOQE$NKeJH}SHao%gzX<3Y$ zWe@RMx1Yf9O?j~MMGq-jIRck{H^X2jdCosp9}FBE8B?Z%Op=#_l$AAfywz!2&+9#O zXjBE2-_%MJ%2ZHcx-^E>za@Hc@6orU7=z{x;s2~&411KEAtY>ojDN8i%NF`#*JEE| zDV4~&zgTDG7!%%PTrfN=NPz3lJII$@0qX&*rm9(AY;{@hT#(r;@K2PY<_Biuj%+h5 zoqLh=JbRA|*?AyhjRjx8?T0<}#giyP9NLepS_mBRDNyADodR-XTcS{?t>>mkBr-@UE zF`pSzx)I{v{vcrs((zd?J2y(!a=+v3q2l9q$h+N5lv9*31WZxj_)}D1B?qs!)zBBY zMZ(xA;;1;I7LtvaR%QGRKMyIvUEeCWmGhUwDc%Xn{KVVRycB4V@i z8}fau3nOm`pCfS;6owyy`THd3nS<%L>uM1WY+`=7nlmt<7Z2CN8!Ddvk*zFGvX8Es_c5ml^vY>s35mAUtl0?5#>l5ez-S(S8t2l8m z^ZP>s^Xo{RuRO}JGl|}GO3qxE2ao;N!;-aqBrQ!B9WDMhpGD(hu`8Kni;mCWx62E_ zV`3E@CZkU3W+-FM!4CMavrl+X)&(RT8H1i<{frZ4G0vY5<2+9h6R#ZXSy+sYN<(<@ zFFWDB2b<3(y~O6+2sHX)iYhPSZ4J9(P{FH^`3cVO!R(BeJ->=p+6HFMU8;=JA9aBE z#UL(Bg@VkMB)F#{O|N(;pdv4a=jIZj$NgD!zS;lgbKd$=SnkyXo=#;%^L`?FZ7o7g z{V!aMk1Z&h?u883PO>OK02lvM(Wf@0HVgK(;fD{bcW_b_AJp6n2V&|WGGB^TpZtI_ zQ%i8IO%*3zGzKn~PlkA%0fPJfKhMSHbKzSO5}Sx+Y^QXZs`GP)t%Z^M!=P2MgY*;# zpl@q69hIsre3sw`^S#%DaGx}-f1-+);-xXrrX;gq)Cblr&zNJzd-xT9&OxxzRjBF| zqceK-a4b8kU(<;ct{#7uu9AB+*cBURmkw&ff3tgHIg~bQ&QtyV+!MVN8Rsapht7!B>PtggM zCn`SF0quS+oU`T?IJqK>oxi21yo&<9nJS0z3bw+m(j1g!KF<>}hk3Q!r?AE@4_2*Y z9fFTE(O`x-{?{hYjr=$UdKNjt2Se5|ktTp{hiYn(9ct?%+e2MK%IUPTEhOJu6=lt& zvCXW2aOofL;#$_zS}}w#k6a8{bTvHj86e4*w_xlMUz{P~M`o8K;+e~=XXmL2fAelI zXi6nQrm&NIH4{Mko+|1c{n@rG*B!q7;lbjb6uq~2A{3R@{>B z7=8fuhxtHfff&``Mx(<56Rc=oZ)^RE^%*f1Qt;nEUP|%-815>E_Qv0&VW9vfM^(|K zb^C?cce8+=iH89yOUJrL;2P&ZmY+A_yk2U<xg?ZXf zrq*(IEN6p*_73Lr>0!?c^H-l`=ct)KMLS*!pm=39b?z(_PUsd#*Eyfze7hW-_qq;? zY)Y}qu9EXRwj4?foZxG)IBO+W!134AadlZbaf#UkZ8bsQF{Fz)8VyCm1RES)^27FA zMLYeuJiUnr4S)=FfzN8UhH5`$TIu+#o}aC^ObXJ1iQyjhyWGhSDti z-z;gxXT6953CHuG`Ga}sGc#~^IOEff_Th6`XF`-=5q#@tBeFX*@m4&KIg^KT#RdY1 zdHIRDe6}W|*k^XJ&m48{rZDV>1jLN_OZ^>w5EXX?#`F^4%QQ-c-I@>W!`8#cq&{-i zY8Ae3_Qu?(C1i^09ZbzA#Qjnxyhpbz^d9>}Jww&VE0&3Yz}1+=>-z&CEQhVYJVyGV7a(mHq!K@fg&y!lfzrrh|r>L z7Cj<6e~{svt@Z(SCp1BtQ90Q^hk1r~nKBK)o|D}rgn^hn@be(^FaWy?WU{#-QEGF< zsskr~X6MF{)%?Nse$f9^5B|HP=_$1`yv6QK>(r__<h(Y}K1E%o>E9p%iIt9lhS&ljgYs>$g6BpX!+MsqmgiGM z=EGTjQ~0~+E`9W|WYBB3eVPF33O~_=01r`lp)y*$X@}jpF5HoVE8x(72Exmws4>&L z4sR3S_vE+9!y(~W08=f<^&;AH~bc>#W!bKZw&BBv# z3Ddq+olo*X&mY3O-(|4O_YYZFDggh4PgLdBexc3#m&|u`51v=ZQq9@(@y#JijM3^9 z)_>H2>&G?W3)^Efwu<4OThf?TAW3)0i%^yA^LGb*=FS$+fjuL(!xYCJlIx?28$C>M z!!+id{w08L@`?72DHLXNk~r*IEfj>y(;vz|Q9r%}|4gpp=FD0N4ZvX<4gts}e1#B$Y+&1kZ3qFs)C7*?ulJLuR=jsmnYD@MYpI_k2 zIw=DBAiKScj2re7-)&&s4JJeR&xXh0$GEoZaZ3?IFCL~hKf!@Z@2sQ1W{Z`pAPp0}Ta z?JAPAd)8sJW?bUwm-TFS>WgsI|B-Ya{#3v3AGe)jlZ;Xtq#fCnbKdWU7Nxz@o}bd5 z5*ZauEh+6?6w<_fUl$DxTV_ZlE3|FD>+AOid_2yl^FG)6zOUEo^?Y3>KHy1T@mEqb zys1rxYs>zy<>UqJMbGC=RbAo05(!*6QNY*S8$oPICAc{FJGY+nm2FPez>tS(=pbWk z#(Ou~g)Rp3fo-hUtQdSn_X69#_gMMy8#pg19Y+V-iF~949xf{2gE#22X<-ehx;h)D zTNeo}Y4btNd^{Z8sm$x2XyM{;37%;g$uzgVMafR$w)Hg>9fQ3ga!KfD zK77u^4*y2VrCcbF{|=Gg^V#vZuINSmj3?i^3OOMHBu&`}{+a(+ZHfeDJJa*FBg>^` zKm#tPe1w5@iFjqO0zUAqgjMmXe9Gl~{BL9ymRA-FIj)xQrm;WF32J9GrRI2jj5T)E zOJ!O%F{t82tl(RnM1y@x!0N|g$S42L776t^Milb?re<=ZG=DIpO#5ugQY~k$*jJ67 z$=-U2fp+47;-Q=v zp8q>nm%NjJo~)2JcOENO-*EwSSMG;;4caA+9!DH;2VB;)T)y$_b0B*>glp38hJv>=jvwnH{kN}I|M9z z!)gjUV`9c|JZwEl__0$0R!>NE;_FD1LzS@|w z*Z@xs@fF^`IRT@7UV(q#6?lGY7xe4zfRCqMl5Z%!#hb2Wb!dV~k0fxpOCi7YYJKA9 z<>%n>!NcHGtHM)OYhj4H1igpI9aect zg}VzaVbaLSU^D3->*g+nK5B)0yhn)a_?c!tvL%Pu6+hVbbn0kuS4N#_@7dpF1?We< zta7!^V)5FkQ2k&wq>duaNnjr=LkG0da%R%{7`!$+1M@2E#dm6lASfydPJ}hEvF|0| z+^2x|EGd=k-Ms`(9Ti~T0Ln)jO~z+2!#mE*-=-H}j|%eNdJPkwzt|3CdV68}PX*pL zq!$jFF%)mCTq4_66hr4j;sU)65;JNep`ttwvU}IFR$VEa@-ETbf5 z24V&Oo`8ctJL22wCb{4E?vR>q0(q4Ezc5J=`{=9Uec~wEdoj%Voq@R?Wx{gpaWJZE zH5|+#b~Noe!oS#H%9yW-`V|tW?_0n}1*gfYbX0J{ic(nAuE9MLE73773%3{)3z>Un zLsYW|q;^x{9(vliq? zJEK)zD-7sWK>Z_?Xb_Nv5yhRwtSvt9X8cw#Emz{UceU{nY0Mk{S+lK|7>2*2IXS^m z3?f}))RtSYbx#CH%@*bR|2mS^E=MZ@+C9SNW&h}eIwb|X=mxRdIAiW zEAxgK66~Wx{baYJTzrl&tb0OxDosDptStuaeMtwI;a~P?wE-@+alk&xx`Op%2@DR& z=gHwCm}Y1bemXwCHp-JPw>Q>iC@`ZgSY zmOqd+Mcu?MlttCwb3}A{DuFde@_9pCK*A&ECj3brs+N{@qPJ!ed|mZ`?(?d=WQhiD zSfPq7HP7YB-N*1~p9vlQ=d!jus0{rM=XMmZu*I?XlAiO?oxcd~DWoG?Y=lKKsBctN z3RBe!c+!Y0m&dh@)cZrZur8%yl%R-bQ!AmzIyJ5|rjYn{S@6Ix%cjW_zi#KPvHST% zRN|rU-a=#UcW{@yWf#p1als@fv@V|@gr1|h>X}cS*ejWvq9VR})BvxdRk&M>Hdax_ zq{uW&zV}H#$Vztx%fl_Ks@4p<_i@B_Wn{xNZsE-?8RSbd6ql7r;Cotr$9!J)p$SXV zv$4}yV{z>eUFyNqz!8IV;_pAurY=N!p5N@H0d^Alhg|`0T}9rlt|ty?8G-#XZ^+%x z-R23}|39mrCjRd(pU)Q!Sf9A+WfOXkFHX#qi~Bv!gUjN>q*JJJYb$LWt}j7Jh)f^&-HQ?KabUE(X_r{I454VKx+3|id>9(0-vmtOs2v%RF?_@JO; zZa29$^X1k#yx>YbYrCn3g*i(2yZ9YDb+8bxT%tYO<<8>cNz=gBU=G~5rodeXS)ekr z#jv3c>`xd5br;l&$+u?L+WugszrxEm> z<}6Kt5vuF-KAWOECa z`n9sm=>}L;Xot+@j$GeL3V+Et{lByHrGOc@y51J2^@wCHYT;n+a{|0VskfT${iUgz z*u6T+VToBjzoFv7!n|5Y zOU=f!hKGe84T?}3Qpp>9KC?g6E0k2GhJ6b;+rNz129x#CE2XQ@&1^EX$ri(d9_`F2 zrUxz}&hVwLrp#0KHZJ)^Jt@)l;^RJ2SVf;%@2oz1GOY!5uVurL|m;K>sPAjYCJ#fw3VdN>fFB=qe3p2*2 zyVew|h2rsa-GLCI4@_{R3cw)%XX>Qk|f)P-Y~Tdv6=V zN9-Hlp)Dqb7r<2Z9a1J1GPB}`cmDOqgqD7__hr&BCmnvj+H{vpFHl;Im_kI z$!0WGp$zh`Qt^5}CEWPA5}N+0@o(>nuz+;xT~Vb%%$q)N+`d0FNEG<1TRrhb`Vc&t zmda!q5Apu_4BUU+P@G%33|?+H3`~J`LnTnSqR62PVl!XcRP01yHq#~ zBky;FPdq!fObSlD^SOJmtGvAAA}n|w1PNQzd3xD+6qXQ|Z}kd!OiBV+M**R zfWwHh_pVO_aYFh*VcBSyRMyD)&~v`xQQD_n9ugV6lTo)&+I!KwRSAL*U+8=rQme^SW(_ZV8UqGh>3# zW1$opP4YYT)z=hM(1x_deY4fM%GLfb@}x7&Zf{{$tGZ+JWk+1vIf*Hbxs7)z3*7&f zp*VB46tZ>mdBKYJiSnB*xTTsrlRu5cGuO27^A&ZxGgK?y?Qtre`jv@)emjc;=$_Iy z^a_ZSQ*iL;fl0Z}*zSK#?zZg?SGb?q;frotDTUC!`Fuw7`o#W^T2PJj<4P37>W1^6 zBsmPeTU5F0F)f@Bu7>X|T;#U*Q*jDu{a#mhi;o9BgR#5bfam@;c4QFs3aMveuOXL( zyP_2&JedSDRT|jm1Sx#Dm&a!)g~(bvweYoDvv|ztdbX^WKH9!l#G3){*vvy8QGq-_ z={829(Yfi6&@>DDVifpN^FBB=-xkNYII_aPI1JsMfj*rb#my0i!NVyE3??5 zM3ySA&~LOF4yIjSx-;T_>LyrI{aF~&I37~U zSHUo$g-v}$d2RAtRNgF4%nOmi_Fj1%vpTR@73)Gup^Kvy*SGzSyebPnHkAl&3UlG^ znaS{V0BLhyH1Q323XkVJVX-ENWtG$g+_kg#`@vc$&)pC4j~dw~|L*wf-AHU7`9t>O zSOfP^PU_fEPgBsxad&?LIAyYaR^Rd03F$@# z4%3m|rPN#G=Oq3$3x!ncTQF=)8?!xXjKf=Ktcc7tt1v z4vA#H_I$@hv{OBFSSDtrhr?UP6Y!1pKQ%q1SpQc8+qOoz+?|4GUqpWIAAaH)l{h%N zFdhD@_{-`~8{(+h4yaS3D|7-W?C+D;F}FJjZFr1lV_f86!Nf=z7r!IclWIj+MmeRydR6e!oiWTA+49{dP3;xceT=2zjrhob=dZ6HQc z1FQHWh4nl0cy>sZ%bEVln66O;NvG8Lg4M-nvX^>Hj(-yT`dPuY75yOkSv%YLtQR^Z z4#Dlq(%7TkkFe|Q3=HhqS#+MX0=`Z@3^#WDW1+vLFk^cjS19Q!ZyXi~E)5Gi&e-Tb z7O%J4VDLQML_=vY9_URzz~5WN@-Jr~@cUW#XsEwL13J$&U0$V;~y(K9LJW+EAJio&-0pM!x3=^zd zncE9<+)zn;o`xh==6werIg&rEb7yf}Ck+U=na5{-f1hX=(1tr2vvKSN6LG+7P4xFu z!R&3)_#4DWA48hH!{uS(U#rvL*8d6&-LJ@Fr9E(K2Fe=R*!aDVFo5<;Gap_SG9CNE_4SirwPyp9cxr$}*E~LPREX?TUNaAT zk-^>P)G;HAP8fSn32(-xvOV2PP}iQk=x8KfJ2(U4*35#zr16dNw!}vjHW-_4&sOC< z!uR_!@I$1d*fi@1Y$%C@fPhAJqPqr!U&-Zewx48^_AiIt-Q>_nd$t!}CZTeqBYE(` z*+sCcKCsO^(S}u1F-Xb5f;5GQXxB=?X5^mxZipPHYq0b^)LC2#9dH;+-dPb37|E+@d z66*D9SLKIKC1HAZ;{M$78 zUutL+S_;!MwD_I6T6Ad4!tK?iLi&(-uzB=kn7)a67N%a=9Qd;dcQI-WT3O?t8)T^jBY{F=Qj54wHca7 z<#-|Qp}gpb25c_K<=;DBVk=h6#KFCXqE+@irq^1F8Bek>x364uj64T36i>k3E-GC1 ziae#)rPym_q>ENe63#Bkz`maQL$XmThRcgc-%;Qnh6mC9 z|14H&?PV?d@1l}o2EKUdAa2>G0p_oAdH4teW~Q!?7@2*_;}7p7UY?Mve-WUp^Z5ldyMInznI`QR=#@XT|AeZjx+G6 z*mgz(A}ezFwGDv@^Io>&9sg|99Jo;&AO8aC2i}J%8`XGbvnwtyAC9|IRE2k*uKe!h zu^l>N-ItHhwc$IQswra6_C3axK=+yx<-$kHF%amu0bI8>vTnf|pp%u$KNn=VOm$L0 zwJ}vNP>^tC!&2m7S!lYiOc-j`7yb?G2NuN09hlr3r(Pa{@wI7;uYZi8cZlP0y0aMj zawY7sI}DfF|FNm@8Zf#iovEgoQ3N6gem+|W!IZK6Fm60%PZ^4ygY^;zUMWG5d?sNP z+eD2kVGwinEEtKDdGy+e-*_PIe^4x!zB|cZb-L5xss8ae3GVEy1+zVg%yQ9XNHYwA zHMQ#e!OIEQ?V2qXw=S12uVIkd8=zvK64xJ?jCM;hQG4Fbo|h2#ftaVVGQMcrcBu^I%*_Ca`&eYqNmDj zbtU+(T7tn-r^)MbckwpAAU-lriT5+l06+CQurGPfEK-cI?1vLpPj(mflxjf4oIE}! zWHrmVWcMP`I*NDs~wW%RWx&d_YCgbzmC0g?S#%dl~CtyDvO<6iV^wLS-;v?9JX^N zIOoiQKla4u8Dxo;mNt0I)t-4jd5rmO^jx_)iDN$?+I6g_zs9$xDr{+a9zb1L`1viFKSp~?zB8rtCk z^_8-?u*bN+fO3h44v2`+Feoe!TvdLujdTV$Lp+oJc|88Se+?^hZ@{)M65hkQ7Dv&& zPxa+-p=x6fkna2c`MhR`Dh8;l;bb#4?irMfT1mvGI`~z{iI@nN;#a{qNh|xNZh-G< zZE)l2Z;AFy1ClNCxNbnYJnNb|x~}{LE4FI$GShmrjLXIqrJn@dWAngz#$-5rN{J5` zp@~M+`O($-F`KkH89!akB!0b-xFdKS+<^VCY)Xz!t?eGP??j*Qts8`Ihvm)b4^5@jeam6H-Y{}W&V`*XYO^Bfl}+wW@Kukx|I3} zt_KRH^(P>z;wDU8(ax5pbjE&;_UNd2PhQ_;4P4Q%hrK0g{BF-#n7qpd6|3(t$IrFc znfT|o_Q=HQwdbKIG88_$sqm-d^Rz6W^UQ(!E_GHfu$owN8io7BuNIGCU~w88A?++l z-vs+MIijzofiP>7CcIge%jav$*l{hzB=hgt7}2i{jhL_A8s9VNU)eb73|tP!O?_fROu6(kV9Fv`Y7i1?jH8kp)Qy?j^e*Pny`)K z^4_HeOutYhN#h(hIKecOh{yf9T+24K*yu8p$>hcjWqex=Yp>iL1)D zg0y}gF&^7k^Oqoe*X1luF4dPWIe!oPk$x(5JSP5|stJF*b2)z%n2`2HA?YG<4Au|Y zBz~xV3CCKaU{H=4zmo6?r$*89Irfb3@tZ5}`qH(dC+pyW5^&V11v~1moSgFn|Gv(^ zhaTUAHa%A`yW|C%k2W&xF`BSpWiEGFp6xPVzA8$uRKYz3Dc5=O35`j2wp#mH2uth> ze=hfhj{_9=?WGp@Kz|61`|Pr$!_Z7_G6UgG;{pU`k3aa{jy7xR{#g|rE0VHlksYRq?|>`5So z&M%R_UV4g$9J$>wt6S&22G@fyE<~w19 zwHU8XY`=kYHwo1pA+B0;2JQ%#p@z#iY-~ zJBpn*N=)o~k$Sie!A4!;`7G7Nd0W+RrG{LdHIDipEV8IG(MMGENPr{fQ$V-6ojvLM z6fav5+Yqk^HDCKdONcw{e%3&ob}hI*m+pP{56Nz1wD8PxX*~RME!#5J0I&8X4Ryvl z=ImXD9&70QEHM!y>}SJHqgkLwKH)w7Pcbfx@>69_qSEAJaO!m=jHTRV%y=ybFU#fY zeLu_WoF#DWdI>*S9>JCkqKr}(Yn(gl6g#k{3`<<8lg>saHgxuZx=3&MQm@E$#cepp zdmrk}yd|qz^AtO;$v|n-0a3vx7S43agU1(tvh5aHuiN2WEozBeBJs~yA2=3(*d$zY4I?bVXt(-jkdtPGSv6;k_EEg_!a)${ASHgwP zt?cH6?)cPOhQ@6TiC#}Np}6QnhwrX`7YQ_vFX1n3wW;I&C!Xt;jr)trgn1S7!Jy3@ z!p@U-=!^zNKa-+|Z5*56`4XQ|4)b=jk+|-n7kqWv4~suGu`&OdVeNns=%HUNlZQ2N z#}&L|zwu#>1Twto@9QTguDbgZ-J9r{urw95I_-mK*(TU@lQ_U2#hGyug<0;E+@-jjtsSb10kc%mWDl@!hq5uK zHWN>|eHE-ciAPR6&n8N|%r;$$J$~)QTFsg4vQ8B4Ga~J*!ci>NCf?QNOn6zX%Nyx4 z|7TUoE$wP$!8S|5f2%9_yiwt~)5f5jIg(xw#M=MM#v;Ol{6_Gfzg7m}($HZ0S|9RQ3l$W~t%01XCsNWq07n{`hja8q~0JHFR z`5B@2>2bWX?${0u@!Zf)V9>V~mK-i-{f9ln*s=_CvZxTEMvnzwPcImzN_qU*YWOIw z3M|8MD7cPXIkua@bBxjQIz5;FPugc*Ah4Fz?bJFuFeqdaZ6|MJ}eKmpb8)U(qZ(_aM{| zPd+VG!kfY*u=;fgx7%u;uyNEeRFQh)o;&*Dsy{Cvdd3s**+XZ=MlDP%*F<-(Ir5XA zyy-d+$en9x4=_9n^7Lxq@}yMOY8Qp4N7KIjR;3^xbR80}?14GGHF&ofQn=hw%2mo0 zWD`!RqwU@nu(6TyDLehJ+}jr&j<^Ut+Xul6B`0XNXk$uax})2op-4zVmOds5-;vHM zAsxr;vpKHu{{sy{HEh`^DTI}j^3g+k%iBwJFji9)BaUmv7vyK-=V4ix`F?~r$SMrN zDlWnBH;Vj^Wh7T>PwU7S`Z-Hsd0Hvo@qLo~PWnZ#3lD)XTbj3rb#dc8Rjj%qldsRD z=iD|6^L+M-H`XUYTLbAHOi0?)k=W#bK&eU!Md>vsHS zwhzayz9sXgo)>#x>K)#CP?Ux}gusuvkZt^nb=oX}S#yf{vlC8C8h#QtoBLtx0y`mk zKrhg9G6E~|tv$X)`@cFByiZ(|M`qiwVv8R>9DPJkbe;r_Ls!CNU+Q6*(;aWwyI>#9 zhD58M>Y%mxBVTq^i(M3dqiX+b{F?b$2pqBy`X;zTcj`p`c1Z)br%G`6#fPl8p0- z8@v1^W)3qIB@z3;@$g2t^+K7u6=`74JPE3m^kawfweiM3L#%rcAY|pA0^f%>VZlrV zuH|fu_dM;epX{FeeDYe*eq;;zUDUbx014FkeB|qI%t=%-r8|*zD72E7(t|R6`UVno z7#`{3sP!64J7?mocmCqTZBOCi(KHAlUVVFaV>~NRPZsTjOHZf5>>UxX&OwV0Ccl|f zt(Y%bbXvAfQyrd;sp9@v!4}@v#cxHVuLJ_?ZSVnCk(ZKNlnZ}OPlu7bEQqV;h&kpDWG}7n;{eJR6j&Y? z6H6qJaIKhks@N-E8vPpj8Ad^gojUJHy%l|}vhcn%Oo$sho(Ilz?UN)l3faXghwAderqsV=cKdlAoG5@NoAT#il;Mffs48}z~{Um6NbPNO($3(rT3<;IWaeeB9n0T^W=TJv5uare@0?KwmCky^$WJ7 zSF_qQdZ&aGbN`{enGH4dfp_rCGxB2Tzha#9x9vYeV4ZF}gDvj76ED6D|UO`P_Mw1CkN%+SylpGMB-l z->+fxQU(6x^K-oHnu!ZPUKO-{3;;7Dcj$MakxhKk!u^8Z^Sh9ntSU7MI5qfNz8J?B8brWr77iy}w<9R18QF`>sWF}Y7D^q3X}%Hb{SYIovecMVLTra2N6(Kl{b<%=J;?@{#m8A7Ms;Is`Nq@z|@5Y;S++ zXSwtjg8#cG|FNMLY4{}z(Yb?YEYeyR>3FN^rq=~~RrNC$iG`3r|OsR(^`EQE89+(E9U%)ejLz~h%C zq+LE_$uY0-bu#tarWlJi0%%5B?uUhx5uUP)&cHPz@O@5=>{oU(e|tQ!BbV)EO5T{X zLN4>e#GXOKa@_X^V&4xHQhNBqp|lN<{ZW~ZYtlraMS>r1^k?~M^gillh!Z^ngxGJV z;ZN*M_z|zby=#oIA2En}O}i(*R{kGM8)HlTBI^9wN(t;DZ~5NUa}t-Iy8xC~k9W-2 zu9R!j-z-7x8Bs1ND^d_8)VpmLAP$Xv2Hv~VpjT8QLzON#VYLG)cQO!G&Ps!y<>%qa z94(%>SOULB74fCnr(_=XYA|BRw+?1es;M42PfnNQa)z<{VGt5*5Jl*<>;GB zEd8P7!T{p|P`us>#zhcMz)1_23^%~L>+Uo6@_2NmEVJJ=W3e^hKiH*v2u6KuU{i-m zVBWt%USzVLxH>v0oA?KO_opNT$;7#a@Sff*O|#FmIxFk<3k&`DI~nF*R`2oh}2o+%%8!iUdH4CvU|&OY)1 z)^DhVJvC`;_}2%x#4iJXO{^9!MBf0z@!k-BM}t>oNWiSIi0@e3?jk=c!F7dAaD=$8 zhUR%V+n2n8-6MqiX4YVJ+Y$cFZD;)}%<<<#8?1KcY+m&PVh?0sqPMX)rM@R782y1w z6KYu_<$rxi*d&z$ld*JRjax{E0AwKJOF1F9iLN1euyNl04*|tj%Fj0wj8rl<2 z^|rJ}o$ii^?aX_@;_ke3XDp^CQ=AbeFq7ybQx!L!glSFzp#* zv3-{#PROFh%s;tkJu3@uB>0LJF&s|Qylqcc;7y|w(0gVkj#+n2IM{U%d{=QNZ($P~ zdEp-BDDA_mYX=C|Y})wQDepSYu>&7s&=*tD`srNIGn@e@ z?h+^G^&5-`AdXye0dqZ*fLr1-FpCWncbq!`N-9xsb8#!X|3^EicTx^sSn@@%UoHVV z>q6Svo@Xr!JaE}b(tXCAWx<7Ca9ua*aa%4EgWG*UQP>T~=`M3OUNlw8Pueb>VYHWefZ4(o@L*6I<0a8}_z?N? z`vhCU~PKwYJU4b(P8U6~!$_xUVS3~T19$_czFU5U>eN4u1R1$?a&CXT=6 z53lq#K-(W>?qft9)4e5l&#pf!RMNr0`kk<})L$?urM|wiH=$Hdk?($Nf|4*>H1xkG z-xahDW^WwYF?-z~(C?c5or$uP7%}Z4Ja#<}v(#1jiDXSw$X3Um{i0mV>)zm_zL{A3 zEI=HT_8iuVX^?Bv#I)i}aKI^Bv>Bl%JhDlLX{*k|?IT)Thcd-0D+~DYBd26r$Ekz+ z@^3uv#W!}oO&4<~D&xHv&e~h@aA-*;>PCMPmekLLWoH(GO}hd&&3l8zc_ldJUpyO6 zoi8DzeV9Z$i$&p@Xp0#@84w=)MFQplg}mqF8d=brV@#Z{x9G@D< z+`H!E^%lw=I+=a?1LXu6nK}4p2+SF#pRy&WUpUE;}L!G{2PXf<8roR@{nQp zc5`*&@SC)g=~>91>iEdt9(V(X93nyMvO0IxpMd|#op5`ks<7<#cy8S^s$)+ZRY$v- zG;JJPpvrqsOGI6IPlfwb2@5YzfW!&wL2A;>Za?0IyXTHT#l9}`SOY0oq!#k?LcRQ& zREp=9S3zrMO-@DDIEwsQrP|+w{r3jICR@4J@h0v=c%#GD?xqki2GwCJUuxUJ|LYSHda_Gz~m8+0Cqb_;{` z6O_4y38!@<`OS?~yU)vEF<#Q6H$oqChA zX2@5z`*4&7bmTs^^v;8e0kvRrBb_HQT-$b{1+-UR44~TMBvI zvo@FO@2H=4Mc2_IEHvm z8Q4~DEaoIz;DY1-U{%HsmN!HSWi5rg@3Wrrj78LdQD%pqs^#&g4&-Cr3YvAzGEpfw z90D{h!Pccp-0F5BHm}IU9@Auk8)QeGfBM}cQ%fvyg z*Mzw?gJDm;8^phFV!md&N$$!Y(2N}xQkS>$yP0o!%lTRsb;%G%>a@a5)%WaUze+rO zB@68Wx`-b<=fOqi=@1{G$mgul#x*JWn5JaH$`u$c%Os}6+To(x>6383E)v>R+L&1< z-J~g>axm`1S79e{V|H~a;5V+HXIoP}&@{#dKUkh+GfgV-I{A6@CyAo&em~e4vUlJ_7QhWmErsjh8)!)o?ojx{uOA|rHZJ_Ek1K!n6t=IN z0{FvWZB=uxm+iy&?N^|o*}R9H|m8^f5I-ASMZ{%c)>OR3RZZ5oV*I^Q?<}% zjXFN7?8n9sXJCC9^=^#x7p#tlfu{9Mu<5JFHzakZqIhQqHDCv{Z;Sqpabm_ z90JAnU*n;rJr$gzn%LqpQ?!e=#qV5C7$RiAYu)ouUarOMnFPuo=kpcIPRW+&s)Op% zue`^@a_09`kIur%n4$~pQbGZ)F`-_VmleX#N3)>$!-9?({-Lfn-o9>&F}+M!$g3E1 zpd4S+J7;mldM(_xBZG3b`o!Rn0^e1@4V`Obx6@aEs5BZ5kjMUbTmfDs-k@cUsW?IO zh8=N!&~-KKJ;Hk7&w)en--dfKZ5D%WPt$RcYp9rPvICDxoN=2`b>h}ul)0Ee9(9?I zeDAKeu>9>ka4S^jA+)PpaB&}XYs!Q;r3u{T*T{}e?fHKt_#fMgqeF-7<0S zjB3I8&qVmzZ#{I1Yi2ezTPZW^h;7==@&J1&jNDSdZ8GcRCLvOM99~KH3Qc~^tO^6j zOA};PA;9i|uwhFd`1V?XvpL%6yg(n#kKbqe9xxoDOL_lT6VcVt3kvRpK>W2vHZDLn z=`QVh-u5vkMv4^n^e*6=EcdfQI>)sivc`=r28k87D)HGd+Oeqb5#P*>fZT#J;1R6M z7gNSz$|K^%dvBK?HaN@k5^nO?GsHl)dPs++VKBT&na?FJ?yuYWIQUA5Jbms^n6qgV>0E7Wm}@sYd&3cJuEw$l52!bO zfd?24k@6SO64-YopVuC;O?W%K30qEPAU)7DsJi-Yq8>;-bih5@RPQ%^H0Vai%aL7Hvs) zYj7|T+o~)ux9txkto*^czK}x6>_R@{Z%=u-IF^2QcDS&g5WmHu5O3_x!mdm%W-K`e zQ{P>LhnJQ3h_MfNVD9^lxm~<&8xAI&F@0|aJ1|@dxqAxup$l&Eg~PAHuZUo{wqBig zt{8_{VUL?){pDj!3$btmb!|WQ6T1bI?^=)EZD!<=)8;s7D|I*?yDn&T8v;{zyTN7C zW;SEzZuC4n9EJP_`P0O9{^9gnzW-q@s~K&C*^ccX8l_C zhZOKLwda{#X&8oP`r$O~QZ{Es6@Dat%L~hq;^|yJh&Zr+4_VL8O@X=7?9bdzrN z{eT+fc>iBu?LpI`) zHa@;Ta!gMBjA{!!<>J_ocg0mOhi*UPY7WUg)DGW@V4RPKJAcTB1 zj*l(S-`y64NhVBv|3j=?mVwW|3=_ZY*2V*;GQjDE0e3qn195_D; zv=6Crv-y*8kl!#gzZT4mpYA?|~Q}>b{|Uf=O^6Oc-yE(Jl97nh7x& zGbIgu9v&A5xb48Z-yE?#rYdpfb((dz^SN%IkKA(MJE&W750>dmxLdkA4(#TPe2Ti@ zHEkl#s~*YIW-0T1e<%r$(vZyS}CMV%IA`y`&sm?Y8-cuav#P%qQ>A0 zFyz`9=$fX?hmTdqPPQ7D<-Jz^=g(QbKI|s9C?)+XC>^wmf56efFW4}e^GC^NyJE@` z*85d0u3epiy~9<6%%E4WVJrg|OBJ5JkoY7U^>MOlsr<6s4mvrEhKp(nT;fmJa201v z*%QY!j1Iwn{*$30hALDOO?k@e^7)<$BD1% zEr_l1^N@V;A{?OZgV@D@U;HxB>YQAN|MP&K690cbm-gOH{ezBZc{+npiwn%m$mh>< z-Q*35*WmK3V0ay^&ONgxp|#pD)E=~7?su~Y4;{$DiPSx9kxJZY$!o|Zt?kN6z&Qsp z@o0}5!g#qg{8{G)VZ52SMR?=PwQ-Cz!k3BJaYfrIhV{jivo4ZkBBH?r<3;)zhx(U(^BTfF%pzkYv80}2iclL!1A{l_%uI6 z9JS{e)c4PYqjl7W^-~wqTeIN7u$_Y0b}8H=zoogSBm1?j6}O+s#`cgi!r8@^(5I?X z#~e19E5*2aCG>ir#t+cv&Cgl}D=OO9xmSVYISt2^liXR^Tq$fI|68vfTFmM|E1nI_ z#*0lAf{(*eP_>*0JKvHX;i`q#qlk+b8_Uc>x5MS1fiP2SW%1LxBM))Fl%5r`{Dfv+ zq5hOtmMZeu^gF7!o7=I+c(|t(6Gvp@%3j^XdnW_oQP6sDx~{?xoz%r6SLxj!JCMDg zZkMg=Gg0-bOuRWP9LC(b0baz(5Bwd6=03#w(4Htfn!5qU+_r|cAL{(_B`F+e&*c~D zW+!e)z6^2ejuE3%mFsbpj zB4shLak$4e1Mm5q5G_4@@b%wev_q^*T-+vwyP%3olQvhTn^{`McBK@vM0^#&@m~rqTU$`wL45vr**I zvpQIFUJp+c-e>o`5TA7+?!jYI@nPjgupAWv4*xZ=eq%I%E9P^ztNWRr&UXyDo`sR7 zd&ON}FF>us8Swj|%wJCp=dOF@x-3;)|KAJuQegHN*Yck^!Xz5iP{78?h;q}RyW zbTGhBf`_`ymY;O+b$0WBI;>5plWu2e4bk|_B@=0li5D;_UmLgb?g=FxTnb53lU!*&BWD@ZV038 zhC=W_cX+v@mF3JeNa|+$0c#463eLF-Fmq-~$6USM$Cz>lE%3kWhU?f`Y$na(>1H$W zPwYa7(3%DhCn)h@`=#jjnKZ5O2CSlg5HYy- z#Y$mem`1>E7`wPTaXsCq0#uMktcPF06 z+KnYkj&T1Lk!Nthaxfm!DFpjRP}cTobU!*pIIE`tuZXRr5~L;c^zOt-S4+`KwTUZi zUIu9!JRrPSnLTaN!qL8}xVY_>pnSCu6)8{6JEkWusoDx=LO9I2)FJp??~9{fIiQjA z2g#?_KWxI=40e>}@G8SKVCJ$4ruP(Ov-~@8uOH1Nn)>jyVPoA)&u)jZ@FC(Z2JE4p_tkRt47Z&2$Ma8%(HG&U1$G|AJ0Fv|m3OlSb zFrIcU8g8lFd81O8pMM%I-`8d*r)hwFYz15P@}%T{Gw_HjFS}Ux5vGRNLK<@IEhr4! zQICz|i7mgA_B9*l!ylc6(BDOoaWBnrMu#=VPBRhI2W6n~Hrl`R7|W-6>*A@&MNnO7 z$l{l4z=q6M&T*#W?Aq^4QO0j!IoR@lKzM(fWd`n zFo20zM_v>@GTejj2JqbeYm=E|H{aFk-q#c3LL&`qq8X8ClN>irrd`aF&)gmIbSKrW zgUG1Af^OffsNc)JtJkfXpaJ3o6|7fwi!>)n8-H&92zDYJ*5urR{|zg}0+o+kyvhi0 z-(mq@Rw%Mr?{(1dr!Fo}P8Y^h%5khyF;1P>lh^3K8Qjz(;qkrSg34P1dCh<2I3le- z@l@&WUs=hL%JvE^Rn3@NT7t6%1oM*piLk5a6#UguVdVpf=|p;kpLne=2H;v&)wj@IX{G2LTXO`WAshyqZ z`i4C0wmbRZzR%#|#5=H~RE?$or;TbEs<^~tmejl`gmpX$?V3f1*VMrVSu^;CmI$hw zGw=?vUw#g3;jTNRg6a;^#5~btWxAT+B`1%eih|_)elhB{e}nJ=B6f0HEqar0=iP!c z+`hRE;Cjokt0p^g=D1?2HNGqZq1HbG+sVK4uDu8E`g9=9_}T`&**9UpP7SzRSHb@5 z>@UsEbi+brTTIK7W)FE=k6NiTPwwFPrI`sZ={4=b9h6y&?oHMwDUZ$GPkICLoj(az zLDdnlg4?x=(Cx{7I6|7_2@^fgb;U@mUb06T@Sz?DT`fUhw>^BUdM*qKegsuIw0jyy z89iymSUU9*XQpEZogb+V_wN+e%`ud(GO57cw~lf*5)?pT$K$TOUiMyN?Ct#<{>OH^ z8{2|4yGqg3vJY?6v>39pyx_5m66me zCT=`2N+JmSU74ywZ&eL97| zc^SBc{Pn#S92A&L1DeNIvhW_-g4r|$dB3$~xJ&er8+CCxBtG&0&4DWHtvfMe_o$)x z)E!~&^&&KsmSEV}Ui_Lp+aRhb9R3dYC;S#NFw>$K=Nd&we|G!JGL!GJ##M^!l#(W_ z>{r1)u9wRmUr~_H3Ms`2XH9vP$_PjdUQap!Ri->hANRV7aMF%p!UH-#XCzaeZ$FL? z{u~F}?2{pl?iU`%GtnfDdOz>UoQ97dIGh;)H&=<+q#>HH+`EFEwVN-qzjgt3SsVpl z(%Zb>p@sJvl~Kj|it{4!LbYry#=&-bdBZY*>i7aUv#vu(-k*sRj}_s8>Qt^tsSLvB zoQ8_O+H9Cqle|I|%sc3mB!8nCOjWI8NeZuo`2!8{NVFoc1VQLKsu3@*r%bEJPu$V4 z1<)sc0i^qpj!|rhhJUTmqQFE@+ntH_;YGMKb1bjiM-Lq<3L#}oHzt{&2|f2$u;?M5 zC2QxnV~=SzICXKjz|0$Q8$GW9lX~-2*};(VG#FM$71@b{Rv3MGB);o?UD9n40OAL#@g-ih$S24!~HB>=~8#Oi;2g7em!25;QfQAY1yVS&k3+)3L=$R8!m zf2#p2+soPB!C#~{Cv-3+@FQGH)L~HuUvcG>QuH_e#97CTfU_0mU9}fi=@M(?|7-95 zaXC12d@%+V_T<&Vx4?~x0}yNVM_3jb3B%vcfr0%+EGFd(>VKj8^_^h;=k~L7wx5EH zzH~n#{q}+$8aUzMdg+5YZ-2wYq|rxyg#n1#yZ=Lz(+qQ3yNy>F4M!X@*8PZ2WhYs2Q?wJ zojj5=>>u21Q;_%lS&D<_@8U&k^I`D2+n`~j&I(Ss;U>?qsCW95bcRYOb2SL<(o`gw zH-I*2)xIt$6;>2xVq#+v9{JtE9e$Szqf!H*sgv~Nwp!psvx|*)6(r8<#JEGV6^6vA zvyrk!-21TvcQ&5o-l#jmzFv;7HKRK^aEll-Ur{YllqG#OqE@l9}x}_~CaEs?9jWH)zQq@L@T~Zv7BC zeiTFI!t-$GlqU1pt0-@!?2^;RV>wOZf$(;*L07MPaex?o^%Zd7a8>43O}dh@V(e+q z%-y{-8+OGngRu$MdRXgS2mxohvET7p@SN_m+X|W`r;gGr zqNSdV-WDfZX?Mc`*&}e~oiJiYzr;htx;fL*o8RUY0-v@8gT+!scI;^YZcYfr%qYuAk>(TEcPZk>%_*{#YqX%pg9_%eCRiG#CW6V@^v-CE6cYX($F=)| zG31?u^K9^B_p7-s2Bxp67@v(2Vd7Y20uKe^am798-SZ^Z-JEu>6>DL-xI^%8*^Ye_ z?NI*BNt!c33l>IHFo)M)r7Jx|5Ko>Lx3B8LtD08)<6VkIy+3nV^Q}QxX%6N46q$*W zCbm!2K=bCybhhTA|b+Q@f>BEe0QK7y5TukWpxUM1*ouayAT|-Fc>X!Yo(U)ajf8O z5*s&FiLE|a0$*a9;n}-~!mAsX;pW0nSbIT()v1eN@~sBux5-%YXTUS4pCW?`#9Q{! z3dK0v5LC}~=fZY5QZDg0Shrk(1uQbfBPVU~@5~#5<>A9{QGW`YAFIJGeH4Kxyn#JP zijY2ZDFC@QWmh|?Gs!epjQ-+?r72NT{rjP8P<=>Oj~a7dg#P#S@Dj1h>`d?D3aX#o zGrw>@52Qir!vJs|qQ&<4i7|WG7Z~P9nU(&p@TdlHmZHva|9x?U4cQK`t_Ssg=LVwL zCL7$o;Gxj(fer?J?}vM@t>@Av48he)zeArRKZNfu+;K&OH9FsxW_ON!h4=EQH#_FS z2Q5y7Gc(SB{$*vhxO5AqM1`RESF`kY!7bJ*f7-Pp3++#R=|m-bsud$_a1}womU@=> zYO&Bi*b@()u)}pz!lhQ$uh9Hy2`-%##xMHv2#%b~g~k<1Y?5^lW^E0}ycM&!|9tJ? z=+VirmS&{GKO4yxCY56mf1F!utO)+TIc&p>&%!>^y7W0+$Hu?Sluf?)4eO0dadxOF zuQg~X)YVUi5LIQ?U6V50L&ey>z(BaP@ey959&FfRDPNO(8gx!yg~djSEVbT9jzQ(P z;l(GetYs4nwi*Tft4K>Qkak!D>)6D}<7Imff5VoR65Q=RfuH#(49w>RK*>C1<~vve zWziyZnd~5m^L~WC6^k+8`62$Yy8t=K$~C8wY}|*Z_K@kmXCNRX2T+fVianyU3#iK`ga7uB=R>wigR@AZYgGu@&73b95Tbn&PU zdEdU?5e5w}L%TTo9z1&U@3Vp+Q8^rv@Skw!-T-WkrhaMKC&>u?{x~na9qdLo3PI%a zN+!*AOVdE8kACJ6Aku=ZL@mtP##fm7($NVqCG0=YMQZ0Iz))A=XEU z&7xcqADTzGJe{{*nf!g#8;Zf$AY?DBGm zSr!XVf^^uJWOW!=^MaYlUI}CR>EMx)?{L`czVLa@Ys_3inQ-Hqx#07QVC1Fwpg_!) z#`na7v2j#cjSY6mbl_`A| z;mHC=NV^yg?KYHCIZqwEYm`{jgvZ!BjM!PrzHmL4c|q?}Yhn07;t(F#fi^KC(PQIi zX(-K17QL!vlMkv314(oK^!0bR;-kUcoNNOY{mtQA0cFbkAZ>GZFSEGY>14;=#uu{J^qv zaPRp^n0ATo@`c)H{azClPxwh!^oVCyyCpG8XC;>HUk+z2zJO|euCQ{lu{`EXIhNm_ z&Z})n1y_Yoc>7X=nT?@bl6>-9m>Eg3`{%>w*AKuuNtJO5~0;pFXgZqpVWj^GK37AmFJnF)wC#O7z zNlLe&ZKparTce9gLsii)VYc*($sXoEGo;IBu?A_5%XBe{cA6f$vT!=FN;Vz*%7NV# z==RPZelO5sH`>Gy65qf+Dsw;xiCI8R8%6w&TJo%1QtEP5OGzZPse`|8@A%GJ8}HRm9IPqlFcN$p>_^ zmWhlO3(2k8xH9ZJe7)@;9Y^o#OAqRS!^8OJy`I2G-&~k;M~OWKf1EKW1RJcUa&96A zcu_V9^xpgvR$O_2HtY7{g}PB(Gbq6Ql@D3e?oYzr=_1f-tz}!!Wy)?d)@9-ge z6zBPLDO~tE9crjIm_)vV;#|`5p}yc5@EG0hQVv&7j!$!ng9$}fA(;A;=m*AfC$0j+ zwVSzu9sj|lp`*ZBOT@f?sYCeETDGIkMHVzj2hY9w4mRU`Ip^--aB@um4BD^EI!oWL6 zez6Su$Czr}fESIUg~`Ns67*_e&qxCn^^UmTZ|j)X z;kw7Iur<0~IG!y6E7EnB^cyH0-MJ42NY}yH4psK(`4l{3peZU^pyTCuTRaQjtM0&XcOJ5b}6d6~17) z)4ZfTn=gW@!4Wt!RGq0W_CQ_r(Rk#1yR)-$1-?xp?hxC@EA7mIwgClTxwupK5|@p+ znRLH9afQP>6;Rj^0|V~rFo%FN+))yO(~BLsTOtuGd0*32pVJrW;F;a+@Tl>gpw#;< z#?g1ub50BAS+E#3Oq>tqA|)1`^8};fNh7`auAsO-8#6Bu2Qo&&M|&FJttHQ4+#)0P zX0*2aXI&Y_o@nOw61&?Z^#$7*ep;{^ql5Xb?JzcDw9wS!EvAQ;pr^GdA9*4aGOKsP zbD1K$-&Y++X=-EV`ACV$#%z2aL5zsbllmd-0olP7W5j#GU`pji7 z*qL8h*@wQhBd1Rc)w!X3UD$azzTza@d7{FMV>D5fYMlA^_0lG#1orCH1r{By#12MO z!_~j7;QaWB5N4JJy-$R|9s^C5A4p#KxEJi>&u)^qB?XX{@c??OsWI366=-Kgb4wlC zo6mHD7k)gfysy9%6wPq`06X;mcS|^V=LneGngkCnYp}2H1M%&hG3fOuQT8vCdVp*6 zzU>H?o>)`}^(n+crM;5NjY;@UG6usoM@u>XJuLW1aMvDf^cxYLdaZ-%6BO9p+HCwl zeV53)mHYPd3ZxG6hb8B=SoF^{9O)2>mWlDwB@@KZ{Gpajtuf%XT+~3`qy@SiS7*(0 zj^d2#VK`ry#2wz@1kdl0lq)uNfRs%MRN38q>);pS;k8ul#uyPTfj?Rm86MniGgOjYBXarA0bm>mBC( z_z7!iQ(`?U>@mAup{qW3+oLUan_P~ndQMEFOLpR-d3d$i(jQto!A-ZEFh`slFKo8974P6cPJymb~GV z*Ym$xy@;MqtZjQ&t?n@_0;X*Dho(klR@+Szmqx2&7Uv-8=lK*D3?LqL)nWc;3cwP# za%c|xC0sS`F8{Wq9II}J@cP#Df0L-6h}L4g%(YjwtT?OLnhbA4?Kzz}(+} zIGeqbVbiB*_&jvh{(t%5mk?g$4~R}#09bemCq_)C3uLy&J6 zocEyosrmhJ?rK|fGJYo+*m{wL?^w;=Ur!P4%%OK)uMK<)8-<1;Vt76H1@pEZC~b|} z54I=P!l!|1Y|-=yI7noVTYsz;imp}SY2wMuP;%iDv=d2lmjt%=NZYI=!%xr1-`9UC zcPlXfymk-ks@2^_r(xxtVC+_?!tRsDQz@~AEjIF!9)6e%uO1zSA)D1%Q_Cbe$48?s z`|fOVfpL--1W)pPCzmaI&Ut0GW^3@xaV}1C2p-@+vlGa zikqh5cO_fgskcwCpwG{UEy1=bQ+~7k9{4+HH&}dDWTHv`(|c=U!YpD*J$-=eND=DkTMP`$si@S7*-LyQEE7&grw5;i>)rRB6c;Eodk?2e@8kC1=CrKx1 z)XKSTnF#?W*MO$(KOuU)J-QC+1V^SSYrA-{CbPG|{z@(ObleW?Sw9vd$1Il$)5UPrmwtCU4Y+GJG_iDK3nY!8 zOySHUXm7Iz+Z{bPm&v1{uf!fYDVymVX-jTjA@5enc_Bt3!^66i33aG9|L@-j^iTW& z9=rYu$%l31SEiTa9d&blO2ZV4b+N`}jL&{O`aR_a5VP)=D<4vE4!F$;;5SQ!DP;y? z=F(uiHLyjh{^<_WtAE@z$4KxSg@vGqE7D_y{>OFX?`D_d5WQ)9&?)l$jj3Vl!WIed zi{7DS0+8iTBdBL#R_;gY8v$2q0EXl>)^3=F^*i@O^AJ)hsrC8 zu{nb0wSOeQ(6d+Jx0e!gTGK;*j%=8khDE%i;nOvc?d7n%c19wU&5tL74V#dKD z_mnYTxFgtWRpXad@|uk{q_<#9AaXQ}HTxbVrKdAtnZLaT_Q^y%JJ< z#o+R@nq?~vlpdLQ0OXXTw|9F(5I(*lp43?}E6fT&>^lnQH_C)5dScKbkJ8oZ>C&0|Ehm0Ma_1@@*fpt@F$Lt*sjlr~5_xOp=OC{eYu_$UEQfD;J#Y15f(Q121}=Vviv6- z=q2EroFcUQEagvVb;GAv0E)iG%x(key7kL3QvEA8rkHw2jcT?<<+NZ>FdcIj(%JNS zpAfkE18SWhPMu$0ep%rj*nWK%TsKl;lT)L*5I^O&@uD?`@=99m2<-6_SV7NJ`P*zBq zpoz&!>S)2I2(2;NXvFk!(wO<&h@&*;|F9pbS9J)1iHE_Yb|wUq-`25J1U;RryK3qC z%fE1yv=paA?BQF3li(t8kz5X|vW<$`80;j%_y-%Lxns|;s)qAj{)nxosz7$U8DhO3 z2_GV_Kwo(H2Dh;>*;-C*Km>A0LHETMvj<)?~9MiUBA;=zl$}WNtAy7vF>nQW2ZA$sLcx zIN;yn6Vhj!!q~dEySwHL&9-97t<%QtE}eqU6#k{=uaGy^ zLmNXk>f_+v7leR#0lkUSm|@U|*Q_0ZigE4mF#V4({D!VP&c7UYzcc3pGpFM!4_lo7 zczpJB{U)>}Ux4lV3B29i^H6J(06T~uHJ_f*R)L<8{XXf<+jm*kjK|EjT#3!4Y^ZCp ze=sN^S_n+jm3LcTj&Y{b`5b*QEZbPkWLFmn4tIZJF!9hHz3a=}b9;y5k|}pyA)MEp z@(k{I=K#>|)%377exdjOVfRnc1tXkj{y7P*S}8E|D!}av_hLun7_PNQ0cN={Hj_08 z3H1KU=>4yQ4B3~E->Cbe6pzg5&v#r~0oAtC;CvG4DAsACh!_aILk)$s#L-$?r;p2K zMQ}ZKCP4VrEARvq8Sm3mo*PqvTRXpU5hYu|=avJktrW4_lt-iWs;aB5TKoK_T3(8y zO5OR?O?%<$0e@HEMppVjL0ZBuRPv4DFxN-15^Ae(_d09QG=Q?UBEQuaZje z^*#r0w`;Rs1H`cMU^SbTa#phC`yj~LsRy|V%1km+jQg^F!b|!dbWLl}^g8K|uC{U) zZY%(^0ZZY02l-eZ55PB3mTex0rY4SCBg0+w#2P)v@ftPVaK_vMsH!$*{zvuX$u{NK)3cS+4<>dE zSLsx6?ZCYHmrWO8fKUL6LwV6J;U%X z^axOu77P|cf_fDj`Cd(^|N93w+@;T4*vd6|(mUS69L_&hW)>M*xS4W&VyjYw5}I#I z#_QuX>3puf-%fDI-wz7p1Kls}C9krpAdde)-plC-jJ2N$W{1UWjhYxl1(j^qf~@Sf z8|m|@CePIm0wrddPz}~<&0uoq zk#N=bDue_CLtCLH`!>GD4zN)_+})#u{cHtvpf zI;2~wEwCuuAvU#Mm$Vhp$itIfb`X0|wUoon{4Pe(A|U~3XkqwsJ^9JQG}9d8#ed%|hI#Z3uf#=y&%wWVY(yEpiS5U^ynl~>l8SKFo^T!x z`ycC)IO{_afKpW45;d|N4+8JO{rk9?u=>QpeXQeoYd$)ieIQ;(kpLO^8!YEy3G z$WP;VQ_V!k_PGM!NdBzXz2qN$QV#UuZ=A)}0C<&R56MclI z&>q<>&x4rl4LAE9oi#r+HjN)vdn?X(`AsU|3`43 zKCLYHEIe$~W<@m5x9L^IW|p0mRQ(+c;m399E~m^g5=oP}#Fx3HfKa~kZ>onlk<|^iw<0ZwvDd3cJh_aAGtYFAQ zY*)2Km5gTRV_vnyFD*u|#shrdmZzkt&WCn2Mb+l zJNoimx|gZOoaX*pK)D#X6|8CXD?w&Nyfs&PC%>XF&gUprYKGw2i6^)l52&%(#2Y|+y0fbeM9QT(S9f+nJe+$ocA=n=gW%(p5rvhLuz2SsRR7{fogu@hJC z9gauee2|SM-&OC=W#H8k%FTNu2Jxm!WE}4_elezIwQ&KNb7&sB8q(E?ueHnp9l!mC+Wo51@K!O@+@fbU zMO{dI(SaI|OEJLj8~41ABP_Tw0LHb^UV~=Rr@hrsJ3U2^hCavF=ZeuO$CQ5@w+jj` z?1$g`{s|4=DAzT628?-2I@sHk-{Do+)epORci_*(rIcS4#>e(fhQ-@XfQ^b88{n*q zBLisO`)-r;<>Ex9o^!6NAMXG31?XfnLtyS>A#U0=SZ5my!>qNKVx<^H9;jqC2K zU(A<_*)VIiI{O`^gPLXPxPetlyBj$})@Lbn`YSTkZ?wM{XMgh8L3P?I|+yG{Lrt!^b#?+lYZx?2kQ9yfviC1UX=ld*HH1FBb?lybv4>4zSG2YB>=fARM`%oD1Y zAsP=Y#$V>9{GkjB2vvH`JXAl)a$e}m-6P9UW1l5|^7?1;B9tPR>Bg^(OoDY74|i-- z*~GcD<65DCu}-1VlRYw7tLFdL-euD*VOaTVcK`T(*_U_v@{Bm*`c0g{AD*cJFQ!nP z30f>H-S!VRPAbE1^ZIjqd=vJ#RfOmDBlyu53t)2HL%61`!v4k)2WiPJ6hfwQXAQVFou?;+2s6K6J05vt}rU*B{ubu39R6oTdyqHTCF9=hPdd#q1{ZKu*;sfH5ETM!5v{@Q`* z6fwL1Mhr7apZULfTYBjq-daX8v6M;t9-sX%+-D11ovq4(j_ct>T`~UpI9j6TT8KH` zq}%y~hp$)szcxCa01uo^nod;?WRz?5GQVvz6K0 zr(#^D)(&a4N^JYbI_&3Cf-ldtaYhx3!CQF=%sxsw_UZvRe>C}Dn!d^w{3Ry2R}I_} z8L`Hp8t|mBqO0Dj)~$oG)voYqmMWWnm>5^%lt@c_hw`B7(6cA$RE_)bTg*ZsYQY|u z;-kRw(kxK9uPs`qe~`Q#c9A(oEn%xCB?~*hS)s{|?+|h7z3};l1{6=L?3(Kes}6$A z-PO=BRh=D}=7ln1P57w#3sQ}Ge5^>E4c!TRdAIYh%!khA8OjXe<#sSXd2V-w3!dBXm68KiEfoYS@(c8gtmv9QFWQC=2M^stdB_MS_bF9z~~p5?g2 zD~|L1Lm9Gm70jmOl`!jrF)pzA1N{f0;F8{qRh1<;(Wi}5mM({+<~eZZuM&H9P>u&^ z_x+xVZ%l**%+-3yzJIk8)Cvvcg^S8@WMLaOj`YmEsrQSti4%qt&cey9HW=!5K-ibs zjLD@Xcs{g0&tD0L{-22Rd|HW}%_hA;r6xv{9F)vkCC61X>-LV1;Tx4K!Qk#omUTVm zf!1ZJ!|A0^oEOUdJFEe-dsedfm9~OvX(u**D8<9K&vW_P#VFQOLf>Eo_Fw-Z980rw zKDC|udwVX#rLF??v7N#M^5b;ozGTx+wmOS_$a7j$!3yT73-wPrabsgCUOLgnJxzCn z0MY-~-d>(Mc;l=ZnxDNaoa|PF6Ie0cUDcNlZ{H24eD_1~-spkopX|G0EXq0!Eql&p| z>!p>L$dbk9x@NpeN9v%hwHXQ$p9o+3S_0O-WJP|=E9n^K6Gl?~xZ>MS>*7JsEs_QRV?+|J|9;A$*|tl5feo2C_}thK|Z!!iUbnK_*K z-N1TjBnZmEJ2Aq*2^UT{C;LSHn!Wcby87Y3k}}Y2zX9#;Vz$1UC+>akfb&aFNyF2_ z*_76xu6}s?Ju%vqXyD554qj_sY-$ZfHPt^S_hHo=?r~n(L;{u>k&ABip@cpX{i%q5MilInG%zlaD5U$Gex6?5mcyFnqXz zeC~oW6dRgxs-B;)cQ)nJpNZi6$3KVMRS&^Mi zSZBTk)U1EWyv8L;&f60S&mms*-gS{E+bP*TKcXu24QvmDP+l z#JoF7s1|=$7}`*egP)NHHme`+yEzoNU3=h1i~`d?G!VbO8i`k}K1ssxBJ)Qd8a5;g z3;zwm1;oIN^#35deSHwLzpjEotJGOStQ)?ru_iy%YGG(%1D@|r9Mp;l{4CQ8fU_<@ z@;zm?@$W<2NAs~sf){6)XAWQe>Y3iQJ3`;m8(8%z7=36@VSYIk$_)=eP`rr!8SRc% zYi#h<{TAoIJq;N1k9HrwBYDmwAHFUmeSD!J%TdU|LA{GHee`v%=L`#2Hl%@VJ3B|n zwKJ68^eaPtRUCJx5DCLW8zr+0*eq39*2FwGuotY+}F<4E3Sb1j&mSb zS()vmj3bv)F>br{O*a1RLwwy?gj-_A@w|ftj8|!3&p1oL>w}>@Xlpr|YJcZWduzef zO_bL>Enc`Vcn;2}v%&1#146$gUvOA+3HsZZ@n<$gfdBO%c=(m(&xImv`6t5k)dwVE z*+cwOT7)lq#qy6gSU?kLYws6EKk&%a1lv87?e%S>u;m4LWVFigy8i_(@TrKY+kF+r z7^Vv8^q%;QRKytCgItQC+%TFE`5gVu^?E?rwoa?y;DJuz*fR?-Dr{h8DPNseL~Fv4 z(d4tv_Zidqno(fM4Es6i!$Y$3qleS+>heb3? zUwMRh&hDDv3l;3cF(XOc^fHheWJBV2b>=a+5xr^77NMQWZL*VqzQ3faCZ{bNgHLnT0XN0_I3Cst!PAdDxDnP8*pzKc9uFm^{K^)e^&N@NF60S2opLal^6aeK z`ts`rTfpeHdiKw}Nw%|3H@Vrva;$W*;^q6v!{tdn@lkI4>%e4q@?ShOyi{e5l=G#l zsev&$q0%{<@3HSsa=K;_QQa)yba_2H(6m=J!>XISqNE%jY@5a34ZI2(^CN)VpX^{y zMfnr@UG&Q{<8(Ef@eS=$#14D;^qfKn9QhDt9adp-aS3iC&iSjzs~p}Q3#H@S;pSxp zrr2%)ZJ+DeviviW%5#eFQ9q021bh&3oD}6FQi(M;)|`LwZZ#OXP5J-%!_kSTc5^g_ z?42y!Ur5^i^kS6tb>)XPoQ2M3sj!%KF+H>CZ;q^II|CG?#v8VRFk&P)JBpcok|u0) zBp=_G@v_lF6yd$QW%NFG2z3<}usg1v^;jP%{bN%LpLQg|<-a;C$W059`c*PN=ktnZyd){}|x68U>s@;f`?E z^wz&4_%-atqn4v^U4UHpLpdO0$y4BXeTMXN ze-U_Xt7n1J=LrU`9=NNU4R((H;(TxLOH|Y^!7T?5@|80Rpkq)zc$zD*qUE_b&$Jj@ z3$Jswn=N2UN*x>PHb-#oWhCEAdeqq}37mtT7EE4Q!O}I~3Tnh#ySK4{4S0V|=6!G_ z$Oq1WjsRs=Je@oW2Z+(F(I%U}C>Q@TCSQq{3;(gN1&kS0$INprgeb9*yeDzD^Cth` zwvX5X^W|f}Ct985O%+4ksz#QWU@e<9ycOrFmg3R(X1s>}Ua0RL1U>sHGqF^R@3#`G zcF_SztZgn1CcS7}S}bo9VgUoP>X>ds^n)Htsv+>>C9t>EVm@^uxO%ODEi=6;QF9QJ zXYWf_9Ui?~j7HNH@Yo7s(wdiI)7N607y5%+slEXE{_+J*TY)|MM8BO$^=z8!SLdm2 z#EDwi$m;egNgLFi;O*c3(9oCkkmL=Id8vxAO_zn{jUixXydSQ9?-c%(S%Ay1de%MN zMmntg7^Hug4xXg-iiu8vn=w&zkf|}NVmG|JdJN@dUy=^?ILBr#Iomb+6=#X@3GHIO z%6sZU9rP2%QuY*qOP8eFM#l{^f2h*}F*gR9j+Dl(zLwX6GW2xMY>6G{7 zEP=O_kGyN-SS<3Ih}To|gxN*ru)Uy`IWLPBqFwCpewHEzk6kYF@ex6JeLXWWA1(~> z^2Cj2DaW(tDe1385$w{_?Ol05H>kg@C%>q2{vV;{N&v1q8;X8|Pje6LEWmwc9Sb!M z6NcDt!x!^LqJPU`X;GRM#Ll9*_XR^vv|I!gZ|Yf6nv(F}#3)q%5{xcuCUN;@QmFK{ zg@?nHncgB|V9&S3KU?zzk4w2IEHB1g6@B^pV=X|@yN+ev_#j&}-bjA0svP%N4B`z* zd+^V(fgQW}_rB`wR$M}N3b*c)_(9T35Ya6j(185)#02QoR|{|1g-iEMz0Y{BoG!iD zQ%eij!PgPvW3TMjTqF6iALaPt;%wgN#Z`Ef9u6~ZX|M&vG@csUz&5K5mDr`W;*KGeVxtcFYHy;ws#$;puJp~9B#*TWGL)KKM; zp-|pH%&p8~d{X7gCp8pgE^6%OoQe3WuM^G~w_7s*5#7TM((gU`IKO7h zQXv}}I&TpDQDo*;15vlPHBRl>Ci}kJ5;9KIv8>sjrR&yqN7o+J z2oXFIfDk4puc^zE$>sxN}D$F)rV#8sL7 zhi^DaO!Lp}Ke)e9zEB%C8(5+;Gt||<@iU0^_n=iawBQk*{hwA)WjsIE-vVO)y!TlpsT#|1UOATD4d*B9 zu7NQ}FTu(ETI@P~exp@An|kevB$BvfcPl#pj&}%|8D)4=METS~Ke?vq3!&q#FF4Io zU^@1eaQR;?d)()%bHHK~{MPFo9C>BHF8he#8F@2rN|mH_jZWYg-5;E0s<57gx;Srw zDw;pKENpKN0jq2KV4a!*bF8+2S>fd4aJP{@7oiA#v-k3bO>z#0~NwRd!m2>Q7Qesz6du5*(lP>C^{|?HnZnFTj%eAcV{8H)r zfj0n5cfvv)ZT8|q1*G|BLCI+md!hUqqe%ZS);Nt@J(&aPOJ_)^QDj0NXS_np<^AvS zgcl1f;7#odChU(FCXX433YrRdap6)~4=)isv#Dc6$A<}Lerls4c?3*ar%1)pz3hA1 z_AdTdMWGmrj6|3~oMd|zh-2MCF=zZ~&gFmw9Ozlgu4;w}KHs>V`af*oj<+%kA%4J3>Os@X5`-;gk8wQB5dLoJ$2%Oi z04s}H7JBA`Z2Sge`TCY}>=X~?XKxTe3Dw@$7yjHo++7FvY5#yP#_KtLa0;YX#DTXr z<^FuQ&%94OWXIl+hVY^VER@u;*AMo}R_->IzgMroJ2;2$pLGplmxV*SswNA*OIqMMMQNIZkuu>1Z}v{NG{d0R20@0LT3fhrr)zZ{Dl?g*9kk8Syj?LOTRQhb*TCk3p3=`I? zFcC3|DVT)j=^nz&H)WVjb-?fN1ir@Y0_5CJgP5br%%RQ#(hk(J%ApG6*WM17;%(t# zl9)Z6a~TsRgrJ2&v#^KGN)Puswx!2h>F$@2u!!nv?m9I#bH-%cFy9%6-w2gdm6f5N zWeK_siQ+q|o#{?2srYGAC>pkn=N9XU z{*R>d@TdBH|G4cOo1(O67%j9Eao+EDC9Be&TC{g*P%5No38}P~7HKC9=f1D&v{j$7 z9V=AYn~3Unef|Cb=W(3#KG%KS*Y$cmUvTz*8DHk`j14{_$DKnc&w7z2zg+hU4>^-Z z_f)-j)gcJ3jGPYBNVmD5;UP|(M)~pw6ItKmcHrbz#(g_~6!2qfytYvd^SBl7x57wu zdPxDcDykRHSHKJz$D-gT@u{Y^ ze1wDn!8{7CxA4&~M`MR75tb~{n9ZuJRSbxUz^RHKU=6Vh)rtg$2K0F8Q(kD<^uEj?M zgy9sIC`?NT6#vE8LB=BDi(aeeDms>0O9=*16be zMT7XR`&5YjGY9TYAx_#-d-!>zl!sS+_53-uHEw?M2Ienm!TWxcLG@mGK0`DG`;+c4 zylqG5uttaP$uq;R-ZYzCoXR%)6yh^_&48MYlKY7$s8|vUegic4aO!!&{Yp8w_Y%&% zOa#A?BO&Lf0q^&EHBRd=5W}tQm7A!Zgk_iV_mw*YW$#qtfh0n@LZ9!~_r>&o1F&@5 zX<@{u6I`d;QU2k!7T**j$CwkQSesbOto`gkYe^}W;)8_qd6(g?YdAD`8uR(9&*Q&q zQ8@L+4dHmboPL`X{HdElG<;eFue;oaj~``xc33>>{fx%?wi88bZwc}?d%{?{Cw6P0 zz$u%C;!c+*?DAzhXgWzczG374UkK8PD_;#C{``+coowd0>z0Y#(Qhw`7 zjIw7&E7h{@g=kqfQL+oU2ubzPaL~<=XK>PNk1XSlesxnk8D59shw?D`_%^A?D-Y&O zRKeF!U7miqkY?D#liYq$T(eq$rFGuKs?g*em_6M4Uc#5JIHG_iP3RwXgAWgU%f625 zi~|?cfzg`+wrZ0MmXWXFn_ds$SLq^1+2Rk^4(m|H!7yBOWgrgv6~G4kEyNY1U!6bQ zTatH8fx@&@cpIk8XG`{QtbYj)|N2j{Yu`GkS>Frxe3J7EA5(EJ-JQR8`NF=QAYX|d z`ISN^2>v-cpzi&0(#q)ZxErG|!AQhs^EN9QJ{IDGD>-;Xxm%JpJ%M{W@*w;!@t>3E zIp0;nTUcxt;%2>sG{q6v(O}Bc`ce+a(@5O7+e<7zDTCQRO88XGXKb8?A-qEgA=(p{Y-<{Lm3Q}_S4{cS1mp$?lBHpo`Z{W5}9j%d)V_&&DBjGgn6IZ;G-pK z$Te)u-ztq&V-Drx`yUPB+Zd|hS4w!rj(x1-8)7GptOc`E7g)S$4Gv$CixrbPOE#-0 zFpYM2M;4HmuyPHiXGY-lv)zT-?kU{t_XNIu#z_`$=!|og)WI#S&unBG-2o4jaL>|6 z=3!!rV?AnNb@wi;?}t}7wbu)DG4PQ*hMk7P*)SQHYnSjb$_dQI>NW12_yW8A-62(aAv2Wy#*PZ|nl1K{Y{%KdqZev^ zFV~KZJJwotq`Ux2r#Fh1q&2Wr?hdW`$#@3cD{qID@N2!Dl*jZ;(a*USR$Wkt@@ZQk z&U772qTR&h3D(AgS5^#K6H0t|K6oZBjf@6I=p>(7c{})b} z&E%mtyzU7bHrpP|YSjGWqeJZU%6_O^`49fcXDPKunW&x;E4yfEjFh`U29w5+zw$*7 z=F%aSH{B0y?y<}3<#=wA9!8}$ushn>*lH(bwKx41r*F20LFOgRv*J;U*W=0H-Uxa# zg^k3Gng5;gM3!l?VFx6L{@?=7lC^o8d;@GxS$(>d2iXCOY}|B+^je2IO1T^Dp-x`H z?TX$hAHHd=dMXv->fha^F!G(noh#udZ~ne@oAz99-v5N}-xrBoFBObu9E9LMdfd*+ z5JQ&g<7?X}q0P2C{LNMsztDnq9LMb8OW%^_S@Ae^Yt>MfLNqm*EZI%J1i!CFQ|^x; zH=}2)7d>OT54$O**w^F1E2IM#w@Zgdh0uf`!+!ciP{O%gO@}5YCW#^dL*8%^(01Kv|@Qw zF?!w2!5^cOq+9cz!n41*@U8YQo9^xa_mpa0=eJ$BbF>m3d^rq%=b7;}gVNF9Oe8)V zJX9RgK&+MbYCih&Q?^Ra2>0Ck3}v)`?_c&7k6y^d#i_r=?pJ3)Q0!C)8baB!!N!mAkS&_;1UstkrqRP&`n_p##f zmN-BDFF^fuwm$VO#t;W=XI*FM<*+UA)R6LbC|}ieTqwRXi9oH%-G$7nr?~C-iM)1m z3JV|WjC(a};q3EIY_hhg>f@<=R9)yQ4Iq!6=V^6wtqy821}B~BgH}gA$I5L>d z-1mOclfGv_=i+f_dy71Pr;Twn;$@Rii1BrU zWIq}IPIKM)fok5-!bz#QrU4I*%ENw7>?GTlRIAh3*+vo{S zvCqNv?+;4pU+m$;_u}T6#;ilus&{7!a8*r=wC80x>|1*p%1Kk4Vk3uRDmAy>kf!kD zx_on5HOqN&l3iUU$Fa*Az(v-?A{VOhGU*<-PHPl@Po55?vN@1gFDM z0G;EVSJZ&3qb2XFAkF_zHUFWfDTKE6fQ44J(CZr2>gg>pFhvgo)~B-tW7X6%=c2J? zXXz$xg85ftnrrpjt`2ZcLA8!*b%1*kICTnuqV0x!b<4Hr{lpzd20AExcFLfmx|nD8 z-yv8-8vN>+2oK4p(`u&=_WIKgCsm~gp~6Y-P;$6g=XUmj9M3;7#vF^EY~^SN*dLL-~b2MM}7w%zr*aMw=1^G{0pYhvy@Q_ zO;wwv0-V}0R?5jG&J2BS|9B5p)A={zt2`X?w2#302D>SW4Gm}od6;v4gjAKA3WIeHf@yDkUX)~rC+qbv$UaKgJ|K&?tHkEIeebjbq*tn& zwHDbO+Ne5BE5zYrrbs)gF2NU@Xn1qXkUtn8huf6DHYmB9!cgxwPRu4fPt|tm+x`OR zoQ2S`C9$?{8RK0;$_2N5Eod!~;EAg@^xmM!ozxESq)Q2(qIpzNb5sjH#%AzUx8AZf zP7YYb8(_Or348p2*be>G{7Oc5AuDAG6t?w;(Je@yHe(omTjhp3c8*}>=hXO*W-m+L z`$)mgr{IT8DtJ@g`V3zOP|l?smYKxMdLIr;GF)J@s{!919Ev|;-LOZGbk?6dO`3LU zKDTJRaN_n(xGyb-2b3p1Y1dFZ;nWwilGZ5<_N(#Mj9m13pCoyAdj|1i^C0r*KelSC z1I)jz=4(T@3z~XW;PUY>l`kWPHS){MO8@`5{ppSo_K*JpmOUtw zNdG+|X*;Vk8^yD(vtdulR4@zC;sZmCQE}BAjk-Ni&e`k$?K0GSn9C<&-l(>?-=G*4 zHn!rIE}5z-Xddgdw@Do9A_uWt&E4+pV?D1};=TX=g72^l=2GtUi&y$ywc$nx+b_;B!=?YBw>b^BjoAObHXxMKIz|!XEnl1h-DqE z%v6Ie<>SA{i9C=#I z(?imgEkhdd#>PC{*{Vr&nY$1=+l&PnF?c7Q_d@^Yo)|*eAGJRz)5n>7PlLCLXTu#~ z)i5=0&I4IfTqDZm!!u0~=9iaUMdvy>vHY z8?5~k22L?L{En9)+TPJc6Ztm9_svhScW=_4tUDydEq4S9s)11}lC$7N8`bix0yIsD zm3msggf~4-Lsg?O-%PsSoi=LTMVY4f-cO%9$G&1t)~DD;r5ueE^ zo^eg$?nN`8aLa74D$?L{mN`PAhnnB)@ZB@kuPqK9@dlI~EcxF=IV^uqzVF`}!Wm~z zm{Dm1jxBZhi+e4xgQ*@G%u8pT>PxV*TP}`*&XRg%G~}#_0sTW7Jfx)~EWcOWtiiaI zngqFhN5D;Do7ZQC zcfCJQbo4ESLtSr?oJr0r{o`?yUKFm*9w!DZ9SrSL2R7GgeRC81>~D^}8}_ojpZ5aa zIT+j$jd_I16~Ar#1DE1wDUY5tRjG~h@tH=f^k4*K!Ec~E5t@hC*EeF1uX*?=sjqmt zF_yn7U)@}*H`5F)B2NeVAFpRm3{5a;s5xGq>?C&FaUJFiSO{y^oARR}Sr{0+3181S zBmC?jhm*aFo97{cm4m?Vpfl7R)8;zAXih#_hU(ErSVKD#w4Z2>LedOzY?VFa3@GBM zquwbOxV2Rc7+#3kSv@5UdYz8FsDH5heXFvx5p5~ke*KXEX;yX`JST>>7^}}`Ya8O? za9tel94X9slf`fJ|NmND;oDYaG>dpKA%W8TXP2RW@g^uEM%hz)IhYH@yk6E#;r5n( z7gc$9Ve<~D3lu{90tBRaxIt(s))AZH=HbiYk%@!gxoRkMp*^g-ZC5CftGUzA!>j#k&b$RXa5$HR~jr^Yh zY#El4*CZFOX8KB7=ADKo3(tW|u{Q5{(Gea7QO3tl4WY7jJuK?y++3fvr7+a4?vEPU z>FgWn_9xpHH_ttKX2pReWo15;^!d!C-nclgH!3EqQ?$BKikui4$q{>`l=jcT=f7MS z;;F$W6*~h`M@n;Y@lUD2c5!<0j1yh?{r*tSh^Dhkkdy#XRKeCt>1+ zwirabxYYBl_}_l!Dr1_zZL|0*7F!s=!j;85@y|YX?XVT@>-Yx-t;k>rj`6s#MOmB(&f1w zW!Pho0a`Wf6l_*TKoMz|-?D{>yc^ zZ~Qv!w_ziu1WgfJ%3ecv&)uN@WxJ$VWK|HdRVL6H{?GICS6VGRc}dicsrHK zsSv~C{)sC}!eH;G{@|M^<5NlVob<1VcZqgV&g$_88)?V=$jd<*uyi}zjR}MFCpz4F zgb~(1(#6>1ZHhvR|FD#FOIRtC86sFT;{?xmYsgk7zk}Cd~dg3kH4H;PYm;#m5g{LDzzo^lTZB z-nh8AH(t`@34<2dzym>-N69U5#}r+>+dZ9a+fs(%9=T{cwTo2gxf#xnj)DE}C?nOy z4n8la=0>UmtgKHsCZ2J_^0yAkLI2U`f2)X}y|qIKostgiLlYpwmV9lGQ+SKc|6f^)2GDGx36} zpNth()eV6)&j&)=`_$_$^THupeDJfy3s(JX9~ip~hCLQ0eDDAGRS8Xy`f`@iJJnp} zOrGMdJGM%?U*(|uL|(04JsFGG%1bR)H?t!)OfbN$@3ql4=NAi3_z#2rBMm^sAF;Z7 z2J~}Z08h@E^7L&=;+bs1l-e^wBYCM#W{}6{g(e$&VlV_7J2&^YEq~M9YNkF~|96-< zhW&^4Gjgz!W`la)73fT}>%yM8{QI(YD#eUKjJ)6^g`JW^L}*cSf7_k?LHkd6SP?f; zstGv{{s9M|*D-xQ_agD5Ok{Y)AzC=MTgh+igy#Ns=$3Y>gX;^C016Uby#kANY=YEr zMm)gM0D>Hgd7I2`ia6CD%%d}6b(ft|-J>EH+z7BaS&v^DT!wd=h$(dLvUtySFzEFh z3Zt)T@=G+!sfDxRvT;eF;nOFo4TJMZB|j525F*<*@#kFO=-kqn#z9gMA5=C$ zFd4fG{+qNE`YhDv!IQnwEwUGGSh-fQdU!c{lP>5}i@nmMm(Ss8n_PG*YH*QuOdAeW z@r1z9%zv1L>Qlc0+|%K-xaN=nl+!bF{rodl)7KQu&AtH4*5T_~e8%T*so$XQF|_ME z*gqf;T74i7Y`{h|X^24mrLJrx=}7Zuk z3B9Z_C*>b}(!0qt8b4t@%f&C9?4`)0Scs2`gyeKBe(th9GP)yF4Y{d+kW<{C%^2Rh z`$^_D&ko{rtGGs1xiVwCh3du2d>rA|Lu!{|0On!D^C!K;vkT*Jr~&DdC$3=k!an1w zSGj2UXt-omb`C;|j=}f!x?JPwa~!ajc)wbc#AVqL5IwdFaDjHaMRw45q>4|q2vZ&( zWdJ_)h5U8QMD{-LGv++b#h&Hy(!!^Ouwvp9NdKh67i+wMf434rJ*Wl$-qIctzg2Pd zhcv~r!KQF0=mnoBt6~219l5us?bU7BA;zd^(ZalVAv114QkK?F*o;xh<_iwNIN;~n^UAIZD!BvpF^c4KO zV#3#NGJuXli<)P--?Mf24Zkwhrtfj~$=?98u@(~C8(Fznfyd|MBAfPCytF6?A_8Z@ zZwpO+u&6EZajW4`RZHIEBKbJTQ)UyODHIwjz;AK~*!ot7+YD-nqi$=X;q5fGpj!n_ zCvB&{%uX8CdJBB^jDc)#O@6bh9XMR7NAQvyEy8G)DQe-v_sQ~X2Nq2`&b7-)cQ+leon_MLrpw}W#JDtZ6Y zk*wqDP_#L2j{Rb_hh(D9N>IA6JAU{xb0sndDY|LS+V57c@$NEZ#}k2ckUX1 z=J_J-sp`pUAO6Eb9r7_#;VQ=IZln9aDsC7^`yD?6tp2Wrxo_)OhQ$kvDJA{%^S`2c z$_@DVeLfU>nejJH_8_;c<{q6b6i<>2pzBP^fa|Tr`dWLzIa_BKGE9fhJz;_+ruz6q z`v{A*e1S76C>LAaMRK!{aKwZ*pr;FE)U%&PB~Twf?F9@SjdT zvGYbrvN7rKQR4u(SL<_}Ym6UW>tf%nQG)&f#`k&x??w!a*#y})jQFB51K62Ee%Suq74t6s!_o45{FuE{O43$C&kTSa#1rVl zDsWJFE*>zwDkcZex%0;hp6L;vd4nb#`hJO58og$TpB>TqO&u8CD`BJcSHP^ZzR>T1 zF5gm0+Uh;MaFn$Vi=tc@$0ND;%->&H6Lg01?a#vcKeUU{u!Hc>N`B1XDl1#O4!!R5 z$C|I{Y}M{v;3zGHN7OT~$o9cS^LwLA7OwDERDoA^kw5q1UTOT67tm!?E_~di!Q&rx zAw7R37yU-DtvW4KWwdA6ly_RJZes{rsJGYk`j45*&9JlXS7>Lh%kK>Rf{6!c*75VN z7_ed8flbB7}7yR#dE^Zo|Al3XV0;T2?aPFhar+II{1!)^FqIaO!zhw;= z`6j}~qb+#A9Xrr^@RC>j8fM{d2wguH@;*Z^D6ekPP<=X?hqIRb z6Qd25fUVwW=s7`$=iM{Kue7I_TvMk!O!+orN&C07qpx&ojV-!$&jwqU4*WCinC`5o zJd*9f`&%U+*q9)6I#dmY?N32N8&mGS z(GawSBJLY^UeRTnE?@hzlvSTN&YmqY!1BRA;l#z?Y+mI{?7k`&PtN=&?n?`X?z*#J z-dIhpo?nc!Pi)0f*Mq{bIC~IYRr0CHa`Ab88+6sEfdiSX_>m8WAg?LnhuUfhHg6O# z@^gErY^TeUt6JjDKyAG6F^zS7@)BKU(roIo9dUuSz!KdUP)2L=9A`TSmA&MH^$sw} zC<5C&a6`WnU6uMehM*r&$d|h86neM42+3vfV0%r*=VYJaT5k?E*Hu&Uziv8cfDbCa zv01I{;PPAYHF!iax2iA<^XiA44L1oro*Td^=R*G7!$S--t$+(#Gr@kI0dGMw)y%LB zc<;g(@l4%NSZXy8rVP~P2fX@V=N*0UPQ)EH`BpMqnI^%6VJ18)%nmXaz2sL{56|lI zwT0@`i2^*-xJ{Cg*W;;n5r3xb#5@W#RO@@>V?WdW;<}#Oc*neuW>2v%X$!Bs(8LE9 zYuSS&;zH3KFopjUFIU`v?5Fcc_h82NrQ3la@!qv3nJWg~HH5}tVLWeJEuX|Az0Rr#gAt4qD%T$=mlFAbg85 zgnN`J<2SwO)+*FcsSNXR%97Di7tIUczGXku{v#IgFY;C|)x&|?Hwo{YIgeS#dA6j@ zhn_fyNk(3jL*2;uO*@EHz2q17%oh?JuffMlQDB2ceEu6ls4FjO*6|*FsG+K}%*TMm zangrzCD3^@K*l(IUK3D>=4Hfw$-FA|^YVh+L@$`oSBrah(uTQ4m$}lShCMInirdH3 zf}Kez+njC)3-%TAT!)^*sDm;XWnRhWjoQm*b6;F2^}+%Fe3li09<R}& zO)NTGKOk%#ZVzc+D|l%Oxi}}vhM1bKVbh6LJm$4N2ooy!NsTP_LB|p!4``ubQW_h$ zunL!Mpqf0*Ub++>15=-D0f#%9e4f4?#JG_LK6XEItlWsMV+UZCWmjdMw-H=zDCB?I z#tGYB>BI4H6+C7xn*I_@rSTBOk920K1$PSF4oNIm^mNm`7QZ?m%0WQthF4>t@fhA>y!y_ZU z;U6*o?JN0Zn?Z_4N!xhOcPpA}=C|2041N9=^nZV2+elBnj`S6#!5Wh4Mkdrd&V$`I z%=kg7nPaUhxKh_#!56i|TX|nW&xLf(G#5JYvXTdtW-4k*hJw<^3G6TE@GqN8(bhx{ zKQtU>ecgSq`8ImnYT|kIIk40bO*@Yug^0ytMRWv9;QZJ6B8B=g$eViKE`PAdz;kw;8-jk zTs%w+yWSlg`_;kn4`r-vfDHaMmh+3d_OKAa7gr`aW0xv#=F+PgAJDwr=)*8+>8Nv1 zaQO^$4bb5idfCCDp`>H%c!mAlzY$}d`s0gJ7gBol91sA zg^{0F<2ce}mY4G*KO2;T#{R&#PI*`ruOXS}ErjBkli>lKDFHnV@G8hqT%l6x(Rn&) zT^YB|uwnP_S*iv`QBPsDd}`%uA`Sf?nD^!oldCrs-&H5My~i+~zUmlT^{WfShnDi(1EtD8H|RZ6_VLs@ zCu#G#L>TgBI=IKncmwToXXll3*k!HUzUT+B%E_17b)+;W`aFc_9)lG_^|*3WKH3o5 z+x z1K0eQi^ASS>F4Sa2u;YQJE<;T5Ri{KjC_t^H$=O=@8Ig01c=|;l6QG#2W$6{#(R0H zV%r-th#2@^bN?xwx5ZC;YoWgW0ZZIZ-jl85ooUh+!pAQMfBn(WVTLa6^3NMjM-lTR zr5kHCC?C&~zOLwupQPV|_`t$rIOA-?gXN^JcvIF~C-1FX54OZR%_FW+5qYo1>AvLu zP3j{=dBwr|V{4$Ql)QuxfK#uFn3nWdG0P+$lV}dGcF|F3<&z}LNpQo3y>(fHl|4As z(=%2PFJv^lhU+0IaH-0aW3VpwO)X|0cOGNMIvC)mIbT6IRnKayUg3JGxjimxNTX<< zKbH9R&ZN^Ak-rCRO5HI}cbpJ5z#jJ6mGgC%WMcOlwv;>l8oJGC&C3h*!6U7V_M&%~ z=O{~b`L2mSXQwgC7O(L8&Rl$J;2qk%`A zK4nFH(TD$DkQUc$3{ze<#+yg$V9~8v!g!lAe38!o*U8oeMyRke#JcdGOt#ey+LPY+ zb5jI+ek}~oQ_nCXAWASePku?ALT;h*6vf~AFrG3mw4XV!ucPAeYOi(JbVx`ush@j zF(Kc9dEq=^%c|=@9UEXvW4^@p94?n=zwq*za4MfPW~4nn5x!Rt7nVWtWe!iD>GOqW zUg5S@d8jq;y7;`eHzYqB0vh{>RXed5|7?lD)SmvL-OL{76ifAUUpf0_L_QkLa^7US zhy5ut#ycPDU>X>)PhYEX@DiH;1P+&`T{{Qasb^qy2+jNh?BLI*(&qX(C?XuacM+pM zIGsh7>cbPtxwtiM0~=j!jM{Z|@Fm8@F$D1GivLV{acve4BubiplcztHkIA;E>`Qmv#-3%o{;UnlJ!++Dv#=1;XK6`OY2Kz56fkZb zWhGPp?C_zS?~FXD?C^t_oaVpana>c>=kqq`P#ysa@?{KsWPlet$T4f-ZH2{-6z+P& zpHF{zjD=Z}@4imW9}A_*)4!}#zlo`(Y;=~M_1O&*W=x0spXc30rTlqZYh~P2 z;xQZ7!3(xR^b1P|$45uu#vVOx-`WtXiShn+U!0Iw8U^jXbcA_>jd-^=be|&T^Zw%1 z%06wc!PqmgFo2k-q4Q+muT{oBRvhv;+^ZHhR^{Sz_uW$YCDP{)%?7VNdb~hgfD4}F z;ID3(;+!wDar9UL4%?lBbB&HkI)4+<;&nfa_Sa@^ZAh~{vXlqyh!<)NYM|oZNyzGD#&3C~ z;fartSYKNCm5jd^Dp2nZ(tJ(UgJgDhh83}DRpw03-@z^Aoefy zhZVaiE6EkFJs2g_HrPRfT`6zqE)!d4cf=K!Uc+DmYkot^Sf$aJkJhcUB;#%R@OeLJ z0+-%q)9p;~E#*N>I)8%QR=&oshlyEn(?R<3F%}#rYyo3e+Wpnq!BpE)-tEGE_H|NU zT&JUf1G|07`eY%4%WF#cm-Nxhca#Y}`&A453}y?+&v2LM1ALDo>Fxcfrk<6dcf(g! zyWb8{PM7eItO#~-^#;6uv@dR49WCrQqEBAq627e3o-Ow>!Ex2K;Qs5GurbpY9zAsf zW8y{%4@h4`9Po4N64>_I{a_WXfVNvG`y5E&bVjBwZtLsjwWzH)I zJ)912m@$7DPClm2Wqj^%QQ=&_jfXic<70_i+Y~9s%#nYfaN2j)k+h%IbRXmsH6?xR zTkxUh95Asq=Ycd!|Kn52!>*Vq6yG|aUaxQPhqWMGp$rmVmGV2|G89>-eBgO-Pmr1E z@Sf9Ocg%oT>`~_$?&6I#tqATFj0rjdXpQ%Qu=fcB`KR{p-Z|YqN0K{ zqC?)ZpQM*=5nswR@6HqMjLCqgg^@68t}$P}ZK#4fEj!Me`1@Gi}WWyZWg(;2yVci#wUjw}rZ8lC}@ zJ34$k&BW%9Ea8p|uCOWFU5Tr&LEii@Reo1ppA>5vt1I9*L{1f?VqpL}~5kLrrL{PSGP&9I$E12P>;I2R1ep+L*;(@?JRw+=AkQX z*aLda4;KsYa~o~RK6WkqZt{SOSM|AjEpdQPlyc8jCzZpGnV?SlTDWFEM09As1Nx1R zfVZT>Tsg=XEpp_zb#Im;^Xo}|(bty;d_Br~wzY?(Go*!UQ>HxjkGLSU(;!5U^VtJs z(8ZyIXO3&F%vfuJ-!}b(a@Q5&_>~u+Tf$K|^-hnEAF&Bq4Cn|Smm2W_KK4*vrEadJ zqpPn$7bzAlWg7D9q|J+aUcxo59r6e?{e`7}bMZ>eZpp>695#2%hAD^jNUKcR^^ZBY z>r1An-2DN(kH$k#KTEDpUXQuO>gHPd*wO-ilss+LnmVrNgfDLXgw^dHF$1|AYL}OC z>r_2K%O?b$@{wSYqRZFm567vo199NFSFtM!pW~k z|6||&dcxUf8$sK%FHC20exrLRhJJC!n2-bP{1F)x-7n!U!g>i?GIqiH}i*4YVJ}N z!T8kmcs;r|Y9?$F?*7n+_gB^YX|6pJANzrExEstRrp=2Y1GMng$5p!VOf%{LR9y3f zkeeoanV~(DCaU=f?_pUjwckLwln&S1QIASIc5U+Y#C8=G3Fo%+Nf(wjv$bB2@shiFD?xXaYlo`>rz)TV3V2cG_-$1>tCGW0F zn#_fzyx?|*!gPZ#IKA#cdLz<)M76|)1^T${&2jde72#~EnReYAr099x_$&V>_<74o z3tUJKt!Ua}jFMyll_i78RjLmIhV2Cw7P{6TCIyD{`FS}w@N{;LBdn{R2b z;M!?0_@%=~YB<1$BsCxU{0j5*xrs+}B5}x_CN}?&iK<3dVjz4=V1{Pw9SEn8T5?pu?OED#k>`aWI5i}s_B^pSi3S!#I+rvspK0E z|Mrp1PnE&pWOZ|$3{x+LyW=N9NAhe=j5S7gTViLlzpq@8LVPXKc>nMI?laX|rGs>T z&)1elC#{2b<2>NcD}8Q5Z1BIqB|QDz2_-vIk3FsOuxm&+=~3AZnA0)>-Z<%SuN)&h z9xTJ^F?STcKT>#2nGc^Fe~jtgw+GEf#oTXInR0ho5}e&N4f>sz^XcS=b^BY)ySuek zhTNt+^v*wEU)6FkWZFe&?S2$Kb<^iT#|=^2NFNRD;{>mYO<=s&7TVu3qRc!8cu!jT zwPWbce)&3-zKDUYwT3+VuMCEhJ~r?aL6XbsX|I}#k2fbt>SYz6tauDzO?v#Sz8Y82 z9&^&Zo8pn%9|1eZL+Jra?p01ZN74$u9+#^4;L!pWRXpWB@7}SV4?5w(z#pJj|Bzj? zlEYfkC(j(MC#1WqgtEo}SemKJJLQeQ(8mMO0-V^m#$w!-n}c8f4U@X>>w-5IKZKtV zw*0#_>Be12TN|t=wA>s){ER*@(8Pe(mxZEIM)_!~4zPRmGPrPA&4VBhL9hnwfsfXIV8znR6NCx&Qn^xpa-ps@FSorJ3wGKP_p( zp82rs{Y+3T*5W_A?#2%N`k+y1fZ*!k024{qJ!O|nw8-d;ziVE>#1?J%-od7-`=r5G zwn|(2I6ww7HWoM6Nv+jZ_|9Gf_jO8R^&Q{gy7Rf{Yt>cK7Po;%#%8!4r^Soflm34o zotv~XI@HS*@3OyO8T2{pk(R0I)w6tDJa(7l7f4)`8^t{6-6+=cQUjhR7Sp0j-lFCC zvy@w~pHHRP-S`iN7&}HEQ)Yf;-JBgDV6>V$1kzr9)JFWfp*PxiMhjgglMmuradZ7t zPxpttX9mE%zuH{Ap5_CU`go~d0$Xo*5Ne-#z>GI0e3X>~<)cxShxzcVz$$Cil5T~# z;bEKo{3UdKZ5iy3LyfL(|OpY4Q;1De3!?%oU>+Q+DcvZ}3dC& zCF=nbZFPBIl_hSmlA)ja1lvDBjrV(ypCa2q>i^6SztO!_YlI=Uo#X&*wyNov?k_my ztj6Av1MtGIz&lT<<`0{p=9M!71z39p>~xaBa;}_Ptnbejdt>QDRvzm8C z&&D6Z1v3>mKCFQSpQGQ}H+A#QXn`yf^v^}Wcr6n?_MoZi$CUy+Av%fi^xRIO=hk}C z9^uT6N|@D_L;sd?-l1t1F{7ezyk3wvX&jwdmj^=}`5EiJC((Yg9}>$}?4);@-|aq^ zKMy*x&m7=MrxN~t=T){T-4(SK{{u^nFlMvJR5fE!0lNH{BE4!P z4+Ux6O%)s13N{*bBKqLXib#dql6RQ-jr2lu4@llg#ZbO92OMr{aaUspx_^;o+ietE zKeUZ%SwoIbVireE4MoQ#_?wPSYDfdHeb7bcbD+Gn#sSReb1PYF%ia!Zqgq0K;L+Q3B!Ba8=)2eh{HNccTI4>x^H0MzFgekeF^$~IRfR& z^!W+uf!&D{=bI5Pyfcr6(s&yvIcdaSv~+~)ImLX(lu%{H#thiCBnHx4jrgB1^1OU5 z<|%l{W9Qx97}qinr@QWve2=~a|ILpf#Y>-dg(g@LCBv~@zX|Uu{G$c>W@Bt``NFna>yc2jcr*k;RG=NLjqPo$LD(du;wmY_9X&qPs@d}jV1W& zc@CcbcU-c4m4H_$E6Q(;CY%12d=vYNd2pKqfgO4e#?MZ`pRwk=)f_XGdL(fPo?aBE zQ9pf4oy)oz9A$E2$`|(f3Xe}VG0(d9_@powU($2(?#=?Z6fzUqo**6j*4CyNOt0qS@%!3RbTM(*z83LwCvP*ipjJ3t zUjxg|r!nuU_xSW)E`E5?ReG+y9sX?E3|W-7GV-q@jLhpZNwG#=`MNLM+^x*$M0k&H}|gh8w}BHnI2wD z`@;05Il>;QnWeuY*-p~xE7lZ~huVP+d+84^pZAARHQM|?;`Se;ozPalM7AO7AY@bx zgf)7m+<&Gcl&)|hfxTR9A$Sj=r>1;zNQ zJ9uu>;^rNb+RgymwQGQEyKgL$JPRs+%4>e9C7t_o8)O}W;nF2@-i|rK9P$P4_-C$g zN$Z4(OTLk(+lr4{DTlJx#XNIJhN5Rzf0+BCI}D7{<-3xtu-^my=Ion=wIx_V48H!M zj?(eNBk=U`2IzUznAa|HgfBzrUa)t7V0m^uzVz@wv*$DKI5@~*)57BBdV6TaRhX&T z2VPln{?FGRr~3BC)?qgU`H;JOam1bG`+kSN2eCz{2b#_%{r_=CSU@#=`rHM=q3lc$ zJR%@KG~pJi#~W^MLm4o^_oq0FjaNhMtM)9 zaV?LPL#kCVh>23UWKvykIYoFNk4g}^;9YF9QBaISO4Fv_3+>^m|5Hlb#_H68qa^g zs_0yFv^*%KC6>VC&o5wbFKx;g{Rk_=lWEV}g73W5R^^~sh)brYi#u9$gd@eDc%0)0 z)@KUkC7mwfvqsk|HTN`OO&sZF!?dNxdds0yF%f#L)8T~^O>n&tWjX!4ryOf$kA)5S zuz6(%&hE8UnKl*RQ7>KTOxN|WyvQ9yQyF(8UraljVxD#QgmTh^CcNvNhqD{IOG8`5 zL0-iMc)dx7_ity6|Gl8u!n)gvjuTS&YjZC?c;r#G;IIPU4Xg#FMiYAzuop^pOod4S z2D~v;4n2vfK4e8}WpKR-F7Nvl@bxmWe=Fi99XJ9xXZ87w7-Q@%BTZ_TUBcARXpqz$ z;KxHFew;LW4Yn~bEXIg0c_fEI`i=i@4v>Gm38%Z|VeOkeQlDd$aKqv;l!of_0pPz_{Wm)0Y{*|B-Ya4mG~- zA4hv{DLV~PX{ki#IS<*%$VgW99v_rFDrH7{P)5lJWrQT>zOU=Z&MGY}krAbghK%3! z?e`C)j^}xw`@XLC`}JPpL)`m4%ECqJi}bLa2&SW{muKH->Jg)C;9)CPY*B%mh)-*C z!duMEw?t#*2b2};OJz4fkiEeX64tBpu}^m32KAx%^vW33KG`zfbGbJS7!k>Jz3 z5jtC`@Iz^%ane&qOig5x4eAv*_1#O{bv#Avoe+h+9u2}1g`Jtrr~VK+@^UhluOl8)JF-G6`3=3^mV+&fl!b$B|*?Fn4@KLzeXy@UZq%IIGC zm1S(W4OZ6w!JMVK{P_+wct9TG50k9e_!uvc3~`0;%`_wJr-S(ss`%$u6#H(R1jFry z!s$^uynK5dct5)cv$+n>P$ZwNH|0ub7HZWkoFCQte{JmQp^oz87B~>s$YPQzkW=<8 zd8L9_$Z|n{#sUcbt;Y-N`r)RdO>pB;S1y;U!DsS-WjWoDTpZyAH{%CF^J^tyeHvq` zmkNSeDs!TI!4jI?1@|2wmZ(g|9_N3-<3HN`&*q(&vwtZ5X`i3lm7W1*dIpBCnj`#F z%7O&#9~~0T6#H00%Zs=COjLnPwN+34s812jKIb5MQ=aA4n39e;=d@eXksWfv zi0zZv4eDzMAuqbm^eN)bpbY4HCk?(FSK@!pg}~gc{b8z_CjX~Nv)L44xxe$5t@*4c zAO7nVo{-KJdo5Cj?N3VhlJ=d>%dM9kZ49MXeu^3zVk2kBE8j%j1#+msDYu6A5yNLa@n0K z@$XdXMC)~1x^e+^)-65^5x!ly(}Dh|b*vfw?0(7;j*yo-fpRD`!(8LL3HDC%?$9wC z8!vQ?8H^7;TQh-IqNWCQdaju$o+z@y`xo!SyK`o|GQa{7Ce`rbEti>(;Wl)+?24<- z9A(`Ps>Achk`5h<@QDK3?i*nsv6y7b$Kcpuj+mFrB96Vs4ovrqI*Zi6)D_O<|;>DvLBmIuwW})4ByrW6F>iD$*UW1 z82Qci{ZSCZ?-9>@sy`Uj5hF1^9v}NUEoAo!$R>dd@sAeY9}_}Q@TSfkq#6aHXH&Y{ZO!*uE6gMJ_gUNM!{H9 zZK@-(fZ@+;_^{Q*xhH+~kI*2*0}_&2pUp=D{u<`u0((gZ{Tv@KRC~TaumxiVNIf*=`-~GAsr?q#js%D@!)` z3-QFh)o}mv1mViF&v1#n9lo?*8k zMTswN>WXtclu>7A3X2+8g}2ugVAjh4;+x=WCFJ4}rqN%%J*b{eHldsB$x@ti6@lu{q zo+|s8^bhOEf2(-ZR`m2d0*eYr_sH99{&OTA3?GW2?OlXf5oz3O*$AHU>I8#PBK9c% z0jC%IWl8-kVKeouoT`!t-+Cm#`KH;RCQ>#zM;*Mqiz$<5B6D-q!MY*!(C~4s^hM`u zFwp2Y%pR@ESAEw-ZGU0{r$!3LW`=_L!k+M}uNDtD9*t8Khho3WC2ad4V%eG0@cXL& z2`)|9uxe5mj8W3!X9Nv!?NQRXe7Tpc*s8hJ=tgJAN5UlW^^gA4SAHKZFYU*V477k8ck(Q;Oy;|0 zJJ$QS;*ze!h4>c*3wCUPu5|vy+OcTn<%ma*aLHe>8n^s;iC=0{#eA1|jNI&qZF7{^ ztqH_>U0%(v_>E`x9~#JapD#k+=&Mp?TV?)m*mL%0;c=$XSr0w!8{zq-f2^rTBW1OS zyBMMIilyunDr1xhWbze!yWhfw!cz>jEl!#5cMt`C9Y0v)b%G8$(o4@JM&YqDD6 zz-OAj;cQicU>ErXLY`iL!((;1N{R-&&!X?vouZ`2=WzbSU}eXB+4(ndzixa7ps-Bm-TkKScTJ^CQMqaHgn+=P31;eh;xk)rux~Ox~?+do|$N!4j^q z@1~@S4)LYuzTrmWuCSdU-SBj#GIqO^%I+6dWAxqvvy z+)zu`Klf1bb;^UsLA$d$w_Z98g@9rBwn!$7bG*m5Z_eq^#!*2DnDo~PNBA|dp9?6v z8d}ZO3%4`#{H^%a+y(cXh!gIt)POYq5?<*aCoK5*9?p0$7?!QhZ;p?~&W6DlvS5*P zLW>u)6iGYo!dFhD@?N4hKR+y-C9Sc5Ejy|>b!y6{IvdJ!J%~jX=p^ozY=^Tihr5 zFGBY~f6?Y*9K@er202>l{9$z?nqDfv4{FI`t-J~ncD(?D`NVLz*$Cl@@i5NXh`Y90 zfP-c=cMiBIX@1`qo>hM0l88E1PVejlfqd^8zht$&I?GG$6k@SdN!%8?5$5Jkhp7Ha z{F<2-ipGlAcRI>GOt;1@n~Px1#=bnXmY9ka#Ag4ZDJ&SZ8~V8qfh~oq{PCYo@}Ja4 zW;nr4+_WkJ9-Y|%)&D8+scyPx-=K`&ZrzcL6VrIy4zc4L_%CrJ8Z2*xTuwQCVtYj77Ch*o!Q0I`%kM5M#D;4##0!n-*_69ff%_-SFgtA|{XzGc&k~?+RKg#FX9w^WUNH%}Fn7paxYZIec>hx(i&u}Oj?{Z+X{=7je;#6 zw8k%X_aV#PoNtg2_cE=LuUekT>^!&PtyRu=dTt_Xv(khE)S+|C*hzTyO$7?#tN7Bg zE$oS^7he19h=)3%B(C-ie$y<#U58JL;i_?{bzu;;XeqMJI^=aswDn+w+2o*%!8wD3Ve!2 zJgS!2<339tA=iRF!#$OJWP%B6tu~aOB3<48R$1&jdK658Zcw^Kng60$`nku|e7<|4 zY*~I23glbXzhWbfxfc$t#N+VKQs60jl3=Oa6O=B{oPQBO z23Ahf<0ns3c5+Y^cZnDvxpB1)#y!u1*3(+l5ztw_n>29O&TMI2vp4M6F&KK$eA{S) z4xLSuv8^y?LhTzTitFn)Y#Cz{s#XlCu3tk)QVeOy`&={c0 z_x}jzpEfV=;Eqmvt%fc4nn3w_JHViDo{N=1wZ%Nxx>KLue-MQ)!`v|8 z?lvKxy1J?kRdYvsE2+(0E1Xi>1ULJea5eHZEzu;uy7OfgI;$JPQ6+rdIhEC}twC$b z4otBdDBig}9o<*8(~eM&%M*9wiB&@|j4}2w+|(_BzLvwNZI6J$GYu`#@#c5NH-Tsf8Cn^#ZoEcPF3JhO{claByYY)_b_`rgK{fZ zD!8=k3mGgik`G>3gogv1#lsi2!yG2UJL19o&{qSWrPcgaw4!W`>>EZ<#(DOusbZYp z6|ner8g6b@=2nwKVfkfCC@a^b4iXCp%&wrE%3PVdpOIXdv@{aui;V95!Np5qC}m*F zyoeQcrJA1)u=Gee|BaYb1=uS)Sxk9ZP3N5#urG?Z#}CO<&@CPmcN_7=_sGvr41de# zHzcbrn88%>6Av}|%z|$Bz!o|itg_JLUc`B`8C=azs%iI#SOn77Eg`EJ)g#3?GYCc`$JWn>`h9(y(wrWqKG4QSAYj z614booOs{Ai8_AikytERt9dUV-0IDG#QoSbOPqmSsrr9X1+7hcP(;|HQ@!cT}j`5I>!GyFWHmHK{xnjcp z)9WfXd{l%UCsoAjJw`*f@!h~NgU*;Ls_>^@C6ClikUdZOjyL)g;{1)aqIt?;*f@0$ zMCnuZxqmWDR`&#tMs0q<&jJ?puHXq?uX0TbjpSq3Q_kysw0PsxP54Il>M&gm-ZNYk zZvLs{f6h;r{2p|Xt9^~-PrVd)!C_TwTkr?^sJ&;NVKUfzel={Md8T`n1)P0e!FMbf zAd&a`0wa>Mz`#tKk5{MJo!Vy6itN7ZO-7diZl@P(cVfGopWMX)b`^r#>kEC z7rK0gaSV34?S^}2Uy~iYMOlX9lsia_7t*U6V8r)y;@a!-nXTv0+#?88-+dJ3o<7XG zG%oA#oF8{q$JWe77!+I2o+-b>=5V^(1}KR|QyJ_ZIv3vD)#tmKqwwk!S2PdXCX}wU zgsemK%tTm98x;p&{ih~4U1!3>LsUS^i~RhNnaq!P=~lm+;pND9#7&CaxSTj!NDEHNQlFI29hKM7+>Gm3+f$1)06_58Sk!ve-G(#J(|CU@$)o(jBym zB%ZMOR?Cj8& z-`}yB&ST@&9v8!pzJU<$7ql-^h>zqr0H?rUv^<-2m(ytS%e zkzdK}a$JQ&+ah7y>>aSLf##w{lkkI06gT0`Z(jD@;fElT7WBlh&w!zE3%ip0t^*9IuUo^_pSv z)-cJ-bMJ60c_0_ZRnh_AKX5w%5y&MrafJycrY|x=V%1b&&OO4(!;Vz{fj? zY}@D#KAJrCr%l)yS7UidaS>YksEUgJMpJjLF?fEazJ^v6s0=LU4H5CO*FM_R@74_4 zb;n6vmK=f0J@&v+KSl0$J{eA#kAQzhI=q7J1!-#JC!hN&xAW?3s8c@#JH~79$VGIH zwXEP#Pp3($lP~h=(pY}goiYo=;a}kO2PPD}XAxH!j2yWdqO|q-?TN%}zg5ncY#bnw zX4b>MZCUUlLz@fa&9>B`jM5;GOs5lV=q_h4p={}+T?TmOtqR(9ie*1rk3+1rD^#x5 zE0igv!`m8N{-EwW9#9U#cTt~&A(}_{jmD)N z+NeO>vrh{tUn6N?(vn(y#c4-rtSlA=a+m;fz+{F2e-IOcYd*N5rEG^#re_7mZ&&bp zFG(9$SmTFY-{4)oDc?8o031(Y-U-IO>3iqrQWoLOfgXuokV! z|GzEXMhx3C6OB*&f{~*QsAKvSZkfFYhfV(=o#;=D$8rbCrq0TZ)XYrnbKp_ymh=sY>h4m~RB**@}<;}v=)S8Zoy zUv}b2xxS7Wix{Pi&sG1IyD1Zj?@pwgr~toZ z3f%Bs24CVngZsaUWv|y*f@?nc|98BQ*)e0efg;S)ROM#^s3&D; zIbS+VK_*0KquaB%x(>0Z1FpBhu)WV$kcW)udo+LYJT(c(q*lvUSy%}<-om6=^K zmM@=QgwM?uiH746prZQ{Sh9-ts;@{t>D{04)7+!y=w@6*XVg&B6QX3zTTlyn4k^UN zYQLk4*77uPJ+Msr>e6?J{1OXq6}$4%3iACrmvcMoo07gh{lFXF^QGl=?A(yvxN3JJ z{5h`0gTAVQDdi=*^wJdeFW3YMc~d*|^O}ke?q4EeQ;iM_m}7&!3WeY{$&7msC;$JH z*L=00DeNr|f^o}TA#8^l*F0s055q|VTXUHUJ;QlVD5G)SMQ}}yg0}A4q1;26-~TiU zmk)Kpozb0zT_;a-AFE;XJ(x_at%wQBvV=M0mA!J#L+~w4gq9Xx@c)mv z8BbMVfux*gMK2JV6K_DDdr9zgni{_qH6GV_xZ~0f4+Z6by^#6b6t*~Pb9s0)ejhv- z%Wf30QTHvu`{HY!(R;06+BX*r&+UOR%G%s_X&_$VLvUx6n&dh$gspwc`GB)0gr(0v z!t$E?u!A~ezx4TlT{aLS(hP=c*?eS%(>JK{bQS9cSHeO z5U2_+mtXVcI#EoYJfE+OsHfZSv+PyfdkiCgMNFiRsBprDcuRRumT18-$P(^QrobeO z&J|AEaCTn@)P9n{W|(TqwTIDJH_<`V8mJ15F2v+F+st~r(#8YBe*%vQlUOvq$AzP) z+xOTRQFUxQ;s+bF_furr+bp4O^lNVaejIUoy2%w3icxXV4QVsw=Zk+lWb6M+Vt))( zVHNT7d$`xj%pZ}K65rnVT6gIh-SuF#aSqJSP~g)XEuqiHGOoPKgc+~xCO4*hN?#*2 zaa0avMkX7BwYCa370Hw1_nJp;jF(Nw)>m)1jX`x~iki z`QOm1_Xn0sx-@^zD)9Bu=igl{!MTALtu6f}p;})--z5ti`{;1xEvm37>ou|1xx{{7Ys40iz;5Y7RziyPQW{F7jQYH%kS)=c}1BUehs-UdtpP~?`q0WOpF&+ z4{U^gbz<$!iSf1;g0V#Fl%rlB&t%EM8F4pNcvfu zs4QNz18{gW8@eVK@Eu=b(V({*4%@y<$Z)WNjc(-~XUp(w1JT~%8&t=3=N~+^ZvWS@}#_TcYkptF?e$*_msvau&GlX@XsS|cHFx)HYcFLa67!``<3;l z_rj9i3*ETw3}ide`IHl`-yAQD)6)yla~1uU?}ipy2X66I<(@KCINs|u zf74GvW_(#2Bj0|9oS&PdGtOUwZ^@}(S*Oe!;=&+mfjJBxr^V-GQhseg8J8WMD_h^1 z04kdn!;VYpJmWL<@e#w{G|}9n(598T;tTOy=?U@n+jn5^{~RnXDe+;%E`6+-1{0f? zNr$cf0iWDrVe`PQJjUD#_P#IU12u0-X0GT5bL?vQz!i0D`@BBrMLWs^p5%8Wpa0lp zuX+A64Z%HWGXzYY3XPz|$4SQH;b!WlF;izMOKtJti2~@-WX8w$wt`WQ%6R{?n!@jd zUGy6(ppFA#S#Qm!t^p&75HRZ~tTph3xFZ_8Q{yJ=dw2-S z>cUulJo$&GmhtMi`9jz6Hz8zr5ZCbtAOep@hG68nwbHb-X1M?KAUstyp`2|j{{B4}Ew&j+FNYbx>SE3(Y_4TW zX@jt}>L*lmE@V?nRN)u-*#D=Ks!F5S&{P8H`^*x{m8d9dNO zB|mFr1s`{n@rU`DtY5YZO7H)J<#*<=X^*w#=WoBlrv1+1cq!!_hyf*u-^B9h{C_va zo>&|x`4{&QPkRwJ#Ph7Ezd9bzr4PjAE{g1xk`-L@p})P`cy{8ViTp~hVzgg$Q~K9S znfF!tf1L~&LEpbmOS$8lFS1tGHuMZE#Fd*>#EX6#K;Li<_>p&IOJ^(iH=&GoerLj* z;!WgPor>|<12xh9$XJLe=?cNaRe1L}x~Gt5d%==;**e`eB;GYnlnoLsvLoQ_<`8(2 zt;qZ4ABP^hMQEeFaE%)EFHm>DnBO#$w9bK%J_q4Lr3SAbt_E|LyzbD+!rn8_fcbF83nYs?>RgobZO21n_ z`rS-fyzqK?6KrTDrp+onZZS+pzGqPpW|ohT&Q3qV%TgA1=wzp7ny6yb2>oilvYCdT za1ZI&=^iTLzAS*!gjryH&47pG$Ds4%!N^p12p*@bpqR8`QL?3UiUVVy^ZW{xY(;0;>SxNAr(yR+X4dUtxw&$_>qohmhvU!7BokzQ_M z=fk^U?n)^vny1QZi7Bx{`87`;qaZ7f)J8D+4qbO`k}CAh0-Kan(CI`gF#4RIMpw-Ux=EUoJ4|w;HdtvBK6Nzu?DdU}2;c<8sL_ zn&Tq)FN=nNX{4Xqm3e#UVYJ&CguQ>c3De_gZaK=mLq7v;Ct#gLE1;JW_fYH)oz?08 zVxdG((>?~qVKcyt-lL_;n{mhtH;g+K#*+Mq=d4r4*9Z#)(J32j+o^jcmptUbr~dRAwU2khynwL;d>JD_wg1S|ry`R3M5 zSn1`4D>T$46)#BZ$QQaj=eW>tst#H*@4>$iH9qZ01n#{MjP94#NRJ9FFjVg#RP-|8 zd!86VqzQENfo>aYk6Y@0z<-W~ti3=-&L5NC-c3!k{;3LzYfAaH$B}I4_NiFb;DnoO z?AYQ?gRr>#E_@zl#TUo+hxzx)_<=8%nZp|ww08OnZ7b)nOW8Vd>(p1+bHre==M7b; zQzPGa-X<2?wH>7=3h}1PN+EMd9a_vQAU^V0v0F+!4vn_P2^Na1f14GYXfNds&&IQ@ zMW*r!@-WZx%a#VNr%u_@`%K$CiLJP$3jK9T`5CQx*|opFQ2AgX`e><&!r6^5?7?iP z@+2>oZhv4Vq#@+<8S~Io9%@;PBloL|x-R2j^0=;$FWzm910cdFxNWwqhylc%s8Y|5(A;&Sm`Ioub@rA9EnJ?g0EW)a3RB zYOv!eJp-erOKh%Z@cB*Ad=_;XWVWjjC$=-39%dSc?gs{=nrD_Q+_*pJ^(*7P{t1HV!*B5A_BpWmq{pq|0&(w1SDa{jPOzOC z!SDB7+_ArIa@EFj<&6+_w21{3)?s;F0e-)!B0e~Qz`pvymfnVZR9h4d1P82IxkV^; zBJTI-vW~m?yIC|-ne`2fBt7{GKV5lTH1%hFAkCz`*#6(-*`vGp(3GC2P0aIW{m-!9 z&+9PbLjfMkwiDxmmSV6=7hLtKJE!6!TH>JV|m_#g-xBY-SUmAma% z0|WB4n%gVL{0($)l~WVMIc<_^jl2$tMJcdmtP1}fvlsI9`$4medRwOVhd%UgmAsfI z>prHte9+Az99*+h4E~h}Wj7bXof>s6M5uv_S1F&h)!ZZfWjn^%Q@^w4DKT975j-QF zL%~yJzGsde8il2R!=Po-Ms4aztBVHt{;qtM`v6GuE92usvL#EFn8Of{x7_DO9a~vr zhNk(A@JX)2XA?VG`D!Vz`lKODPT2~7diX%Io-$8)?2U6%hv1OQ8qDs+Ae4I*!27-C z{H5~%Fr{9DiTAYx^^GBrd}=Tpw^ip`vuHP0)B;KV!1M#v;P%6sgw5~I@Ncf}JgW9M`(EaS1D^ea_-Bgz!ioXJdoJUr4+uiHC&$3& z+jPjGZgk`D&A4KrEAER7W7~-_o+%Pvefa{xO5qmRL>z-lU)A`yf#cCs*9G-c?hDFp z`=OJm3G{Q*;dX}-algb3M`%w4%yi@*dKKcr0%vim zhZ?+|T*3`BHZy4XjhC+#qT1+HLjQ)(cy%RZ{Z5?|>nt9k(;9zV{KJkJYWI-OrtjSS zez&BF#5FeTf0y;rJ<4js)u4n}&^KSz%PdQO&$BM$mT+X&~*w<|UVOXyCQ%-*{msG2*-^9{c=M5Z{j8Mu5jWyL z(GGMVc?GAHc9+L17Gw9{@#60M+wd>q07Ng;&57WfdoSwHy6IFdfF-MwMPU#CsvPY`zz`0mX(O93YZqwizh3%U|r94SZdHKSDd3K*AJ$yfvpS0 zBjuDwAbt4XJ$l#jKRDIk6@IFpBTbHc#21EL?>HaMbvcbrZmxLOyb~Y0kb|at6D+-< z%VTHj$qj?3m*i`rc$z*#f8x)7{nwY7ZzOI%X{NB6OU+*Uz~>SV5YwsurGF-G?KYXW z|BPY79!T)a<{!jJsb?vXJ>=!hMd&o&T{L|V1f7pbK;){tdz~75n@ik&(!=VWI`}z) ze8YzVrDd)+VEMrmP>E9EF?8>nFvSdR)oJm!fj#7r^!a3WT`u-teH2n}E`X>8%7~3u zhlsZ&yrtIMBlO%K)Nn6Ex0X|)(%ny>zwtRN9ihT){_3L2gOiZoZ>dz1c3&$eM1u}_ z=?{_CmfRxl;_#1bys0_nziNc`O}gBoNewK9Qy<4M4IyUkHn==&N{8-^`867=hdbiB z^UADCl|5#>eF?1tE%>qv7BIy5E$@|ci818?xUjVa5|$uqJD?6elvUABa1}DU#lq5w zTVPMUGS@IqXmwt)Og$86s6H81YT9*|dD zoxEOO{iB#-_H=9;K|MijcI=C81CFB%UE|6bV)a4?95dlA{mlN{rZ5yjRR%)E3k|-H z_*65+w_LwvwCr*>efe6&B8;2pD*D`2gXo0fj$KUKi@#VQD@4^vtA+Nn_4siMG0CT$ z7llO+@kaSv%qg&AyYKx3WzA&BSWCWrPfLJ|w>+jxo@8STb)#D3v8w1}Y<)Yu7v#tO z_PJh$Ie&5c1X^FRp9MMD2tlVO#Ieb zW)drhS%u5ME6{*XBfo#2BUfSAX7Ui)690c#33uoTlF3V_L8Y}L42f0ZcIzgg!PX%d zH|`nxPdo*?*E>S4p&mcGB^vh~8HDTSUY6-^umHV?8m{wcB-^L64GZ78;>ell!nsM2 zJbc;0jvj|MlXbCodn2ga`OdETG~f;WLR|hvRU9_^E-V;76BH{9xzWj3eAvqo`;~7O z2GR5899YA%RvEI`H1eyzEW&~BbES6E)M4bd60SY+GV7Ps8^fn5VZT{t*~_5~82G0E z5A?Se9TisNmwpNu^tl&bLmn8{6*YXjROfcjZTj-#F-5pNb&(ihuMRC@3Ey#X0t<3_ z%#B}Ub?DfOf2j!D2IGGL|5#90fIJKYtvX$PtJDHgd%Wd8d`C!XcIwN`j~3z8+@s=J zcXe1s-;XuR&6w!(5A&^Gp}`oC9*dX?eJnko#@o1|DkoTb|z zzp|?Fmhe6MEw_3+QrI*m7;MWVphkSZ=`+5fs{uZr50LskxdGni zQ{ZHo3Li6jAB>r526Jt+x&3HM*njmcFWtLIP`Y*$P9I+Y2KpLYhLm}sj+^Mo79Pq! z{^I!8g}C}mig@O69Y`CV!=BqJT)n?8t_(W?idPp)L-JZ6dTTT^*c3QxbQAZTpbJ7gQ?%jQiUfajX}2%N9^*ulMs6G zG@tp@nQPf6F@sU0hc~PF9n~0y!?xhbv4iocXBZ1UmIKM`C=8#j&c(Bl_(HZD6+~^R zWXAzmsND_LccP5dhT3p4{n%sr@u1`)br-R7El0 zUvNVBakU;adgZ~Hp6a}IMHKRtLDVI&R_g!w7wpd14+AJW)_B;EbUl|V>D01gq_KKq z-tY;%@5!=8X+R5UV5D9&QwjcxTeAwVld-S(d!r+6ZIpv$sJLeFQzt~Y#z{#}U{`LkE(=XKmezy4K+6>25? zi{@9Ed~zpw;Y;$})v1YdE^PvhdOwJ`q{x>&_(3`SFnqP{oN(xh12L!Hz?_L@ydEs! z%IzAS;bmC^@_j#}aqjh@c=qj3*@P9A5bjySAMZOQxURbc=O66{=|@ez&`|>x&MfKh z)r?twnJbTv;?a+ZJxE;)cM^WUN%eQkbpBm9q__;u<{5A^{h#neyb6!$tmRmw4knL^ z`Lz8YnQcFvc6tu5GfRp8u9%Etf`;HGljm%7{wXj#>j1mSpM2di1`n$Z!U=_!Wv2D! zAeB_}3q_vnblFzC7)Z>SC+CIiUXk49@ca%x;iX1h%%>gk{vJP=yJ90oSQVnfdYV5- z^WayMFMJwd#APvYxb>q0o@(16#C4$z%dBdyC^ulh4CEPKi?HnV9ckS-4G7*vvwt|@+@iniUuT5p zeFDMGOOM~%PaYV9H@toSaLJVv1NqXtB3u@6OzdN>0d6BoxW8^cmYCQ{-Zu6Xbp@id zboDeCcXk*&E~cJqj|}ep*o(i7iDutYJ@K1sD=|rbu=&R&0e%PYW z7qXXV^TG#_DEsb;CJ~$!8qvNrrJ6q;6)2opatu;F`oqVb8vMMuCXAso`9L>I53`G% zPE%qr%>7ER&9elKh+cEZ;mR9Sw7BMxnU0sZD!@<2Tc7-?L^ zOU7Sh@7|Js*t`V}N6DGPe99m!Ebj2kIL%Q7_nK_yNPi+y^0TaluORj-QfDRJf<`;nU#+0EPqo|h)WKri^-=p!*X{&$i1(~HR6BZ zS?f^D{(V+hMKf&MK5wAmw;4y;`N~IE^8tPa!k2b0Q0!s|FN;*TWI$*6J-Yv1%5V}N zjEI3PX2Edi6A_}OpMp829*{CgmrwZ=MO+a#EVgi$eQvgZ&Mj4Z`OTBUNLv~FowOeo znrQLIDVKSV|01~%tH7&%s9}iBH>kQ)!#--~!PAx{5dO=6w?({0!TA7&4lfs0yU@(} z%o|?o=qruy)C}z>uE2F&Jud6533rB+aF&mfltLBQm086LjL);A$v(J&&TL+_&zZ)M z6nJ&o9tJMc;~za@(1+Vnzx-v{)`#Zc=3mJ@2Ya%!54WLz{$Nb_cV38p63I`t`*(O_ zoE}qG?8rBKL{6=2$&CTVRr0pVcmEONF?U% z{d5C1>!YE3j9M`ctB^@s^``+}Y!3I-RJiU+dN0n>dtrH4=9krke=MlG?W}{?8oUk% zQ)Q3xM-Zzw65|i}) zyd?2b4>ibs{DyB>`Bd`2eLCz?9R^1l6#1vm8T`+W@jU2tG#jvKB=(!$0tGognA1rM zShAv$$2=S%boU`1!kuCCbBPHl(ZM}W>mcyrMrjW59Bczl!Fma?A4iRlXD%il+7)dv zF>yb5`uBlznbZw8HVWegxMF!e*~Y$EfVsSq_uCmDJT#!(_fUVz+h}lylbz*;%L*~O z?`g5_UOnVodfp1g}aLNe^xL1xeJ8dEu`yU;p7XdL-}1YZq5bL${j4 zg8zB&PJLt}8mv&qhWysK`dmq(3L^(r@sTDG>{!@1Y!8$w5v02&3OT_{jK<{ zr513vqJpExMfR-82LFt11>4nm?8!t`PI($t^B92aR zM9aD5Oz3X`kxu0M8X3T}S8T!6cOCIUcQwhBB4YT+h$q~=7d!0w9f$oYz*$T4q_Kg2 zz`Kmj!P~m?<@F{IHk$LdE7?cgp>OF0Tk?^nSF;>-**QKNf&HGk-^!^5QM8y4mkV8Q+i;w_^` z=rhC*bN;hqkN4`JtmX_%d%jK@zqS>=SRaG$dPck`#{%BB5RKI&2idyEUMyN|LF;5Q(_a}}eYX!hXKL{l zyv!$tM09wepOIf>dsZVvI@d7Ij69m{EQTs`L*82&h0&K?aO9#W!7IZO+B~XwOy?QW zGm*_OBZo3qs(Sp@B^7v6NTJq6}DY*RJw|w3q2r%cT16 zr@@|*esF}ktt}|ualxgEuPzRkz1jaAe~Z)$ywOqoq8Nbv$1CEqIsN#PG-4*duHZ(Y z+PCfNjN}R*ig42KW#R<#hqpFHg7lmwk05XG!mU-jGJTa~-L!mu@8{JH=JuxWR2-db zkHWM+Ed96~y3O7QkIVJA8NFXAZS?n+iIRjyBe`QEu}vJ4#j7iSLIH7b%++*wA^mO- zU8{Ii!xKqYn;GzV-%#jA8Q5ms4E|-|xDGG0(!Y_YJhcUeIQ?XEu3JD9dGGh#8X;Vd z41wcEhk?#EHE!CMW@~QM-0$ylp?=9NNQ*lKu?JQ84C<7}iGAQ^jW#dp9gB&h-BEGH zT~;rMR|E_3;gG=5EpA3J)&(<(7 z^)==3R;Hk#&-lH*UzlY6$-moaJ9hKcf3|<9L2@PB#4c@8R;M+G_k9Wh`FS+y{eC^@k0gG&#@=!A_-u2kssvdzaZ& zp0~0Hnd4A#>8NAiWW5SvHjGni`Pk0Pqu+d)=_vGV8ka)wS;Qp3O;JMTyp!7GT)!iSjgz3Y_fW99PzFR zCZ?+p^Ots%Yb!hSt*QSuxG{Ss^{5dO&uK7L##e*o8gqW@C}p$*DtNP!fw1NE1lSd* z4`*^!xYmSzICx$wG@QP|B2{T$u%(jkKja~-sf>l#Ye6vdfHJr5o&pAK?(lTEE?-$6 zjXnKb@zim5S;|8T*gvnFmp?us6n|x)bz~phyrRVmM_l2(YmanjTGlIdY?{yrs&{Hw z(z<&v>CGZYTW-jwWksP@(O^{H8zo#tOE{Wd!Ji(RE;VRrfp04>gUwDoK6lbZ9IhUM zZKKvmXJo5D@QiZ4=I>b+^@%!4PW^;_YY(y$i&NoAn;q=^sK=Kz$DsN1fmn3ovTSKO zw0`N3(PERgNSVyFKj>Ad4={=Yb0LVGV2nJtx4X{mefr|i9V$sQFM4Kj)rN+D#= zwvri*`#I-)M3D&XDSIo)ihl2JzkfX*u6y10=XKBfoY#52oJhIzlKAklgD^A2yW3l$ zKA8DfdNwfL(+lYb<~I%))`2V643zAgTZ}LE%)u_H9vpgTg7=o!gY`OX{-%e%kmFWG z2j79@_vtx!(Qz;;Oq2)jaeq?)LX5I>TeR%_{3-%SYv!cer;%aw2<}~jxYkS^9!_D}HL(GrluAXdALinP23H(o$@X4# z+DZ3!ILR$sD2bb%4dJrmfDyd;jGklZv;TMOf8;xVaRT#vw%5VdbWgF)s0f@sWh5SC z8C&IJ6mb#TSGs7rMy!*WhaQj4qR|5dm~>+=`swz^J)Ao94LwNp2OP-K1$gaKrnqks zdv9|B#cDH8u{{HC3@c&&Orv1pf4EZZ;sYYdUj-Dg_i3=@l6arySDaEgah%n#Fl^;>>P(ooW1UXj3=?EFkn6^ipJXpxaB zr#_SAG!3bTc<*>#U>@(`J-*|rq5|ovNJqM7QI5k4%)x86Das3V&};Q2{>FG)y5#)} zlSIXQBJG+)x1ArCfsL!nCioUysS?sMMMv$nPG~eK1}m(U$2KdQ~L4K8DlVH;CJ*L z@LIg^d^1+;Vf&%u6dA|T2q&xZkiPK~zi_!JZVIpK*0cnZ-FTum%g*ef2vf$gbH)6b zs()$=cPvq(oj2O?@}un%jrL|d*1QhK4SB}@Q1le`m^9I33>+}WLos6Sm>&8Y~C-G^jFK&9E1a53c_|U3)kkt=$&x-G$?B~n_pq$0+ z2`i-@7V}xgybZs7lO~;BlY(Q^Hc4tye`DFe<9H2p!TJf?2h^&EiAx2MsdsO1xnIbC zU2}}zZ90IymAB$Ti2_`;V|!la4bWQ5YPQBuoVH;e9-Gh$lvg-X?6hW_V{QWQ#T4hb zFb@AOE%E-4DX3DeiG5gJ#`i!o*1zmT+ngKxl0ynO+l)PTOWnk(8;+p*xN!WM+#6;W zoX5eouGsss2E6nFA}Vcy$Nkb<3O;AK4BV)EbR}pbCX^GHB58Fgn#H zE3x{11$wTF?`BmU`JhbATUmep=?nh4-95~Gvkcc}>p+&vA^M^|g6#4SiWi?V#joYe zQ{6UOqB`dnzS7IVxG$Q}kd;ZpPK8rmk)K3zLmo#nHl|m2DnIHv^J{s2$JO`u@$Gm4 zAHK9k@9&!MzU2rVIA=xEFI<%lW*H4<8Ee|;$S9sJh0%4MF&+aiiCqg1!3v$l@b;P< z9E)WBLrs=v#PsdvJvFjg@f~-@4wOvsEx}JMvvJuNedy}fN_Rf*A^u8Pxlx!5jJrm#0_Jn6D_Ax^FI8<`2Sw5%S=|{Gw6T_3+a;PHKZ{^nLz!)ciJ8;y)*Z zpjM7FI)*?eXNpF%>Y#0jTK;-dz^j@E(8@>^ylWMZj@8403%;VMcgn!-@)hR$l>^^7 zMcD7kM%37)1q0ag)x^%8@SYP@FJsvtck?jHR~>%bXFk%fdN^!bDq1R@k1umvF^bJu zPHoJF#yw-8{lG!K_~tkod6dncOn>lm@=S4hLv43$7RT61RmWUWw@eYdtGCjD?QYas zv6eqLjj?2>*F#GDYH{tUd>p?0EMC)A1haYj@MEMgEtzsnRaDQLy}H_CAFB1N#; zs6nQ_Nhou5ndH#0e>grW0mn@@fHvpDw0(mkt#ThAdGdmB0~jZBoy!ckmKFKaQQ{ z5C1ST_aUD-T}@b*Qb9VWUAPDASvbNx%u({2_ycTSuwaEXoXR`S`>b6+Q=5J;UY0Wa zW?tE%s#-|vJjBP}VE%9&8Jgqk!LMnO$D+U*IC^3X|Nh24bm^)@#ux(l+pZJ{B1EICuy|RT7yYZ6AXgs5+2!SURaL&bA*#Ek=aACR{ zsRw_<;JED)gI~=U{K5}k+VVWqp1I#G#~vO*lQy1b%EaLqGPN_B7TOXJ56&Nd-S3ujvgh zx6*>He*TNHQ*-&;8|>LBt%b=-ZsKj+QGBHlj;g=dOm*W0%--&T{n@U;daHvJ=VeEK zPB}?sKbc~}-dYGUJ1ZV%g~+ds#yf9RVT$EdkRICK?cW%^Oog%!e?ifk7kr>YF{U{z z!-s=(p=L`W6|vpSS&i`pwu8%RL43Veh*~j@p?~BY6VT~OlwII6SD9yCDqQm2_Nq=>i;z{NS|JE^z zH?J(9Jw6eX9MUPy9FPcI%HG}Db@Pn^-s@Y}tzDD362|(Pi94F~z^=WGhSsxQ&C~nh zd99`_+o!gBULfQf2ru?jk(Qw#S?4tml`RM1hfDI{c9&%eu{d_~o=k6^=v zoNn%ly31Y6Xl4w}8ZG$87$+fY56fwRhsb}Ife_|WMSu7+T>JN*=yfa)dFK5aW6hYE zv31?rW&ChH&aQF6c~QOKa9}pP?i>wkw;trBug6oN7pv#|e)5yu%y3B?^W92lkLj6-D5S( z)=Y78UK`dMKSJM!if~AzL5o_B;=9qyB>jhU;qJQ$*i>!+C*w_UATnPBtIht(Ta#;2 z8}9hS^vYFTFk>^9w+Gd@B32upKUWKm7V*6N(U}wx>p&Le%KYwa&eYSp98FAyg7DA` z%h}%3X;e!M9e7klQYK zH@yX0Cio#FKjSToJOz(4b+k{=<2)DbVVS)wpJ0(HlrpdKi%GR`#(u0+WxSz~ccYS; zJVac;kW=`fW(|7xQifW_aF{Ns?bf&J;@{Lm;Tahn&F0o-Yts473pju4Mv1rYUtF;2 z7^agReEe>P@r*0({X`Hohp~Qr$!-3A_EElH!64=rX8nXbMcB7i5&aj{f}(?__}q~l zIOfJ&v}XIxwQL4;>v|(P)|o@pK%qYFuuuuyR^Kz8g0)1inU)}@mn4gV?ytx zSTR-?s+14W#NKwK^7()`F_!W6b85P^u8({t-uAkT+wN;Y;s>Jn5RB;NMy&qivuSZo8}n;T&VAo~VU6ievbK)rA!NU^n6EPI3Fg zMA*K;3m$%#gMmz2CREnIi@z<>mRG;2Eb$p#?xV`dR}|y+?CDrHma&(InPbhaT4;^X z;a@Zu3iT0Hgz9%BPB!!L$FYHUtwJ7dFrAEyt%2ofu~OxV-?TUC8AYBL!6{DON}d@# zs3_G0@|b^k+lpGSpQN52bjeWAmQ+#6Sby&6Uc@~;60mD2V-1zFj1sm}F#M0N==Y;X z;H{n0-A_BFa}VeB+JHN)w84&jkAv90(r^n;QSwbgK|H03yicCxo~`jig4Wx)+u4=9#Bz+ZklnWoAy@8yub{ z7msjW4->=CyzEKdqZlr7q+>dPchET)7B#HtLU7gTs-He5ckQ zTESRh%2!T_eJWDm@O7(hkH@oKdnw$&kglT*Z2Nf*cUMls@w^%&qa$$}I&~2Oo+%&hMpR@nr`B}I5S05DdR}y;Q`PIZ5af7>3_A%EP9k7a8Z= z373ax!Wrp7vSn=illz^d*H>6z!!iZV&uAQ|a;vA7Ah&|C2E6oOz|;lU!VScA zHVP0wTM_SPGCt>xSgGi0C+V|%>fyeQ-0z)RDI!gl_H8qPx8IF~2LCED$y�FCaV_ zACG}2Rl)Z)%V|wu_aN32lb(7Et9D)Pz9;_cxQE8J0XQi_8#JE$!qk{s=zC2alSyI(XlwQ%LuKz)FGPrqpn|eAkou1 z{I{gDI5BGx_MD~)5~om7KkZD%Jr0VN_fo=h>D5qPlPP}OlV#t1dx*L5N+1)hL9MBY z7<+iB#OsUO!ez;a-H^(vsI;le7C2dZz_DRJ|pQu#3OV$VF?d)VsP-%VQ79=8D5(?({I)T`DONq zpZ`T&n6mOI`Hptw1~5P8YNKkfHQvNKUrvU}szYHy#c_U7$6or}Y(Q2gZQ)<)d9*j4 zh7aT!NAa#BDIEEYpu_RU+53r>R?vZ=Yq%vR*xplY6|4yz%k!iDQQ4|z^mW5ViT1Tv zj9blq-%T`N-lP)d0r4ikbTx44c@LEtOIa#tg8!49G{M`3E+s07a@lKMWv`j#e3AR9 z&p5qPt6|RDzWiC&e>8vbGrD>CzNAU|7f(3t!t-qgP-OX)3Vubh> zPoMc;FGRFh)XsV<&HTxl2wYX+fhG$T;l8O72CQV~d~aQ0`k;R_i`9D(HH*2-LnCQ> zBw*VK8xYyE@7k=I+QoX@`_R3pB+qikKd3@G-&Yv=mT@w@CEUd2j6*+RH9lRX41TMX zQ1p;-BfUc1OS}G(!?0(>S>|v*K55e5qvz10ZG*(gNQU~SCt*pkK4>xy$%zlS-L=z4 z7ZbWWtqnggA5IYS0I$7N-F-K-IKgrZ8s^}oh~7|_$Myvy8?i0T43@4Rg8Mc+hl9?Q zys@Fw&o^G&yS3wy@(-NJmQk#6EGXOH2s*B2 zE)rGUvWI;oa?rg0G(XBj302vdAG!U7RPWk9`Yo{EtQBh9i|7(;teS!wJXno-sFj9b zBn9j&7HbY+_rc;9kUFDWG)sFS$|es$^=S%V=%j>ynSX4iOPnLVBbafc7QV` zeeDIWRkNX}Kmser9pLB4O(lgZ9T?H~FF)n(5X^o19EN13^J@=;kk@EOnt5d0)76IAbL7Z3E@OF99LvL!*v~avF;(87c0TvDH`;oZz2{A zUMf+0DnrVt`_bCZ5DqS|z^=<|k7K|`-irB4dndKP2WK_D?v$4BtydMflxuKt8`$Tq zV=U_z@w}SiJUS5UK*2jz`9Z%&(owU=7(3qzR?UjRkL!kE&<|yZWSlhD2aKWm_qKG$ zW-VcS31habcjt1L4irzRhKTr0eEEfoa3|Uf91b7jhc@n`^Ct|*(|0%wVRN6ufm3nm zB6Y}QoHWA`&lx9nn3P^>30z$TeO$Gc+qR7{y1lF5@|BObNyVE zaVF#C{x@?>)|3&nH$S5@ryfW~&;5rstHSY$f+48C|3+G0BWYBXzvSmcW4tmXAO87% z;V%b{qGtiW(5v5TehZjl%DWaQ4=@xT^p3>Rp&oc`uOb{*V6X374PkTZ3lrpJgn5h? zdgp}?H{!M%tyBaw^|pm|?w-OrHfJpVtILIb*^6Bgmb=WjPial8f2;EXvZqWE|6{*n zX-`(+xckZwYpaYKgQ_9B&o=j7@4Bea^BLv;&fyk3P^SYQ7@w%kU-IXJ49!}bgih=G zfFffTCj7bCtyfEfOetYr8~!d;hU9j}DmSQx*=IGyC8{hZNN)~KN@6TJuaPu#R|CRx zGk6|21pOYcEPH7MFJ=86{@QOGw(b@$KkqoY_6oyW#tM-CI2n0EN8HP@6%-FAQhb^X zMe4dpr?xWh&8B7;*&~48(zulZPdQT8hXV0D_v>tDI<|YBxJ6Nul#hSKkZW&wCF@eW z!#qFmP7kDd3nu3qcSYWoBHuR1yq4V>+NPgl+>D56p^fHI}Cm2smKE(tluXzr# z^A?I;J+=eyp*_HR;VFLLVP$O8s)3KLucT9_$q4fGjK!*^&W-s{f_H)@ci-dw<+V}j z_((F>ED;;Yx>3aS&&>Ze1nhd4;_cVW&z$yH)Q{CIWAF6GBTfoXW1@_YR#b!Jew=jg z1Q}ry^B$ixaptl$!bm)=2UQ(2hok_oCw61ft zpXhjDISl-n)vZ?vjV0KXx(;tm)`2683%6*`bI5p-A+|r%iC%TNXtYlQ&KfA=!x`1^ zxVThwTeFwommEchj`~S1EzO1(+e9$K-~d0YXfDkv`ipgeOao<@Z*YARY;a5GGdi}= zPrVVO-*Xke`<60(8ePr&P;11+_jw#U|1{3hQv%HsY~EB^M6>HvxH&#?*yv@5tEXy! zY2h*IBXyw3&iD8vClef+-1J|bDL+(e8>PlN(r~$hqSr3UsJ5;Otkzr-pRxUkZ!1gj z>Mtd*kI1$k_OfkKJa1-##{h*JD+FN^c#Z zYI-Fp#A|Xh3?ndX_9PsTq5u&~-D%CKGL$M=gJ8J__4KW=b(9LMJ!XOd|C*q7#ck=K zI&Go4tAZB#h`2vK$x!#q6kc~7ALq>oByXW2sLL1YY~f@19T zZX0$i)`A`vO)&Ci6Kp~H-fm!Ak{=~0Q6l3`l)0iLC=?^>4R?RTL%Rv08I1-EJaj1Jn z5uT+hQgK$m;7V;?>{ zJ{VoS)xhBC0m{DZL^bm>`Ey;2wP?rKyf{Ie-F623%~xTux(ZM)6-*pn4ZA*Ub8mSm zBiv_P{XF3c_vDxc+b=kUTb{0yOk6EX4Mj(>+rI!8KE|MJkx2~<{N9+qF`#U2j^jm@0htLnT z(n;S-v1R09d~B}|3U`jsQRW-WSdu6n$!g4dEsZc>wTO4$r6V|>t)%{!N+kXv-l)!7 zqOXcPJpaLFF5jCVrD2z}wj%{6tTRVXM{PL!w1o1WETkaIk1X%rLrA>%l6ux>a?(5* zYOy(wX+!lOcb5t7-_r!?7Z-@c7aSlux<_|Sbw;)yrL1kk9|vWi|9Dy9%{S%~zOByn ze^P>9k50r9t-A2+#5bCk5kW6jGcMM6cbXFV8ACEzA1TfR*CjD7and7EwBjOs*Tv2j z)2kvcGrH>_OY3zrcvELtp{?o}y=-;nwzce_$MG_xzRe7#e?3SF16`rWE+ z#E!Y7!u;9hQ{`ZAFB24(G{E7yG+vA%!zqTzumc%!Ha+Jm#i!~e+R1jZu1 zTBFbRKczu|UlMR@#1hG)y*+5iq&QrZZUpkNLoxqs1z6Aj$geobxU6d$VeAoAKGjB7 z=*52D|IX6l($7a=LiR)~V@&dcoeG$-z8UWJzFOE~Dx&cGhxmGpH3YPI2xZnUsMm92 z&M|!tT6$ZdIEXzXw@t8?`550B+?JkD)D?!XeHm7?a=Q7auzKJ|3{+8qr4DQcdb1f^ z7G=0ki)Fbs`-gzV_auJzr8uhSZ9vxY_K;L?5zW6%#szQG;VRSTX~7NfdXlwtp@XhK zDvVq5%8zr46R@rMFm6gxfkXDJC%mi~Ze0l%-HngK2?tcs$x{O!D&ME$ZVTxCVl}w9 zr38(ihvM?1S`f;zOOn}Vx7u;lZLW!~;Pj({EQ(XO89o2uj2uEA6Lr|mGS?=5ZU$j> zji|h*4B7M!Lzf6c7*lMFtp&H>snr)gG;B2Oc-Mhl(_iyab5r!oYXlif1F>~r6xO|z z;EEqCPkF8)u0P!jAr0%rv7g=Oz}Euo-)aM+Jw1gFZ=cZN09~%3Vjrel8H5M?)PNcf zlG-UJx?+Ecf6jdAhl3kI(S3qAcm7!%p|rAF)8ZOrg-%wdMIF7$Ef}svi{GBYjIIDl zyMwY!9tb*e+3;Bo7}J-r#LsALWB|E$GaFHcT0>3hy7uBQmdS z#j{v`-tJyPQA8x2)4eXfzuTSm?x@EZ{Vd?aOl#pT#nB7+a3y(KK+1Xvv!Q)f$(*(2b`szxb`xHH40hK6z zlwM@o^}f7?8h2%KW!GdW$@DyK{K;xLZ`S8yey|y>^Vv?8G5vhkhT(p)Fh_~83;H*M z&O3ea;*s}pkNX5v>ePjs;q7!!C4zK{O2lwNM4l5rStdA z<{`hB#)mY7(Z@z-YFO&eA4yZEzK-=QgJ8Wx^(SMqFK%QUR!{!K%Q*D)G(gKx4UmgS zqV*ex)5g9<{DeT3xx=(EcXI+?v3)CD&a$T~XA(pz-{jGGZX-;&tk3TY(jfhi1RP?s zM6#{D2fg1IhY>n`Vg8FYdO9(Vw%!htgv(oC=d`D6uKk{OW?tC?{r|6Tu_}7PJC7<- z*VE>LE=6D<%Nq{4rvOXlGG5%DM!2bdrBMF0h)nIuaJBp}SapYa%a6Cv-wb2U?b#mO zIn@gN4ywT0D{QC6s1aiR+>(~R(-m|ztEkro3D-lJ^=dpe;%2cDR0Swt+mI&6n3nGT zx%?t*4jSC8Zi))V-$y@3*qq^tA@)l@TWL{Sk))N>wm#y#_p=a-S^k&!e7G)Zpdr`*>$s zC{9$?2I~(d82h*$a`dmd-Jhl>*bc6wAy-nl*KC#=Ig8v-+*a2%?M(-ktFb2bnd%66Fcv^mk|R?Z_24!&wE!b}8V4y^Ub>GGDB#(1R`w zI)YkH`@k~SS{k=Hnl$@_O1>~Y{;alZ{L0{?ytUR)Y98B$Id@gz(Rq2ypH&Ynqhk5K zvw92fog*oy<+|8uxrm-TtwY^|7BKe4Frlcdnu7Z3b7~t|@4}`Y^!8TpJH1BGY8zQH zdj$ORJbA1LWz6B_{`}cRsTeia9{)sXfx@c8G&RhMy#6{%$G9_o?>pwhxwnoNVs=p6 z1t`A$YO;Ffb56hb7i+mT^!;9Trd`jj?zSXNg zy*t&0KcC7%PJ{xcGB3UNM?LYAg8R5ib9}eo{=hpid6|F49h@1&v%cAoISt+VCO6s( zt55Xn?srY-w4g!DW$8*a%eO62KyCX*u*mTcYj%W_&P#TubsP$P7kLU=^UBGkW+G?r z$NXQLQV_ykvp0K9!?;lK+G}?)EG71l5+ov$1-~Y8vV11|4&gB$r7tZA_ zEJfpXUz{{j7qspiqP>fqXjG4MaWvakRoKe7yG-BY2gp!R)J?QY(1Zm^8H_m@PTMTE zNdDvDduG-{t?LEe=wTLYaCL#ANAdiUxOuex_D`H@DhC%>T~x!Ev07Kt_;c5{lH}HK zis@Rxd-v3!$4<5QDQBJJfi2t38Bq@hgFX0+!~4__@|>L#yP%}7?Hnila~jRg2Ve6jnU>{nP>;O&j zDfnysBpm0b0XZzsaj{<=+zz&u&ONR#a7!x5c<*}d(tsk&{*j0ZT`I6ER{_hz+53zN z6MbE>A4mOCM$t(PXna;i=EVz1?4$|fr#wJm_Es#Lqz$bHOtD>-F`|90x}DgjFE}_= z(xJpO?)5G8)evR`^~b&EZ^Co#3;$=_ zI68Ey13x9c<;&lhVlT$f{;y6e%Z^69MlsgLDnYNztrXzzP7n5u;&X2@_7wB}ZP?^5 zJ{=?`ZbQ=M`04w5?CKkXZp!G~=!MZTsE z#=ajfjy61piI11zUzSaI-8z`O@4M26Z4Dw>R#!CjZU7zMeDOA|Y>FRXN!Mp-^Pg_@ zpw8UGs5;94ye`zz$`etf-aAynFJigZ!B==i%Om`vW=mS7@(o=+sX=R}MK02}msq|M zo4K#7TgMOg4Wo5QBgkzxFW#kg6ATmgbo(E2R2A^U`nqndOMd(iFJ5CA9RKt{|4l0y zMen77=^w>UWtoO~)`6poi0>8SgZ;8By0y+_I`gH}*Fme{E@^o}8cNx{YhZ&m{J8dz zh8|u(o<3|x-oR5R-qb`!KQp*_-+Rz*$vMV0)rWNfY!|+w4n8efAc|M8gK_wWA3xv( zKVry0dc5x&4*S#t7BEla)dTe)Aw995^ghm*HkS2~bwQ_ELcKSC!VA~UV1$n;jsoU) zwRFFIyy2keX1J-y7*~yQ{NHd&UHtHds>f?)^NxCpnk-fgk2)g$uReYXj{&2>ct{j^o zjzk#>)4GXrA2ea{OI6|5rb;TiS|+*wTps&b)WPw`=Xt|7+2CF24EtEEWi)#}%{uV| z)fUOYgZs9^oWs?0Ja{4(=wXU75w+m)BaQEC7)lM7*^KbP3O?eV22Clc!J9MIOSUm~ zaZ;Z;7&Fs@zshD8t2up~%XlNsAC6K{4{OqyB=CAHd*MlLZFgO#*U9{SvNF^tOcQ;b zp@5ee>+kpvJ-+sq2JM_3hvs{IByTP^W4_oQi(Goa2sUR~9=3;!F71#6J+(r)_@^M> z`H7ES%=*~O^VvR1mDlbYg`G#nqvaSy7#^T)CHS{l z0Y_ETf=TZ*_uord7NPmTZVeo@GJzsZ`;hFG5l|JJf&o4garF)jXlDBe%Bz_7FVR}+ zc)O3V+q;r7a|5^`Mt3p(Od|f6p$b9Y6!6+q#spp(CW*FOs@uI=eT27Om2_}VI=5-B3^_Ie_U6^${UFB4 zJi+{Ie=0=@7a&M;h6Cxdi@>WyT0SqCz+x5#JX+`{Hqj$ zDeWRmKBNQ+5K116ZZxlH6hEbgX|+im==AazpYi8tacBW@PWBMQ&g9kC4@sv$hbs(@ zV;R;1Fvv|E{zV_8zdh~g*Ubz*q{0+GFoy7d8n|@JIsA~a6zzJlI(Bj}`Np_VW6uUr z=m145Jz58InQ!XRuxyIWvmj3^w#Ub6d*!={m_Ly*i0W!+k4_|&9o-^1!E$qbw65{L zW+m}s6s&1Ta~oE~u)Wk1YQmUb6*PZ`HkY`G@gbRi>F4xV-o8dee;-$4+9V5Do-|z8 z|FfF(zV+e0u{zeVM=f+-s^F(Fmf=A*7dLH2mg}S@RIxs1gSVK|o1}o3JZrl(u+uXQ zZ6^)Kw?$fD{q`tD9>FaE@i*P>}yfZ@{ zUdAfmX2!e?=m?i`@6s^r=n(wzP8$~KdkSCAH_-Rf8C+qp99@?=huOY;;27gYU(~OI znBoN@{rgH7_lV&2s159W4Wefb-|!pD<+(DLc`8oUb?e?R>j&8H&uDz`K^Io{@}QTB zpK!XjIozMe7`%(>VA7{Yq9rX%_x$?expN8-c-E3sNQMfIUgBq@Ge&52E%fu{#8GAu zwEV6NZQ5Z4GOV6&u(P9`KAQ{n*_h#9c7EJ%hKgmqiZSYREQSTC!_ndjxM!6K-sX(8 z{w<3X!Y$}QgB-kIcUV>FL(0z!<3?P6h?}phLH|>_(6u>{CM_O8wp!`p`}>*y`FtI` zzL_E3wO^J#)!e|I!CIgpt1jF*z!+#nk0gDDDxkY6^ORma&!>;ff&np(@b1rk-l@-C z3TWv|v&&6kx{jUD5nn^e4<>PEL}qNysSeVfrSm`S97#jkh5kvV{6B3?TA5vgkCWC* zZk=FRGeT{**0D=E{?gLNh~b)W*d>W%zgp2h#+0zvGQ+5@T5xVk;2rLbpigA z(D!%SByWFOVb+YNpsD_u4_9OTjNi4u-%;f^oH7uaPFK;yZMs}UaTNA+n}B-nJY*lv|7U>%bc|VE{b8e2i~det>0d z=+mlYjTpvGrySS&F9up9GTS6+47 z^T9xPwXu@6Y|7x4jF+W|L_mE94R{ivh+Il-w+5nmwog%_FL|#$d3i2%lst!A;X`q)|GO3@?r1Wk)LF3tPsW zW*VrX>Pc}+3h?C`2dG}@DI7B`CI8J#11)oq8;h9#$`U5`D2^e z|65$k1o7vBb2xkM5_Er~44n&uh(ev{?y)*iW+3yk?XLyZwmk7f%BFx~bNakmo7Y|; z$98!V@kzJ=WPPk5Bb^A!AG}2(KUV?HExgh_Cq1-y82xK)!#NW*7(Y&3c-ps;Zj9C8 zZn87*YaAC*HFtt}LoUEwi{rWjkQ~xeh zcSruo1$CkPdj)-+E8*JNU4C&$4R|{H^NPCZXq0M;)=t_G{?rT&r`N*z+5o=y)LfVp z71KR~7~WG63u|hi!K_-UyS)tG=g&o@FM1Hpe6uaXYvI}qG5=_#p^$7`MXAP*B-hR^ z#q<($lq;48`#%a8@Sp}x^w=eJ=F%}XcrZTf(1z4@mY105L&scxNmumo6rNSp(dF?O zocG3_bY$OI%&6}JdhKSoo$YS?Hz&OlIUHPO|KRU^JjREM2Ga(MZ)n*n2ZA%p&SM-= zxpjKthUpLRkJl({DbfYCyFG=r+`V)vrbgT`#gm+*AJKh)1-w=<$2-hVyJF^Jk=2F8 zxc9yhdXNHmFC9kt&9ZdvZ8qWH3KXeB8qv&$8#;PAOA-ae5C@ zI&cFoF&^fA=0-DOKCb7}A4_B&C}7!+8W{ZVJU=@n8zuye0M}dbd|l06I&J4DX8W+7x!kW!}J-BbmM9#ZX7gCba2dm-qVav&IBfc;2vWAk=lQc5gv!f>16)UuaQXq> zo-rK85A+n?Y^tKEddt$L3IK7O2WtyYI@bxn1sWBy5bVq{-fyT-|$FlIaIH zGDZWoGj3whTZpRBd5c)r|-wzoBHG2=j?9&m(9e@YT;DUMDgnl=UE#KA9KNmUcP8U%fA|cH5!77T_tT+)aC3f*j$PEWd7^*ot)x9HI_Blm}3dKV;qF` zht;&;xFNSMcMjGaW$eYtj1N5Dk))QL*wVrC0gN&3%6#nl?P6}h6h#~ZjA6UgpTE8= z9aBPVx^=I(PYK154;9M?OBXn^+R17+rm&rHjh0;K@jbe`zsLA8=*HN&7qzRUsS1pp z5IhHq)%02RKpRnNG|kujD28Msp+;0i=HnkrCVyVW_VUcx4wwSS^;N`20o6c7;nI-8 zbky292=fN(fL|Ts3&Ao{*!WNS%F0uiFr=15y)(Gzk-aF&^(_9_U;r8&wy^3}J3mnK z82?UV2w9$N!!@2gp*ckndomuZ+BQA$5{**qoaKqvH1)vUYZP^we#F#l3y4_egX_(V zu%$%-9_J4um*KKBwk(^U{ZSFqZ`Z(;{vKlU+Yz)|?;nm$wSpfr50UY(;dJCdU;$rQ zf>rVRaBI0bnB3k*Uus=RE9;5a>Ru&SM5V(S#h&0-_z0)itj0@Wdhk{)k-nRA}7ANPL_ZBzF0p1y&CB z>|VQ{KkB}Z6iN*#be0)xf4UbfXWF6eKo$7Z!gh6Y{-CUxDgXYECOJteG3@R-iGBvl z=w$O&zZD+*;;aPx@Jk1C?rTEYgc2H;vzQ9b$Utiu%k;CEgCiIRJNWbtiWzLv?OU^s zRTrXdp3<#7+1#<4igl&@qv$j%ad ziqv!lfM+?A3s$EBgwWS&ZY9x0zF-Vw||(5QZ430mq)x*UeSkdX;xP9&frT zbn8{XnKC>O9fZ0YbinXz4`LN6<8*64BIA^{B~-)7r~K{jj?%>24u4=&gLt&GcPcSDB`!?)gUVL=jTH@ z#>^Xrf~Pi=FDs#cqQ#{6E=amwrxaJ;+Jy^?H6e=eNVPm(!ndSAkwfh*xR@0UIqVJ< z|BJE8#cWq7q*_{hvJ8D3W?|Y^JqSDUl@`p8WD@jF9A4H}_%pJKB(uvUsRx#02dk|; z-4#GLM-e5ZRo(Z^b3-$5x&J_X;;91*Ts#HWHPw_7mL{L9NG^w;?t4sz`U&A-{6Amg?ES8Lr|SBgJAb7-uu2OrM#5=z|n5I4A1EIBxu zs`5VI3h$wCY4Z>)&VLTgLyP(LjA8V{UWOtkWb^f5O1MS420pFw5Gz+l(dx=BY&5ok zf5wN%Y>y57{<68?8)F=`oq7QS!IvM`#B#s~Ia6%XW3k8RDwuvXt-GK0=kNvcurVT0 zQ3t)dlnWClHOE_ij?!IHNmXI4&Nuszb+{h(L`09Ce zxA!A%R8Q(z6OFB(i~uKEqWzLm&>!`lpBo~g0NHljxNiWcvRPZR-b=UPA$k|woDKSGmmdE#Z z<0zVv@dtGmRP%9c<~UdS0w%qkF3ui(9&#)L$cb zus(^89G6I!{^}9m!v)4^q+#TjF?c;q1AN>Vt6@tE+~C8-$%!TC+k6oHW~#xTU?p@7 zuIj!sT4u)MG!4elV|T{H1&?skhCqx+(*e7=EEDZi3uHdODMo8K>N4js!d4SHQkC!p zR(0PEcTJY1+J2kxyt^Sx{m@gmI4_zO{M;egpJa@3UfHne!Ux`X-3&_8{e`v-q~wbd&WxsMOpCnQtRc#19=5R>6b~sv+)fkJ z4tWkcmS;(~|I-qBjHslj8J=8%poCQ)t3dh6I{rrQ4BR=;8bjQ*!SZAYElc&HS=WQ4 zDRrgj@3@QQ=xM<;#xc7%xdoyNH;W$hz73}zM|EeH)Tt?B*OF=|K2#(9^Q{b*<TPvNG`{V-#z4qRdSWTBps&IaUq_;2n{Y^$l zS{zRb#SP+MX@B~Y`WEv!dx-F}M3<^ISQ%Qu+l1SZ%F6F3UwD%L{3)Kg4*bJLUl&+6 zJcAZ)bEeUgHeL6xv=zRj)zPPh&D@xgR;Xq76y_{l!LKjgOo!$VreW6~if2x5fE|+y zz?kVbf>-$pZGUf(LG^a-!m&r_9I*rq1N321R3^#&V3|4%1>&o(E%D1~#%|5^;txb> z3r9aOuAT8?$*l;cePx+A#gB7&$$nLu6%>R0e}sy=f{Nfnj5Dl#n#A`RoQcH;zgm`}mPPwH^2!U`?e=eg54)Mr$pwxG}QR_wQ&<)Vv}v0c&ti&G8wUx^wt z|63eNEt?}bRUt#MQ{wQGvI*0CI%4v)Dwvwr#or2+&;#QhT(-SG$PBf{8rP>VrpsK+ z-`a^ZCT_r2O*&9NKZBk-4yCXg zCZaa>Ua*R9hdKQ(iW{?}NoHm_hBDuAVwp1jcv|19%{X1qm&RnQLs-tVwf`#Mrp64o z7?8nlw3tp&zy6}=-*^7fTq~45*ap>W^LhIjo5_nYLLaLP=Ql5AXJdLj$Xc!z<2()8 z92tizPRhV~r4hpF7dI)eU7LI2mx2Z3Oi}BU25A4=M{jD~sV1?M4`8)LXDG|UUYEq@ z9tficj|Q+t3?WtW;5m*3kFp+V8PmhRR&ImG zZu0!cQ945Fjylp>rq9*0S>?|m6L7&L1=zjRpVs`>h#wrCAv7WwNAF@;iBZfy#rm{< zag1GgyRbaOPDc=?vbpa35!~qQY?rz%94S_bX^T%`!e|HlwUhCs8}Cq}?kw_%+f*KP z@*Y0Cv;znEYQa=i(}apP*fl&vwDay2ShFCmw?}$7@d3Jwp4eM|>|?&r$VR4lTk=kP zAwZ4}EIo-=9_m8{)A{^RZU-gn7EyQd68uW+oper78N zE6NK4eT9pk9uwJ|@&*?P)CZKf(%$vhWta(u=88N>hGx;Qj_aFxHgJcD-lGykyW zrt5Nj>;xUQ6Xf-`a=fk;{_$#qGa1YIMT57{&{du^GXJ4izKmsStT@p-pSPE2P`?Fn z`1W})fBa=NMt@n1gWl+aG1Hk#2DX7{x);B@L`Nvsucu^bkUqh9 z&R=42N#_>vl9obP5#tCahb8fs*Cx}oFe5tZY6o`xcVp&LXZ*B71>|>F;Z(+c{1KpA z{!!sJmR0UU6@3+`PS+r($FaB;tHd&2Q!yz-3x5V`!Ft6?x*;`_B(wU!aZv$#-%UnO zB@M`~vcj!WZQvL&)aP2hj&SRJEz1Tw$K_^AlbK&7?wPI*YfiDdTVpJ4^PVFSzmTDl z(JZ67_z;&PsbAgV{@@{RstUV;D^K6tk|@0 z6g{@TgC|wpVe3Su4M<|Sjmu3q&!g*rbh5Kx5tn zacJdnwAuY1>S?IJPU(E;5F3J_>|Wkal0{c$=~2jiZwTpg5<}WXpdOnG$uri9@XeDv zC0YErvsPF(=LrN~juaaP-o@A7QgPxVHE3Izg0_=nvE(<))?xKW^xBbLef!9(bv{J@ z;1JwytqUIyWYAApZ)!YcA_{V3=bCBDm(^bo?~0J2Q^U&f)^nB}(A1X>l&!&_#YRx( zdkZ!%mybrXouQH0>E)BNB^S-iZn6)G0D!WK<=epraE zkhZ^$<$)P+htuP6S@(E6$apwI8LVNMb1aI^^P+I8(KINsk@em#P|R3l&jvkbVmK>q zko|PjeJhXdd5Umvo)y+I#^%zH!t#F;b%lDSi~hOXkDD^!7%CQpq25^~IGw3Mk3!j* zOjea-9X^eEV2_s!bs*lPlBOljp!Rv2%J-ePkCD@MU__o4a95eWaT(KQ%Y}&gwqAj2 z>tlPp)rw2ZsVCwyK2-nCFWsZTW<0Shd&ylQ|NQ|jH=lrhr}SW(x;)vdpJeCO0DRi4 zFq&yxds>@Ca-yY}CvS~k?kK=ADLXnePm1O_9Ohq%3NfdTIaUVg!nXTGwCsZ;6<(<* z-z{cd%OCsk-QsY`u~qWqDICPI5+hhMG=ttJ4xtO{c=6Q`HwfSIp|@XhU~}k?i+a$6 z<$(s?titlmU_^~ z5GnG0caC@KuR&u~V)3!>RsOVXCVfCh^1HX`y2yyJl+#+_fZB3C^*=VVWOLQ)gJl2* zXwY@lSo}IWnBON|jW6^T;*sAh4>#UXnBdt+LFwZMJ&Fstr7=IrQu&w zEj%+)3y|r|-NR>)!I(bqXnp}czA*{=YiPjo1y=Z%>7v)Sd;6qk>k9CI<$=yQ&l%{* zPF)sxlzau*7uDq1--PorO2)JVD^wYx245ZhDSzS*q*smn^g~P|-Wx%(!8^&K~|4s&kltXDJOB^CtqBtt_edfq|yAro-{r@i+5-I zNlVLCcu*86Rvc7?mIDQFXB+*_k|Ud|!;yKXe4pp*}^auVXkG|;EW@tn_YE0kwi%2fL#-r&Sm zvb^n1>x-UZu_y)~-(6R}BTt^3H>Bdf0uxaGtpL2mDSq{WEMANCkOJeuUb2zr z{bKZlueMnBETbsuA(js4C?o!20(nK9Vsg1aOx>mi=&8i!9C^`M|sp5`SK;26fz zbhfd^rGd=5aiv)V3zy;EBUadL&T8^+J92fBBIA>X`Jm&4c>JX)Zd%7`OIHy&COFXN zsEYDL_N?_ek%Ohr!z8TGQ3@QueMgKyGXhOn$6jh5ct=~+GF4?pii4ad*&!gmdd z+!upMs@M3c)GX@x>qr$x!>+GuaTFA~SwVDX!QW zqW}TvMeyCj9tKTG;-|W$P)mg&W#rkz%g?(RcftwBTv36bA=Zo=)50=Dbjxkz^@RoE zIvRCg19!}=5~IBKp-qztB>SY{1ZNFAqOAo_(<>>aCy4HP^#MbLlh{%<0hRSMz?=Dt z@3^)=irP@0(<=JHTQ`<G#f#UUGYB-(_8j&l?7Ie@-$#>2TcLUla5m zrqYJ9gXsKFmh;YZ#me=~P_{Qx{Mg_g4mC_g_u1;;DSevw;XBCfiHT&3Zz`_NmBsXh~{h9li`Ao{DzIy=r3M}F(-B50L$+f$+*GW+KfcA!kNZZtp)riT@dT*us;7{ z8QQuENg~O2?v%WXmIKdQd3@K5 zbbgsS%c+lQ?yWzQ9_S0#tJn^)(U3cwv=i^IVm#Ajim*6p4B_Giyj$T4!xemm=_zfL z?PL#&t)h?j5ZLBIqBO8RpG`xzR-y##ACVhrB@)fQ9sO!-$>Vm|{# z*p_WiHD~+M!Fz}KeWpeD`KbvmJfsVUG>U1Wojv7GsVMiHtif20`*7sGFv&`L1=7?% zfZnf-K&CT|uFHGSjLz#~O@B8yQSg>eQryd*Dsmv2{270nD8lzlRbho<9T^82aNvIr z|H*sf=Iy%hdgU0J>iil@jyb}z>CNOdFrK)!SV=*F6>ej?orsYY{5M%o3T9fVz**<` z_DEGB?logne)Hv|z4p?@El$+X7;#-*;vyJ(G}6@ID6Vt5HQwrIhTm70^UnsA)1^Ie zw8Fte^4-4)?EmEc|9)JCbZ>}(uy|oTeZANq8SK9tbtk)E*Bk}d7hVFFb~(U-b$j@)(y26XrXl$UI)Hgd z62`7^#4C(FzHvR%bAD)ocZRy-Q>9-`*3}&h-^crr)Qs3}bF>>K=T)!vYPTsX=NR%L-F9r(NEva5>i+zjrr5*^lw! zJE!t+ne1{bKd1uFzZBB#A3Nx8-FUIrwi6IIUk@zv_VRoE_tCT^xs0PkGSa{l+3irdOZwwW+uNS=%H> zJ&VgQd8sxG9ib-7imIi<1&xyQa4D)By`uNN7A1cZzLk%M$UdojfYo&R_u?xK==+Ut z{BDf~%FVEBTRtDh*u4*i|HJcLO8ol@b#lL5kH-{3BxiYD>R2C#sh1U?t~3>Q95O`1 zKAI5mXdh)Ww&A8XXZYPtu7bgd2GSlpiA(s;8ZR;}(DmU-{Di4HNSxK zcYZPu`aP^8|HDSyDE$O{TNa3onTk+oGM2!z9!LLlg>W@r!S7Bhop@=Xa{1N*R< z8)LXVpJR>YTocpM7M7Q_8wf`(vi|DOD6Vb<^T@Lu<;P{p@L^vO{&gRS^$NNW*!K~h zPuY$EGua$Tne8+zntSI(ucu#wl9cG)*|p!80o0PxgV$1j@^?o*!lIvJF#E9{%or7b z`F&nM{i1NmzM+cr?A{6dTE%qxE;jgXGGnXiw1`U9EN6L=7C4?U|81QaN11t+bv_*C zTUQj}pR>kzKUWvFxD`|Joq;5_tSJ9)Ji9O3?nRMln518u0$n?@A15v`hDq`nIh|T6le0HRm37>K09Ywf#T20_h>*%(IAva;;JzNm#g-e-^j*7;T z>D5;lJJSgkdbCjU(Ku>1j+6Y^WQ}F>n&9v43SR502d&)m59^!H@|X9i2?bItgZtYE zZl!7t!9ZtHnzQx#SEhgrp4mv39izEjpI9A`VtR7<75vALX4q4h+uIB2efmd-?k=Vp z7ctDARfCJ0=iotO=0m^aD*O&?B$Mr>+@MBl%wU?O|IM*2mlz7a*VU6vW20o+@#VN< zqBH*RQh?`Aiy?1=9mHrP^A^r&bZCGP>0~&<+e=9(9l-8F+N!YOt~Ks{(9}CGQg$#D z7WHEq+To$xrh>b;xOy*MpREdQ`DvK?Q4OO8YJuMOYRX$Thvs?8!nD^X(N`FcRjV~% zbU&sk6*a@|grPn!T?~c6HuaPmbct(MlBMWV75Ly3^LHGTrQhNxoYQFx%hot!Yj_33 z$-LwBZAVdC`DYvuZ4GkrY$tEp+&d$hBb|tce0dqZ!-R1%*O=>(o?J3 zxPIth5ZGSTxPj@Yml<~@+0?+iC_>(x+WV@(SS6;R?cdxxFIuISkNrk0 z$7L^7AfW#y8dT~yDDtvze~ijlP(lpb77C zis?&{EwzPwn{MM0vjy)l6O1t4lv?cN5YFjDtmWDSTuMW9&>fr5y{+KB41OA?0Gs}#;>x22ID)Z=KP}3k z7RF3y8B)S)9CQO^Z24C8T_T0jQ{zx5n8h3`H{{>f*jkw zRBkoqI>IM(Be1$uGTj*=HC8y*w3$N{!MT^Bsu#A2G zmhAg4sw*u2sc9rQG6s=+>1b|~aUP!fvk|kA<>eU^qp1tytGergP2*!a7C(o~Zbg=N zzJ7%FPHkg4Rc#1{B2G-pMymU5-FEz%VE z`#2wUs|brzj8OfuE(}`4W(!}k@K9B#_Gi~w)x&4(~mIk!hz$xb8OjueFUejg>=SD461Ky@Lck2%<;g#sZ4X*zFb;+-)8HY~ zfTfy?SLG(+w*s!Wcar%VO2t)!X~RHcerd}%D%x=i9hAIa)@ENJOzSS$ni_LA>)CE- z<^UYFPaUqhN7D%(GZGm0$v|X_Znqm@pVCBeQQs5zC3Y#x8dilZ4x8xU0#B;6)fPLe z<^w-Z3(mA<@op3LQ~z5!G&r2uxm?&GJ)J_t;`|b0d7)xI=6@=K-3=?Lqz5 zEYJFkx-gLO8$0eqNiG?up?y`K-dZ&HMJb(IW=CH8KJ!9YEp~ORM)@v1aLr05@g-ME z?=}?m+_c580Znir`=Z#aT!FMkm!W~61Lq|g!jUz#bTy+{lEiA!m=Q~`OV zmud^5@$)BnP!^@()RX$XwW!hDU6|F`KtVNAIRC>Zan{h8m=dH8f39q&sJ||>f9eyF zSD=Pq$@(`>eV*I4LXlLXlCd_)6q1xa(%cDgl(Q*LvTYChy~B?46VuXpxjR-^<5vgQ z<>dIK3ycLlwsRR0WWvcf?82FA$KpT6ns~Tt9GSb-;r9)Lpxe?{n6aRV9t2x*q9e1= zqgDo2%wqoZ5ypbudp6s=8^G1w&BJ@+H{!0p$}l>;821ga!H@HFq4-iY%3a@z2Ya+( zOWie~zEQpNpG^ZS>A$8=DBu4#e^q#d{QFV3=Zqe_>y{C;+7jr)$iL!(ePgh-;W=zn zi;!5SDp5^SKE61?vMDQVaTfE-EOc)b>7HMKsp|$H*)Ya}N~AGZv-)AJpn|j-OMZA+&kc(YvoBxhaZwXztH> z^!!Zj^}{#ag`b6uw5lnFliu+N(-+3$K36Tq>8-&5>t|v<%k)v5{E1d&$J5LYauU@R zci~S(BPDm79~pU zhPsTjAaw0%96vS?)!u5rm`!pN{NW~MG2eveIyow>-H!A6n?U_{8DXhR0y(H8NS@_6 zqt`3}(E`cN1SUc!7JU zuP}4+9rCF*;uNN*VncR+%w!tTMw1vCqhrRnv1(w%W}(}^KL_DZB3~OAMvaF(sjsSz zI6glg?!>U{U*~MzY{mh4wMvKnu9iT=mO|_wBF0JPT3~cDjT)voliAk{zR#S87-_i& z&u|(r_PnN$CS6A%qhll|*zaq6yy0XX&WyKzgz8Gym&&9cufmM*R)?;5Hzg z)NeV{8f!z*xP6M0uUdwyrs_gSuBH&sRZIW%Yn3DmQnYRMqF&CP=8Bu}{#O9lN2TzS zHYHJ&v?(q9Z4TbuNvN#miJuuKYNEUsEo}IWfv1%D?~64lHl-G4c7{kwkLXgu36>rH zM;;OnrC~hk;YSNisGi6)ej#(|!Rrpb^Q4EcR<4oc+@^5`KTo2zG@J8IR0r)@o-{w{ zCmympB-$OVDSW+FOHBU2RWOE?)W`%}YQId`>1%M1o7E5N$AWBi3X>HMoq zABtc;h*@0*a5~FGcwt#js~k)@i}+n=96qMEZp3$ur@+cul%MJjDW<-Hd1?bS^|9oR zE6m0?c^NF3tOU1nnRaOVA50r}m;V%HBHUw{p`~48xcjT}api^$EQekNuC^BA4Cd+m zUk&+jz6KAz*@7KYb)ag08N_l?Fg-v9WKyiCz^MoQPXFO|TUKMrHh*k9uLnzf0`c{| z=a8APSrYk7i6*|y!%Jt3KyujyV4&HqF8B{VgMB~GH5W?6X zEeRPoS0z+3K$hj>1m@t?cZ>~kF@v5KxYCQ`W#T$DH&{EbgLm1M#UDOtg;58d!?{sX z{Kemz!uwUMCs}RGS*^N{o)UMgUakw8F)B2AaV$2rJr#Y(nLu{CUgEMMwm1Cm3FS1$ z(9wf&l4V<$~_4sp}()CH5&Bl_Oe4thhVnA+W7DN<^kgiN_tVoc z;+ZlI9-sxkFPz4-0fCsTrU~bIm`uXj08z; zADhUl4_Ua4*4B8_zkDLUJNjTZZybtL%~BXOZL zyx8&wGRidJzYV1n`N^94JN57h3JqBKa21AH8i09JI$f-BqU&CUqDZzE%W8TG850Ka z4P{!wyRWrm>-|JB^Ntj?4PAgxV+fqCDxJO>gLj6Rv1Cl$<$)UC7@O_~+g}GggZq;h@F4q!9s{kBVAY@#MKv_LcL+r(Jxyau3K26f66l$fO~vQ zj%o?=_iD-12|0_s8Z<>=CsyBDDp`47i8{73)>yh3c(8Yq>ik%`J~&=dbwvRjRF3t| zWDHfrblA2BCy*gbT5OG%89Q|CA!~8BdLpj95r9=zN}z2wkz|L|Vw|oAq}lrl;~MMe z%ry&++dUig0;GHU4LiqCG_c|?nryho@7Tk5xfai%Z)7mrpPs;RF(GI=Rt36}&matB z-^CSO_`IIoG4F21PmI0RrDj8USv^=e?jIkQUX2OHBYWq-nO!nMU1U7%n*2xHSv?jX zhCc4>t`rg$X^GRKmC)yQ<5@B?WF^v*>y6T_)et3crng3a=0K z<);{F3%9p27O|HJn|t5K*xPQscNrX_N>Z&cXrB8_v^I4jJv#dW4_LcGatX`CxTJ%U zKS~hIG^Np7o6o!&N^xUk&onpXx3d3+mSZj2zcn0=euSF(DR^c5VM-*8qg4~l+aOa*m3@lIJwJS17@3B6~F^xpe zw>>Be1M%2LRTv#>jln;kf_7Joc=5>x*rzB9qt~l}?9+6->ccejOt-x8Y9YF2jKT3s zHQ}dy2F0cgrE3YfqS6c2ILi7N+mqZB>#HeH@$8$}Zm$Wuhsu-2l`SaRX#z64Wd*C@ z@wD1HLDJ996;FJ?-Wn3NZyYHuWp^1Dmihb0PB67)K5nW0+yQqh3}$+~s7c59IY%Q| zP4%XySIzme(u}WIMJmI(tQ^4 z*MDgXE7%@wS7EH=m|{B4e*FtpRB6J3{q-2N@IM@#qz_+SWKgBHGj&ck5)DmY`$yGw zcv|Jg7d_P$N*T+pYeAdjS)&vgvKhW|p&{t+x&ix+jD*EA_wcXh@1eW|b{|RT51U>0 z;HgG;baz*U#8@lzRA`4L<)3BzSzWRi7KwXv<)QO%I?i>~#RmtOhUdv08nkE@6%=&v zN#BPH$)ZjYJ}lza&OePKLxS;Ui#lxRvBK{M+F^`jkI$Ej+CuC7T9Ptj68$s{%BzTD zytbv1_iL2N^6hRMD`O64;(BQGhZwqlB%bY&6(HfwVLsj>ou7P8LJ{+N(1ACCdbZ1Z z`n(m5E*%^FLv9g?R8iSHgifl~SFac!6iIH{E2S943$>(qs8ms$)z6@mXy z2dbO%;P;k!FgoZ3|Mry)X)5(#)|Y?$IKCP;hmXLYxq7f6pY4%i*!O0-S<>)JnWkmu zqW=hExH{HeFq_^$4S%0Vz9m~?*wrVn{&P96a5;?m>)q*yVFy2CTM3%G=rg&HK3FqN z(e)j1NSPMpiQ6e1@3w43YimD;Hhug zn5wD_hgULh!izRIT6Cmbu+b4L*VoZEl>pBD_8mGfW)>+2=U$(X`52=`aTq>B8@}gT zVTeaNC~L=w_Q;*5Do-Oiwn-LR{CQIoD%3LR<@lkb>6j-flDEd>!)@?N^@dp6Q<3Hs+{ACHS}>Yv znU1`Oz%S7zAc=56vm~DRsNV9!`SJAi#V7nxWe1}NISBuaZ=kO4{kc_POkaA3W%v$0 z&ijQh{l*qgdidLfml>%+yE9`^UG*Q|I6e)X%FXcpXLayrOk&kJrlfR40}=*VVb`=L zutB_wH)si`1+{~yvQ=AL*f$>*u(|Bv51ITJHx0VNbZhGmmGEc7im~qJFs%Qs1sf_Y z@oPvcT+Cd+&zqW#?Z!W$@R=se^kX`uX-uo5oiGK{O~%CbmO+9gAOO3|yJIk-5-5ZYM}Y#bAdS7djJuV~)@K7Is9 z-A?9hhNM!#SX0_R!2;$K@4>bK?uZLnrb#i=qA>p3lPf>U&VJDmz_^Y+^bOg}jutpG>DnT9hi7AH)v6R(iYz<)Dz@C0gtqh2Msbj+ZaTRZsuZiN{1JP5tT8gQeN z`4K)ofxXX?eU87<5q>ND@BJun7Y;EkUqLL6*IgRLGZkT{H?>O{FX7pX?u1LmYy?)s5&cjZFvGRW39xp_Y(17_b7bkrUXiN*fZi+ zgHu~PpbzIOByX)DV>b)#P1_v2pz#0oq$O?#{aZMI{xSXGwgxL~W_;9j8Pmj$ngy7W zwhn)7Re`!XR!`Pg;EZW{5cI2v0+`2J`^m|f^jkPPsOxL zZr-rO$tzo7_sw!%J;#IoiwNx_c`2#~>EXn1efa9iw5ja;%=WP;zYw88gC3^f z^E(?Q3*=R4FYd+LW6dD8 zM+WE$Co)-WF&V?XOwgcG_FNoVuO)H+d550goI$VLbFaI#F{Z?#=X6UYnY;R+mTAx8 za9XD}bfFc-!4t4-i50=y^JJ1@Nb)R$KoqAzFI4In zOO~DTlF_Udo!t4HCeLMeTRmlxnqS;oi;9l2Gm!ZN7QT5Y%BWh6C5P;L`)A^#A{b@G*87J(+1*%pZvA$oh@9J-~SY7!M zS`5oVS;o=IAC`e7eOQ(f(-nWoVVbnQjN2-~Zamm0jxW$F#4|-)#dCd@dW|1p8 zVr7j{Bmch^J-(_)iQjIb^mZ+XJuOe=w<56k8q=xvVY=p|GI&(}n*aG?0__oc@cc=8 z*y-*lT(E8=^~VFaY&R>$G;W26repk>y<3UVbP0c&@ILMu6gx5&QyTvARfTEj-e!iQ zhHJ3wy?EO4+?0&{H6c%$%>$toD&=oABkSwYykRLuGM`R|UnUK#bfBr`MxqT*9ECcjk(;D; zm8)X+8nro$Z?@5m?{BXsB(S^iw`)%&a&pq7I${?3uQr4iJ2Ys))EFGn5HFtdO@QYY zhQpnZWWFjql~jFAXlH;0c=c!d^Ra{QN~|ihm|5eNJ*_bN{*SUcT|L3ZlI3Y~;haOF z9@Xn?#Xr&taHxoV&aE*RFs@EK);0sh9@^}^uL-U}l~frtow(^8d;{Z1c-20oQI3na zA(e$V=<_t(vq}TZMq6WJMQd;EQc>0u1RbVr7<_~45j5yYY79Q;ULsj|T8Um(B;dpx zQ@FYRGdrizRC6_+<;BQDTK|Lm7r!(MQ4rw@JmlFL_JFJJIlj}Wt$*%y ztFGa~=A&#IT9w2VY^%fW6|tDB%=$?;mMP4b!2MpviW+7eg~>ygfK4FJ%fw!wH|Yjc z?IZ`w86)UeQw%N~;4K-iRELhIr{E{nAC6^pY}>`BwCfkot+!C2t5b{d@FfGrN3z0+ zo~4V+Dh&QCX6SVHV7jbsz(~J>`2f$-Xa(Na>nA(*ZZ|E$54I zoBrtDIyQV=I?Z0`N%lp@M3GZiug>(SN!tXmI8cc;jK6`KH*3M}7I}JY6588SWqozR z3cL#c%c1kPoJ1cgy3tq5fw4rb(EcaOaA&p4ZLtTLl=h)vd)vyle$k~l6L#Y6elqab zJ{@<nK3>xun5Bn#_D=;O_uKkY)AiP+txXyC?G% z*HY=Lw=r!VX#tmVQgGrnH{4Rpy!pM zEzlX0?6b&QUnqBC`n{1ixw5}X6xX>E{m+@g5Ua05`qA`$@=nQjc_nb#c8Kp_eZuz; zKN4T)ZJgknIZF8sNi#&|OfmiP0yPF)L~(;o7uzh>?nv7;Nj@A^Sjf1W>TqbJcxocHB=^kn{mOQ||Anz0kpW-+buqgc_Bg~y>_=~7S{f_${} zMN*2?C+!(>kaeXFi#Jb329t*Un!dv9-)(g1G|%;ERUzBIOL6?~)B>2-Y5&zQ~FEp{-&-;RS|0HGlI`#%S4bq0rfePd`cOw=ZGy&^E zC;a>LGJG?B#lz0Y)cs#KrnWjjF7pKsW&Bc`FUR=9`#q@a_CGWo*H%72QIA~B8As!{ zG$gaWrN-9;i*{&0)!hWzHOQ3Sv7SdwpXulr)AE1)(zt%^v?%8femPJhdSR0fCfy1k zS&_-NG##TWi?pacb|ftNat7O2ZgS3IZP<3!MVPy+f$C4ha>xE!;c)dPm|d`dPug2f z8b4ymakHI7n3aLolRkqv^B%sPR7!K1x2I0Ko4>ua5#=r~#$sL{ELOP)tF#+P|JOB6 zQe};Em|o~&v>U(quz~P#57T1@bV#~Yq$yq|7#GVJ!pG_smNymzsoxLt=1pl-Vr)!{ zhFHQ?=TtoZ&=psHQiWBwtucskIOpX3D4P&!AcO@m57gJq+^YHdG%G$Ff6ZmwD$Pum z|EY;Vids;Wc%Pzd84ut46~CBe`*wOgp}iv)atZ&6u)on%l=+``)z}8L2fKEf zvAvizb_X{1)|tC(pFYgdA4kY2!>&`)=ts&UOq6&*Dr4$Og6>n(oB`a3Q}b~C^MCNa zIumy~il!>|qkn}mkltyH$CyTI%DQRdm$pR_pcSNn138Bj!c6y)$RP+a3?Yx^#!*VOT#0J z$2k40sCSp0&@mm8EMLGN)fma#DmALhJ%*zGrf_#p3l(U@lg_kci4Uvo#^amdqBhUh zm3h#P?f=kMIgjt>b{3blYT@=P`j8f_K__*R@Lu``$)tnrs4H59*DwC$CzN$l-O z?QbCY(BT5s`3?Mn^mIP@p*4ORz<7ys`|=x}83_7pN8dTCA9q;$A%5CwkCR91!k526 zY}V3&Mjh_3t=}hF{XBt8DpDj8{Z;scWvbrTt_%TZn5XYs6Tp8*$_pMD2oZH`*FSe0 zw|JL1&E6V~+2NJ^Jmw{_(t1KqMPD06QeOS}aS2!kmLjMKxoJFiEIZiIZ@p}wm`#>9P z&1U-WHLpa$;`NyBZ^t;NN+7B_0fXxFdTY-6>>RrMR*%d}-JyAZ8b1GJje7!^K0h#v zB6Pe+<5e{OX0Z)=ziftpfEaP{xf+yukbzl@EtZm*iH|qQ;kx%)5GGel+8qPw<&*~A z;pQ1U?=}igoYjI(w)<-s;7I|8kBfdvZ1DWWX88F>5TD+yLN~K+;-3XNps1%n4ktID zVWSYGk~lff$98wAmCyWukW2fzCOm}u+a*>dZ*#C zQdewXd7A2WHrVy9vA51FK5Z!YtYLbCDO)*jS$%pKwh4`!faL`%C zTs>taE^~b(MiD`j0WGeHh+Z z!Rpeh>G*4K2RwchEya#o!QA*gv)$V_ex`iI# zQ_)RI={qTLRElIQtwMv18tAiE8NNQW!RU%6aJM{K?xSoZ{Q6u+p)un*lbHVWwJI8e zN~-uHOs8PkFqeLY7hXTc{I)$oEo7{i#5tU3#0Nex_-wc?tYeHs&Z`-!6XQgI5ywH+ zd=b>o2Y$@Ii?m{jE@hR-f!3gUtnr?JBVF`igO#r^KeUC`|1ReaY*M3C=JBxMj6m;) z4OahZf@=BKq87stTy$_Cs`w~D@x}spXQT`MadEu#iT$*70{Fl}48xCvHoj1em~uvz+@bc}3OhcKxu48ACXWnZ*l^3)Qn)E

Q;GcJS`RWD`WqWE9*ed_=fku(x!(KK zk^%YDut$p)bc}{YZl##t*9*6FXoFv@Ev}Mlf@bx_yzMTYKIFxa!!|p~{I3~!x8x%n zTcZW@)}N(_m8SHpv76tZ(1e?oFTlxZ`Y>Y3Kpd*o3-AR1#*bEB%XGq(JS%LOmrq8+Vf~zm7fl{F@W-_hg|MuYN zFO7u8q&m97Z{sZ5^l9Ltjd)-c%P2gPi5^MnC}XV!>c{J8Ti0CbN$KYAuq@q)*PH0o z)&<-(jWhUDeKJPtYQo3cw)lN^6a05!kI$lN#&ujhd0+25=VC$t={kSLaq0bFz(-rAgKdJx8?D9r z3Rs=V_CwKF=0kCvPKN>>qSW0XkT~8~==-RW2AB2cWG>Ig`R{+j|B-aoVO4KW7guTN zI&`RXhXSIW5W722L{V(6-9d+dARPuO7NV$tiLz(rSYTq%AYox)02b=If4u)+@57_) z`A)3$Sq^=8Cg$o0azANCUafMF@y`a&9^)C@HgiNf^Yd}j?I84Js$iX4gudHMae0Iu z=sv1N7Z=VoY81eo+7vn~aU+?*Pec>n=fX;@86b>pVo4<~lvCD$ZP#T%xZxRAtQyjj zpS#aOgG7->(6QSDuG!a9?v)7IyJN37@yB``<6wdTD#~z%JgB|@A3SG!oVAr*K=Dy^ zjOF*B|L&Sd!8MLXdAYL3$9U$>Lo0fE6^=|Mv@-3;0%?(Op*t~#vVQ$vP~ zGLm*^RFPu-6v4=nC^0^%^>D*F_-!6n>|4_ca8lDR+<^d3p z$Cxy+3g7YE!~fL;J*lj8V8b4=2+$N)IQdA~rCKUDUMhLutxn>CGx!hj96rZmqVqjQhW4ODZZ-Fo!4o`dn3qto@lZ zMcI?0oFdt28(Z8et%0%45u%o7&oN;^3fensaQ@f-JYumZx%){}vMwF(R>|N!8*SKo z_B_t49??@PWcG13><1Te`tOMFkc%zOxKab8a!XXAr$%e;N>M>c7k*q+H?LwH{{gS-Kr$N<&pp{>61-a^1Mq z_eH51>XNESIA-%XdS68k>bK$8s$g6I6@;wJz+b8_SoLkz1ud{eC%7xO9X% zseHbSMdS2gm&jP!`(Y)?$h{T&&66Q@lW7=uRUb-}ZbI}lZ;+X|m+hR%>n#|NiJldd z^+~};RnEBoi5fiZXDl6jypr6tLnN=p>C^YD4LJFrBD5H#FNbh1>TjO) zBM6Y(+IbG6-b_UU?i*cyvai&k%#V)M1~AfYyzzq z-+@=s`oRi*2dp=41$uv&Ez0zzKg9FU3%p_RP9N#R5oL5Zqo1V7BLIC@{)X3mm0{zK z2vXc)O1n?X!2r$#F!XDM)!s48pjR>Gj_3O^zK_y&uE*p{8!87HVGMOe^!Al2%Q&Dx zwd?laNA5+vIYoo=(|B&nAai(i+XWV{f65-kC9_eTLXz5bBI#*^Z;G*Wyrhb>lm|%i z9zVvzy{&t8BezG*r%&ZAoSo_kXYKfoB{_;`$0v%r=|3EEPp#+eJ6VKKMuY`@{nf!{ zMHov@I#ki0XHzATv$-aDG441$(|5@llwFW-59hl_CC?GmXnZpQ46}tBANTegEaZ2 zE+sGX1V7Gf3FBN>lg!zYcYJ5qw95izAF6|WSq6RDJBV}^M6e_qOYBr_h2q!+Ebx^* zo!h<#Gd_P5X|QyZl*pjvVr}>tkxO$|8qqCLIg|CifJ=Xjz!f})OG!0_G+#RNoVde6 zxpS6y|8^_PKIzB`HY!s7&i{H?$9q~-NcT-7X0|1WM$K@+Lva^-cC8--bLhD3XUyB| z4AVS4q_4l#&>a(7N#Nil9I?S01%p&!$51OAx#uM)-!H#$f3Ysziwnc6H~YXgnKbNJ zWq=Dghx7aEcv_leOlx;>4{Y^WjCS+K`Ml>zB@TO9e*(@Kaz@L*G{z4P zBonMjzfX(@tuKY>cgh3%Kh^<{*fQE`y?`ph?y}~%8f;7D-ftIexXf=HUT0chpG}JJ zX;d1Hp$~8^RSTvS*J3Y`Kicos12wK&TQ6Kd>Q^TU%Ny0{@A%6Ym7xzYIac_0UMti+ z?-EYPlA)3QQ?TzneV92@3RS;7c^-E>Q`(tM$_EU{RLdI7r>1aio>R|zpK~LbYeBtf zW&T{Yt%Upj!dhYfx){;#E`4fqUymQtUXO zgcc}z)C3C+53@oq2P&HrgNYko2sgZ%N13LNaL$e)Al=9FvJc;(T?_h2ZoCLUKb>E2 z&ruoNLn7(KDpSrCm4|E3Ebwbv6MS1A%|33ir6+b#Xe-xWykmPYDta2@OsO6m3CpG3 zeGIAlp`>(=S_4*{-hcz2=|P-Q8m+E#p)GPxMS1Iw!LIPBa9`5I-Ynw`lfq`m9r?ZV z;UjzEp*m<&J5~IM^ClCXdEtLd0F{qbXvEP7ylWvV@-d!^TMsor#NjaU(s7zpW_1`B z9yW!5@t)F=VKpS1@lHIMHsaZLM)+@?GJIWViKFwHL3AUvRJObjo8naQxW68(SZE?u z<=GYo2fMI}Jg#FI9)pwJHi(};)}V_|Qt-$&bNEs5jcgZ1QRotV@xx3v@N9p|rm_@v zuUJev5uM0|?yzLM6*_U9VP9|%Im+_;>~>4+ZK?~(v;F9Ldo!vlc){D9U&-ZoB$+oP ziU(|8gUtdpY`mfjv)n?-B-?`4ukT`y`F&)qdn>qISRfJ|bs*m}F(_AG!`}Dzk%sDX zR?L`qNs(1OF3$2*4~&n zLmQ5qDMXXUKHNp84U-JgX_2`rO^M1C>iSxuWL*=~WjnBvYl`IkZzXzb7=yE|Dy67J z;PX2PqA;F&xuIV>=A3ka?g7adV=@?T$Em`U5Pr)`Y=Rl;Wj78*aII-j2ri83154G@ zQDCNz;$TfM-km_QipCUtQUJ?&!c_NYKRlnU4(41pqJM?!Dks6PrJIgJ{HflsjsH8Y zOFBg?OoJrv#{*;)VIB;^WBR&q>^j#B?3qu;rrl+SVrx-s8H;~8x2=S83gdKnMLHz+|@x?WP zno_4w8Y@E;lAT~w`P#XXpvB8M4KmVz|f|?@cU~z?tiI*YA3b8Wtxw4KKBW>O$tyK4^D?!d*w^xtJKDxX+^ z(`7As>cfFE3+VXlW>kK}y(djyX*WhtP(`BnX8*MqI9C;CRVah#RVc0WvY-V+zBBPr zOU$0y1P}hr7fq6}BNuP3^OsbzzINRE=KGu`D8);@IW=IoYZyvb3E&o=xo-aRgM4+y z$~a%bdP@}UaNfc1N7d--Fb<9F^+2A_eQ&~^(}&aC^WIOBuGgMM#Y!WXUu1z=YW&|f z>MC1)-j);u5g4_0pJ;NR1|9hoiMnnlneUu5j0)(Fll?Woej?Afzs>o6v;0`Onj?kg zMq%NpPa@~c44kLi8-ovOL+X4Ds&3(oEU7CSw7dxS{uz#Ebah~;Tsr;8ai$`}Twx9G zTPB4x!m5AvY-O1unN%+C@h>0YJzk<(6lNEW*i_-o zB%Wn?s1dAu@7@?UQb7Gr2V+=w9}pkWAPbo&jM>>FlDnFYD%KG;%4t+ta&sL4d>~?X+5qnGnhxA^x@`K8eKl%|fx&hC1A1GavhLJ(aU{Imy_~qsr|Qg{K6Xv_s|+J|AcR z&L4RVQFs9@$2x>tAIXsJ<_Y-WkUrchN5~n0@tK%IQvX=kmvgOO^U>q^6{lllvPMOIuvVFOu$Z} z2!U5p*rV8eEN9PD(!A8cokJGj)WLl*R~jHFHis3AvZtSw5onpyAk-6b4aV|F?6m1* zTK5;@%A~lH&b1Yon^KNc0h~GeQTVC>`pZVMw=b>e^V(31GBXoPb&65`l|Fv| zDS*aFoOQM}65s4PeWO=pJx*A)26q_f!Fat~kjOprtJ&>{z_ZR{f2EZAKQF}KqQ1EBp8(o<-6%O1iG2sI7l(e-B(tT-Xf&W7 z$bIXe);kgOGF)FAcG?wY?|Q_V{gc_L`6EbeRu{ez3qW?JB`ObTgd3mjL@5>(xNcB? zymem(uD$iA2S=K)B6KjUi~mO9auGE1OQQJp^|jcYtb!+-m7%~PjGj##K-ym4*^^>R ztSI67&y@M1v2*RH)-(dQEv{s0$_3Px?L_O{;;t9-yLrW(r}XVroMcy91Jp%VV|FR)I$}?^Od|2a>+Q^?u^Q*5j_KhfT=^|0-Lf)@Zl2W?Kjz<^2zpAZ zrrnTiO4X!|vZwLXKO-3S$pT-UZ-C%ASJ}wNb~Io|1iqY}B+@xk0E;K;fNXLs3m(q@ zu6PYk{c?hxx|4=tUR!2xR`#sjsT8})k>UzNxQCScEhaXC%m_c$c|HS!%6nn?F>P3D zu0ca4Mq$37!<-~wm&?RInGc>za-nf$x+{bU1#9?SA~6wmN@EJ z1Ju60b7RX40qKnl#y4#)O)j3_xYY zIb5bXAALz38hGEka7H5>S79tnacBtR91w?7^M>I`FZLb2Vpj?a=2WVb+{<^nCETr?wPd)}V7a5xD-K zP&_`b4rg!l#h1Q%V7{`Pmgmf+Yx5=wEB9;C74bzZUS$9|t(G{QbI-D6JA}hp_%3u4 z&kYaJhf}pTp!Xj~Sk)2D&fdzRr62Wa?-N_7l1oG1;|_R;`*$h~k}0-<>mnx1W|rJb zcX?w2Onez7GEFq5=2>g;(-~#3&(FZMfBWL{CN22N?<1<3PiTDHLdoath1hUw5(Wio zLHXZg+Q;`n0~5XrPl!1CD7>GI?-po#GY%$Ml7y}tM{YWPD2}NQ3%B?>gM7>?!`DWTn|HPxh9{p zG{=WTpibQB8#MzOa3TibQ#n2ObTSw2ULFrmFE+55NxWZuQQuQ%f(JO!-MmPA_jJ0r zrMeRT9UIt_E4nv9gMMs_z@LBRMG&$WZ;82Q&?ZJ)P^d){t{lXCu^D{0vjv}c8urwg zjmIr9@K-(fe@ZDWYbeB<H&ST7rz$(Y};`Lst^kiK;zB_FMf&;E_UiyH^ zDJHXTDI+Q4ODEpuKY!UAOEgKXhb;+qA|K5PblYZ*W!$^u<*rH18j*OgMOKpYdLd0b z{Q`A*d&AKy>+qMX3ToP`fb6O;p0(AVrdWJuA-B1<->LzOtmlgo%Is*kUN~MpQOOSW zDWFDGM>_g3_WJnMK2igtCnUTOCmC4Zi0b;GSouW&{ZHk>mubErtiQp`UpZ3Swn+Tf zu!{}-SdGi?kHQ~sc>Y41ytLq9Bu!P)63g+Md$i&cGW&O3;(J1i_Pxr(gr~;Pck2K8 z!1|ur@;p~JhqRTTgv2x{KSo2yN z1}kgQ8x78=S9D`fuNC7LdkNA(9f<0kPRAeey=u@=;pmGFQtgW8+~a>+VtR$^2H)}= zz}xn0l%*2AZeN07)kdH(NRwt;N1&fwvM4-M7GJf6!RFMnENZkL)vx$~r0xa*kb<5y z9{AW^jWbXz(YCn`rhmV4V_&s^x(aq+Uqcz#A*V@8KJdSP|0Yqw`V5}&qKo#Nt@p<^ ziN4DlQQ-l7_?~+nFNgbLfx8B{s92$bBhM)gV8g1npMcgk-E6mdD&xv`+V!HncItZ21IdZrFPkaN#`2GNB3v)Llf1WuRX z+`=nSqLGE>bl!9${&rA@fwdWUp;-wvpJ;)MZUNmrU{C*b0^1YBeIN54lbORpiG!pF zqk2ukiPyEDU~3xPJLpA0PQQgqqpk4f_Ij{A@JzIne>Z0>2}R=-v8BhCsE}&MZoJlR z3~mlHIb)#%Guy3T+*M0#Sy9*1+n8*0py)qgI6b~mcw&-(qIp(d{fWOUuW1RMknMm~ zbCr3@;T}quY)TW7m0^1N00|$iSsMGz#wS~p#yg`7~e1CXiB;TdH zU4`eL31C`bE}VDfp6;;?Y=NB>X8o%Je?eF2d!8fzz$p|n_D>Rbe5k~zuWmiur^H!- zcv80o=E&_4dn{>2yNPRY_TUco$6zad_cXvx6BWqIw!~Qy&VbsRQmPzVh%E;cFl>$h zmU-AnD^%mDUO0pu=X#0!@HkW}F@kw~9}*#a(6e71pgEfMzUbsyaXq-7V~PF7)Iq>{ zJ5lec6&U=-6c5a5FYN(YFCshW}jYBVR`j{cG`tf?Kj#S2b5nK;EJ)B|( z_NTeif3VL}t?-XK=N9_S7p+UOr+HJuaP^!jreRt@7mwSM;qBP#&YSq&b@5}K2Noys z{`mrz7KR{lA4>bcT)3k%2PVG0&VJcD(NWGyz42)mQn~4MUyJ2{lHsmT@M7d@WXAtOse0~Ncaed*E*SSI? zL#{((wLLXtdT%9yO#%3ElM#gKxnfb!Stv|@!*)3E`^MT2cv;Nnf#Io`s^WpWebr!g zGUuN0e;2(ScW(^h`iHY2+t5`*20o}{VoRkCURb6DmX%2qy4H}|6b&FU>;eWf&&4xY zeE&1jiu>Ga;jB9w7CiVAjCs+`{--^g%Cq~#t6Y0(#hYJ^Sac)?bG>!p{T3^nUs4Od zAW0Y;pMe7(w!-&)+K}*BPP)B%KHWd=4$l(n@l53G9;U(LMcSl$s2F?a7{ZbYEBxS6 z2N%U1!W0Kt+EXwJm;9#>heuuoalRFN6h|;?eiJ{VuTRF4?V-v&9W@5qbFZcbtj$QF z2QLPaT;d$II+6Q!YdOb;*Mun6pBi#Eq6*iEbx+I0CW{)pK?=*K{?;J`-I^bf)p&!qI$F zLg}Cq724sx3uQD-z)wpVKFFuA(&A*Mqdc3Y4CurZ4I8*!<02K6R8xAUy(F3cZvTwo z+K*DszV>yb@^N8Uu=0g4Mnymgzxkfw@gMf|LLhE>{uOqnE5p9HSh8$4p&hz?!H(-- z)43++@Th3!%V(d1a};n@pL~({Q!(DP)$P%hJxOZ7ZNim2F6n^56F5Plu? zjrFSCigG*kd-@P_&eHtBIcyhhq?8_Ba}FKrWUz3LHnhL8mHKMN)9{+1Y+HjW9nXoy ziB(2$WRxr1(=BKI4oPf9#2B);-ic?{>O%|vy*jw97SgWRiRR^0;Olsko<0Nz+DM0- zi6wPIS@D9*0D8Z&0eeZkA>-Tz{QHvU2HjABdzKND@wFfAoBfkrdS`{M)9N7N_2lUp`5u^#U6MSQ1LK3N;wpJedNnG3JFCT)VqWB*8XbOox4y0aY zZ$)2}j>FE{IZ%{Z%66zb)4Swwoc?k*(@n2I?HfLvRU`ljuQ@Tf59#cZ>yi~(IyB+l zDa^QJ0$F=qr8yZjM18)B&o8yYtNd1;RCJYnQ7^^`GZpZ0n!aeARtA<_GUF^7P00A3 zO<^Zp2!kV;_9E_6K3EI;RQ=eb+9K?BP{7#Fn?-joW@6mE-!QdX8-*-AvjNdWg{eG^}2<;m3-Fi>5rI2SdE7pP5C@jZhU<9Gx;N6Bi*AxjZ&R_~E)R@;tp*WStZ|w6 zJ_#D%ez5=fdJg}+gm;Iy;%q)w4$*DG+95I6a-4feIqPiltXgCuQ?A#D7L7?9 zK+h!`aK;=>P`a6k+btC_dzdyH`mcb>KHHGTd0;yt`1hjoK6R}3mpnONjMFDiz!rXw zFV@K(X3pz`~q`65;_u!v_{y9eX44n3%FNui%V+-UNr*P_J0lQ3qCFFdLTMoCWe z>~Scrtlq`kKGxtX&*44w;r=!sspGr*6s~byf)P4&=F>^^Y%&3x5e>98GKy|*OBV;e zw#G4^YhmiwYix^AF|O5?!+DeRMPv0Yf^$2+`&~?6zUMM&Jd`vLV!2+$b!{Cf&UKUQK9GjN?*`%?HFcQlV1w4?{M!^( zcBAiAJsMlZIbD-v;LfW|e5SA6Q#S-#Qc3Z+A>mLX_+DLzZq9RfzLh5EDcay8&Q-g- z0EQK0oP>GTx_auyu;G`n{EstENE5&o&t~j?%{B9e0_f9ajRSZF>;G;sDevm>iS-Oj zb<=~7)?9zrrx?4Q8-b>>4K9tX0lCf&Vd!pI+N$P*-7EB=#{C@p2Zm7Kzm1u`IzUs- z@b9jX101x^K(7O~xHwV+_C}@Cjl4mW`fVP2=wpMmPix@e?r70P2P^u+dx?gf+HkAc zfgJ9};Q@=^qK7Xsale8Bel+L%DBepv9Dk2uRs1FPy)NQdo$;tQQ5$rPGN~iUlg{=2 zE4(<&20M9v^jzQPBHI{yl8@ery((i%<7TRo-O}CS-cFt-V(sqGr15FGZH!*>(~MlTMYTgdzf24O5^lg=*gi_yrMr-?Df79huw0- zOcw#@5Bx?`*2K_{Em`6e|Lr(HR}WLdRp4@t0`@*V8kX)7iI*pg)T5ge4E{~*vAejPoQpb7f#$^2oJ+;u-J-crb`?|Q7%fT^t+c`4N!(lE zwm@XaGiN|11bx@nuxWfYeCctIyb59^-#c2+?$~Zr<9E6uN}4Zg7O8jFQ3^($~S&!k{Tiv~J;iyk%nqZ;rTP`?@^XZ1INOJ`q409N*yz%|Q_5 z?IR5=s-dTS-6YCN>FC#MAbQxU1AC-TpUgI)g@!Eb49>!h^R%#(?^)i>PNjYW4QTc= zLl{|FgclQLZKCFkK|a_WiV`q76}~cjlWY zZFUw0+R5W6&YhT$;v==qEu*rl3nXV!F5-9faTv5i8}Pq0iumA0edK-$XJ)F>y4zbY zXtD`xJ*W&5z9h1_yOP<|hw~}tawlph+e7}`LDF6pHRRanB)Ky>6^nKWam7|un6uo8 zUi{mI*6&{k8TT7j4h+Yeq20{=&r;O1;(D_jWl#u>C$)LT^mDK>7>Wi-T{$bsvLQfn z>P{hgp9#c-p&Fo7Y)kT1TTm;`T--hJA{v@$_ITE`pERQRwLq*d7r=|mTo}>f1KN}7 zSVEnU#<_H&AO<1Z z(~$SX7nTP|S$Lh1wDorYUC;~wKZja8+$zLi&N>*fPKEUIBeBv(PvjfzBdtjDWJZ5X*XH$#u7cxv9gr9&vySbV*f`Jx zrxj|#Et4`@_Ryami_frmlV4!;+C=o_T<(8SSr~b{6Lf5JAo|H|=%7hQGl( zo&Gf1pjx``0xO+hU_u?v5{Kt3%s)eY(Gf&$Az7;L6l2O#h(C;}3YIgH;-J-Qsy12aOkE3w*2>}G=G+?vR zRE%}hgAeEU@5aAETye)3{F-E`V5JB>x9CIS(>zFVW9P%F`pt1o@U}Tkv zeLq@b@Jr6gFHfN|J|`Ee&1SRo1nA~D2R^=#WjcFoC~Hq7&bI6jIbO&@1vfeTwpkk% zU(KamL56haM-dxyjMw2`cSvE`0*R>aCCq;}1~Zbi;fqNo-7OqQUf;WgDm>%B7`Ecz z<#DB3AE{FNy-huDQ_e?~a)(9YgThSF+(bp#mmb%1FX&&gfNnhP#3dyTVD!dAS~{YJ zqW(EcEZb8twt@FZw^c!K&XvA*1*2DGt1$V4F6Y&SqMb%Jvx``UK_@=Isq@OPZA}6t z3^XCbMiuz7stBi+EWy>B%e|(-jx*7@uVigMu}JqKmTXr?^(j09V$};w^Iw9)`FCNw z)iHSUXE;Qp*RcUBCGKQnRAss8?)iKLxDF8xFnt2e2k{HG0MG z<|hn{VEhahFgr-hYHT9w9Xpv$#&qH7t;UdCp@<>+BO(5yn0d@}poX{@^vIAG<;++~ zi{%^eTfGQw$!*42Hx+u`>5{A{I^1eTHVwbob&kVQZKC#y)6oCsT(An2 zvc@IOwDa^%e5AXZy|l8U9Ti+l5Ij>nabGP4t{jF>ITK0ep$g4>6oGjY^hBzuKGF&A z?$9OM5=orA9-TUO0X^q*fMg$S}fp&om+V zbQzTf_))9F8Fp=B6FSaIzz0d%FxuFjBKL2^cd>1vj^5d5KjkY(_&u?7^JUaq=8X}< zbYbIdt`S<{N7Y}egk87vN$(P(-Y{bb8>mDIH)rGY{f5vq)ES@I9fJ*{TG^73OX*=< z8zxWmghwO!4#B08HU+v$rVPr!bMbDNTA&Uy>I`Yr(hc}{lN?OCorMSgs`tF>&C}A! zBuk%4W*Wno?qc*jJhSIr3)S+#`Ne1UKMiF2SUbwu8;SodyvNecUqQVi4yfLT=WB3% z_@~b2wDU%yWc$ljv>3zlOg{^_4)ZK%KI>vthpd_TVy+Ka8HEeREMc{c4ftTuWDMYU z^9@P-4Qf`>zm#%G=v_V1c~OY%87AQWPnLe{9@f)KJ08k|yBV60HGM5BGCNGor*#SL zIKjdznLO9R8rRrp!r{y56mrm&CfED2D?%;oUND8TX?iomr4HmXC>rgT{uHhJorS;c zWpP}jHaHyhk;aK{Q`$d2$@RsTu+Q<)J#YU?MH(d~xX^|pKZFKz9BI|>&6s#AuJlm5 zDs|>M-H+aOs|FuSo0fdWou1F><;u*Y0Y-fHQXV#$f|~RqZDhFS&?!hO6Q6`2y(o z=>=~27=UfP^q?{*7j|TdVX{LlQyw>pGOB)Y){h3Pk943>k9g18Jy~2*U4@&**kbD- z&g$vVr>DL4bH396$T9pzcB+w-7m+FU{kRjiDC*)!4OPCE4Wmm5mULbJHT&FruOVs_{v`rubsECaa94OfiCE*0L{_w8Dy?no!d(YUAZU;x z4$~SAU!IEC6b%RZ^(6`o-Q-1?o?PE`KMDhHzh^SHH{%3#1^jHS3K#RD>D~)7IyK`D z+h*%Ze^%|p&1dS_$*s1ut1SYz1X+t8o#*?L$+s!SELL($^(Fp3ybZyR-N!!^UX zVAjo}Ah_13TPG5)g9Cy5@;^`uYcj?89-5tZFshhsU(Q1)LI zUVN#Bz7<-qtY0QwGcceB?IzHCp}SGkwb9cV2#;g^Z*bZG#^TXbQXgEQF5`ADPww$kucZ%M%Tbexel6jj%$LGLlH zH16Rx4C9+aFWxgRkPE@*|8=vMJpZooZzR|4y%W_tuR!e)?;y%u1vVHa(XuzUc}_DDm{II!7J`%aF4?8jv?Yv!`lWwZ|NapsWXz;G)4Y(bvkuUS#H z9F`B~-Zy!F)-qO&n##iQ-AzNt4RVDI`+@a7lE`MsPA8MXF1)(d6hb2%q_X>}sb9I1 zWTAl)ZgrMGOO=?3)E($qLL^4?kry3P)}ZyAQFF=oJ!|#dg4)C7QS7A(=Lhehpddbv zU;W3%O>!lRs%^L-wVrv+vZBK#p}5h=LcG^ogI;o$myD#fMCM}?s@ZSEBY!wY@yluW zlR677+$EMX)|pKHZN}yayO`omJF4Q0rbjboif3-DL)}Dgw0tOl<}n&%n;VJAF@~b{ z1bxyua2yp5oAZ6bZk$_chBy1GfR2L`;p$Debw{#jOw@JApQQysXHwYZH5%0aP9*N} zFcv$U&O+CPhUlZheM3LX=(Bhpz4@EZ4i9NT^S^uX`FI@|G1Q&{#;(Juv)V+PHf3W* zc{|9i(*fd{hIhV1;zIHfud%;^8FGX1{8nA~q+3qpKaaXftAzEu|Ls$YsJO!f9QY1D zy?h4RyBLDeKWCiMCl{{VYh}NmFQ>b0ZFsNU3$}7Lltx6cUg55f+z;!a2SrY2;qsI( ztiO#l+shoNt(bd}wgs{$0gVWH6VRwj01-j*(q&DN^u{$x_@&u^)@&}sg=S_TI;M!~ zONEd!(3m;K=7DjE8mNS>Vg5@vLn)l+8yXyB3-@N>8Llx+3Dkt$^V7({%aIKG%wf;Y zI!c8zs%hesSjoCOuC(IH7QFYsnD^WE6mc#b<0pR?nMt#8__#i3`Ai$U=4sG$u06AA zGhuy~T*kK5BXPnLZP*%>Mt7GxQeD6A!d@fQs4#8~2Ai0GKCcz2nGra8)qc^H>wQ7j zKDI~G*us|3Qb`xyU+e-Kdvjfibql5K_Lgkn8tmsXLotb|LCsVbsyw#|4aCht-*y2# z@4p+TAL(XWi!^A;{RniGdnX!^xDxwjwZZc{D)7xKiEIBjYv`dGyw&iLZW!D`gKXFH zOrMMB9#V`s|$y%B4JEyWFO7jXeo#xDT^aLLi2qN@@3VRNwfd1({Aed6Dv zM_SX83-8s1(AZkT{(c%wZ3;i}?SGn3KD(OxN3DA1i%p|#q^tAy(&64lVx3Gwy5E_F zRsAes=g{3aezi9Gda6Rn({M6!w;)65YevWUj?mj1oPf*dhv%8yj z!+{1DMd0;$@**>?t=fE^YohkQXF-3q;Fle8cy$VA`9{amhm+>C>~Sx6P~j+54Xvgf zLjokZo^Etw##Rhi*T6pY=5wV+D2|D-6c0Gfbzjm5?48nDG9u>{Ho0!$_f&mYzUc(K zojDnzhu>g=FgMz9eJhq%gs^?H9BBBG2o%kqEjEvcGx&XIdw} z0gtJ)i=IBp#tzdDJvHQcp1ky{%OXlp9RP+rGxw)_1ka!K5r1mA%6$f&{C8CV+ak-U zqI3>TjjR$54K$+q5WpSHCSbcpiSk3IqQWpk5RRLL0h6SVJgzTn7p zT*E0}K_$U1lIk0o7^CIVQ%_WQ9+Uq|p6^!R$i|;GruBvY_0*H_W!Y$)r_!_A4_};3 za|-ln=2bJ$YrKU2E=|MSC@mN;J)N?&y=mJsTT!lV9>{mSWqZ!0vJ?01=xJ3bR@mNS zSJbcKt5G&Rd;X0-&(cCp zu{9fL;XwcD`3-&k66STO5xv64p(fXu6)Y^Eg_aI9@wTH7o*I$gh$2*bWDZBVouqan zs_E{P-(rpWzBqrX2-4$C*}s+|oC%7kw9`T~uktiBtl~azzTaTqc>S4cfe^wy6f-kO z-N1=bR{64aC1+_iuRk;N<0NJSP0{_wTu54=%%(pn!c#?x=o%L)y6Czer!VS_Gvsvu zt1n}U&j{SorVY!tq>;`yd&=C?B|N!Ujry(#!WdbuA2_cFv7e*ZcH0DIU$>MVukXT* z1+H+8_Yd2Bn<%26x5Rix2ELUaf~W4QLA{>~h5cQRHc&p=o%4qsowN!s zj(-bI-6~*b%=a+LCbVLS2Fx+yv(?5X8h3S_L__@&p6$H|BS-Q6!TAzC4epCWSMb@e ze>1j-7xdJS!k}XiV>_&8PT4+qH0R29VGf^hDhnNH4yg2jcn4=`KyWohg)El*9?5ksV<&L0;g!go^ zbvSsuXHR|Te#|pWd#%N{{Che7YzPifG{eKXytkPug`r!uVaLWycIjL;7C+a+1#`4u zm(e{+I5wMt4bQOlq?Z^R9gpH4I*@eEiR^FvhkblLip=Kh$NUZNK+GA@uTRQL^?xp) z6A$|Xi@%2Fc>dIwLIJeCzDKr!bI3WpT9{&NOwtyHfg^bD9i>FuH%#W<89v`xJ7c5m zAvk)enK>O>Ma_C|I0MuhT7!M0zZX9u?U62$Wt+3`@OEdMd|U%gY)qk74ui(|P8vB|7gr2`qrgkjv22TVQSDrWSt?$H3;G2jdwKRY_ve2RI?y}{te;kf3G z9;}i}qnsNawDZ|N(G{Hn5cK=lv!fXDfwLjC!!T7pkfnTWM5Wp>*j6uqyZlBkId4Zg zF^<9$D~%~{cOeee?*~=kF49vQt4VI*AMv@neQ~MEF!(#tl)bp02X#F6h<4t&3%%xs#AaOY$NG+P-e zQg_~uDu%uA*L`i+{PGI!yXu3I?cDEkD1%PQInv6EpTc9?iqL9%2h5YvD1En2jfVQK zLXU1^kUy#n*N(=p%%A(%{zY8#zpFoIk_(nM3A$xKmn z+nn#7MbY@B@f(ZR-G-MdWzcnnD%38ErzwNYxqi40&^;Gv_5EtfHVKq0;cW8l31i{* zip!-lcNODzzT5mh?}7*#ns8a)|1i~97a-~w7~@#zl3ZiqTqAnHu>%5CdNZwLJF1@) zg3jqP#M`*Wb@1ImJv$1z+JqBd2I2WJ?^*v>d@r=DkrplKBY7-t-p8zgWMK~SL(mQkS*~z)Sc&B ztuDgd%lXf6V1vl|;C>u!@(w0-=s?6+1?f{?fBF8m2hLye| z7ll?yxtlSS#xiUWo5J{CMHpz?3A^{mif862k*3k)o_@fxbru?BAoN?-7w#wqk@)Ky zd_8^$q>tjdh|3Qtx!YNiy_D}yRGsmAIM+_6CXo6(_m_SQO=X4(4%AyI1a}GUvz-U8Vo9DQN)iR|WPAagRI#NqcTcgc$9<#%zXzlk zlOX9B0O0A1r#@)5?vd25&M6V$D5;d;jVTIri`4| zD=lj%_8N;h3+R`Y+Y?|-lDLNbA z0b4bzS>mE>Hu%UC`nI+c8=qLgfhJju{pSgvwFfXmH+Op1I|Z8)6ongi^r<)}9dG4y zukIJ`erB$TN%(4u8K&~z$1b-VWjwyZvHtqP zZJ`eA@9V;dQ@QNsKE5Y5)yDznwL#ZTo1W$!My1^mqCT_V;hptaxHMA_j%_K&g5NEG zW0wmqpDtiUUvIP+!F%juAyQL~*OYVomH6QWQ!+STixUR%zJmW-DW6)PLq=9~<`LHj z6%WT+V`G38S1dEx50w;Z-G$HiC z4m$UO>nO@y*h{N&)Ujy+kN49=&wARCo^>o5a6V)`KNoE+O4xIt4on-CODQ|_DdA;r zP|rPwMrETgUtI@|{I`Qr?s!r|m#wf@D28OcMz%a=2m5^3nMTY=z!}?au)3=ANWnHJ z!)K!3>ZfS-RD1Fj9b21@r!t`iH*7N-jz(U)uWMMZ|NbHFb0?$?)2_x>k5PdN$w zjo!1E({@aAsx!rZTZa=a&Sb8qUZ7FKVEprr>tU{(q9JNLqiwjW|Hhl#FZtp+9p80T z?0UnL=9`w`>4x5LX^sktOZvmWJabm|pd7cXl|{9i*20C8C9r|#>h!T&%BolH$61Y* zc->kXh6LnLY=8?@O^RUB$zIY~yB|?y{$_E7s2o#kzrdSto;Sefl&}0QTyBsgd{@uK zkh0&9?5hg_i>tBJEC8>&=t1>~Hd;D#13l~t7L*do(MzKRR-Vz2 zm0_ht+W*&(fs5#3&raO5&l?>31WF&dKP3m}{^C#kz3k%?U!1#91H8-2QEp-j_$JKq zpBh_$-`+LDrC|$1cGiaUd14%{_58yU+UDcm_Lq>)^#+>UyJvpDm@a?Qga__{(lY~} zQo;Ns;>WMgBGZaQmAhKtv#T7nU0c9PTr8XzsE7|Q428|QQOv&j75b=7!DZul9?kc| zaBgUSShW8!Yn(oUzTNqbjq`Qj-uiOfsnr5Ep8O}=f2)XDRUsg+Jcxa&bdVmNok?;_ zOhns`YS0zCjp)gBU;hRqVW+JY$}UldUIyv(x7m^$IeE}!^f~yj`WxHQY{UY%xB23S-#rv{Zuj%1rncj)-|FZ_aIr2z7ykKq1Kz8## zS2DSsh(|&cge?p8X@*7`4$W<6@m{O3McfnbXR3jOvT15qZ%V7|1wEg6asBOM8fP(A zyeqpL2idm3D~(7tC)|M^X2s(n89ULa;bu~E>nwWy;ag4V%~xpOXCazC<2Cc-VR+jR z3_|gFma?N9Z#lI<(JvV`8J)>}Qv!l?qNw!MGwizWiDNm_c<578${BkI+Yed8OT%_@ zP1``SvW23Gw@LV@!4y|!s6oo-avXWGnKQ%ng_(crpzgE|tWe{O_*A6g?IyHWdn#zE z=HeMEJ(RrC=J`k3!R+hGUN79B> zc5rfL4SxRag%$G*K&duF>hATDR6<^f{W+)Y^{*N{%313}-tc-D-V75|WkqZ6DUs>; z5WMi*2*VfheR;mroTb$@_WhSn3?kO7fc0U$eSM07i zp$!Kpf@_L=eXJnz)Opk}9mPLK9k}7LlYUD)=;m)*;rovw2>$boq3jM8d)S3aI@e-S z{7q){&yhsGHei^Mn~1KQ$J|OQJU&1lel07b>)cP+F#I@cFX#NX_B!gXo-J-0^$8Ee zCZn^G5ljr-O^&_#Qn8nesQl4M2(Eg=Om5q;kvm<;x^XS8*O|@EG{3;B=0W)Io<7*6 zn~{inO0NvD1lJrzJXPfdse?>dJ@={v*!DuT%hp2fZ$^D=?P<7p6ofbKN70ks*y*ng zNt}gcVjo54EVi=JvcA$g(T_-PTDI6cR~heeu9!%>U9z3OX-=@|g`eb;1a-Y!oTBx! zyH~mRs~Q{IML2Py9-Nv|M{j+iXb{>6^}ot7u&xPKebSID3e=#J8MDzv&kTP0^IoMg zg&n({%}y+hp%nd2G-~SyM*RY%wNZ~rc=z8_>!z{WuCHqKN)o=;5db4)4lQa-s=VYu5|!b(L^d#gOhgGyJ9oO_s^T2O|xE!ULsY z`|3!&t5pvw>cqp!w%|}Ei;K6q!naZVnOuo0xyA8!iy!iW zvYS3-ZAifp587CtYpe0;>>g;HqXygLw@|+z3u-Ct1@EUN(Hu9Y|1Ci1gp0Mq1YLQcOAKw4%Kht4~H`4Nh3XLMlk^4+xCtuKYd*$Z1#i#f0D3Df(uohjD4Qds*M zoLX>;1!_A{aB&9i`Qj=%_v1YGKv?2Nd#-;z$8~FiuF`}%o5j9mpK-cfGO8Rh0twqm z(`wyG?E6P})^P&7pEojvi?%Fzsyo?PC*X}`bJ_QCjTp2)pnGT1_4p9wlpB-XCrf{w z$Nc?h+EucDb47gaiaCu6KgAi>R$ywNh}T-&A$pB5OX&lobHD+n>Nb(g2)bB%=YyEKNVGVe_{1B#Y{0uTX7l|CE8Pn7UD^TA+1|}&jMCGT?LGV+B zN9T5PZK^R@?&UeWV*;gftLka#ff(`GbLVkhNjUC3qzw+va@g~O0Jr0(u-iRfW9Ed3 z-8zl%Q=B<-r7x_|sAo+lN6`%WjwOBcpw&YOJIV*cvkpIYy;FluG-u$@0fwO7m4wST zYT%|)btpWXNkLiG6#u4~4Vr%zTvmQzPWKI1;usf_rFiT=W{~7PXNwKai^uk>#t^bw zmDbm!qP>@+aK+98rucKW-?q&xJ0^;TzUV}A4?Bn~mgRmyXXsMz&z^7B=Z~Ms_)Wi^ zK~FXMV3md;DuqJBaGpiENd|`(s)2XyHgf*fn>3r`K*?DakJdXugw7#}#sf3y%TF8V zXVVgs>e{;DnE-v*Yi>^Y zmkMy_WE+@BZPccgPIOOVlI3BjQgRTHejHwl${%T z02K>#uwsi21oA!P4CJiu@jJxNhJQqzSD82?mg~kPu5@c>CN8-)hTW8@!57or@c`Fw zW;cgOBdQzd_Q99p%4!Q5b)g2g59$qry_9KZ>R=rC-Uxo34#UNVs=<4+GI(b!Bb6A= z1h(*p?f-IcTyIDGS)vJptM<{+P2Lo`(u+Mc)W&&bqhaxjE{R6AJw4u@iZQzXgj*~Z z16t*A$8OGxTYHd%1U;U|V-1`BRO6>UBQaP<7s8eI(#J$ETDadqSpBjH^h@izcb=-; zJN7#%zWXen;pfKfQ8J$G?^T&^2BGtr}dQY?%=otxE8k*LYE7221t^I$>u^CeK5m;Xy72=~$pn z9%s?;Jibk`5%lTf7PiVn1@BaOg50cjiAQ}dzU=oM+;}Fk?8zEbixTi5*Cl2))KO2< z2+GN{5%%zzeY5d&9LhB?dC!#K*Y8B8-?o`4G%cq&^Z2Y?-XHvi21=FRJ*1$%zT%pG zIhb(88;_sn3{M#o+Bt4HE{l8N## z_)vZ|=Kr3GFI08lda*oCZx&$tp>Vcn+-tr|7>|0Kd)6NhgIru+kWqWYl9k5N*`1vj zpQ#Ud{T1=JeE{5<0l@rWbeIS9#!$J8;RN*(TcZzRzt zE9yJ_3;X(}3Z8X-V%Gf)SOU+w65U>j13ntVfwvyuw6vo8zV@9xgC_p$#E`LlVDS|> zocG)bw$2;CjG8^D-`;f?XR9O_Y}TjrsY%#+s*RmcQ>U&EshIYoPzcjoi@9b0!0)~q zJha$O-_&~3MOk?`^DaOdQu~(tTI0prGJ4^zpZ1VzR45tVWG2-(ok5N4Tg{ll_gKc~ zuBASPkTB;6jOhvhxe@1C%?MTe=ie9p)en^fUEq2Q_c+Y_FhSJp)WCPkF5PEYGSq^4 zZ!JK#AY15jyp8PNrBeLme9_Z5&SCv-%o!!>u%cfbxJ9VL(x>~`y%=|bt(h42;WE>H zeE@BqXk+y&9Z2-~glXe4@mH-r$TvGtDeq^pdxx^K6Kimlp&M?<*M|Z8{0?~gltMjT zis$U@O;7x5FziZicq`Sx(1y`G!`X(ZADfJqOU^^nH)ZHCT$5V$((&rkmu!FPew-fS z(B0cBjNeV~tldf4$Bj*UqluYiBcLedyJX@Gen#AQ{S4)2$LIjAXp=+6@7(lgO?qIF zj(JCSu>JWLa892Q*ur%hHK}`PXQ3w@zUCmba2;cCXnnUvx}vWKExQ_zZSU`}qdImp zL@o)P!yQDHN_@XM${g>Z9z2iIq^D0g)1z3KP5<#3GaVB#&d-Qvo|b~4X#=AjcI+J2 zrA*UZi9h3_S&xSfWcf7(101J_+PfO@)=~jq)bo8N&p`D4nudwPvIl)K4U&%XxZdsF`QQe3>(8k){4;Gm(-Fyy=uGZ^DczHgRcjeV|Az4#(5%rOMPJ(De)1T^rZ zHSH}Ah4HHo;H$~zIP1GMME5Mhx&Hk z-H{2CDM)D}HXc$EW{o$c?6=FXcX$s7frU6c@oD!?Qg8k~dLC#@Yfo|3BJa~$`aYlv z$zt&vxPU&Jr{d~D9k|A4@Sn>E!8GpGistp+rD1Hh529`85ty6h1xqG8ViUv0Q$uJM zy1X<1cmD2iN-BcOF9$O9+0JyMISnIwnF;win&iJT4YM8@z~TqV_}NSy9dtFo(J+f{ z9<}0n-xlU4tpq&#jxlq6R-MUtXn$idMTz?sS8<;C^X%-f_iJAAE z#d9Y+amYk__-EF4|5XLM=#LBoDSf1Ek0Py(Zg?cyZqxd6a+Z2v^IGNdC@uCyNuS zaJjOxXlIEgSy*!J+4Z5K>V6+^TH-u(8gB>_bB@B1y8+$r8ikJrlbO{T^j)!;74~hw zp^u%gpDx#{pVOp|&gp2@oFRG?*P9Bb6ySDGJ4oVtp`t(cDM+n{ShG0=KLil!pnQ-{*Ixhx>Vk#bk_9Qi)L(*5#KzET_i_11+Ir%#exu`AUj zZeu58Kco4)OboL#fX){@J5)CVdrcqBT0LuU+gexjT&fSTWg*g5{ilRC8pR_0-lXPr z0Y5nPhBNoHP-fFeu(7dX16o{2u6G75_;y@a%s)pB{yENH^per9{aCle0ZaY0KxX$I z8W7+?_cPqtxDYekR1pE&F3K@;YyOs{8Mvs>rot#w?8GVg@DNdnblWl~D1yjkE?^}jGER_uP z(IBJ#;ppsa3Ju#;;Dc{s_a5@|xK%VavlD;L@`F7*TQGakJsP&fM_gjCA0;2WaC4Ie zr0tzdA&WU{VzZJkSZYC6j>jU&@w`-F5w^5HhOQu0xOjda&G9oLi)vk%Jd10O*WTl- zfW_iewHjnLQ}8L*`6qplL#v_zknns8TfXr%{!`>{*?Ib4&~yaG*Ls36Jz~SnCXq(w z4-DR91b@~l<5DFtv?=(r{2v;m7?g?!IV*T{aWXoBDu3@(2kECQ>KkfBZj-*UEcLU{ zxalq9x$SJbh8A@stUw{s1gujvX$aRQ{WW$KX6@vhYT2^xTJfK9G#TIN#BI|YV3|yy zbVA=(WVcK#-abVE11>l~yt^OU|AqT$2E<}Xu!5kl#ej}2TaW#Bw=?m6O-gx`iq?@w zg!k6#aOH&GQ1Mv}baQr)Y!3@cc_t6Hdj(1d`o5w|TJhrYU)K1%U?c<_t&^CUxRYd6 zEZ$Cc61~2pNhklMV!(l+qHWhcV72O8e9u`8%Xb$+#GC+_|FfFqu8yGX4I9zXC6DP1 zaHT;{mf`CGlSB`eHeiR?5nn0k!$_`8Dw0jZua`4K6kSi8=uK}|pGT*my*+dxTW<MgoGqXEQ z7_YYuZ~7R4sc$>k|IMNqQ%8zktvU(SJ?dHM23z)pxsi3mGW1T5W-}w4X;i-yl&KFF zrG9M0J#_=|OC)E8SZPs%Bme&oH~S?gYxjrB2$z&bKmsFYcxJK zj7Ao1VLDctbnEjGoKhbpn&qaBsRP_WrK?loDY(;N)#a$8`%6&1egNGDeeJF@VUAkV z>XC}>v6iCLzY^Si%MX=(3}6UnRh>x=qdxs?go>q6G~XZ#3s;|!s9S2##gCJ5C};g0 zHB^R|DQnosl+A2F#%iMCP8~y7vsYGlzC?f2_hNJ-9uGzo9(1 zL*rT&iOZ+f;PVGzcsX4MGS17R!nOY0y^24d6XWhaAQJ&wAcChjD0JgKyjT|;E zLo;0kVeWhb8vAH1UX^WUGpg5N=DnZbBC8ID!Tb#<&YYC|6yUu|p!8ivBPkWG5>L~y z!V@otg1XTa$*Hi9xcfvj7Hl?z?19Db_LvxsOuWFpX+}`mzYW-N_5fRe4Y={PJ*sNx z!=mSw^r}}r=IZrlYRte$G*T5}G z8Pb$<*)*{SJ?@o`PnEB*j@Ue08l!Hs(948LgT!a9X1Q++Ptv zJ=8bg@>fQ!l|Yy__lOBEH-e73uANyI&CS2y7JL!X(=r~^1(qYp;a zazB;)9{PFHnKYVQ*$!uOd}0>{V|3(MV_*e3>nP&JlNo|IIuD2X^x}7cF1)C$#ho)k zaF3ZDEYLs3wHLR#-zK70>)>de5I8>Qq-4u_z6buUfcGYy73S~Yy9kjnF3r+|@FR`5 zRckRO>u7=Z&kmaLJd3t23Khl7ECspM57~tQcI<3wIc}v6*yr|HGI)vuC0niMIlf_{ zbnlmF<}m=@OxA~1#g}NfW-)%e^P1g0-V+NtEI=Vmhk3=8fOGDYNqWd>(C)ZNsFiI3W1gr&fMWuaGu_H| z3|UL9UY*#+{9)-5o*`&66XKrM^DizIA>T1WkzrnDVBk}f5eF#n}f@R!`WuW+k-R+u8 zi{EwOxu3=`f1oVB4&l2;Id671&yC)PaQ*OD3&Eg=7Rm7WM8?DrjDu59$6N*fa!&Ze zl+DzCuO)4_YGYXss{rr3U@>X>%xy?HmMrezxm!Gb@}d^aP*{o`r6%xI>rR;D2 z%}n|9JjyBR#H1J}*e1)p|7FkVV1-Eh?wC9(KemC!hXdH50hJsi1!ABknbtjeU8x!UO+ea4{Ek_ZW^dP4U4J0cL)Pl>FiE<~`lNLI1)A zq3TKl+VeBAtx*re_xRnEbr4rv=>s2J_%5;j7Ok8rBW~t3wb;9=a1;X9Q{(-wabwd4LDZU+{ff2AU5vgcG$V;or+9=Cs0wT~=|X!o5j2CyLjB`!%>f!V%jB>O;+q z5b5ft4@u?J3-Q}b8`}Ho0@@t4h9n;)l;{lve+5I9$k~$Pb}68Vue)%xe+i^*QG>br zC$ss{1|;6M0o}OI&SS{|oc@Tj+pcNB)}TG)%l9}d&D>Zz_hL?b*$!uR?O_%j<(RZt z0cUWY^Q@_P`1^BD%=FNOgoau?tgR7;PhW`7WVB%a{1%Gaok80sg@_b7PeRwodu+;4 zTlOQO96P8L&Q*SrFfAt<_K&|i=S&gZOniw}dwucAcwQ4iUt$6+#PKIyvwrdNIBKgE zJS#F_v7zOtT-pl8=PiYc@pqss$^>Tpx0UTQM%t-uPO;-dp-;v^ocYxlBO7$UGM{sC zZy!ScswmNxu{wCk&=ZQ>WmwRPa{SlW3VoH=3tFr5P<22PY<;5(Y^elCb^7A9Kz%qs z)2Oc~1KqMuOG?x$(Cl;@9J!$+`twMgdVU#?K8_|}k*^3x{8upAn#HisI!fU@Lp^-~ zCh%I}KkX(RJlan@{Z20C9`NAV<(jZfcN)pmr(^4ORYAY&6s~k_hVM=5L=jJ1Y0H>o zbo-(KW2K9+W&T4@PF4kWDVGKZ8dCZPeOR|HP^z`)CY`fiBu-sgi#NAV#GpDI7&KNM zZ>o61*h^EG%Op42Rho?Ji>}rtroO?{E^*TUtRhnQC`CY17)!7@Ygs1oC=&!Yi4R%<9!9_NQd#Njgy(*K;$tcI`TqkzGzf`yp_6arj&qTXZhHx~} z6iXBb!Mr1plBfJ<=Kg90FPR1*y1fCb7TDs4>w2*Dkv09ZJcz!V?BN&JF4lS7q*yl@ z@l@d4tONt>5vc(WO`^zsN;=x_J}-Rmse=%n5vuw%hfNyqNO_tcR!Fg(3vjYNx){Ck*upnEe`vy z4?g{=2iF{iNuRphrx`O}h;O^wQZwHnzK~eMP zPC)Y`6*%WLg_#5!kPwuP0WF`H&44`2>1T`4YTB^+)*c%1){%Bwy0Jasx|rBI7?wBv zl;|{;Q< zCHy(p23|OsFxgH*BalWFo05lrC^UQK<1cSxT*Gq% zUAPDNp==>eDx4-Nx~Ywdes0~K(C-`hcgDK~OrIwR%dShX=9mxe3eks!hxys(`?P}K z(~_IV%JEfX3xrNo5~X=+&~TS=_-m30Jej8mnY)&AR$2|fwFY;Ye zLLXWt$-u$)WJP^EVo?6(eUNTcg5=yixW zC0|#9Cf>I{2zW}%N39e`Xz5~%#2p@us+26OEXT;jEnwhND!g3t35|Ik;s5wci_DI| zj`jUv;pHm!hX2f8{xc=tp9%L$m2jcTa1ihB&t^nw(Ug`fWFh?A4Gxs{in~tx-~JQH zYp0{uL49;x#Ph)i&!mZI>A0z9jZksp2FOJ#K%bNYEX~ZF+&dC6;O|A&`tBf(KCg;F zoUiUUxr_=f+0(!=+u5WyU-A0hbS&Xn3}ufZsqftsyg5-%v|vLih!4MGsiii|XQV4x znDO3t(kPblvj)2c+To@1{P!7aM^JYjFJ;-l5P4M$|Kba84;eEDuCduw+6&bS-GrmP zPC#O~GOWYN>@xQZ4y;VYbE==%;IDbumSuwrmvRlQV;#|fDC)|a!{jC^qbAQP3_9~s zqRVyNW4HCf@RoF8mB~SjfAEjLo9V*HaG(sXm!9(^0Cu%9JX{cr+g0=->rxy2Se-$~ zGt-15!y<6}e39*cu$86PmgB&(CKwz&mi;c~OxCNty6eCroeS94NFU|+Y`b9m7Yyzf zhwHVC;KR65=&|%>cRzsqe0lBW8i~!HBoe`exQh@??uCn_rmyhHd~duniu+bmIVEEz`+x(l1=U*aEuD z<#5&rH`uYyn_cYkpx<|sFy=vTVbc+QrxzrmqL~qN$fY8isn}f;297vDzQJzP^NJiy z?W}-{fe+cg6kRrxvjmk)o57T~zUQuK)3D78@SO?Yct7=kMWx5se9ukn$d4FW{IL@! z>bb#fevd0JdrTKk3*y_}3V2|W1$gxs$i#eBofy^JJukS&7}KRYD{+o~s-J2$vk5qpP|Vwrtje zUo*8S?pPM@>$op|81L;_9UWZpPt+qc9Y+-D;ojLA@W_2CHTFruO#zic+L3w~_M7u9 z>W;ARW3E(jI{}XkkuvQo&ZLsR5l5Hz6VW4%zzTq>+koksn!S>OtIc-3C{D)P^z6b=2k%MSWA} zu&7oge0#(jl7D`X^d5W={dfF>*YkMZZVZsxb$jx99sqhv0B7C|#;u&;nI~TaA4d`s zAKc1nPgbB-WKUeTt4i>SynsjU=%U61J(xJJ1&8>=V(mI3SS!olH2*_=rm@wMk3L(U2>;ojsfo)0qosjR4}DF&-o-07|ZXTKbzZT$?W%f$$a_XJ7{CS0Y+ ze+#%blc9&*IFxbGg$XAv!1aM0?9xa>R;lwAuPO||a6f(M;@s(rTw|=AJxCDO9R~TU z_F((<0o!FTn>M)q!JY>!L51thx6X5hb?JTC;sXBW)?+P(=b8!XCv@qXQxbmo!@b*m zQxWGXpsPe3wCC-h{vWMqx#%a$6ji}u*#}HzfgT(4L7RGo&%@KbOhLTf1HRoYV)><6 z%*1{f87Oq&(W&krapS(i%6iTv7Q}Lk<#Ejn&h6t~tw9q^Xpkfh12%TD;7N(7SJnnm zaq1A|w~u1mO=W<8cf*JrMrW|$5$)K7Y1rSDYq!=;BL%Mgj)>C}Ez>In%aTSm z?3Fe9(Ck7ZbmEcUUu@05S{ygpx|{i+muydAea>TqrXBQIq=e5!9`JRc0Xw(Gfjo9B z!%v?N3ky96u=i`YF2T)*BEb3N^Wr$b8CpXasohYUWBt`g?tU%-t?I^8wlc0&u!-@cq@%^N}X z{gd#0*A@R&> z7O4xbLQhiAZ#OD+TFxe#Ytx!O`B*i0x=5o@1ARShA!^DG$qnG_;u)D}aB2X19m&uw z)C-6G)#I88d1-UN2HN2~Nr=ywM(4*R;^V_*lHPXucwy8;SQ2E#EN-iSVg8bCEmLJw z67^o%hGS#{U<~JC)$G1ZUa{U{_s4k{Y2u3NbG1PAnLCxlti`H&O_(#>fz%B-gRV?Y zbUI`S=3Keeecqv_kla@rl6$TR4BN`*=v|jdBWr=UXbxbH*JH8ei!S_LR1NcLTi7`Z z0~WgPE#BHW80-0d^^(_Nu&uR&>9_8)yw2HFr2ZSHe71xO{N6v|<^)&VyxH_)o@CQ= zJ!+|13dQbvbb3Z28jUc4m}oT;txZMA^AaKLcq+PbEkf0Ab?9{5L7zri($Mf9%&)By zPJOt;rpoHEandRDsCX0F+AfszUZ_J3H#q+;%oIB7JYdz%qupoUf7J?76T0xf^Bz#k z^_k0m{x6445U*OOfHDc3;mY3#J{>WovXOB-EBOZ-zBv&)-hAyo`y)>0kfxp)UCdVD zvq_+|Q0YG+**Nj@NK2G(uSf5H7bRm9ny}tB0z=6VUicmc&wpNU<3a@sZSRf#H+?}g zV3y?OEoH2=2!=;oXEn%Hk5nXC=rGq1UQd+TNT{^GBwlWS?el&kno(?hH-kthyo5ec{L`Ld*6*e5Gdqv%-s@xUjan2ly{f z7k@qQ1Kk-XB@HzdILY!K#JE=pz4-p}mxp%u*>{TiiZgyK#o1epznhHpI2y;?~XN`HG1-#J&k&N3_CjQVMl`!*A|+> zq%vd1%BPW+SvDR&a8ZF&%6 zDldK3BZF#7CJM#Hk<@GWTI{%TN)kC&7yBlRffsJQS^5Zjdef1Nf3nMj)}^W-ijHB8 zQQ7Q6q$V9wPRC!ikJ!GoQH6XUh3(pT)xHJx5^A89UhR z`;bw{TvA{E8)f{hA?C3>UYOtn?Gt=h!5J^gIJS;wty&7p^YkcAX+1vVyyX#GlQ7jK z9cNBEC8%)2Pr@TP3{&Ov@|e9O*=9?_ZpeVpqY73GxW!I=(q;Gdgws~*P59x-B1!a3 z9g>la#>X2>!Qi($tQvcm{kpf2O{j~bl$b7*H}rz245YHy{fG3yA*_J6rxKru^zJn%9{A!hP z_@hARYcPOis`JcWz7ssrsSTN2o9rg5i#s>-z3!M9G|D#-ad)+#u%I5=9xK8uwIghK zk_Sa>Ta6B9FR?jlb`<5!xu6ZMBJs_9EK&Xc`p}nW*!^kYx!77?BrArs<802~zFxz% zJ+Y;rcC4YhKCE2kMk|l4M5-UfCi48;r2=PUl}{HOvlU#s`-JvJ7do{p7NMnBDE2%7*?;7~sMlnsQfol2q8B!Wc}c&ahv3Ai4&E)c=dnEdQrDS(=hu!D zDfDRNUhpM&rqT%fFPFlO4N@kvfa{=&rqb)Lnb?D6GxwpdahP_r8y<(*t7ot)^|I@ z<73^?`y|)@f02`>pG_mF!bHLUq8je(5ex(C4O!~1hqGT!zSTDnVPj?}mJ!!Zl zTTwL1VJSX7dL6zVRt1Bxnl$+#&tu)1$1`@b*(4UO^gROezuG{+v1Gk zD;5_%HxmX{>5!bk_gZI(=;kHyitp|{E z6`0?--d!JzZbs0XkSrYeVX-95RF`i0%|gp#rf}u72mIS~h}Ao0F$?W@(kSV|?B#u7 zR8*jJ@0oivc(uQH@P0*9;jE_r>79mOoIz;0wNq7G$Y*mnf*~Uq@s;C(p z530lEBe~Qu%aoG-jN-oI(A*7J z&)=UaNE4u3qnauJ-qRehf9|a^9&b0_w9@8t`%GJ?C1@jk@=oPR6Ml+ zt)dlh1J8+@%k`phE}Uz0t65?v>cFPo$*BL*2pU34Ax!ZxlWw$T>-c-IP5E-v_%w>C z6gksCKKmD`%@jFmN-%b=MfV($xk;0P+*5IR+L$QoX;)aF(S@?&bS zdbb8=p6G$xW3EdyD8 zi1o9dMgtdbM7Q!QLSo!q_etZFEwdI?^N{md&GA0-KPE_Cp>Sc4U(`KboqWfRu-xWzjvFV$>GVcYOf6Y z@~0ec3{t}U?VE+qT-TZ1S=U_?-pWhSZrf-qwcvc|Pt|~L-?L5f2F&O5JKXX~guCYQ zJoMbdu>73vT2*w(5a3t{PM*cWVsJ0SL-f4_VX80 zq#}l<>cjfdf$Y0c7)jN*w{ED7(A2@tf@3;(s!L?+KMQKV+E_D;E94fp%<3-7?q`p00T@iUfAJ#lt*Z#cO^gN65XCtJ>(d{cN_7~}9C==ZV$ow#%ss$)oo ztJh-mg^#Q)y#QNpnd9wX9T3R|G#+RtcVgelxdn5t#WJl;;FH|Nul zwp|qNe!m5h5u8~Vna!RnbEYWQfp0Opz_uzK!t_x(DB{0EymcvUd*DdDjxA$~UpZsD z(iFxgc1d;*DTB@BU)kp0)+|NGnLa#7!mE$_G2M2Cx-l-;$nRMfGgUmqd2w=Q^qCpo zOP4e&po-W}cyFNs_H(1zgvFcKfP49vm*t2-7TTcLno5N=TQS_nPMDWzhK(kZ;OA@^ z_F--XW}7QwRn=zUrq438-hLHA9;?Dr&5L;J^C&#dIp=Xr=V0!>S1ewv$1IPOWBc%L zaBcJO+K*%2;kUE?+>@&Z(*8%lOWz9YkKbnr^A=FTksp|uZUb>{@@TQh1~eXfvoD#P z4`BBVHfa?2pZ%>zDYIAMW?vKNYEQ$YxxH}Q3=P;jc`rTNVoBjpB~>q;gY5(@vAQVWKn2mZU!~eJs^H?KC@V}kqIx?QM&pM zH0PXiW3GuZ7<8MI?+g-qGDRHlQWtFH{MdyVlj#3QIuE~`-|vs3z2{wbTT6Q{q~3R% zkP(s<@iDVkR@y@)Gh4LNLPb&U>zu1(@4a_InyXt{~|uut7#sUEF4PLFoucu8o$QFez$4mqIEuA`HEO? zr~~(8O8KH|_H@D91YD3QRqrsf9lxxfCO+2{Tpkn}+CkTpv!wLq1`6Sn}nyMx~*V%vP(I$lrIP_W_C-Jcv z{+|CvygwZvf4vz848DU(cOa>ds>aIuGHCdqo;&sLB>pp##=OtWt8(lO`Z}+`F&0W7 zV^aaEmpvq-Tuh0ZPZh>Deuu<^_xTMv)>NC#L*pkzhkLnrK3$3s1xCL(>!i71;&^IcXOkAo%zpBTuVcu6VM?V*P zWsLAKuK_FD)NzQMtJoXm-du%-n|h(LF^Rh~^dzR4{r|ZhcM<8+W&eM!Bi|#gaP>y7 zP5~7ED*~(e)#90eR*)tZt#E;>-evsC&MGwh&;uV6tGNe*>#=l(B0eh6gxkY=urPTU z%AL`Hps^Kj!u%pRw9SlMv(v}$zoS5IS}^kxvK?__5BLYY=MJs=fNxnY+yBmW@gQ3o z#TDUvfemc+m&dvdnxK%WOYRiUpz`C{8_K7V(^z~5HkK&D7^f^^KH7nveiqMI$91I3 zJP(h{tK%4!akFDw1yyGA)2Y#G7z4+zF}~s^9XWr$kJd{ytUIm`joH8XO`|Je>(MrH zpiUBGs}UA5 zuhAP%F56BHLc8aZh5kFpJ(rVM8E=Ijoz>yL+(a6@bSDljH|HjuF~lhz)1b#;FuB5Z zQctR+@n}XS=k{w2T6kQBnOaKV5_ky*R!zY7OuKG|wNSU`HRqa-TA$5QN-V2f8%|9rU z#-raUH*UU2K(!Ai;joF?P&7Rao1#?FfN{BFy_2Y0b0%(Xc*dM2YdZ zp4fE3`aOXpl4XLgJ}8AfN9ws@qjK@5g(NCm)&%EMZ!z@GG7N}Rf^l0aVCd+(;r#D%Ehss^jeIZ9#TCW|_=GWyE6=IpZg7A? zmhY+GScP0v7c@mDag*5lqhi%)_*A=z#KkpIp_CC_e!&lZ&!#xN$P@QI5dh{DLtW-s z@?CB>xvwC=yV}n115{MZ+O6IDHgWt!1SpV zFlc`*X^Su;`?&~uWo{A%ZrDW@6<6Wqx=zr!@{ZfI=L62X$1>HJKJXKp6Q-0F;*bkA zAoWQO7Y$K|SO0WKW@Q8|XT7Fl+GTF$w!5IxqyVK&S)_H39Ubcui!XkjBVpMVv|lb2 zPshlM9p+vIJjh1P6>Ep~57(xNI?4Dp_YKLud=ksbEpf^^b!aqY+DSncek-u# zCdF&w0jofG8Q;zKtgprmW27)XGLyUK(~O4aLhxFXHeBzig`bQq^S?TGUwV0u#2R>tyF*j~KQ6j-*pY^< zipR%G6~Is!k2f#0fZiQt7~GOa_k1^?ZQ<%LG{&!ydvKk4?_TROcb5wG4H80!PX*r^ z*MaY2L-9zf5MHR|!#7nMSia{h`4F+0_NOOeSnO%?uT~m;np_|@*M*Fj<4AM-;<2sP zopYTbV2DiSeY4kwg+*y-n5=@q*HmGG%2l?E5USDF#oe&lj!rAo$Z*7n2eN@Z-7zJ@0ak_2D+) z@l*~&%}kk^MvFXUI+>!Tc6hVFj;l_31T$<5pv@|oD8=Z~Bc0KhyP}O89g>F$iu!2( zMgw}5YGCUOd-!~;kDoB88V`PJhm@EkZtOZ4JP;8GS+SdlD6xs&^){pt8~ou$F2!uG zk?3`k>3qHvgG%UWa>8skdHGZW?U&iZ#091N-d9Y|KfE21WvjWG2s!K^qhV|5bize` z!*?4Omx4z$0d4<+(Yues%&*`jJJPm`3sR*mfv+{*HUWe?Ti!3p^`g z@6&sBv|73l2TimEYh5`!XrKaCKZImVL?oS>oP?%zSGg0~_rPU`JUo)vMMfNRpf4xJ zGVggUIig}oRa8>&&S`nkt%f{wd!&M=7{l{QkzZr8-!qInZ7@iyVEJM%v$K)0m}6sNnyWbnE0|<6aAVy_xZDnp5b#3z;Y} z#)^BggR!R1yTd*CxBS2qwp(eGz%boR?s;G{CiIWPaq-&l&a@78EPf_F`yuz37R$1o zv4+Mr%uV=&@=7C7QJ@7c;`2e-!~oPQ?~=<-tLgr*el#htfc4|0F?FRO_^xy#cO6&6cXb(ZoDjA#X)>Q5N1Po`Zj~JegpiNu=k` zrfK`*afkDA-dcg>4Xtg50V`FJ*Kh&ds=}CTjIke`;RKF9j*zK8(uihRJl&tuk9+Dp z!EdWy;}xxI^vAX&AwK(6>l|rFM=WZy z_tVbp@%Y{UBe=<_u{w<*)+}JyS*pEj4(%IEg;-O&9k7MV1v{x$Y+Ub|8^N zM^$46J4escgP2#>incP(?+_0sk;|D}Oy`G)`~MyCeds$Q247v$0oAREv|udze}6fM zK8II8K*ddR?zsucV;OBJH`^gc_<$#??dZVzZMg1kq)0H1;L3|S;yTc1?nsq%&M`iN z4Kzl`qp_DM6a;INw6RRbex)70bl7phWA4C6N2Z4w9#3j&beVoN8dEFU$VHPpti7v; zN$naiS4|#^-|Nb>Qh( z$;KxKQ|Ogl;i8L$6|kqKO56`{TV~ULy|Jh(okd(&-n-?}uV5Sfo@>-o#-UN;p=B-G z%e=6sd{P09QnmxHCvxceNC{3B=@8qJS+smhEHq45>_d_3oA;QIn?m>c(pKYwx# zU3W4L!AxJ2DRG)*OMfKMzu3FrydB+QumvLuJcwzr9i71Vfw^{Gq60et!!s;UK|ug{ z&FYO$I(N`9c8fXFcRF-Pm?0`guI8Vtlf{l_P7tZ7PLAHQqJ3M|S-!wF16)?Zds{HiwNIHRxaEB2!)BbL z5v7Loj*~5zm0rT~L&5m@k`{oV4z{K}COM6oWaq6<*u8i-nlQGENmv0S#_NOaf_o${ zehtme`ib{^EFt;56u$qW2X{`plJ^(1>E0!)aj2<26d0sn#*KeaUd;4wOY-P}Z5H(F zGFjNDeGZ~$UlhL!vbN1;DD+r-sk)pGG}gil$#5{vVjgqGI%t}Eh&*UaB^|#K=*t)V zXf@so?l8?Hzw`?A%^2lVnag+!2NWUM){{7_m_yel#Nj?SORn>y1NHQe!IU_8kiHO) zdfVT_Y&AAle3eI!80b-(M`|F?W`k9XPj&gs8lRZm+UU}&2TStK^RYc0`1JDxtg98m zs$@l~CzZr{nu*+%%ek=S@i4fNa+;(&3F-So`gqS_8u8vIgO2AMVZ|(0QvAlAW?b8f z>(9G#LmvyM#k_bdanlC3l{=X4K}me}1N)O{e0duFH}Hb>Y`&d3y{EI%Ef1dT^PuT9SIgx&!nu3k#WGC_sxjuS z4WJ5Rm`^lA! zq>*v+g>=S$2^cWrEtzyX7n|bEasLr@D1M|(^|f^|^>@8@o3;YBid^94%D4QXa^G&NImk5N9q*2>_B4RVn4-w1L%pYbk+#^Awo3UIc^lBVk= zpS~Hmy-4W?P8ga^OEuQ(T3XXJMimuMJ#Alg>ysoXh4S^`qORP zuo0Co{LW=@Z@=%QBJLjQ%9w#i_$Q2)cvWW*&U${4`(2WUbF>DD&-I7UA7~@B8F#+W zfiL?K=@J{p<2vmidLgKQ<&n*##MXp_5Py1e#TJ}jzmOEHB>0FIppK>hg2y^jdp0k2 zO0xxwlSj{b15jf-ng*R409RCD=kyrTK9G+=S9NfIwLe0$^5|JLzS56;+R9yw5lNQE3k%yTl&2ST&XN?^vq_U z@Q?K%udh$1AEbBSHwz!Gph=JMqt>9(OCu=0m4a0V2SB=0h0W6QsNyp->MoFlojYpa zY+4QJoS?z7>?7&8C9(LrYBjILH1F#!hJtmuJ{hyontCyQOJvAsuG-THl4l$sm3nC; z&R>;gvb~#>|1FX=Q5L^WV0pSsYxiHoEV{{LGu{au##K#mrs*MDF_esFT_HSU=NELW4Ql%Ca$r#eToxJkVL31A+7&E($KXKchR)%iG{GF2Zp95^@ zoU9}a-?~V2Hmehl?;D4+P6^@kI<^ZAOGb}9Q@I^%?&0yn9M1hbL$o#v=)6q=bQ(07 zxM#|vFv<~@efA*Dr<`f%m941ZFr1TM_j}RT?P%Vl1wm_7sp7O`Tx?dynV;W*Pi`oP z=lu6w^{CKQ5B+X$<7&QEKzMpHk-eNq*61qXyHXc;pLT@bR%1_V>^EY`D>sq;w>)e- z`wxb&`^aOPDh-ZcZ>qS-BH4-``1%;TcLsFe0`or(s?tG|6W6)*z7^ng{StXNhH;7% z1F4t&R{Uwdn7of7I5$v$;X?$l{+udJ-j|FG6OM`oo4e5b^lDu0ZwCTi4#Sx4(%wRg zOulvt+{dVc@$FcWu-=j89ZtjC6;uykW6}Gx=g0#Xg?D1mw_@wk5|Iut_tu+ z$AH|J6-m>RwqeniD_rugJ8);U1hgF6NgjudpxwoBXm3Nwlkry6{!~2H_sWZ!XBFUz zX9{R^mU)(=RB51A5>|CL^JWf8$ZIKp>+l}_T23XHb-W;I0u$oFxLbh%8!(XFUoA6- z(eVqI7IeF-$lVn&Vxg(HZX|B~AMYiJMFGzDZedxV1`j<*GAb9K@s zX+!@DT8Y}GXShU3IanAIO5}c~lA{$mG_5}l-xxw)7v#G(6bo7tyZ^$tI zjE!wBV&Bjl?*h2TvX}qYOH>Iq(|6DMG4!Y{_@3NL=d9X|7NupP1XWq)4-!JOmIrwe zFr9|UrlN4Oh)a2(N3Bv<;rALNxWn{vJ$=7GPfHcv9?7E%*PGJ**UU%9^uzDHt4L6S z2Kl-yf=(N`89i65;CEZ9vnbA(3vHEN@dCU&>7++IwYj-z~;X)p8@>|8t;E7p=$R z2VA-LgS4nEW1S4HVY}LRrb)9-!bx9ix$hF`==)wCy}DGPvtEy$X=nZXq!@1M?n;>Q zg^K%)7Z3C>ZL==~Z7AgpkFi#@DzcgFO09I5XTIGII$1vZmfkEpr2atkGEWA*S(aew5e@R+sG0OuZYp-p zzsLQIz72kix#iXyORhKA)7;xhIN_Eg*m@M=bk;lO>=uALn`^Cz(SiEoEqt`+8AyX( z@_2*^nYPB38Vn>bKU*nd;5VXDmNT|V3qUSdy7B$UBUcArsrJX~ zYqTKTOpgYpYhmbTB~knRS{Od!2J!i&LH7QNq&?D^sPOu4!-WH%@!w)+vDWBQPd;or z!WdwgcZizwRyuI7A1ey%Ak0}79k*$TYs<{MFsk=E30tZ-?%r`j>OO7_hRiSlb>mdz zvVQ{JR)Ox4JbFyagpR9}fkzi=Kz{mZ;^(eGeg@2=w?9YY65CaL(RLLyPYHxSF9jrg zzYVQaOu!P2G29bmJe4>5#667Pnl$?F&o69#>j#I9%V7Q?3CJ@WK~@K)(%603s6TN$ zXS>b-PdyBWK$gNftfdMMFn-r{gV9{p(*!*F>;-UZ**x0a3#A62xKT?fD`<)h_&~JVvZ7T$fz{k$+9aIt1ZUP1?Lt6&2}35_3WZ1Jf+U z`v@s}En2>F3l^7XLCnZ>jC?OAey2P-t4FJ|1$aR&hI^}X8ggC$@t=}JcFr`x<)))S zW9?azjaF5H`avN+WD2w|L^Ba!z?aw64ca#RdbA|ZcN*nu|*%@aXmHUA_ji)%(nCox%Xs|4GTmlQJVnl&XvF8^SQa+p7v+bPz~ieY#Wmr; zE_KZ3jX?KPF@NGc)3L`7hciy0#8=CP){c+Ev9pZG+o)cYmYO5h4>!wHLaR>^`6z8h ze%YH~c9SC*ubIeKT#&(!#Uns@uoDr=*ic{JIF`$p=aunQKqGQeu-s7t^j^!etPDx8 zGSwx5Q4!R9!dmpCm$-wOcR}*dAozZECy{3U=;r54hx6EzRI?dul%Fgv$==H?P%32e zB{?jA%lwjGlyTo~S(wrMo&S?p2?cu|69tw4y0U`tF)sH);f;E}&BTs!Ov9i&!&5Xl z2Qg{yP;njDu|S8O+NX{O_OImM?o~$DzxHAcA+KJIGL!nCSal?45h(`;N+yW=jn9s{ zw3YGs{mb8xfXM~8XRHYpKhyx5UHVjXRDh?PsQ1lyX*{8A4qug?^2gn(u|BpB3j5Q! z^v$J^aA+{-{qiSEI-1cVm}S^4*8+Z%kdCWX!>$<$BHzJv;FW(>eBPV)Gq1^<6ucSr zqruJW3$E;S6u(&{GYTM-vYl1`9g;pThQ`-1UfEB3sMD0i6_YgK0lJf8Ov{(SdQs(8 zj*BobVyw1Rn4NFJ&Oj=LyZwMR168~a zTJ~9d)ka0MFcU#~vO3e!SktPqSd8!q;uNnt!HYF}33jHEMRU?=iNyfR*b0PxeHr|s zKNuv(4JVeh$u#ld9=zWa%)K_RVrQopp1Ea^<7`)QR!NrmWP&(*i9}57dj{IeRG?^t z8J_6Shw(rmT4X z`2H5lS5#9&`{NtA=YmrZF|Uq{y%D z!}cpmpj;A5j%BhLW?KSAtd@jgiz2LX*Txb9EqL>{oTe})$oJ>I#BC_kR%jW(!~9PE z)=O)uY|1#;3ra}z)<%5v*b&=%H6b{(1f(Y9h;>JGP1-ni*-11QXGXob z2UaZfB*l}f@#Pa~%v`#clg}t|!JU69 zBw zrP}Cy@s9?6o9hBGnH_vYR~2rY@(q?9O6QvPmx6HOAaH-|PbNv$(8_#G8nns^d>=QX z_ZA;C)765!ZXsR!k-bSyDTtDH)k4^R&1B(L4T2kIQI%s!%zON!;V0v9Ephk;VUa>n zmD?9=GjkB%`_eb^VJYKn|Eju81|5v0^L>8dq(hFd<-819zgL4DLU(d|<8&J9$a4B* zL>$>Pl;#Xsg~#uj!sSk;t6kR%bKF#+t1*vuha1uE@iK5@AAzl0HTl<}OJ?OHQ>Ame zP{t>Ve|JX_4@Y@3hL}3J8DUSA7sjLT_E_%zR!7Kc+eNtg6cRaVC$;?kmt{l+L*xd8 z{gUTM@_w2m!r7{^EB~m(P+3b@QJ_F#`G;2jAwK_h>NgI#9pwIBQ6^5+pfz81w7af*Z)03}aaD(ta(WI&_G%pH3 z|LsCpI!uH9TrH0gvLWQ=Q5pOiVFvD=F68`yD%|^`2mX53dcRz&MJ=^AqHHW<8$M0P z^{j3lR91sW);hE$k9{{{HgRp|PQk#F8uEE?9GSOHALFz}LHWT_{^=5y=Xk3ND(mXF zU2L9KwxJiC8E<5o)h~3CWLoYqx}eB7`tPTx;98&S+(Da4NZD|K3|VACh6?r3Aw{m|@5iIjl#vuWkFrmhS-Yz(UTRBJQnyG+}Y|jwO82CF*M$qe` zWc>B@As2M)HaxIa0LkoF((K7{Y<=Re@1q1Ld0Eh%A*tB-L`C$cvfBy}GZ*N6R|6wz;{0H$i>@*^2{BCx?#+#CG*Z9@aL#o&y~Mx9-RkjIbm1ldNfm^j6#&ltvCD;m=Eg)UZ2HmAJ+}(qT!kbYE1d z01DI9#kFGBl{gwU^%rjIaDw}5bZ8EHN6mWUESkm6;>zR7V9R!P+HJF`;jKheEb-@d zU#!NF2fM+~>xSs`X9N1?)DoQecPQwprlIuwZ{l7eqCJmh2o32GHyL>935>0HmQ+mD zBX12-sr=|&m{GHfpZ!e<&oKV0dz}UeJ>f{7md9g+Z3q{q$vmu=cZuf`jcS>6QtU5G z(isgeUIPr|oF$o|5~M9Wg@#6FVdk{4-0M-SRv%4NvV@cgd|uAV6chgX#I8ky`Km*@h=X(<<%J+z}=jxt`vf+eC9 zt8Nsj`Qx%ZLa11-&U!f+{Pk=cQD^&?AOjQla^IO)@>RGcpbIn{YQ1gZwCKpXb+~w% z7D#Ai;CNjbaScgjHRLPflXM1e;wGn-z!+twiTJafock-lczI_Kgyr*xSuI-X+W{qK z>bTP7EZ=xg5E!VhC-cYtLgl|JQG>B($Ntf#Bb^m+%)%?&=5>`|X zpY;dBc(VUv71}3vK=k!iuKbZKKJFV0ohw7hha9U$`R-JDEZ2r}ZW>Ny1ZU9kha)I0 zRm3BH8c;S;NLIE)(xcmwvG(2*?%Liv@X3k!^3Pr+s{ zRZ%e(q4q}&92lYnW_pcoUEH6acR|MRCwZK@lZ>pc!oC&lP;Bl=+8Gb(MY9C9-rU2j z`CN!|r%Pjjgci)(r;P6328(A4`!-a<`DwSsvjr!17dtZ6O?YrU|CjAD%30Rn8qeXP zngtYpY|t0?7^y=I8bh6TP@SmtT+tY9D#_lM-nGm4gH#SfuA0CpH+53QJW6Uen5Jvu z2=2)iIdJqHLqut*ByyJ?^@-YylC|&2p%F#+?~xHA)3^#U*lt}`0llE!`}ccwoVeEx z9*=J0_nB8?on!}0TA9v0GcSYeK?C9%GR)x|_0ChLL5kMkH{vpWjPk~d?*z~)C#2qc zxxOYD>J zjM@{jQ3fHnqf%T$Ds0kdQ+O6Wcsrh(eO3b>oB6@nxh=f1eKn4MD}je2gSb#+-iYdl zAa_&+7KEOmu6=s+$$dT8EhoUp=Ur$9IMEQ$CMOYDB@<5k9FEAJ@fO;i{==uBvui%jBi)v|kBi=7lk_c1@$g?y6X;6(jT$6?nODbQGFNe5@A;I&*;(ebB6Sb0JN zi{w~NP=^LCIj9Q-qkH)le_JZg_A-ABPm#N&Ie-_7dAx<)y?uknKnED@5N zXUR1A>kgy}9o)a}yHM8ho&3+=RCkT>*)-Z@arLwT@;?sJ zfq~PodfhFt*70>?H7d)u!40JbK19ooe$CsA5mQHsh8>|eTtyG(RcOKqPhHA~$m3SS zReT5YV#Ed;L-HYYQa!i^Z_a3gGRu)1StSR1rGm(dNvXtfd=biSF~o0&7=!wjkQT|v zVNF}Tw<2RPjf*vg6`No2$E0eoHKGl2zom1(jyTfW@P$_6ZP_-slqVF` zQf0hW7Xp`y+)3=_BAC;v1{d`1k-iCu)U50mMqYP?_AGf^+n@}+3rCRW2WL}lE)LKA z@Z$taYf$@r8)T>55FL!w#myHYV5)%uscf{R62&af=*$hy@pKvre|FL(F_(!dnfK$N39fp?IYVDRg$AbIxwVj^ATBZwZz| zEuSf_32;Y`+L08d^?5;#C?jk#DkmSjB#7@mA^l}%fPObWcqiSK$21=|_~8G9AOFLe z9^btYJ9_H5Iir%$YVrd(+^zyS@j%VaThKF~Eumjp8y~EYfip*I_z8dQ=o^+NXd{JxC{Q;z%SX-pjVEiO z#Pf$8?m{}A=~QIqUE%&NtOSpjXT`He->0)^R?v1ly(pGEe8;@rHU4n0e=_m&@ML_j z)A;DTGdSIo!wIVtVel|EbGRN!&;DVW?Vu;ziAd%h6*M8eN`!3SY-n% zOeT;#mgP6tn|aa~4JB@C`cS82ia5v3h@Jg5qeOg|F`qj$suHaC9u}YdpVPFMM^gxg zriu8W(-?>Es{`zBawG$6ue6!*XAW#B^xAMK6fZ_madgk0t!N7J1~`jKtcB$qllQ^VE-wS(ifYSGv%ZwVAkJm;~h37BLp6 z0hY4tmC>uUscNCJzPQsUlg0c(0w2IrRonshB3cw9oG`en|9PdGYvmpI!QKG zTt9yjPZebzW6bRD7`x{_L(Nnr}78Z8DSg4B3V*?!65)9~IH~))?5X z;7Y;-)^xFXGVVD!hdVy35Vl9CK>pA>#5pgC_O<*%#SnMUXMgj6W%BUS*PSG-jG%CW z>7+`l3JNrfc`81p5NV?sXhKY9o zrf8lbGgs=7lSg#u)bD!Yv;V3~4sZQ&f;-A8M5EM^3gx$<>Z+K4W~F zRfm^}y5DrO{?;4QB88xKrT{8-=s|knY4Rmm5odn+K^B|%^I=&s=&Y#^IZ@8Uc#I}>{kNTPJA8vA*5sdbYy^DJ%Vez=sv>tJ?|v3@{0+6*IKdqQb(6<_wr zp8ltshKYw1Nl4;vbicn;{Eq0#6;eq@DfGN{g&R{=2|6XG#kz!JZB}@s|$|}QewntXlJ%?Uz*@pKN9&obi(&(9K16H90 zWLcgQy%oI`Kirf8OD9X3%Q7;8UaN@sbH#Yzh$@?hGtYmDGA=e$fnf5L-=618Z!+TQ zh?|vU&y-L7mL>@p!i7ZY{w@(u1`HRy5LLn;|I4I%;ZX9rT|_q;Z9vh~F+^L| ziGKLJ8BZE`i$*gY=_g$wYR}h%r>hJbD>kK2(})e+uZNoSvBzLsHD?h|TIErz+W_YM zQ71cCE|}^5o#?mVBUds_4r+>gS!Q4gS)AldN3Tpr7vmwY+oG8HxAd`{d4rdvX;af( z5;#NsqPL~F2Gb&0FwYG8j8;E{248JZ4_!+thTGFjjZ_@?c9K|5xPo!ZMv7+7~ADa!s8>Tj!6tA1_W@Hmb$1EGXu)! z>5~`9cJx##^A0QC^0$!3{@ zmuCMj$52+Z>LA42;4rX*@iiRM(UUxj5d*Tf#`$778!(8vwSd&+s6uQpUaC>fPZzrKvY_|nEZ z%S@HFvijdViRp2&l(3;r36{$05cQUM^d6i4KeT?#DcVS*mX!^-E-WAk0Zz0>v<3HU zl>!&G!xar?Y}F)HQEPEAX1J^3AI6ETo5V6GCnTea%nAPQASJZ1Q36Sa&wTcaGf>j< zjvQZSOgbIxXtRF`p6c`wF^VpJ@wCK_EKQit*gF%MmQ~{KLGN;t5>SlTCDvJaKQ+R& zrwl+#`8*%Zc5|sIR^l2WJI|$I}ta&UM})^+=m~eCt*^b5T5K+ zrKi}NV))=CT!azRlWf^fY&=ZKigd@uCMbfG~yLf z{c|;0P^E0=9_=dPl7w%O^za`ApA;x1tmIZ-8p+*2tyuIomQ zc+R5nS{u>b(U8U$VBIgU(>}9%TR!_P+6LHMz zWke_DBK#-McnfV>WS+7vef&)uRaH#+i-8KbEzJR3j8)0xaSn8M^?FR6F_vqybB1;G zY2x1FQ=kcbyEF}tZ1_O*l2z$H_St3amK9~&FopqbAs1(Rki*M#>D38BT-4X%J<355 zlPeq{=JZqEJ=&I@XkeLNpBp&x3h4LArZjwuCFCDhrN>!6GpgG`wEngM+o4NCLRbUu z?lg#@l|g4kxGc2Un;IM(hqb{=Z7_P&2Z-L$4H~SyeDL)g^z%{S z_;|)BSZgl_4Nnzt!F*Y0`>sXu_spToT{g0r!+kDli!7?Fv4*7fB4YEynFjOGDB2_q ztC}omQ+X^(8>xuG)k;uls4`Aw{vE@`sRrsuoLdPmO!ta+C58zC zD&wn$+pl?(>*jJe8>}JO%Za2hPw{%j6LutOFq7$5BN*?l@C@bj$Fuo?S}O_66cTxJ zA#J{+fr0muIQK(U@ceo+F+aJ6Of=NT`*VEZSmjB6UXnevdbb+)u22&74HPl<#USzC zWW{||+BGE+CkBLxBFD>N$vU*5R}&|1f54&JX(&@@B$N7v68A&)wBXNb zT&dtGYJE#llQq{jv^Bx{QSrVr1K$8^V^WX0oR%na1U0;bnBW!Z~)6aRwYy$jxs zf7v|hsg8KoaemALurkmP*OU1U4m4RZ83z{U5~HLmczn1AUMUd3+(WfcHNA?wU~`py zYv%Q29|F-1pof-g)efV|ugD zh$gc4j0~DTlo0nPX%CVpnCwHt%gZ>EKkB%!ZY;F&%*)9WJQnIJbY8}2NGI4oIG*T zr3JSHczAh>x0S6l8Y)`Ah@p4*s0Lf=zH}v?`PIM;C?b9M-k1h2u!PsGtY2NsJ}(JJ zQJ1zV7GLcqXRwSnE7YaAoEF}WP#0-6%%W>pZtREv^LoS4J$Qfm2;3rwl&A*{CF zi8H z+Djs`cPLU6MY_)O{3Malva+I*ohV!ReZKeakLSPV=x|(Jo!2?u@7KFDmQHcW%ePN zv_?@&z6046szYJfYM6ZXquA0X7k>_@g|PLOFzE3>W^5Tv4SFKX)OBUw`S)7!Vg|g`tH=Dp_iit+f#WM z+2cB>ty=|GuUk{S{V;T#cSihlNQK^xABofMtprrnCg$-TveLeYcjHXhtrk79=~pAP zl;q%#cOaj4T5M)Bjb#b6+hq~hD!H+sN6RT_NPn5b8{U&7>eIS+T(iv?r|0rpQ95wG zIIf!poquPHt8Yu-gX<| zA{|4#G1`QEwfTej2aA0BU*h?qGmNmT*E4bclKZ$mNe>VEuLMJW2W&}?B&RP&p?}3q z^1j`Re2yBTao4N3Omb0vA1S>zlll0srV&{`is$g%-Q3N6v5So}+`Qz(&ivg<%{zjH zx3wqHpive31>WVm4i&nZrhpSy_JrRJkxaMq4jO2)P*`z7lWMNW@Nai*c;Lb_M(3;2 zJgo^rh;t%!vU!7fRl0a|XaSl@)8+mVrfJNaqjkyhfTg&OvriNPY;k$38ua0JOk=I@ z`0QqdZ}(-M*dd9P&o3XHELc+HHu`(?8T5alLJBG`K}EwGR@Ry^(cF+W=D+n_yF!m5 zYd!J%^jG3Cu42rX@EtAI3=uv?oyD_{6mTB@|2z2+Te8uLg-x`_QxaVovHcSaIdD#_ zUu(iL>hx%#o389Xn86NTjir&&?$?eRIN_v*10ul|J}*%X4Jhxu0$tX9I9< zG2Bh+@wuKFm1G*CeSsI0yqU~GFp6f!Oc%bX=kr?n9cMaQ%aTN%omC&o zGpMZaWAt`vP*$Ma_j=gXPRfF!|Dw5mn6Tzy7B;LtA@4o@@H_TaCo|k!v|l{U^&$Ng zw$iF#Rmi{im#VJMquNfU_=QQ?*VuL}ym3o-%J(5;a0aX&bb|vS%GBoSjlJ|of%6JS z=BT`t#&kIP+6Ni30Pk2@agb;GDrnH{4n^EwZwUW!=5WuXopkhbhcGEYlZMwgs{jIJqEehP-TG> zOXgn{N4XNVA9xQuUlOLA&Z9o_T5-;h3~~Hy&du=MLaA34$u=$iLC=7r#xy?78`tO^5~DlklUUb^Mscaa z_-iWkWAX@e&07f&qF&N}-(2SAT?7k`YmwKY*Kp`+i`YHegc;T7P=-(=m{jCo{P<$< z8*T-xem48%5KnD+i{MWQ*AphT;?=GwH2-F_L{mZqH}tV>vOY`8Y)0wqd7{NlHPW4B zfXV~(VC~Hy*7F>nRS(n)t^Ik{c$h!z{j~#rEpTO9j&GyzroT{pAd^;DnoxUhLrh<6 z!gA}s%jaU zuU4p)@wxxgQ_v{y1L?C(*tN}1H)8|0=>&%hIVS2u`LL-VMcWh<_0^b^jBXYu37 zPV!puAd*jf?L*&_6`5H8z~)g7VX6&a4wYJRpU%(?+t6*Sd}4e%y49NFE`QC!K$EU*G`gi zv*~}FShJsI%zEuF^j~^M2;+5QUiJxjk1_nWGEJP{OFpM$_vf5at4*|Qp`-8U49>Wi z%>6YHTDY-QgW`sFmV3z`%#UIVjgx7V-XB5v6xRjp?T&w|&VWxWf6m>9;)Zw6#3HV9 z9`j3yZh7q!vOZ*z_c?XBj?3tVI^8x_z{{zPVxcP6mky|c+YT0>x|{QYbiSb0SvQCb zcVoum`THyzESoc_lurM!qA%a|aeuc=w2h9D_Z6ETno?$(4zeq`Vz&Uq8|h8(@qz(7 z3E+QI<}FxOd{V5bcVrF2Hqj}I#WI@*KPU?WXjiTYZo?e(x|JxOQ}RFPvqO&jZ)5lX zh^thgZgtl9v&|I-oz0`Qhg)#W7zdweM~&DvpEY!Ty&i__RU_%kC-7mFG338CVeMsF z7V&m}iwPFK@w_?y16;UaFMe5P+KfSHX-p^^%ID+3c}p5lk@C zBDJ+IK`ZOCXtv#$&5GBg!k8*y0KfYTFuDqT4qL){msxD|;uyMrej)7Q-^$BtTku5| z2ueQ~&86lxTdtc9XzjQ((ijlG{lH!f`d6bI{6pAzKg!$SG37+hp~LuVbQKg|CxGn zM*JSwa?y?T>&5TpzQ;j(+AUi8){_pW7~-5GgclO?;Pf0Rgi#DbX$m=QGZbat6zP?Y zC&rw&hm;SeFr;2ZUMrlx?_n#fmD!|@5omY=@b3K!AQ=7=e~*b}wii=qa^X_JvxgQ% ztNCEl1Z_B3!P!Rxl}Jx-yznJAk#d$d;1BMT(r_riquD%Pk?Xye4lriNd^BlTf~9C@ zt3e^p>@X@=2kvujl5Jv(yl(hj_rR*+NZ9`}2L3y3#uS%wk62wTbj?ww?Y<9Tt!r(t+$@YYYojM` zddl@$Pfwr3=_4h$wjmp~Wook}pX>3SFckjd-}=*B$5UYGEei}+A>|i3IDdo(NUdhF z5$>FIFmtw`@+prJzqjC$oNhAZZQWU)F>7e!1REUc%k$J!ld12VTEW05g=~j*;Qwlf z=58+*W1~gyol^yqM_D-Q)q{SP>cVHu+_n3~ssqlfOnWn}IIRYO4(+ryHJHp! z@$YnH4tn-ICa)W9p|OlD-A>!q9)ydh70IoSJ37N~xNx0o?0awE{3S=x;5)0LNLKV;0_E)d#d%q(R2XcH0UJ)k^PdvV>Ku$`tDlN@%<}0$ zh$1CD-YbN8XHiTX&$9P6!slDGX~){m=pXf7%+kokr`$uZxUwreV0qNEtr^#x;NN`* zS61_B3r&t6D0{lSlr|+;(!me$aW@ol|*CrZtbg67qkDoO9pFh1j%WDYaV0Hg^`5tv&XMN`8piJR^ z`hhcNyp1?%fiTetwjJl(&Rd@l3>|#TYmC@I^VOuhmgjUIRU@6x4`JwRW6*JsGSwRz zR5Bz+DB-@UNR50rx-tZI@T{Ui8{E;gV4tY>m3u%uoAIGds?gk1m3m+C$C!63p?kb~ zNzO>lp?-c9!dGk3-^owm*PLc?!FppR9iUDUp-RxXo`Xrsh2Ya>2_cO$SwLGP6`F;> zRbJmNJ@|y`J3&}j!N0S%{+KXfB-R znHIh<6y21#XE3if?rU-dnT``1a6g<(p9Bfcd8aUcsxmIWd=Ca(NM~_TO3W=Q5T|M( zn)>BHs_;+Dw2x=``%`GpwH3nP6afk!^A~nZxnFW~hUy6K|shVoW%1X893D}6s$E#7!UTajEt_6qR<y$qrpv<=1(vdqOO^UU0m&jO(MC7B%DL*UiGxA#LPl>?Pl$?x;V3je;)TxOWb+ ze;U#6(hpF7YOGjo#&5W5w9x95JG`l#!-faOP`^*}g+I^o=$%nBwyx+VGwfl`HCOX+ zQj-)MtDV`wVTojy^jPRLKZOo2{fm{HT`Y}sW2bnw#oO9sK`lB9_Z&I^msf0otmE30 zKFJUpp6?g?@gA~QE$3alQ-u(PcItm&CKZKAQOztD_g_9LpJj$zk704rWZH1#08Bp1 zeHmZe@oC>cI62agc`u5j;zmt8{Z5Vc75o9eDF$%3Hkv)<*&^Fw+l4_!`S_{t1NfFU z1OCj?rwXINXfX4cxVfJLtG5j!Nve+Qz|t)GI8BYt@rsv2j(SHV@*e##_JN*GKcFPb;raQBH3gKiFzeE-g@slDoav!bJw#qZ zik7LD6gAFZBG>oNO6U69=~YmZ{YETzGGV4CROz33wNRbS_2*+QLE}|RSiN%woBB3_ zZm*jM!6Wl&#j6k4q=dqPVXE{bdk6;K90})aBy3Cv7d~su5kDN)BpW+Dy!JpJJiKSH zeR8wvus4Cp?tdgKfSZO~WS}%Ca|PQP>FsI?P!m zfeYN(XEzn{IRDtU*Hc4s%reD4&@2w(y6F|~T(Bu%4|s;Sv&(f`=yLdR*gCkJ?oV-- z-(rT2CXC#b4R;z%pzMT{Ri<_&9lNaJdwegwYKa%F-RlA)c6hJ}Wf7FpF<)@^&cLlz zUC=814y5s{IiE*y^mKU*oXJTWkJUmD+y=%snOL~FYKqS4p!rm zNbc$FfEW_Sf8UpXees+6)`7Cb+d*NUszbJ;E(eiPj3 zaBb#;e44)NBgUnD78EzP(c!TkWX_qVKZKLmx2Fz9eL4qQhiWqy$rBv0atP#wsFK4? zP5JzCMF?UCxu-Huah6~$y+oZqe#CDxtYxNejcN7d88|$~5Dr;6u=Af|DEvr`P_R3N z&IJF)zC5#F*+O@oE2KpFOSTKOJj?#P&t8Z$iU3KDgiaV3VSwrpF_-VPA|k@+O@KO> zgtt@hwdtfWM~e2}b1-e(K{&99vzrQx=%z8(ik7*ED@#>5TgC$i>>LC7_j$(gfK608 z#m#rZbVK&!Kb~>SnPUCctC5jT8&sat2bbPaY`=aiT~YrnbW+R54KbB)#d-!@zM@WT zf4y*ra)r3X+L_grt)uG&da_>=&r;G=6;iuxgidd@sHE@@{O`7_5Xk>MZ_43OwFOkK zbz{?brrVK-L9*wkO6d#NDjeFQk8AE*lsrBX$E3Y81pV)sc;>+tdEKzHH6*=9U9hYs zQ#6^)@BSt)#C0~KiA zg}%_OlM1bTVutr;yFjlYQWne^@qHHS<5O*QYObh|>&ctB4#$aS75Ey&3KcibV$Wyi z!R^)p@X@xR&prciarJ3&!%fbZpXP_&lUBj!t{NqZPp7k=wnZ>cP^Wg2N*FNty|~ZW zgsqBJrp1j_!q{=SxNl>g{8sxTdIpp3*-X1U=Yc-o=btz@80)t2eYLwQOFI!yITjbc+*Tp` zOgA)`z7K+o+*#fY{(I>-#+x2zcDY|1-81l)W%MtnFIQa2Ai)s3_auxf&w@2PTP;6Y z%6j{oQ(0YRaio?Ssqq`eqW~AUoz6M%dK+nj(_Eo>z$v^ttqYz_y9*1s#`|&s*T$T< z2R?;}|7K)CtoTpt;LmEzTT`B6s3eTH=Gwe@9++LB2J92hci6IuGLlM#v>i$0Z1V!G z1wEW~F^|n2XvTgn)x#Yz1vthkK|bR={cgx6rYcg*eGAdNRh{1+5FEcbmlSlP1sFmv7I)Nk*>|PyfjUk!nJcZC2nwN z59cyuE6q5Jl zpzE@I@K&`Ogx}{nvTP@wOFV*e*$mkc70z+(qlq5Z`D~Kd0 zbh+_XoY2aD4n>o{WS}fi_X5@rDTl5DEur$gCYdGo#Gtb(r1JpByLd=my`@!MhJSZmU@(8B86LQ!Qk;t{{6V9?h9mM;87?{o&sZzV}T za?t(tR(VbE*}-=S3)&zi*i-ZwsY+!dIKT0wE9_7TV&`Sav}H<#&+{r%&bMAgYw`_n z%_((CyLboGdzpZ>jw$=ltVA-55%zOG*RM6_|K08{#M)eSB792N)Jy0XEZaa7y< zPBd=UCV$f!_#ZQ8k*5g@AEQW9N~(li*Z8f(KNk|VTEfl2gG;K{&tylQ2B03-_Ab~Z z;ALS1jN?7k)V^`#pBL?0F;bNjY&PFPlp0W{dpWb?ajq7#o^2~$q% zVA!EP@*Euhd=FL~xRE}pcH*~Fdls@GQrd7+yQ=-~}=e`L; zB$UE)A>jC1arbg%@_XQfFHWVy_6r`YZP-S->vsYocotHNFYi6p_{qjwmDBX^&a`!a zA?{z-i|uLS`du|!+4J>;OTEs((c32QbBvUwl}o9|mds+KmuhsmpF3(=yTV@XKU(;h z*9Y?j!kn@Ue05p@Cl}p;0o?nxk^7R8?C(Nm5aAosGw{}{6FfZ>$p$J%k=ud=f`+{| zCFJ$OqKn$lttyEu{GQ?UQF<8Fl*hJyk+Na4^zf5k0a^vb!kbGH@a8<3t0A2!94tgP zUQ18Tw#1ec9Y|K{iPq^`(^&?!aK*>0sSrN>9{=;+WS>V&Dc>7Jp?Oty-@y1KBw;D^w=QWMk}Ys?N1-E#P^j zUYz_d2Nh#(%4d)lfx4u&lJhGzCW)^S-B`ka^|W^6Alb*KrSx7jrM4~lsCXv}clBEb z14i!vX*XMP8Lo+Q4qg@AhXcOXc?8~W`Y`d#FLIO(q<$qPXq(3MDt4Qp{J1p~$@Eyr z=%2XC%^PAqsZ!||De7(GT7ph|CU~1b7wzx)3~aSvPh&!9(^g}&9-&4tMK{3yh!HG0 z!@ZmvJJZc2(ZZ?E=WzPlEco_01in8vBXNKmUN=1|e%S8B6z=d$F1sdi$tVq4m~jhg z?tc(J6>;WONEdojSR?Enl7s$zvcchNSBS8a(i2x_40P-&4zW?DN0SDi=G_1YPI6(> zIEQVOTC{JAi5{D(QjPiwv&11eT2!s1iT9EWV1+W*7IK!_t_`n*L}dxKF7SrTitVr^ z$b%hIT~B@e_>w2fkPSMB3aB$iF4Bt#-^@@e9tgzT;bZSc@XRX~>z| zzpp9r>~DMd{_|pqBfIFz*=QMlGAEC6YMkmsF1q~A@)EE~;Uo-LYz!aXn6OfFV_Ne1 zO!2D4YV<751-Asb!1OdvCM^yp-?a;bC(F2}JNgZTtoDLJBU7d{%!KBmvY@q3or;v) z@a|7_7^&;bRMS_|`GT9mnS^AzXZaM@J=Md+(0r!VY{K>*(8JO}1-S2c6!bqRft&V* ztmAJ7UKY(o*t3hJK24>)ecs3xOyzgyEOVUqLK`0MoXSFH#na-O>xJt-c#r&QJ=DAN zyeIxQK4nxinJ)YcD_hlgZgv?AYVQk9MMiAJ!%npNex2`y?ON2=&Jv4n){0WD|NMPE zkrEBQ2qQV8U{W8>pi9{e%WU<@wEaGeTazPZ1O~Gr%?(sm)%}|0Ee)#l^W*i_1*#$) zm~o#-(m%gi=$4#;hXOU_J;P~JBRW2`7J}c77E8FF>rb=_?#=RqCF7!5Yr}3TPmkg3 zdVRXvZ8SP$>%wOf2R6NN8+9wH7K$eAAl-~Mc}=K)^az_)UY7R>J})e3c&Iss*PRn9 zJ2|o+`P=C1ffcfvSsfJFXA*&r6zz(0@aLj5xcb2geh=X6@LMLdIok_#>y>EPu^t$; zaRgi~H)0zfZ=x%sIJY8z^In4A!LMEhpg)T1lxhs9M@EWJ^DqyW*x!`@y%*aXaQ$*$ z`OaaVV>W4Y;y>%AF*X+&(!uqAq5Gz9;;I@cv+^<`=T3Ek^2c0sE4wb=VJ@yVqiN3u zp>IgKIB%H?lT2DkMe%~{wf7D3b~K@Y|McG__-#C!nJh>m(^VtkOXx2OH4!Lqxd{%+<#UAZdU+i#BF1~X^%PAll3gAwZG zs#4;60#(jaigb~(OBXuPjk0K=B(NMWHD3qY#8^0Y+?-~ME|`Dqs94hI#4ct>lF#ra z@y=fz${unD{>Q(vnSt`SY+`ux`N9Bi>V%QHMJAuG(3o=^JYE`HAp7VCPdlU;%`#+2#8(x@Od`tllD1uunxJX`aS zi<_Lst5IdnwZ2n%*1;>W^kfevaIJ4xw1KSfZ#E?>a`xO>V=Pj)W2;j>VC0J1zK5S{ zk%p-{j`evZDxFiNyZ?INlHKVr?`t1cIByHx+;;|;mJ{nxjU=lAKiR0@a%z9*KwbDP z(D}bBxZ=hEaOow1{dpaVrpf`YaNtz74V9YZz1InABDa#%yvMR$de@t0UX z7ZWy_&)5AT3b3o=HhG_rbJT!YiNDZVVlMtF*C0{H3{Bj0;NtqpY}kSrT5h^d_}%7# z1^VltO)&=aLY&xtBO~cz+b4K%T9sbBAjq}yh99Gi*&kU4zKVJ2JD+Qcif5YQtELB{ zRrn0n92HNBomvFzQ#Ba=iQk;=&w_DnuB=5Vh8pwtfC6U|E%Ymgj5nF$ZU|;i+`=fY zz5BH;z0_%RgMdpmIKh_Dj!am$jV^8u72MBfV4a2rZd#ZPF%_EZO-UKnz8eJ3#;eeU zYhBRU(H%yen$50_2q(|9xkBJceJcDLh{}g`L67r!5}VX$tlBIg`@{~4=RB6F{Jvs3 zLyKuPm16gEa|NI0kMT(NeE3;>3|`ntSk4Pga(jCSy3{!`RMqAS?MrD|6`B!DKy;leSVszn2g)w_Am5`ZEiqO%Jhu^l9f}6>7IO%CX zSDgCb0k>yj^wjfoEK-rG51HV#82gg<^OKlSd;ugx>rjuXPjIW-2XQC&$UG>M&{(7A zLht(*aI{5;*kaR7u8fN&ma03Xi6+*z{;hrE;G!f4j0*YAb1ju?Yr+sngmuDEFzE z@jSBTG3|JxAzFyIUWT6{0X`N*!?;~tX?3IvPS|-|OtR)WrK_Bi`Lj{HGf|IBJC#Fb z(KoS?bLu4T`L}Q6eZf^f2a6w_hP7MxJ;>RL5(c~BA!&E9{EiZx$nJyQ_l7~nE@!s7 zdK*n?iS&KgSBtd=T*uEeRgB5ytbz|pa&NnK=b7yFhgB4z@=6FfZbep6Gw|ZkCUHzi z4`y(86Q!6N$o{FGr(MT%<^6*N|NXvQejSx{vVE7R=~8babzHi+QEc9zL>t!IVzS{L zaGKMbtqBgNB|lDq)0=YYe#D+8+wp9{U@bOs^L4yz_D_(UE5t`@_rmWeJqX@p#6Aqs zrM52_#V(UoNUy{Wzsz)m2bp=4aN;|j3w-12z%np()E`i)zYRB|v{;Xe*U{C=Mt0VN z_j0dZLaj$nu$*Yjn1LSMw@?)BjMtzOTnFg4Km!g3yD(jaWqd-tC1iZN#KQX+v-$HR zxUjtdTd!=9?;LuB8L<6!-*8vCnMm6;Xi&Zh%I;}{WbO=BeIu4a)@~FwfAK&q|4>k_ zjfU!tZfv4TG#wb(3PF5dG{6oa&AuN5o-yXS&EF_}`O;URM2)v(itp`gkcHN(E9 zLR&#MP<1h6;oQ?`GSdmN`>D{^BX;QJI}-L@$s-r88M7RI(dXK6BUU~$Tz=!wi`8Ni zFI~riA;V;Eyj7{-(@SW2t_K5;8nav61Cah?yP)tn4?XLz%j?D~o>yf&#{-=oJP=Ra z$Rp|P@2EdNU6|9HO@Xyt$jZwECyZ4uiGMwxwWRHV58R(VaRe7Nu6QGE;+h$CBMI#} z|4jH}n~Qg@At-*f0PR9EvaAzulv%o%x}D#_H-E>TiZ_Hp&Zd4l)QFC74&JD(nHXNU z0K(h0!?6$6^w3%n2RtYgF9k>$T+pQ(mkniIuZei!(Ot-!C;`1LGnuVnEFJb74zH*E zk6+P-V=jLa-tG8J=fCtP-%BQ#5|e|I-!Fp_&OmngU`2f*JEO*d5n_KYHS*Ilkn6kt zR7_#MA0laTWVuh(R-UW)rwzY(xyXjZc4L#rt|C{?5NPKa?wYmNV0E)G+_#Xjq?teQ zW?Z!J=&sB}$t!sL;Yvv93I{3TT>chEt z9=|d6Ta9qU>jJLvJ1y6A{o&l>;A&vzzJDp{>6DURrFQ2jc8KQ^mnL z8nktA7i?Xs2d+Hd^CjoN96O>cvucu1#Y}(vd%9Xwko92an!>5AOkegR_&j~ws6&Tl z7~_?hTI|{qM6XWSzPo>GQM015d^WLAQsNxVZm1Ws8^*8ZY^bDG{B39pZ}Oa3aKcs+ zjD~X0%WXQ`tp^nv8lu-4{w^h=yv}4Vy@K85?STiKC9r9|5qqnqO-sr%ibcNLwsh)_ zJF*?&C4VQ!e{98jrf+;>jZfiwhhN~MdFO3nR*IZ_=ZH$;?w*+rb zDZq0n>!D$x1WbJO*_21kSU%5G{N}1jn*xk+)@bf`)1S@Oe&u=1Wf4O0K~J3g-zxe1 z;G%AA8zq|pmrL5im7ZzS>@O`>Qjhv<$pnF}lcrPr7@hvK4 z?r0Ir?eC-7Prg^;y~5Vc%xq*Ku5~yDwzK0{yz4Hi`W|r2b~3+3 z{_KeZG`quH&fK_Qr$Wu`orI0e88|XQ6+1a)!{X~2Y@n}*h64sdf@uk^b}WRS$?c-n ztXO6w-AP$P;shJ+OO3A)(8NL=o^n=6k)8@!LDb{;gwmr6Ne53Y+7vc6zQcCuLKM#SIXwy>!9Fq zV`%OJ6P&(Gi|J$)kWB|W;ri*tj=Fxyt zU$7lYg^I;0^kiuO{yaPk@E2!+hR>1nH>?(Srzxxp>ckg`kvmM;+9NtN@1c<_hU<=%3-?<^}}Htea+YSNaO zb9SXVg%%ddd!8X&`|+*46>o+|3w1kh;oFf#kX{%Ai)L!mgGgiCem+%<+3&_)j@?F+ zCcYPsIBHY3rNy9c+#=fOn6sM)e&X;^4~2$;3pl_g1BM^9f=faS+f%ol$RYtY^PSZ- z#hy6l^)Q%d?Z`O{8>x5ER^P?S+N^OvG2XvAOStisxDi+#8~vfp@;~ zTi&{I$V%5@V>7Se6h#|Z;vCLEGI$7=lRUtbv&)PPwQ0@}CBcHTkv$LF;{8%p(1^&R zUNtS~F>j1eYH}8bx3+`I95>iodYR36YrqPRNU-sK0or^CmCsP!eoEMNtM^#?Pb%Ko zs6~alj8J2nE@~d;wXD4mU*PR7%L)_S1 z3Evyf*#k#{c^-Apb!ZxuBZha6Wfu2SXicmCwI|z^=(U>{&b90g9)VoPepiWpzUd_R zv}E8q4;A?hcl10BcH!z3^xiLn8b5} zo-BrGIVt+jpud6 zO@0B8&NXs>6+Yv{eHVNtT{mVuQ`b-^&x8v*$l0)`AA)-)2^bkm*=m00$bOq5jF?n_ z$vOlYSuL#x_yLg|R)XMc66?=qRphCGX{ITiE5@_71Ub5C~7R&J41Nzr> z>Gi+{_@B>Z;s_H~P^dwDwVny@f8}C3_k;gW2XZ=+XEz^eM%%Ha0`Pt^{`@dJTp9r8 zL>0bo=gi4x1$i`RLNo3k z(k4vV^@l?9y~*5O47s1FO@o-+IP2PTnShh4(EKqS~1NrUjt>0_0hVLZ$bOX4){D-*dMJ}#@V{*Mm z%;#7(@x*rOd?gXeq7-SzH8-5+IuyJ=yRxmzBPh^2+IQecT~^oa8Wx$&6ff}|=IV%c zcy(D99D^d6-=laMRi-G5<{Brbyg@iyvs!#|z=h>}+)S4{No7wq<Z3RVvcNT^1PrG!1^P=j^i1&3NaE4H!1Nux0bN(E8s) zWw+vQleV+1eBW~Vb0N+@vI8m>>%oB|#>^yBom_66Dt>uMkp_iYplh5ROyTcFmx0aL ze?yb6!q*IJIok?0V{b!WA9Gf&zL7SoS3=!;?v+csFW=K9+elfR27jJGO2QHo{>@bB zjSDJKR9XEMVtt447g!eeNqSz_VkP%X^#o$(+mA z`!zlfm5S-snzT@Zv+O#w0l&>*!6$eQ-R`Y|=@d`AwRMTShKvhwWmh#KDDr6w3~*7W zU3_0LZ+C-jTn{o>`~>`*%f!y(rEFxq6}>)QU(`BFoqlia!)FOcF#2->TL&xR z!VE4r-mK0%Q}WT7<5!Q}C2Z|~0Um|^5!FI?{V~{1tr~H{9?qD2Hgo`%E>s82cX?E7 zq)4N$%@oY|9{T$557;?Zg5wotFyBQwbh#>5aGLuVZ}-WR*O1jGbXeZ>E@XUtKa9Mb zM;_yvF)lAzoO0Khg%)q3G?&$~XBPix(v6Yic+~{2D(CWCt$3Jy!3yqd&}WTx%KV*h z0I%jQG(FZF*YEd-E-$(EGQJsYDlYigtukhTqeE%Gh8A|rQKSD}K7{7G5;(J8%5H~g z()SrVgfvwHnsVF?mEE6;6EyS5|9Ugl8Knye?^I~?PJa|WFM*O(>LrIcyKs=f9;o1V z%ncefV72p^sCvqn{XDNuiwvI%S=?`HZF~jJUbcXu83yF8?2bbsQ$!uEDP7L>foG?d z3ai>xC_cv@zuN`C`wy8Ilr;tHbW*^?!-&=4{$#@-W9sVh7KXL^imt&LG{;dF zM<4fq)E6_@f~i|6{mfmT-nRKd3 ztB{b1XAulL^+WWDX%OyDE`h-Ae#%f%98h-LNoj7#wYOXZs@}s5&*q z*JYV53w0>O1+Fv2PHQwG4%LNj*J9Y#nVhGpqbjppWk9o22H~r2_r;o(4y?s$ zEydaz%1oc;kaV#odGf5^P6bBni8JDqu7$ou{C5A*O@U`3G>8McUc@d(D?zr5`)6$O zX_)jQI@sERtj?9$ciBv~cl~95Ufm|^JJw{PWQfypi*Skd4tY-!tN!_@PbC-y zctH=oYZ;`+^RV}H5%xB#lh;*i)Lx>_8N2y(V&zAi-8M$}dG#DZ({IS#?+*Li3fXf# zeO5MEA2S^bape6)kX9jqz;O~5d+;TOnM=j98amYXhd%zhuLnj`g4m9uTPb+UMnU7E z7luYHmg~yiPH|&(d7H`e$rmUb(}RuN7fqe_naZL#gD9sy2fmH&3md=nWcrQj)TLZW zP;ug!Yk{WdGYgC3dY-00S<_u@$~3wRozG{APZmho-t4Xv zmRMg@!FA5%vwPxe<^bu|8JO|33r;<776!jmW8d!PVES-h_}E6+5_4W&PnIc|u$TQU zh%=sqCCOY*_|p@I{ZxeS8BT20g!Qy;z4Ca4?XOuc$5GFsb z<+E3Yd_KxHmC#cC&e+iBkeC+Y!k$UP=~?7zSy=u*a(pmcUPF9%K6^l?Xo#@1f`}{$ z`@XI-RXpwi{ogB7Sh_hzm5hMO1{0>YY!z+N;& zT>Mlo{#G<$lFllmG5V=sn|J~H@w~0Z4P7B;r46a9@xj=NL*k&pm#BWi2ONL%hM>i@ z9Qy|Q$?HbQAZJ#vERG)jx!}tWA6OO2GnZgH44 zK*L&f@ae&|{T~m&rUzX?{Z$OB+7?g0IB>qfgtHNby5nrU5zvwC#!mdVk)ExJ_I-3f zhdC?c;nmwS#5{MNzwGuC{+GMdmov%Io+OavA~o6AN&58RzAx&Ht`@tR@+^r5Yv{lK zjAXZhaw%qk260{}j=RUdQM)^!fA0oy_I&OK45@(eXNG}kg)=J&2qPuWA+nWyc5MTdYDhpUpAruLE3L!SzvjpJ1k2IkYZv zVNH7RbYn;ptW{H`1r2vVnCS)MJ&f69u1{)S+eLUjP=lWRv%+8d)!}hsHh!7%3l#f! zKnE7G^C}XSm9CFp8Vc}p@A;6jO#)Uo^w{a-r`WjMM4Y^gGaGv8;b?t5FrPh#oqo2B zX0%5LiA#E8(au;{tU)NbE{9{O8d0u*@&ucMCZzju|8A0RvvA3Cr{(?f+G<4fiqs-m{Ff&uZmXitllEdvDA9#04owan5)qi z5}P&(mX|Yd=kLzA>&IF6dQpwdJ;7(QFFtV4jN#&{v+`OYn#8kxrHR~&8!vcdX;W^Q zH|{A>hl@VWtTt>N&Ck0p98T3lEEVL6l^b7lQBI8S!(HSyOwZEEa(U#>4*V!<=T`0rv^ zz*FJWxC zT0%+6WAI56*G2DjWY%$<&*Sn^n8W*3<3U+)Y=a5xHSu5{n>$lL^FHD5$;bEruYt~# z9WWwjb|1&wYJH#FPPt%Tc%z4k>u7R@iR`R#F1>o7Mzy#3 zj%I`|``VI&w~carbN|z%8Ryy{EcdziZe<>BufGFJqldxnahlwd;f1^Gw}|B$cPOyH zl5~p=(0u7td~iQrUN2s!g&fr~iWiMlp`-}Tgc#ufp93^5g9pZ^981Kh#M z{|eixtjEHt^f9i8--T6Xf%j<65{b}b6YUSz)Zl39(O@n!pRP$0ZO+2&=>x!XgAuun zFvfuuuf<)uGns1ACMx;!S-8Trt1C(z@N#Y<=dN(QedI>|^V1=>n+n@|{Uj#NI|^0{ zd$BuRmFe9%2ieL-6IN0nrBe%D6&(v#r%Jv{9J<^QG6%b{0+03dX2yEKX)2%HmMGw} zptBIVUYFk5=R$>>zi2Cz;8yc2m<@kL9Yr%X_K6uKO*RvDPtc}$gL~uF;p&jZJz}Lt z*U^=#hr;4dJ84OmCS2j5kJq>Bve$!haqHg@;cId&hCMzCjoXib-VQxFo6!!r;RnUU zL9{! zSJC}>3}n93gXO7Qe`wW-l$1{v*N;}EvuRTKUAWizljxB01{_Oog5`S$*5^3)l`Fjh z10_{z^eTmtu3j)&V#L%^I??M9orNhqHEHG#3%Q0QG$Dxf>7GO$^iSy7a1IwpTj7X> zJ4`opW;4b_Q>|${bj~lp7veNXK5CH`_yo^pK_55K zamNT@UUhG*92p|-H+si;u%XA+)BGQ;pvm>Riay)O@RF%)Ki`w3N1cWh7Y9K5z5XoA zR+YT>s0(*QP5Q7%1NoB?N4*bX<5a>abN6SV<+&2Q4RXNqO-W$U=E44Xhtq;<>7cpP zk)2eDBC`(xvivX=<~!yXx^pktlt>e%sc%g4GF}#Wk~;k#N$25L=Ckyq>YTq3K1z#dB;D3m?2np8&C@BKZ$f1t>cLitNA9v8{y;vTEX_`+jhzEKj*c<~kktWEGom?7&u z^)%|AnkUR2QiV^#4!{-9qfqu#_Cq-#1tIrmL$bNGf`Bu=1yIEhj2PNH*#if>_8@uyogd~!Dd zL1Q`#PK%*Qfs^GO#dd6I;!>JpYltOHI`nYKHHcO-1^*3v?r2q^eYX;Xb~)L2hx5x< zX^sUqUKw^;^zY{C7qC6JtnEd)=$r^`PmO8N zx%(hIIU)Lu5iy|PGK9A?f+3uD(Qc1`lh!%G&}tX9hclel)kF%tSLUFb$p~m4X%A|b zWvp=4P5iUb3#ONIHpv!E<&Jbz#cZb9ZzBbbeCY3R+LVSCj6}St2c3U)VSWkWv@`U% zu)Z?@zcap)~3qZlKtweYtPZSD4t(lWsbI+cvfsf1|D|Ikq^o>rBNYm;JVKxDeIsO zwclcj6Jm<6RUQek{4Q3ooafw~{e|`=$BU=jNMd8WcT#=N7KMhl7Im9vfnyC_V8#8J z?D6whs=1mV#4cEfA5R~Lo#PT=OA_x5u1C=8{jWh9BBd7#QK@0Gyl&3M)c-;0eKlch zD)&8mw8IIpIxzXkbXI;WhI&5yCyY6qg&n!3Ix)=y7G`y2Ewi@K^V!i*7JmtcYzkEF zJ#36+EGhH`Uh_8*DOZ<1kJQ2;buuVhx}Bvg-%Bx+EG&NNhm~a^uu&2Rm#%am*~Mwd z{r;lm#Lmop_!g?aX{ES)SC>9*I0jo6`$6&-LugHKkrmw{R^De!EeK2s(*Ehkx+D8Rwg~7F#*|FmBrC2R@lvbi2!Y z_@58AI?{q2tTLfddn^P!xr|z)_{`g&#WOWL*w^DLX?x0JVa3@bTDgjAsa5M$RxWSr} zDqJJopH{!H#BrH9IJIbva=+U5q9J?nvkB+hIYN-61YiAm44*?y;Kr7zY_aJM@=cp4 ze|gS^jX1i5B=-%m#Z!xJTo*z8pCRn#vtF-|zc|f0QMljrKCb?G1I!}V102z%{9-G- zyZes#+N=QoTl@p2zih{QcNbPy9Zp(N7sXEej=ydaf^+ptF@eu1U9{>34 z-gHJe`;7eCj((hQ#d__1;=r2{`dQHnHNOvlf=jM!N?HWDZpx86Ov}Vkv-&Fct5p-V zn47wY)~{1wQYGNTjhB==)h{!&$bY{dF4)@%UbHWu?U%J^cAK7XSDJ%e9}I#JeS0`< zBV)0rN-*wlH#p1lsh^muD{sCP=Vr2u)uH4y@SeYuy&3Iw9D%jQGU#SoKs$I&Lp@t4 z#68ucKktsf|8ip+17z&=^Aa>~A1ctnD!kph00w34gh^q>^zykL9{;gNoX&HdcKupT z{}p`{&v8a5@(j2QnrjqBE_xK%?ub%9-+|xaAGVfYQ+E>Xl;z;Rg}ar#&0?4KtgDj+ zm7VVhLzYOW&AFoggIafX>+mu%%NVE_zxFoiaQ>=Rs42efUx>$Ug)4iW7Y1g`=F>N9^E+O=iEEO3 zshDHm?Jlr4IEdZZ7emmNAiUWYf=(ljLg?WHaO~p2a$C1i>C_M4H&%zy6V8h|v|C|`ww&#`!ijrcdPI}>>7UT8XBKL{uY=wi9$?IOQ!QLy^q+MM z?0Rz%bFPe5_CM47WNh5S5-cBUBEG$?M;Z&H7~P-`9qNKv#^*J(tIrnUbBDh8A#n*b z-A;riW=H$B&A@vl&&6xzo!Rv>8_9OMl_G`jshaGMz=JA3I5Azu+NqZ+>rYRv$MH|m zLc8ftM3w29G+XS1DaLWo`9nV0hkZv=Z7ayR!gWfi;k1tN`qR^fR*uhwlMa`~cdKM9 z+@Tb=7-}fK%rNJCR72Wo`@ATnNlKpeo$+dk6I8v;r+urwqagVwFL<1emjc>gsY@m- znrBSR^CYCi3=#7u$ym?d{EM5>S+RPz7FGDZ0jK$%aKg%hJsNF9|FkT4)}$td|JMm? z->QI&-zASFf5#p@rVBMHT5RsDR7|d)ELcr>jC&0B@p^s)QrtSzzEB;^8k;Y+|7OVy zxkkihuC>CXQH7lr`zf_^E&Tc1urd{grsW8OymBxtJ`}S1bOcK2NUG|ZIJsv}ao+En8ULBq7ryy_ECRrY@YJy?iTK*5%5hR%D{r z>^{o+W0u^JKD1Utl>K?}wt#5&>AX@4w~}+N?o|0=T)hKGjd&K4o0L|GdV;5rgB@=N zfO%JY&{dbQx&Xw3!QEiV#vQCYEr~AV{r3O8p*`(02*d?trqJl8N8A3U!t;lgkUc`i zvQHseYK02B=T+g#D>=}9@lIgdI#YZ^2Q2HADIST)rx|}apU`WucrVa}CE{i}^gC4H z&nB95ASym)$tUrfo8i~O4I)KIt8@6JJDP8Z^5j;j{(()*KEG!=Y zZm;v{?WPv|b6+aYj*zmp(!Kca{wVR(LK#aaNBm_rS}`|?>-WySgg5W>A>^n9YvTLj zD}l*EdKU?f=RM&6b}xMo^4$@6VW0zNe!j`4y<1wagZm-jW5rp@64WWrsZ{ z9l*b5;?O}iHr@4JI3qugn%X6>8TfroY)5VH{L%k+oLItdUaYzWE5_Xxw&mWY z&Jc{Ai}F@}Fprp#;87p#doR^0J~7SSyeu19eJ^$XM4bmu7A+96)J zrMr;leI0?bECDY5;Ql7-a2omO4cy+LLoRQw!2dEUpV?Zn>l40XP?@@L;1>Ul54OY) zp}KIaoHN{dN6~iqKcQf2Hkv-ERnA!+huqm?v#liC6$7RIm(iejxH7l;td)%2;GXce z7A9gJJ)UK-T2sji*lZoeYCGgxuI@4GcA z>X|)$vX6ruqw=Z#QZxEYw1nZN+&AqWPH~3A6yta6l77EbxHRsBxO%pX&ANv8?z6f= zUB+w9FBxTrJ}cVCJzP)Y9PsJPPN0#SPfPq;Fly0Xd4o#^CjDuHyW_Ip=M*WkO5KYq z`}BtWD`jlvGsJDPJ1feEYg44(ODOKq4YJHFdA6(peR^vlT;;ui>i*8k+fZD3KCSE8 zg3H3E3BFgPOtv)%&yATZ>@}#uM_hBORg?y5=t#wGni!UpE829lX0xUl(zD6!6dEt4 zva?@#4*MrpSfN`$9o~P%GwQ#Dt;bbZ);)oCEw{wf<5E`FBMFz+pA*#7a`EH!#Y%5r zwxuC^I{5?EyLW=gu~(6;EC>Jl#t`v2hzQkVC^)l=tebD3CcYzke$z ze5g6f`1fW$vOWbgDhq&jvCIu|wda%L$VG!s3ne(~EKRRE&QE~<+J9FkP*RhB*rR>_d0-TeQ z40)x512-2aJw%R%x|C4e8}Bdb47oq@>3fzY?bx6vbl;nUlN{yBo6(uadTj9TBAjN} z4W{$jvniDGip^WZZCocXe(_F{t!nchFyEN&Uh0oWy6Aw5P(Y)&pXc(>g~B2mJzDs3 zAJiSTgm+V9Y{{7`XwkMxSbDY!|GS+Ht`R%oz%x5~TxyQQ^9MhS%jez{&O^&uB*yo5 zXG@obll6r4imdP4!#?2%Jh|{gEFUIgBllmyq4g-t%gRObr}0WZvhOJ~wq>3!eJ!;F zkMMpATzINQanZbn z>*+)7Oe?1HLZ2kxQ-t~MQe5b12z}N?KmhkjXXN+7;YHQr*Zh1EL%*Qiql1F$ytCvO zqe=x6%`kX^lr1gXg;R^u<=X>Hx%;3Fe0zTq#p#x8D`zMdwA2WiM=s)|r&l4}dpP`! zX-C-u{m>~RPW*L>Yggud!KUb2!sb7>se6DWZCq-Ke@=(7#D&~5**H^Cfko(=vJPg} z7{l926ZXom4&P-QEw-4DI9$gXThO+=i~DQXy!R9=$qchTE%jAZPDP7L~G{;I^=@Hkph4%k;>=Q5}C|>qFPf zXcqTqH*IY@Ak_Tx!@?=EAnj}{Xw2k&h58p9I64$YEG!^PezVxu`Gj!#fiC?`+y~pc z`T-tuWG_sfa!m_;(wNG%E2dAxmy@@#6xVoqHc?+OGf{&sq;h|BT@0M$y4km~ zFZisFB^@3%0m6kj4l9n&@3(#lsSH)N;@1jWH+T-qK(5UhSXBN;gN+lyrCK!}ExDH8rAEe48-QUzP33 zkdtGpC35Ws>t39IH_Xln>_857a+|N*QI`}Ouu})#ppfYRP1!PojbGeK_iIG?g}8u8ufUJCl?z{Z_fP7B_cb9Z?w&hyDZGIEC-1rq;t|kht zoo?}5ltS45a22F!8q=Qk*0?w5k(hla4;Q*N0MA2$CGTBX>gbJB?0QLDGtHjNe^o%& zpXyNcBNykMJFe9FjtbSJDVg2ScvL_5km|w4jtQrLl6-l`KAHG^EzcU__wK>Z?dg31 z_nfZ3D1Ozwir4PvDcK0S59^RuJ6{};=L8yDi`#RE1|?0>6Rv#D!71x{Dg8=Mzv!~Z zr57-~(gXOK4QFKJKx{*^m{Vm$aK0}}!nDE9zkte?YtWvy5W&DrkD^<5D{Iutan+dM zct*J|dVSG|cJJ3jr^+Nzm1`G&MK$0IS|k=`c4ZlCBfZOCtB`A(lDYQ*WnBswo`W{t zF|gFR160g2WdrrKC~c+%RDRVYLw{Q=oHh{Na}JpAg9aSBQYv3|T*Ah5j>kWPM~eHm zYEhx&5lE9|@ZpywyRXorh7~Eof{{}EJ6vB`f8Mtl)1N|j+}Z2Ccz|oMw73THfAuHA zTuK9W3`8&edC(+Em}CEVEctp|Zf~bWGZt0C@PC!!q%oZ9lCDc}c{RePg}1P#u@aos zXFcPYo)=@uJuP+RS>xI;YVc^MaPOu|YwLG`T;3a|-g0EycRWGQ z=4SaJZ=QcXSRMN&SBZ!6wz2GlSc==LuP7?gq{LqxaFALY*l*)+}ZdDUjhzR01cgzom`I)s`1 z!S@W$wi~*Y?4Mqc?{zzao=@DBeUY7N7s4lx;I?bA_&ka5T*+Cbci_4~6!W)>BlpfL zVLkVvS^VdX)yAE`d{F`Y@>N&%NP07K@t~`ZQr|l>SBE{EmWxd;?oc0!xPxWGfzW2r zc;+^i6Btd`=e78|d^I3DC54xk1r+*Qje;UVgx*7R>0AE<=(*1V{5DTxcXCKGmPC)bVNFo)%{)#)YIea#CFfWjdDSw7X_&dXAH zO*;vb|Js2ivqp#$e`(X=s0whE7{Kt2Tt}M3wIh#Hge5;EsIQ~Pd+G@IscKHCE}l4X zWQBNZK>@vMt;2GwLqhHuDGi@I0Oyx-7UeJrv+5d+C&wR`Pkv)W^YUMTqeqSSTgQ_9 z=&w!PY-)s8owBiOdOlp}u7H$W6RKaqz0ZRqMSITza?Y$nz3f{;AbjiDyPg#BLp7Q^I6i?{#B{es(M+(+vS({!h^)LY?X)h|xy7O)tL?;QZu zgNZP9rzhJTvW0f3eS~ezock1#!|x+L5ZmU??i0_Z9Bd(E+|;K)M^oIaCxeLTGgz11 z5%kmSpU{3p7LFPD296GPhqgcuHc_^jd=JII)t8sCx!NBFZ8d=te+}4w(TuPZVg0NE8p>H}TRW|W70;d7NuK-j(z>1E#8F)ua3leG zU~f_>Ty)fUwO*E zbX=&`1Z~St!yF$CHby53r=0SEcS)QtH2nd1)p@|Z|9Qg?XwhUc7kXRkl4P0#{&SMR z)U*Oh@UO>%&C`Tk!zJuZ-gY!83KW*VKZ9OJCxLV4P0&5qg6zh;hjZ0O#TI`nX8lf! zURzo#{3PcIzto~-PHdNt+38j!j=Ya$Ju4s!q>PQyw_)jQp@Mo*MfpS z)A(}6~C>;H#>SO$_AO!*rrMN>aR8g zE!CqzNjdP$)C@-T@no;=Y0{C&>B8d)kMO1wfKTfd_`T7bW`yul8Spu54C=?W zGw-v}bl-Uebm9H^eV)nwzuoof@*I52Gco?hkPPt9VXr6)b(Xrp#4E^IeP^KdP_uY% zL=<~7J%<1OfBJ8(H=wKcd*lA8QfOG>$}XHgO;Aw0#=eW*0 zDGKTxsu3TgD`&9@!A3O6Ru$*!S#tDEKRmx z+tRs*=fQrV4`|}hYg%9qTR`uN1)a6`#NQ7diGDYv^kaHI^gA;ToR>=2-_4OYdGT@i zT}wmKyIuv?dc6_H&$VQmr%1U^xklKyEDNtr%z>p`$NqYn9mVVWVawWGVlvli{+Q4o zC9nEJT2m3~d<#+54HZ)pwqfuKJP@8%Y_*y*+v9Z6bfq)&J{!c=_Ku)5&Mmy82tj*k zvT|-x*Ysp+{Qh`Le0-teH^7cNEP(w_@KkUv2cIdc1RaZ$fQ)j%9%IC0v%Vj#cDNe`PEJ_ ziSL4f=f}W@alJv!if6hx6=3A8hjP8H+^;$IFAVEhCDxT~V=Hb)QNU7th4JAsT=@Dk zVE#DRKHQDHnG{CBYlkV$zw1JNmofnIu8Sx3ne%O!Cg++xD>9$2MQb{CK&Q1%aQ7p> zM_p`C?w0>}tFv80BXF))chFj|MI-v(1>dtC&|#njn>STLaVh44Ip<;84Yb2TEeRyv zI)lI6ze9&1E-&_^)6S&l^%`D7>sugIzrcE3H$Xs0%!C)E4--Tx}HOmm9vk<9(~r3T!E7`?ctpLRXh?| z3Vy$gz)mliedJlsMY&Vuv-Y^M&c9ZX|J3$q#b=5c<1!(_*aW<{bC%#bb$Sz#F2r?s zjD7R3z`XI{pm~<(sx7j@Xp0wOkNNpnR`y;w?=*(2OK@ZKXI9q6^_{2cUnbK}}{!f1h+t-a{58BB0 zkmu!V_GIFq#7;`Bj%}NSjenbtcIEp)o$KOyamLw>i5`kR!Gu%lPATigPtJEO^z^{w z^A51CBnM|laeW{6R(rhGX8KD{p-XF5@K)m)k(_1H=UTIPW~n8U9kHT}usHv`C)~5X z$rlamq|j-;E~ReRuIxij@@%QUIXoYz{W`%aq8k6S9#!76KKq-}qD`v&-oH=GtM1Pt z)@>k@F{)5COpgXmic;qNec^h-kqr^bIq1ncJsQ2Z6^^#*i_4a3(JMcn(;Nu8ACbli&ZzekBn|LD;*)pD?G=9+;(3%1uwgZ8f2FZ{SFL67@VXDjA$7eW>pm+MXYD#CzxYQ+xf>sV>$MkRC!Te=f_oCy z_xd2TyO@Pl`e$MMYyq|>*wT-<9@r^AQJiQfr3c*=Sb8J?9-eQdN7{?=zRELU;^!hP zOqi?8`wLuY%=E3RF!AD%;#PHSI%%q-)BqpaIE$U%8BWU=CkhG-!MvD#;7}S5r#O3d zO3nt_Q~VLkU+7ZNvrK57&=b7I`!Jt*5<0TeM(DUwmrn1{!wuou@G50G8ydZlH1hrk z_V=^!b^3E<-B9=B%{GPLfPIyp!%90d(Pg@XeiVO(ZK4!D zb>(?F!8Y{6(?ig(@xlE*qm=BIT^bskVd#tzSMtSH&U4Nz4WpaSY!zbz^vHA+&+p>5 za;+FcmcJ_p$BnO$5BsQ3nrD7O^@;!QJx=V6qEL z__bIpYxH0pI0wUb)JR2?Nhh)zau}A?k~kpFoVAZorDLGbK3T9qrp~IWH{hdB-cZN$xoqOf;0^PDGF@}_#z>v|^fMDyIOx&=Pg@NA%c(y z)Gb{))HD#)u6BY)PybNw_p5N#m~>(0q8u#WHW514*n;m7eP*-xA=YWzL*_1q?@ddf zhO;{!_nE`uc1F<0;u&&hp8GL;^GLLjYQj(Mx2~)?tz_WeZtTWl-g5T%?Gu8L^J7$R zE>hNzJ{wKxYPuPYpULa+k38%dTLU#Wxd&&sBkixh2`f7C+Sua5j9*B|Xq1{_bY?Dg z_c{RI2egM?L+z+ntUU%OQpK`N33*)Vs+?;=T|Jpr!8&@9mM>p*EfeQ{vQ_GVyNr=C zVcAg(?~n|~&3dr%2^!S9)*@WdQXm!|2!R`jnBzha6c?HnxC!k zlF1M-DxShd?~kDpt#tYCzY^B9d;^xQ8!1-wm(kgYca(mCbk5eMKs7op?iXBqBp4H* zsnq109cWBePL4?b-4(C3*QCaYewdmt3+_hivCb)5(W@X+{^p_sP5W67Qzxsy2Muec zHdKSo#eWc%`<})1f3m>qtpYNhTM@hHhHsX}h( ziy(6I47RoVdK$R)udrfcHfle43g6zj!}_1ySYg;YVyb9kbU#X!XAwe<*!ZjNdG9;|9Dl1lU1x3)>_b}2gilb_hs10v_@G^ zLi-M6s=e3KnV}glrjG|}IJ}xF{YEJE|N2Y5SC^po;eGI5iaC=^;h)j(S&_${BsM#G zH|2(b;;13ls2sM!!-z`8xd>Ov9Telvv8Q-avbhIL$bG)3O)jR`eu8Hr&-rBL7V2mS3b z8_k^E6-RlF*qbdU!HaVm7t7?#$5@L_zsnIa?{hw$%0-Bb4~H{MMxGwJDD}A~{+pDC zUB14Ah!#sY`OkqaaU@LQR}Dz*lFRcSI49*3kFVdfbBt?%T%+J_9R3K*H7i3=c0~E?TvaLEjIncVH|tW1+t&=oPv-V z_+P$;17}lgpJ77IsWJW@JVRssPj_6ct`5*ykG~f-LC!!+Xc%S0_VzrD%^K?ktDDtW zQ++_$pD6A)(x5-Ocw$$ExIB;VJg1t`{o*D;rF9y!91%lPDh$CtlmDHt&C1$xPt3)x z{u`AVo52>w40FHX{1v9q{#p_{7qgQ#{Yg=1_(`dEx;f72KM3lsPGKMFcTnle<8sFg z340X33VmLV5Kr@ahjjl9@J}>?+)0+KElq_k^-dNR#z{EaMjc+dg~Pp#{C0Y%JuX^x zU9=jf$KQ9Guv<{3{A#!nm5;m!-BjL*-L0)zxQ!ZRgntm;1!NM~<(& z@wvk;annNXq2pfuc+37!CHqM=&a?3N{TIUfr~F2Db&B%dJ>j_#8(e-5C%!sd{Ft=J zx0~_MwvNs@3cT>ya|5>7j$Bmb%b|XMaD6T0?u^{t=$+%fe#W6WDdj z4c_^Bu}0}ydeSWpXjvgjM>;F}7IjSn);{heT5LBJuZ`wfDv$TDGC~^$J~3w*JY(^( zs*7;tf+mfb-5F1$pBMH1da%v)t7!BGTg95!dbHsAX1HtJ2hs`*Sy99(>_4SKp0Lb} zW={SM9ecbHXYH|IC;OR_q4P0e@xPlGuJIaHFCGhfW8GQprxou|+4=f8C0&VTsH zcps=8HfM_h|Kd-JXGQtTwP?&=3uS+@p6l56@*UtO`5|HT_LG>3AC&XX6JIqZhA+bC zG%py)J--`(V9W(~I9hDZ?#KSc6NP3%!2(@s9NtdZt8~kr&Sqf@`L#(D^3K_)+SUXC z|6Jhc?%y=?Vh~FA4H23GvT)-30m{B*?lTiAdv_0p<{T2w@ob#is&X8<+Ya6|w$k6# zQ!r5Dh~Vv>hj$x?DLHkSb~1LT_ciW^;@Yrl3^#7R0tpk0pyWgl8~-F zI3L5my#P7a)|&F&AsDZjrAH?NBo zpY4#)_!1{&J!y36#zu@=MLpFE*UEXb0~G8Pm6} zC*fd^p5jZcxhe`Q#gs}{Mb}md*XO(hKNAx7H9sxjz7GW6cR6TEIa((PT^*mrq` zIH#HGohF&km&PWcIx?7@SQ1N1PMg4-COcAFmjJ$bQs~=Di@ES8$aCanp}d;ktOu@D z)|?+cM(i@zVZK>z0--#+^AMUU>&%;1nk+kMA)YueTxOjEsto>Jd?Wtg`QWQg z{ll#TJ_x!~?%>Y{rLgS#ESS-;J>i+Ic)&7V%sStapk^dd5gXt9jud}4r)V`8)wY+4dvO= zJijtL8?9m=fpe5Q9C=rWVM{tG`xDO>Qg&fdDrQS$;*!xa_M=}Zs&$>B(CaNF@ANlsQ21}UFY7FXA_SJ;~(C{t7Xq&kM3C5G4;Xz@6ztE~Vkq zhbi`twImab?Qrm3zW9EGIZImn6Q71XE!xDhMBk>F5IcsmG<)ozkfc;W&^(Ew zR=rd1U4P6~Wjk_bW5VKY5NfGMVLPwFx>w$i*v7S*-G8HBmANp0&n&q|tdx7#^=;Ex zhJQ4Hx>V7(`&o3k*a%l2x`M>1g@)Y?M6E{wLQF^&?tI=4`UGx*x170md2&I^gljVIDwWmEtCgFiH1L*Rrh3-dBMBTft3Og%9^2s|6u}3XoGS_Lm>{E*G z=5H1Hqb>=bKk!`l3^57TGRX{jYF=X!wVhu<(NUoNVLbfP8K z3c;hhCQKj28Jhv6Xrx&t*fr*%>)JiaT}ncHXYyKLho2uF5e;u^(AVyr@VaVW(B&*U z6VvY~UC=|`kdld=1{uMs^aOarXUxrxyYRPl61>gx5e=8Hqb`-#CP!cr%6Y6Q=5a0r_7a_y|)LX?2YF>+;!C%HjI<8Yds0qo^@4d z^WRQdyXSD?h6`A#TColeM#}lfr=yg@H61aq%=L>3F-@fb9Vr70u z?IS7cw_+boUKAquxL4x{$Gz~*awi;)<1ESlw7G95Q|zc^#cnzqk>m3wVZ_s5cIi_z z-MM4}4oeGYURWz$s8ms8o#L77D?^~)q4%QVr<4sz-iO~_UJ^F+$V2JLm9Wj#7TosP z(df(SxT3{DY&*#LIe(3nKB-TarZHRY?Y;9WUH(v}$&MeGg^LCZ6VJNw{=vNvW*ydp zG_G?nIQ|pMuO$od*-}i;S5e-BTn2N-s=g)G&L|aYmR!JN-F`stbJkF%@r$QIO~7#j zlI0;>pY?NkDQGvm7PmxMGufA4`1sxjVQkzj)HNe8yBP#VFFVn^^IrJnW0LruGq|3P z_QejI_c$xFf!zFu;ex4^!ty(uNnksMl{Ly@vXp&zzZV-r^u&Igr}rt4(8p_vVmW81{`vU=)URqo%X|y=jkC)l zrn(40>(8Qh$71MuNCite8`63`PZZ}}6%QB`(9-WM=;?D@=(b0PHfk(_lW%>YSGtt7 z@4XL?RbP`wIdMP1r$*Si=!H0ody3l+GoXu02H`Q&0-TC`^()*dv1;lVAWXc&s&16&mqae8EznG6nmpP<8g2FG3^+6QhG zD!*D&f8i&HX_q04bK}!WHL&ygyW-D;Je;Qa1U9ByLMYEfHq-iwU4!LfRInpO|CbNt zFEqh`>)bq4MJ#-FQ|OYJhue20D(^%Uyk4b!vq9(mN5nX;uh%=#5pNVL;O^FZYWL?0 zK5g@nU;31ZRTuS?yWfz+j`XWI`xh3fQA=sAS5ZDJhpy8)8jhAg;i(qz%c_zsfoVbQjT%3 z5!f-b7^mmEDsl#D(P7_eFx=z{2Zma(6@z7Txgy4Y@gY7_Qz!Hq{7+2hn#{?mU(mOH zp0L_Oixw+_;P5RISi&`LgSB_#jAaXi_3lqG?d)#lEY@p+J=y(K#q#sV#Roi7U{j(# z9XD;_Ic_{#ihB?L@OrzanCrEQzF=2R6-9$Yhpr8t4Ka=%#I;kU?2f^1{Py*tP=EIv zo*K0f)EaESHP4XsD)@kVICm?Ub32D{CU5k(jtZM{-XGc+VsDFqFsI{Wrl^mgtG37F zw|f>)zo4%;f5A}2y(A5`e$*5+T{~0^yskr8a2YIp4Pe$}E4CrAm2)hU1=&&w&)xnd z{_iF=`7^&Ej*w5K7R}u0l!5xt6Rt; zLm7COKX#ZA|N)5Z?%n|{#k{if*d4JUJSt&$sy@Jw3!<7A1RWWDo zT`0z3?NW;mYZ1ouD}at+JXf(#By(MqK-U^Fgy~reF#1Cr)K7_n;~x3+_jePelTk9xv+u&Xtco=_9NZLIg?c#>t9 zE5f3)u&e2P@b_?o8BY1My{QRLF4TjHvLZ}8WDREynL@%-2`h=*g$Ez&im%Ve*we$s zxMcMdMcy-QDq+u{U#Sj6)bSjmmoiGd zRJh~|=0zS8mMqhuE#GGI{6JsGwwJQ44|ZXs#x?mMK3_Oqea-g_6`~r?+MdVR;#cdA z3AP_+vKsX$T3~wx-k#^VsJUNo^qO+vY{DDO*tEjT?3&-OQ^n|Tkb2!Mc2wsfxhO=A) z4_?1;#`<1uODIafd*$FwrxUQq27cMq%fKh#0Np3a(cl>u)D2vU(vcJ6{E#4N){^+r0t|1tj zW($))0M6kIt{so`VZ^LRwvqFNbXJGU1M5ua;)DUHbxs234C*L%nm>LFc2vY<>QYNl z60{cc-{8j%l&ta#9Q{R@HtIFIM4RKl9^mM}6npLCoXQQtx?Zr^7@ z3qBlx2M-#=;e5}W?-8fm1(kd-WE~D^lH_AFl(ggCE31ykCImp-_Lg{oY!QYEcgK%^347P33HkxN@1d}++Yjtr0eth~*u-a}$ zE4U{7+^9D3$rlOJxDk&BM_d%P4$Z{`pZUt$*0ME*oQ3-qje?EgDQ5%rnJc5JYqp9m zGVY`N&p_$VDpa4%ws3zz`1sTEN4Gf3SECW1=MPbgzoNlfOvhpR@uA`)Hxtq*MfiH# z0@4R~vWZ-8Q*rE^pfW~+?>~MM^P;xEf3MBx*w6O3ef(Qeq=S%6DB z>*>_HKDgVrLOAVLjCJJ$L4T+T$WskjySc?UzT=_dHY3E!=o}btQ7>NIG9Pu9#K3{@ zSePo$r%i(!@ULP4d{%s>xPad1l%=W26eIa^~9>p}O zAWPGRhdi6_?vz;CvdLUAE-Z`Bsdu2DsVjso%%_#x8nAo~_xAce3m-$0x(;lAY{}NH*Q0(pu0rd}Y;5Xx5k6J_gJ;bqbkoff*V)|= zkMbT~^?L(ej5{WH#_LeZ_-Qcik}vlxN!Y;^@tj3gD%ap#sW%sDpdjj**vR+WSO4kK z>-oooK0{`(oBY{$wzClS^6c+jnvLi^u3VVgp^ZMj9Ec;O$Ts&mnAozL+zGbBQw(=xXE`n8~vdmr@VB{fy_Kc-2#f z)IPY%Jw>>fq00h3U%*G^9bkVxpqY0LcxC8Ax1PLz-j+aB-dp9(d>5o9k)yk{8t}?P z=L~ycqMn0d(r-RXN_N9^RTDTlQit}2R>7dS6a0NAqelzWFpcw7oSQhm<;_F5_Q?Vs zWpOt9(*|ssBo{M$O-T1_Dvb4M5Epvpp|e>W9G0~Q9zH?V(e2US;<)%~kp_k4v`71= z0>rH5{Y+8=I%oOF&vL(cWxblR{T=N+JUeQLBg1>_M$I9S|CY?k+Q!HD}3cKQjb_ z4h0l;s}4`Ps3=CAFea7B!SHTDs~8a?VW(1}@m%-?A?___0z1tChl3p;xY~eK_I!bl zP8&gppEWyqK$j*MbyN)d$8W(i_0UjdAeh+(vGWhMlDS%j+;v<54L7RCR^y?HuO=GI znLme5cMTB(x|>q9i3t0zSwa^bZ#JH1;S3#=CpdoRzV+>2#gCR-V8T9AN(r|{#fJOh zx~m2FHN76b7F$A(h-Ug`>4%w#N%EqWI@L*L!sxM&4ZjAIE*9;&3mlh|*AK@?OaC zcRXD8@PTJhPE37oC1!aT2;-AhEkU&%CXi=@#($ zXaUbo{ohPCx+|YI_ZWhDxhW+6)nuJrqcQz~j#y`-OXF)E!O6$EklDwY-8jfS=eBM_ z)naqIPs zWb!u`CST`1tRL>|Qzt34dAbS7H3p=0)C^zl(FU`2Gnmiu2r}3qQPi|%VcD#=%KEe1 zq>g7$c0(=mKEj5ZS-3veO}T3tcE^B5(0Q<^O%|&-uPJRrENN(t0Xruxns=lde%7#s z+{#+I80U$-dnOBx$$4ls$XmI`zGJM*X7LQOZ-d)Ih&M;}t7IvAA)~%A?B$pQa&C^4 zC&wAm^tGH5K1Ln%hJT=fhh5RS$xiXEp0m9A$HVTgrVuwshqMno0OxTh;NJ>Es&-bz zSepl8#N>R8X}S-Osw}}KS4KLO@$kd6MhrZehpC^Vly`PJFIO7YVu|%x$HW1hHEEJ2 z-{J36KKtCQt~bi1(>qV zQVj~6qyZ~uYm;HLE#?exfKS134r}sM!N=h|^$4uRLW2du+DS4p^5+Xae=D$_ zDq$9dk+^XAJRv@=8vAQT!z1;baOXrv`V`R&ht3@pTjyA^qvxfhX5A>vJTskz^X%rs zvkhVXtn)PXR4v}DRZ;91#xu6=ErfA`CcNq|Vc(BOqIT~Kg8Sb*Y+V)vG2yo0zuJJQ zuI9WRS0k|Yu;RQvzSpSkp!mfcy#ON(BcC;nEwz0vu z$VzcUkMpRpv=)YbwFKRaW~!UmUD^M9P47gyEAK*8tO}GotH7fP#qe@m2*`RFP~t6P zEY{p2uH*NOFk3fV>?4Pd+70CG>4}5GD}lW+WP$mcJaq(2*%y@{%9 zQ$U}48s_KgLViy(I2a{ibKXbd=h3?2lL2}ZkygRELweBO(}JZO?kQPOv%+7O+?7df+$@NOYsw8D4 zO89-8-@jh3UK-DHpL<-_`2}MSuWoKr^0sqEYUpK zgqczmx|TgGIO?EHM-%igx`PWu{h7_i`fQ`lg~>vrcnWu%cnqQ4&wwWTL)~}v#e`{{ z;Rk23ISk5%jL%(RWQaFg8>2ZU!grS&xDh#QW3zhB5`(dP3-2Bw&|gYYSY@4Kc$Re}K=Uu(f$W?RvfeI_#F z^~Tiqa$kJ%K@A=}t|os!C)BL6m!CYXLsnYR3T@A@7u>hfQVte2Y2Xh=6ym9b$`32V zFaPCXeaAbBK4;OcpVVcx7mojuAWu4KL@6hBaxGiExTH7_%NIu|>ddaOyWjZ7B~lrS_ZSVQ{xo;`?5N!D;a@HPHyxMCsDCPR(%p zY-?d~kQQBB*AC~{JHisK;Ysmt6aV?jo0C-8>c~*^pW6Y79%z$v*YXnQZ|3D z8ueVa-FHK)E(PszK>sePkkC(yvR4m)EM^K9t2EfG#anTH-vz>(MNcueJOZvfi3c~X zU%GeWIoz4LSDX`P%|-~C^q}gSaG5h+F3Uryak?QG8yQlt%Sf>Q@>v{48mwvLR(yQ- zf^fF00rUS*iQn%Sf=RU{E4`^fy+iEejh8t4)KVMu-G{)&F|(O@yD&N#mnPeAPL=K3 z(FcQG3=!Y0(V1_{T|ne!PTK~+e}K~NfsD(xI!GY zJ0Cxn)dFXJ!Z(*+w4}ldpIRJ{=Td$^OM3@fg0W7Di6DF1+&JYZ5b z(w!1TuX1;ZF0~Enj^H?5oF97?Qv|NfS2F{eB9rav;u4YVzX@ zx==MLjdl}mzOkS`J-XoS&UeMGMmqFHa}bQ^-HUUqI9Ic12hLbhAsbX{N9S1s%zFD- z>^`0MC%e@sLiMC+hQ z!3cOOyoxtwQ$IezRL2Je3$|!edbJLASmDCGcC*<%p5Y!Bk}O#CI)(9p4;1^E(7%7^ zQoOgKSGjnriIgua!I}3B%+xnP>aHQ3sQih8oRd=9f{ z38PO|TJoTES(uyu5_B5fKy^K@CudyHHmZ-%d0QqXmpdyoJn26CrjwP5mf7*3;_uC} z9%zt?wzvEUuMf3KR`hL7y*PS~gyeTUF!D`17{m84MJBE|a0KV5tjNP@vF?iOgP9Yx z+0HFzaKj`UP#s8kV$d1rzR>`H``q=p=JrQt6IlnYaUH7UjWsv^il16)sAF&kbUNiA zU-Cqo)(wb+6B)+PXsS*AWA4DuZzn;uR-bexv_khYW#SdyFU`rh4Xe~FV7tpep6AG! zjn-vi`I{d!YqKYwj7pHN;d6l1-$+<`;I;VMjr)KuY=g6ptf8gVk-8o;z~am#QFA`m z9(!0T?()^|rm|eldeV6KO!nI|16MhH5dU!klPc|KnZ`co(3mIAZ$X@v9Se_#8^Ksj z6SiT%Zw%H|g$)n+=g(#fyj*X`JtI7aIx?1STBZwsOU~jG*Kgv#EZUHVD$MU_Fpik+ z2{^hFNcxTQGzbjMw#u(p8!8|YiayuM&QW-jI(jrl}FC6({3K6AGux`v& z2%H`d`=@gT@|7Dn+;|5Zn`OzeE!3!Z&}ZT2m^tj|_swKtX9C7O4XFLw0T8q5li1i( znSI)~5{rB12sbnh*o@e6EQ>XS%~vG!!&HI>I|lK;i$Al~<*YgRNm=QVW@?Ra#o*_C zM4hdsB)xJL`aH7W`N&)wb5)sip5+SbbT!berbd($Z3fR5HuSok4bIs1OuUksj~Cll z!+U!R=zruVHK}*R%x(K*yT)|jn$Kc*;j9EzcOT&L4wqoM%3@G&HDNpbOz6E7fp;G)nMW5(I-ZyOCrG{{4Z!;a7`(H`D)G@{;>=`iwxqj;P#w1rf7y}%F_bC2*Lp843b z(nR)ex0bWS6ECX&5m&CPCDr+sc;%gg+$ctu{2I5wz$vEig7;vxDJ8Jfm5B1O}Z{-9SimCb$_O}}P7 zlhqWaV|GK8XuT{B7P!07SLH+CJ*H4x@DnkpI!3X#aXxI!hV}c2_6aKRBqxET+}cGl zk7D_aNfP?3A;pyG_OQuj7Ry^0OM{+e2w~&T;`Ckb6+MrdgDM*bOL1+QBe?9=BKO0^ z@MW1hjJRmU5`L>t(%7B8O$9s;Zm=E3$Ekrn&*uJN>kTXSnL&@^zi5$hAeIJC5vKY* z$N$c3ftB^U;An;k73x+%-lRma;fy8QYNoW(9Gt*4wpr(~|5nkYZn z9(QH*7QM~C)1G!SvHqQx-1M0t{qA`NMk$-Ypu~3X!n}bZKJxZ}_a!D!e87MOV;Ytx zCl$VJ(;&ZucW~g36R%6=%$xs?;vV!Ba`c1nSp617pOgQ=mL%;5hfKgFPWGx&U6gI$~(jLm^M;;0dN)L+FgBA`q>V`;&TU00&I z_~Syvt0nAR$8c)Be+}*(bfqd=fAHUYowKA`NIh>3CU2_|?sEP1DW`ildq-u#(5_mP z8K!}w_c+14!T{zNA3{FLNrLjaQ&@Sh9ESU!hMG5Rl*$={-9EU(`h*7RK6nbs*6PS> z=5as5qZCN(>;(%sAN6mW7QT>bz(SQQym<35?67o$q|Wt}@zD&kocahEd6{@l+e*>5 zH1^bF_YWV&yq&wCSD^*FJlK?m53CpO%;nnnST|HVU<-=})zWoq6U>qB6>`cr`|ZCp zP>Sy$Is_GA!ip2Hle4nhy7G*q6DAb$#aQ-hr!JKxcSf1)k0>jwr zSN?=3?oFOtdo_&e)?xVz;nY8@Shn zz!L5OT;G$kc_O(!P;~~I;}%W*qE8E1Th3y@y_e!YpVasrD(uOK`8er$dywW!=(Uyz zCV$(I`yYl=B2>$K9T zxEXj)WwMai?-`DNyAHm2?1CIkE%vwuFn4zh-22LNv@MhRbWBiE(x&S`>z;S zt;Dv>n~UF5vjsV439h|&4QmthVSlLx6*;S5&HaJ=#vH)TXRoHF+b3muSH97L77NVC z>m{Cf(M0=yPewfBB{$+48@s5J5V6=4+_~mtrq*>lF(X#k*JMD3DmqwVbwhkupO51{ zasHBq1zd6ZOhc}it>1MVG`K>z$XOpM%6b@Vyj5Ix zP@QhiaKdZPeK|Aj3$5QG#o>K8uX3`80o5*wS}`%lfc0l5uzN~U;f0kvo6_t$PTDbF z-fxWtT_~yoo!(B+KFXZkm}W#`d|zP>1z}qI&2Xg8c5r!OLivAv@QE#mFB9rXm+}5U1&sW3n&)q?4%XQ=JlQ4R9ovfF(CbiCe1HYfE!LdT#KSUZ+uX`Cnzdu~J zzXKF?BPx6b`x6pPy*6h6C-I=wicg|7*U#Tp(_pGgm*B8?Z842A9rvsQ7_Y1aCav6? zV5>y8J=_K4KKI*>PIx8%hFCsBn>OcoDDtu&JyT+-5XI>Ken87u0hiGF?>kTEt3 zS4TdCnjUT-sDGyFRC7#fl?gFZGVzkS1r+z$1cReg+2Y#0I5KtzEa4om`oEk#_)=H? zc#R58-r#_9Q>D=EbPY|pW{4ZI6NNwax!5w@8Uo1{?%kE}o9Q7`5-eePm>z3#yN(@$ zJ>~iL36~5yuGqb7i?U#GLrrK?ZxdN+mIfWmbH=LZZ=!z2J9-#lfEV7`$y>Qr|D$V& zf~j?UxF#DoDGA>X+$fA3%;yE2B8W9Q1*fDuZ>xPBthKu(?ip;s%5+TVQ(TLXeLN3; zohs&hK`E@l*{tt{9Tc&rL7emWGcD@K*?>Or@?EO@z4i@;#s06v)0|KE!6*s4#F5~r zl!wdw)yfFE48S<+zj1!w1=J{0Zj5M zim-ROaAI^G=9E7W|7FHmephCX>iyB%s6BY@*Py3Kmq5D36<%~OXNNcO?B*}gzO6iO zbnFI8g+C&MXYXd5i=v)7`tmjAy5#c9MR60qKkFCOAD@IbO{NGB`#wdRZ7X5b@_3lL zT$AcL6u_ak(PHmlGuqLk8#raQh#&eZv4tAb@%yDL!EXVtMc)ZMPwKX^f7u4ovo!1wyc3%rt9PBqwzBL8IE)>>O2@M{UbK6 z*JJty46Xm(7aD`LX(E5$dpz3@m**L?<$QPCW%yQLo7E}R%MoqEeWAldRTj6Q9ir0* z;nq&T13MjIRk|rumP?rH$9$(C`R&!FyAP~KY|>|RP)TaclmF0GiJjz`-rLF7p{2)kiT7gxy8Pj97YI0|rO zV6}KlT?#&5IB)9mJUsHBwpb+NEU8ylz+ky1B=gL~Sx!H(?>;xd>%1<--?YFO^+M5y z@9si5C*ay4AD|K?Ca;^0Z;h|YK9oAqq`|4kIbujMc zSg7pnM8g($!@$ciV$8%QYTIOtqcNWE%^K<9k=yTz@RF8GykLRt-+Xd~1MX*Iz zcaeeXWx<(eSd7uXsi;Nj%5CH=mEwUO?!dFM$YzNj?l>-y_X**i;$Mg0m!%i{;e0~M zBK+7#N7(yVpXw_loYyLWaa`lQ->Onkiw35Bp#|l-xWr2?sIAJx2V)HtwW!?&2ilmE z3+uaPh>cvQH)Sp0>!uqj=Bd{&^yy$94_x*|3Dh_8 zhjz0XZaZryx3lK_B%K9{{mhl)66U9th(jN&7rGqQqJ&?UVM*NySZ3l#i%zTJC)ban zs$jwDx*AZrbBpky=1apD`*p5^8&^ z!0{Xj(|VJD(a%uWnwy6;vK3%)*#?}Sx2I5lRm?L!B;HN2Vx1-!(VJW+xpFTF&ssOa z#Y_6b+}c@ef9GiWdiAwzy;24iH57>@F`O;Z&`N#6N284_7QD_9rgq(`(CT>E8nJr= z>hS7MemCKHVP*GC(3IDo&lhK~oY4{Fb?LM)?3^+i8950rx0t=qM7;#VZfxPm~?50qW-KI zph+HGE<$BWw5Yt#ioMUI<3+Qjyy` za!up@@?&Zr2jy`3|Sz+$DuqE5eL(&|_^d z%BWb>;&%p2ImHd>H929I>TB>N$CqpY!SVSCeW(Qbn^bN|?ap?6LS+lJic zcVqx*+&CywGNQ+h&JdfJE;_DhBp+{HH$tBaSsnFRu`Qt3?ry<8KZaS#7hw47Ix z6F&NkW1qPHNmnR{;CZQ$>e#kQ0wWy4*|h^Z$-C87zFQ|7C9?bQbB`Ou9Vy}bMef1B zY%9Fnnu#S_bQHD7Kh%LXTW9jRn!){&)@*{*kY*P(iZ40aGq|G@#^1Js1>t?CmSey<=&q(SkU2k)HSjIm*t#mXU;QNwitr5v6TI3(V>VfMzVTWBMQFb zfhw<5z&NFz^fXnl)2R;fPg}I;-8nNMKOQfBTqj)RI_<2U7hrAM3D{?E zLhfyKh#nU~km>0$WM^{#54HiD##7yP~*foeFCuJ*y!&^!pCzI+AlD z$Al_wPvYYeXVarw}2&m@To70AP{(u8$CC_5hn<8jtc!m(VP?>!ZN1^E;2N?K4 zm!8eL3>$lR!ucvw*3|j|!w*LJn)Np%o|A@WL)2mRL(Za~X#vMZOTjbo58azK9Is?f z6P~xWr@2cWLfV8AVzXU1%Shfq`+s(XLzj)|&nr84+14aR^#4lv+xp?TuP21q8a-B= z%X8pb^x?)z#Hnk~LZQ1ZoG^@FZAq~tEiIOn3@xHdw<R2P@t*k*a9m3!;-k!cI)~GO$_#j^OSp3SeKBgh1$1sw zV=ICt;JndVVsV@aS+{4k$;H}XnV z z!$tE;6gwRCnXR;&dzX%=bpms}_hdVx7ampDl&AA-Qc<3$@IK5u;mo%5eTK{JI|yS> z>e2FK6@`9SZV=8?Vt0@z+RESj%EDd|Wzc_;8!YqHWq-;n@R8C?;Xz3TF6f~J!yGok zz8+>YaC;UVAa?Qr|omf3a3fm7AVQ|19MW1tp>)C$tUGNHfBiTVdd+p2Wg2AW;hR{G4qm(hV zowGduJm*o*n*+J?57TB|1??(xIPiNW^V=K2d!rBH)Gl9WY>+CJj*6ELUBrEL?-zoO{zp;& zs0JJ75Qhi*f}pZI5BIS}uxFkP%;#CRFT_SjY>gB1|FJvH=#l-34)UX1=l|ateOz{| zA6N%WWwt3{)UW1=touanPuI;A3+r~mrTMMo^IeXuPdHlOK!J2DNKlj|#7 zGG7UPKbBBIgdR@tvFDQTf0^Oow8%e0c$#<)XD3}2|7ikK6O~wL$3a-q*&b$2<(a*D zdGPkVJB&PI%Fa!!!7*c^d`r(8P|^i6yz)p5j-241q2}ADo3g(AY8KCK_BVtaD=Anm ztEc@-ywTomm~edPQ#>?a7EB%#56=u-sbtt=_&NTx`14FSOYgp&zHaRVhsGFCvYjbN zd_ReQhc?q6{;WD4IVG$alZOMmdO*8Dwh%d+&r?n3@n?WOlv^RDjL!z+avfOOJ%;6c zilefNH)ZoZzmUz478t*`hqzGkiLQ6;iQim0%QJd#zF$i$j49WJeV^2^F}zGnUlR(} zw+(2{CKcS!w^aN+As+*$RVsR+alxOcW9SbM#9gujd>3S(z7N`L-ikiwRmscfHblGZ z0$-jR_3MZ#6_##+NxLMJpJJ!jCugm4X8&oqqxv9Ixs(8J7MUn!v4pM~to_RvY&P9p zX!t{uR{3z<@#6yVp|avucQcoG7f#DIg0m&n+C`zB zdWf)biWa4mWkI{KCqT2>n7p|Ew=?(f{_`A}Jk_Kgy<3DUyoc!I zQLiT-MLqaTT{&OW_II3oWiV%qC(nTL{S9KRC)Z8gi^S6*qA+oeE|c_sh*2@&ko-Y| zE`8BP>s9?A;`3B?^Uo%VHhL;ES~wT2h6RX!m-xbqr7dL9r5BbA*a4>_8U83)t*Adq zNd~N93fI$I{Ud6u)ubN|y14z8JxueM&MdBn(mC}s!ENbZYDn?Lv3hm@_PR8ALN3^A zbpZ+26W&<#8oNA;^!>5Yh%QYxQ}`f8?g(J&Q^M%*Z9Tb7PhBcC&{FJt`gH!twTE4> z-PK`2WXe-~x@ekW=8{-T*jklzjF&~hZM#U8awUek$~@q-iva~S>OlYcMlrU!o@TZ0 zf)&w6h1;)kk)88Yc(05SbeY$?T>QFT4$lTkFYjmeDoJUcY4 z9(>mH5Xbgypr`hp`1Gc`+|o#wmNo2v1DOW!bhkQYnB5XB_-!=tq6rDFRdG%99dWtt zIVAgXev&qWHIpSwK3ol7C!UaPZ*N3@zG6FH;OD-s(z?k@Z~Qj=_DWw82# zGuZ1(na6VtDqGW6*d+vF&4R@++9n!W?m5se%f5KpvRr(yx0)s{dIfDsD)NKcIwV^? zO0kRHw^V~o9}$ToG;3rk-L=Wt;Xd@(rU5S8b8*a3LNm^%3-e;L(ckyn|2syclP86aHE zup|S{rCFVGM|{@Ay_rumpuoQeMC+^YccC8+$tsk+S?ElSLH9riYZ1GR^kf|*8Z=_l z6(PK`67^L@`227hG;cR0Mp7 zUVvG7L1rPL)6YzJl>J_OygZs6wT`9nkFN?#exzbWJu3D;`#QAHr08$Z&5CD-d3>Oh zXC7$gp(T&Ls!MqXVj*%~H<(@S#EMUqW1fSf@N6{SVZsD6ez)2KLp6?wM(L((_-IwqeD_uiv(%>To$SzN zAJ1yJT}u@ko`9^!Ug6|=HFoP_81A<;gJ}8>s9nwL5hBJwSB}2ediStD>Gj+uRe|Mp?4&T_im6tyOp}&BOF}`H(r)97bH{9_`OzG~e^17^eS`KD#`J9qzI6 zIo$7SabpyOPO25Ja*f=NUE9#8D+or-XL00<=@3z14HIYSuwl97Sh$%hISQ>d)-82CVqk156qFM;s8wnZBKL6`m}uF(cHqc8 zdedd;P*CX(L%*7^p!DaczA@6*r-vbheKo@V#_F(lQUJSVwwX3X>dC(~@cq~)erM*h z3=f2+Cx))*@L{MRIiHOu6Wze1Lm)J~;{J#isd(Z`Bupx?VBZc~QL5WD@o=CaP1jRb z=mrCF>S_37SL`+UsBrzF4jXVU1J7^Qg}G6PJ&ew9PmB)qtC6x!mo4e1#w=Mx*jG|s zT?N;}dWtS*YH8(KCp?+uDmSXorS4~=75itm7B%#qcwHv%%utZhK29&Lv&gI|gwe}=Et-GiPF4#LOBW+dOIirXKB zi_M2MC~UbE4zQEK)&J_~ruidy{J2bj`GlE{+OXxZ8O+bpWVz|#xbQ?mVRNK5Jxjg| z{}{#UxmIl2LkU$rmJ3=7=Ho#3g^Kwr_Lv!Yrgy^XUMTh)@Qyqt+=sQ5%JMP!+7!++ zT_>*S4ju`Hti!}u>^`ma-nXIJ3xO2 zlBo8=wn6K}(mxv1ujHpVu6hE<;#9dmv=7g-kcj2!#w792hoCja5a8F9o$IDX2N(GX z?Yu1Lv$_?gM%@xK(|OG~_gnm@;hB8kC%=<-#Zf)a%Y;+yX|-A@?7i|$T%_m4-ju45 z*n`)HL4`%_gjpP~xcta#g;9oj!mw(Ruw*=IrRHoU=Aa7$>}upTdQOBFy=C3M^e( zsdRG3h59^2l$vSdrZ(X{`Yx#k6FR+_q$W-FaV(?ErVZ?7WGT2=Q(QUuP zL4}s=(OzqsFzS+U#yJ~*+%ADGzg(fo_Y;||d=7o3GU4DHN9w=-2&}Kl6#c?Y*l3>j zVPX76^dt#g18W?5-v&Y#@OgPuCEOmJC`__cV`{y&V2?CYm}FPXbGY`vn;b*9Hi+|Y z`F=2HoRKX4kshTNwCA}Rf5d*~)s$jh0j1yVGI?fc# zw`kI&=V=h#Ed{psw`2?VYLNGj7GbXJ98L>74_Aju;ZV|7(u%EuPx`y$HQ0OLm599kInxelCRPH`(c+PVGPli<`m1 zwKvg@#m{9saV`p$e&UoAUkE+TZ_TmuG0gpgaNCNZzso{Uoo58fQ3gz-@gB|?@JGB+ zrA^<~Yb)4aCTnN2y8}1V+>i{x^67aTH7i-1{g?aWj{ch8U zIo&KSg9h=Wx*E&s=#5*0^91P$ZKe@*3fIoofsgs#toDr>y>0C+KQf$Q-Ssq>Z>k5$ z8!TA0t_9uAoh9q@MTJ?PcmqRy28$a;){vQ+EzUmSB7fgUhvs(Q22FYT&}1XQ1xK$b zyj1)6exsD{ArmPwLj&5SnKW1IK)$o4fAAf4}y~E;X4^-Kd?gvGKiVTcJS4&5r%NeozCu_*h?qH9lQ#QXVfairRPdf>s2SJ3_Ar${{>5-XsXD}JNa52( zO}6vF7F0W$P?-FmHsyufgn#+tT9d3;xSu-p9v~N5KF!0zq4OX$CkoP{%&2g<8*0>n z_+`&qD)~|juuxfk#a)|B5BtK~yl#*jXvkg}MPpr6vn+0~K9yLN!@peemswV9#%^`` z>z*y#E6Bz#eX|w2<%PPIJWJXGTc#`#O`ZAu^h2F^#$qD$w`!*0&s=f%!{3E5+f2z} zULH*9&F9{vu1xw?nF7xE2|)ub=+OfyE?Id?T*TRW&9M#Q&8a?oPseZ8Q=IVqksR4d zeG_Uskqd1yo)_lapRH-rBV(&O!hcZ@FmKK!#hm5GOj*B4rsR~i1|ClROv{zZp{~bH zuBHD%Z5N$zVe?C&s?30m6?sPT$FhPUao#NTx*EM&ut2Wks6`DAKf=GfhU9lrHl8zl zS3e&s+~}8vqn>bILqcD>*1@+^f5mMQE0(d}l4>_y5`@kidxs1Taoc?&y+ zWns{oTG909Ca`RFr6%jcka;RkoWV0Vj!4_EbM0$!-hR$$8EuIrQSE@~RFjHtAxP&Y z2z`rG*(B>#nA^z|rd%k-8&x|MGuLXll$9AM(?J^}nT=eBoa?f=*9UJ#?Wrv7y7z50Kex22+KZm{sYfWzp^IKU;_)6n~Dh9gOSgXbnP-m>u#5_qqNvu@`ulz2?tG z9&W1V9uD6B6jW-nxz9?_?A}(`9w?!K3)B@mA2XRhv%bHUMqYR>^SL<-JAL&QJ=*ty z$0rOadx{JO`5zZk&U_`KJN~$)(|aMNJFig%a}_m;%{E{k6Yt>2$G^n_f9~4 z6oo%sd!h-elU3kUitz1qSC?Ll)mCVP*nhfod;D9`^_CQD&VS%Lb}MuqI#gJ)E*s<5 z@!2kQ9%ypzvHskn81y&_;)htU2?xw5zH_l?zEqbcOn57{_W2-=8|ch(?@q&4*{_6s z!7bMq(4e?s8x%-O9@HPpIHip}d> z@kD*=Nc?y%v1PWn&!Czr{m)b@8ldDL1&jm!3^UX(d5ZG7PiTl;`jBEXJ{F5 zyu+L8zZW^7|Fc5TagZQoWHVy;E1bPS47 z6B;BAJj$8tEq^`~m-ptGq(xQYzkPK{k1urYk}aORnj?!|u17)7QeoQV3NfO`0CwP; z4vn|GD_qNSp{lDLaOwN)V)wJ3NLz)0a5ok*gTK-%?it)lRl?Dm25edKY3z5Stl&nX z4?FZug{%`6%4armpWNBkuym*$T$y0b#$}n1UgT)uWl0+Tx3mDt>`sH9QVZ2?zX3mL z-5|*92VF~SkCBHAIogDi?T-s#l`tU0VgS?dLFkYqnx9 zH1qE)rui#`R&#Ck%R?Wimv%l(>$^jKtgj7CRUZr&mi-cghAXih=7Csy=e%&3v&%Zv zjsW*<)?oG7jC8~b`0BM&Tz!t~X)9IuEn5!zt>&%hM-^lmeWE7*{3-?DAq1Dxyiu~exh5GCrm10|bn>Z$v_h#+YF=&+o zj8~n-j_IzYyV~iTXL1=I^@|mU%iJKw&w$$Ab%$ynFY(de2GVgFk7@x1@~8{iq*r@H zvAZ^ZW6Uh~-o=`M5x#Tkbt!6S=MgDcV~P6Uv5W|@f=e3g6p{B;xi$kg74Wl=cVpav3M<1hsL$u7u%nBFU}O4 z*{s^JSaIN$uzmMA+&#)pkr{DkwJ|-umIfm&OvGiJm1K1HI(8mxB%kq1os5gCz;{@G z_;0EOyB%&q^KECznnFI&Pw9Cmvh)#S)>qTUBgW1P=>OcCFNsK=Mrd{YYy*JB&@gB zZCGn?LS~of%w~@phbf!i$y+|zlY2=VY`fJW?sM6|UOhD+%aGpkU1f&!E&UcG{7#0% z*<9m&s{x%c59mc>9Pp50a}v%z5-&x^mFzM-I< z86bXFl27AY{lETQ75Q0RI&#f<=RmYL^IVo;#JNpD*FkL3gcJ99CfzC}vTV*2?xkg; zz3mxr&vS?8bq+LjmlrDSS|^U-de_~uJEC^YL|D}Hm11UDqUWmC!e%!;RCJxf18`j)I_P0Acov6uF9Np39 z;B{H5i3#1^a2mq&pNqXF^RK;e9WOiV6^?#ar%hL?_)abcZ0DJ8g!8y2WTu`b;{rG|*;-sMbFCh`)_fhWz3eWxTBAIxd8e^3{D8=RJBC?6EeeGom@DSTuq zy*1fey~D`evqDEVo_%J*IUA>y!I<-BqUwz4`;zm*f#_@;vjG(~F!*&fnLf&bXFGj_ zsZTR8NcL3xrq7?o_nq{0OtE)mG|cpArXK6Y_^Q7nlN|<=bZw>P%k6-g9Hgh zZg>fO)(nKeZr1E^n+eJ7=En=R9eir;7K4acA}3e zniv$hN4&~+OD`sxpjn&@9xbk=BYG*Y< z%Ol;iX?V6X?2hgRqpm44m5%|q>F^7g*94wn^cA3Q7YU3XZpEg1aTczBmT*)z2kYxj z{r|4_%#l6{UU+xxMzOaG-@y+l6o3Dj08?e(=)+}WY?s|yxOP}8{cV|qf&U5eeVp55 z@GV*4slPEtkF6}_ed%?0<(D3c?Ivl{;X)E;<@eyvOe19`8ldU8EZL#& z##G{V5=yT<6Kl98?Z!!l%YG#avjug6(@#MuEShtGjhUkj_uXl%g0d?eX_xgU(JZo5 ztU0dAj^44wg%w|gD$a8J9I+qg+%GB!+O5YjHH+}W+wOARDhYk#>}8L{_E1-0&gR`S zpz0T+g&BPIy!quk93GMe3x1fA(o_;oBM-Fh~c>^(6ApIl6S*Wd(fR>jnKe zm#oY2{TSO#U0743Lx$6;!A3(3s?JE+0-hsZ)$P16l<5D z*&`^`oWr-@?}?>{93Z?&nbq)G@cpL|co<#7tfC0T9GbvAM2VJ7=;mc8``&Cooh+?U zr$h+`4}L?+-xEQls-6799$kvaa0II|6S$wxb;9ijqf_fNVg5HRkW^j)Ujw$n?ieR} zzVQ|8p42D~?|Ba6-k*lNGko@(8_6QGchSo_9Y{2+qmpX}V8-C>@?ob;D3J3GcWr7A zALRWe7xxKRedL@lyD=X<{`e`fO233?F{eIP@YcvM*zhBq{nm{q%|U9yrx#;TB|$@M zxa9#21)N1N(Ft069TQn$Bi$J@2xq#z6ZYE{AzLs(v3pMLfE^MJ%`&!6pXB zQ`aLmg@DI8bh~@L_{woJ*bHx@c2-8Xv(g6YKl44(LjkK)bmT*N^Zcw``=N5S2R!et z$AZ_3__1NLujN`j(z~mMhHc8wH=KJDLi0rFX*1X{sfq4K>SEKZv4RC>@l|qv&%ZjR zG24OeX5~Pp-f=N4T91X+i+H&FneeN97uJ{acJCR!7A*$ok+m*RVLXTzN78P|Y^tJ~58uA2cyAFWM_2z6-wjR}``peR~exjc3 z4#C(5-l9C@E%m8T!R3KY^2_|$TkN$!(X+KhOIY}h1YB1TA^feD;PSB-6|A%31-j%o z;SEd=W8%p}7ECgL_qEx|@=Tw6oIIJh_sb0YwIpn-N;X7kpODSJ{hQAJFv7srEO|e3 zQ)*UUqwuhdJ;NE%*$L<<+z>(*>ycft2&&eH;M!dWvgdrNgCFC><-2)~`U)dOO>;?p zN9{%=z^J*mgju%NG2-o8al=qcfM4o-KNEnfR_-cv?s^orNs3u9`QnoGZ|GV5Zn%-JB;USBlN>+TaF23V*i)mz5<{lq z?BFU{I{zMWsxH9jU{#2kW69!VKk#|aOyS_FY}|kC1lV}HgU|JKOsg$|j@u(l;hf=( zEL%LAHxZtCf1}b@I`|^7wQ#o52YNHBKRVTV$@`1iv`cG0{OzU<6`YZq8YiO9LmMHs z-h?K<(8k}bT(`+<%M-I4F+Qj}_ZBsfxLOmJU(A$!j5Vcm7mh=$&P&mEm>wIkU&M|z zi9+iS?zf)!5Nz$DdGBt_&N*w*qyJXGn-Lwz{ZfUP^9994FY5XISAs(}KM^kQUN^UM z0=AhK6{zRvF_|5pS7Ud%xvLg^G2ADxD%=co1G$<*|eQ>eWIE$`1nv%4QwoYj4qIN!-VFwYY*S^Pl~Qy&HRqwhj+Ty z3$ejP*t&VNB0p%y9ewud>Q$W5yG`^PgZSvlS@`YuS{!sKnw{Vtf!bepg`SHf~6H2#_XDFNDoJwRieF;kh#kv5UxzUB#f zw6Q@&QQyplgtPlvv81ueMP6B@L-n&##edqW&D%<;=-V@RUfM~ZE7|xzlFmD>#`lfm z?bF`76r!X>C8W;tM79vJw@5}t8R3hTq{vnjBH0Z|sP5~&9w`z+%5Eo$3Y7-^Zs+&E zmlvnbbzkH2d4IyUs7iKg)7$#t`sV8}GB%0$9WxYUjG4xz@d2rEVRdrNMFOkp$r;Bl zDEq7z?EMnC%r6SU)RD1NXPOAkE>IV|EOTkGnl?Y1&GJV6ufeZrG^AGP3!nF^;QY0V z#A{@}qs8qQ_|)J`95icjux%HJiU#set<^Cw))#)R*Mh+;yY11WSh~nOg1bUQv|x3n zgk|(+r8b^x{S5WjibyTfs8rc8y5O_DgCS_*%@ zx=^RXwS3PreZ0D5Gi1E@LJBQK!oVG|^xUdP+!*FhpDKSJk|xGOAbTT*W>-+}iNUbK zgzfpm)$z|qYhJg%2+yf&(1Zea=>1)T_7C?#Vi9AiA1#ZQvqjDhM$hRHw~@dvnN-Rt=afsdc&4YMAV-&zK`w1o-Cnv;%6_HS`9vVxD7 zCJlOF#4kV2>R9n&upK-E{&8~r)MM#4Q#sE0f+F?{eglm)QZQwgfl$l5ZR;~{a|Z^b z(KP>ilDp){^DSt~9|B`(j=Pj|gKpiCC#hqjOSSQZ#yXfJb%qp7))MwQ)>E%LABmTq z5}KK7(FYU_Y&un{ zoBU#o!G0~Nu&le1cnt^>iYxYG;DQ3qR*UU4t{fqA9Ja&l={>k0;DyYr>fq&d={SD!Q^2h_I@}Cv&&-nZ~ z3y%@S3|(ljD#S69ojBCkptiOr}6 zT#(%g&+jB~GA#dP)-YwzINb+ktyK{2RvnF08@Y6@lP5vWTxCfi*CGtO&!O9hTfQeRj6sW3Mhqyxfs@eBc*!eB(?r`a1GQSEyp9>JeC+tpXt% zErpZL<<#o<2rh5G7WxFr(bId7Y$_LF&zd8o&f6Ju+SndI=mh8ZRI$=J4Q#bP4yPT; zh|@p?cIzyGfdiu8k%pGwAuosSOy6^LHuDSIOC+cg(XpjfC-Oj8`c)lM`2@(8GgM!GBW<#BJ!rQ=t)XR(CMCy49dv zcoY13A;&-SV?NxHd2nu>Bcw2$t@Y&tG$TZo`>w8z*MEF~f0>M<3k?Lz{>q4-Z*#ZR z)9AUZJFuM$f(HG1{BvR@ygTi}`5nATw@*)%+%fl^=)x0)j3_%K9OfL?6b=sjM7tM% zAo|^kXrHV`tBw1BZ&y3Usc(VcqO)Adfx)=7aW5QM#F2I59#S;hDXCXBUAlr@dM!Qe zqb~lez?gN_`t+!$420&?pjrA-xcJJ9H#btnz28(M`>~GXCLDdpk;W9vCoK2e4(kJZHLYJOz8m%dQ*`!1f_9Nxa-1W&TKYgf!+=!swvxH$@w0fRrniz zd}IE>iw#&_YsdE0Dm)xu-YAzC7;wN2@Q0T0I`S?xR}OdYPGot4id|6L(Mz7ShYR6P z_G6*+ApS06cHJusC;xaUGH2`Yk#P;U?;6XE(~@DiX`ys}QV7^=)f1XZ<a$?1K|D10JpN8|BFjV3ax5!_x<_sI6<0^T&s-5 zEZ69t2E*%m59)q$W4Te~;yYh-SQbzY>wPrfQiY?ik9m(zZFs~r^rX^B=?SoO7Sr#s z{)E#tMQ33(xNT8Dh0lA*x1yP_-L@6=_I`su(|+gKTYo{(M0+|(*O4E=SZaeO$HIUQ zYS6xx)vGlx>BFEAT=i{Td}}3755_(u9~LR%)|^nu&Ofxc71R2Bhw=4k;zI{jFn44O zdoxSOsD%pXulE!ldPafeQ%&LO6~_Cz9{}f$e@D%GzA#fM25fV_;4_ctKPA+K*FU2{*C3t!2!wNse?YqT7wY&HX2OF}^a?hET(k0fFx)x}_D%k>>?z>fz%SO)X z3f*ND)UsYpJf1Ny-YV$QiWq68_pL!ypYf1YYsOoiRY8+;vJ$WHUGGLb{cSMav}-PR zytji+YYc?#IY;5!E-O4|Qvv~JTFB4y_o#ziGR%oJVOe)Z!l(YGcze(}GGtd3hDmvX z=xzjWHcAUmg(yPUiZ5i6UK1X(w4q0uQn=}PnUsqhBH{llF>XVB+!Z>nem4XxMLLvm z7yr$Pgz;e#^Nmse{Ymlngdcdry9#oQS&f>~f$cRzX{tgKSNcAmJ{!qHcD*(%U|MmX zY{q1->>#PNl)Belg-L6xNcfI@!s7Y+QA_y=x0rGJ?$-Mfm(5#2&87#}5B&N{*wO6ZEGzKvnz!O@ng80eW`S#UN`x-2P>SQhf5zGfe+co$!kte*byX) z=Ny4d?oh*vTQ-uj$C`+3ZarR`SO%jmp5fkol@m0ILa19md3Zfh5%1^~!#^I2?s`KZ zpI5+uK}*C>zBFQ2(RiR9PGm&SAKXyY2=_xr@S|%OAAp|-``VaK`K5wzEhUUjeG<+& zWv`_X$y%^+<0tsAK?@5Xy#?>@kI2+vMuK^(0%{gX^G!Rl=q{PN@N}X+#7t2TY=T$7 zHk}LN4a4MwJ4f1Ju3;A6l4F8%RhL5F;jLsrqk<4Z!YE%<$YFL1B{|1I?_(%ruTT}< zk9N-6f*JD7} zv=bs8RgGUyaX><(cu!R&d~oP5Sy(j`>>HXf=%_87y{A~LZ_08gin5@7mO9+7aunWv zmq*p(f0}^wZ;^e9`)UKJ*wUO;m@O&YHqBr(1LfG3Pd3V4U+WGPHWyLsGC+2_s&wCV?AV zpvFohXsL8VR(!sA85w}(AJ0R@^ET4#r76fc{iVb2t%ty)jIW|H2_ocT;G^3YOiy?N z&#KBe@iIl>luZN;-I$-_vW+nt=RSuO<^w_1!&qqjAi|@pgSfo^G7b84Ricw0TG5Ff zi8CQ?&R{UQRgGRzFClre9A7_{8^Q}#c&gN2TZ_)wY>0m#@3h-w=`kopCbj)xrxOD*u!(q$U#kM!ppHL*UMQ+{sIpkoKJUC{d) z6#wQWb*%H83ToYumejFlC5@<>WX)K_bGaiXsWd@mFv|{@3aj)jP&Vo@^zvWHkvYSJ zO$Cf)@Kc*tOT9zq)Sm|j4VF9EY9NR;jM3&qBH8nz8m$d@C<@ufA7I%81DJm?_*NZJ zscb}<8`jh{KZP5)G?VVPa**&_#!L|j_l91kwDCW+0v4TVMfJBYVSo5OIRCB#U8md7i94IP-j;moaNku@-~3o^g6YXC zbdq^HF&LwSR)yc--;MGbZz3EvHNgtUHQb;}j3L@SmOKsL!gwFuXmRE}O!Q#0?)4w2 zpJPSaO11dut5tBhT{wh|Wc=r0ngXwvO6zBYy3c>Dg!}TpgXgp!GN(68xKtU2@&8%! z{<~CAR@aLRV*DaK7!Gao?Pb9n{-}lGl?u)4#lSi;7;`fw&J=-vJ`a%-4Rl# zxhIdz9;S@_ohFmrlk3TrwO`TqSTP(lILj5UkrNgg?WA{)%E6kYEW={_BT0Qb%ic#B zJ6Zhi&?2!(BJ%_}+rd6rClZn_`MOk z5y<0h4Qqa`E8|QWGk%%^4=-{);r3h$SgcyWz3WmypHq$GZt`>xp0?rUI%_(6LU`Ur zC&uM|odPWb27z0eldz&i7Sn52DcyHdL{91G}H={v`_WWc` zRlHmr4xEb$Y%|dm7PjA{)(6cwUv3~a^wpqMj_=8;9=5Npm_+{h5I0Ew!k;arP#TaS z&bY|5#FYnOgM9^2?a~lxR(DdAS`W5+zT=M>4$!Ba`Lcq)pf`O2E$Zc*%63JepKk~q zu`564m$@pAeDoAXGB%DSySFMN%cEKHOfDeyGTpxVGSsD}z@Zp+r^|W>sep^G7=(s)!QZ`fn(^O3E(Z*dRV?n?9G8z>a}%+*eBQ4X~Bew3jL^C|kamo?D~K zFM9KkT2!rpL+V;EKT1caOnXh=q^gQlPN-tTUu7CQsEhP}QiJ0c=}KnF3&qSwIl6&- zf2s`?(1<>reP}z(e-L^F2!9E((NfR|)NY$knkC?2FZeMsqRD0olN z#~1q($&8g%Xc(;pCCL%|GDCIj7}rSJM%NNU#%m4eXHQdQ?sE4kZ&4aEP%=wSDG&*p zpPr{Lj_!uZoC3D2se@OEVi?|PC@lG-kD5NG#Cx}S(qXMZk~(HPz6JY^%7+&;0&Gq; zzgzXYCh6IpGyS$2e1X|&-Q?t7BVqSZ16-mdaC`czqQV_}^3ON)d2}rn zt+@}A=8xf)%cRi&y$146E888$yx8m3QMWgHK=z}KaP4I`E$yF2oU@Jz>y{ru_bX5N znbw-O(;dej{{|NBV#rzzvtpo?IUbP`~viqKi|h~C<; z1#IJ#uup(UqWM3&`xDyVQU=GD54l}-3OL^SJ=wEp8pP~tL%(9?e>4owtE^SR$bA<; zCd~@|#5)UB(lRI;xP%LQwU%BlnIOq82=_Kdvswcx<&jVR+xrRUW-7y`+#asVUK#t| zu9DO@hxEUgSuu#t=y)T($QY6{-m}}vH&s}WpGxgs9+&LxtEsL~>#vP1=T^XS#>#&8 zco3QG=mQ%TwBU`&`4BL(BTqo~J(4q^@kMt02pbjrBeNGQJeA?0i>9!)^D6Co(wuYY z(Zhlbz3};I0qJ}t!r(d9#LdkaRBC@>Ak*v_cxQ+`1WVz+0gI@`2o;Z_i3a#;P&90g zsUjy11Pia3A7F%rEbl*3L(psbNjIKc3nS8x3E_*5;7-LW{OD+1{55nW8R(Nrj7ELI zhrtBgpOkTzwul5>r(pW#r;y{y_#y5yAA?u4CG0tGBs_Q_gXfOS;F3>Vrmub^gVo^_ z_{(^n!;|~KwZ*oeOsnyY{XM8$FUN;5Hdj-et3-EkCreWhOd{y-!)n}~U^W*&eI)Tb znmZW@NkKCBL+K88a8oMnlX)HL4_QIqoytPxenTj|zkpK-xIxpR_er$1CrdkURk1lW zIUWjoGg>jSVjgwR{LbZm)DX4@6w~(XcchJJlIJEerp--L=zFgMk9_+{VvAxq_wf7l zi|i3{(8~&hvR<5YdH|JLqyZ+nE!d+om!4Xx%R9_0pjV4lO6JoGK{~=4?-%rFxT-j5 zvl_Oe63yJ%O^Q#{;PtpRQgYplcNwdS-ac>1zufSf^S)yGW_|i@)f{fev^2UkirpDl z4czcV6`y=(I{DVeWKBjUeW-d$QUe>jnYMG3E>4V3BvUFX@sCvtv78yfk9%c|hvgWz z``T|Z!s9DutLxL;otL-`0U6Y4sJX4Lc;K2ye|*~wMS~P@@%$=DFK6OyENE%! zV|i?xShdrGj@&gaPit~N$iCi!&vmk)=0^mir#0i|A%=AQp;}Jm!$W#?)eyM9O$Su} zDhb86&(h1SKZwtnVZyRLQYiIxJ)dsCd|IX-p1(&ah4HpfHC0pa`F)9g9Utmm$2b!6 zPJV{dRXs$?hOy-%ba32h;FjpBV%%&EiT?JsPAyK~a}y?8kKs-}OQp>{AIU%ctzP^9 zw1cA{TX2ySRt5`^85;O}st12^HSn z!tQs{{J8mUc8LDAx*!);hsd>;lHT;aQ)vAjZ-R|&lzh>VAn zFeBZUYNh9K+oe^|y5bysuRjSLFZIx3#VcsY2_s!hlYgU$aVk>WV91z{SiQQMB;Cp9 zc14MBuk$ma7vK#lXMf^`G-G;O6qXlwT?MaRI1jhc8rk3Lbs!?I7pLc}Ie-wlVOP<1RK3}}(j-{|VYbG@tpyCnEm{K7p zgJE5K3At>jC`9i|pna&TU0d!9^W4VzW1br-}_e5bJ#65%~Hpkb05P$*75Q|#zMWk zG?po6b7QkpY1gu=;Bk|^Sq>^f{W^8H`eq@gIO8TYe-lQ^*Zc=c(>u^mu@9AD?8l)R z9r$X@Lb{~mC-=pM<*3>f(mBV<$bNHWHuK8Ur6qmf^PCF&8&yj-MaOapX}NUS{#X*_ zZVe|6^kRxff6BAnDGcet&FV|&%QMFOwlhrsv(^{t!nI)aR5jtm;zBCApdh|+vU9c>?|)GR-)$--|9nylUN@pG(UbIqvnt=w4Hjd-Z&nE0meoNk zy{oXk>?H}?swNCRRmig1Yq?>rnRJ%)Ntjlu2R~=Aw^HDh$Rw&2JqS0OPq0`{EyihY-> z(}rsm+@&K0RB@dR9Bt77*B+5zvoDU`oYYKqF#T9d;sd(fYb1YFQxRQ?D_~xf85jrY z3sDy}&~Djs4pe0E<@pzRQ@#X1SWGvLAII2PeN17(i+cR3txCt9Qs(cn+Ol^-Ae2AChpOIxnow5WaQR;{i=^oslYxGzo_B}b1fewsJMmu2xBYshmR@q<{L z_<}zZlEGU~C5HMN^Uu5OM;rnCZX|KMpW#Mmn!+)Vz7}bP!KXOTA zAe(=UYfxA9Jk0+%fY)JjM|tUB3D+Xk_#67BPoYhN{5gZeB3h*yC%K>QUZsvjEJLBi zJ)c;&$qFzEGaNFacu~A9TIZtTTip`MtRsp;6r0CV*ZeVrg zBkrG=L8{drat$EDLq0&_?|HLq#~+ybN1I-856zo8 zVZ3M3?r%`?sUvolYw;{U#EIZ;7MRE*#>_sw}Yap#se~v5$Bz z8;D`!sw{mAA0!K z3~utL%d~jRc}d?mr|=J6?ytzB668@x~oE za(PB{)FI|dGgeqlqT{7?`PPR8^kdI_No`CDR1?--p_1D8 z=R4C;D=ScF>Lyl0Yj9O^EP21oj5jq_!9~mOl7Bpn`xCoyg0l`ydb5gisC!3keMZ0{ zj}UmL-ybvQ+=AC04df8xVX}1;<8ak-IXbtgRllPWp2pig#=?>SEo>Qbj-)^Qgi;F+ zkjYx%{O+~tIH4zpv|q0!Bm5fhUWtfq&`;*{T{5XJ)BpaY{Sj0e$zolnld>Vyck ztFjbc74dXujv3#aUqGjK4}?5LT__F^2}P>M=`82(0Bn3u#O@gqFU zG>1awPjS1ihWcsCx%>U(aOjMvd3{c_d<|+7Q4A$ji>`pmX$M=G53mpsH46uaL*@bV1(VJygBK{Fl9q6 zdO9D6Nvp?jlj~Ed;+CTS_mF`sCvMk%=ofl{O!*)Zc84FQs!}hxj>9k#&#ms37Buwc(cZE$PzA*jHPufRe zp?Kl8Cfqe;KhZnqM2h9B@zTYkFj{>8pUr$sflTiie?k-d8`+*#dMv%&;KyaX7tyz2 z$0c{$KN*(jce)B%Pt=h*b)aKUW`br+ALt0K$BS>m$t6*=Sd;beXZD_fYqH6_4AsRh z2V05%H2GvNUR&=&4}Z+%c6+K|t9u-jGW~1KFC}4B)_uBR>SpNARw=XlW7pBj2xhK*|;P4qRQ{^WvzOG8OFNfwC(4<@#Yhc1i3 zaG2FGTOXj}ID0Pg^FrEhiz5s=9Ri|PrpS76x~ipsymqTb8^2JpZMziD47+HsJDqIv z9Ri|#-!Vo_nLZai5x>~4jmI3$!^|~mAk0z|4vqtw^e~b8P?t($CLM&ZU>lGFrYUMx zLa9GX-~-Fi?)N@1Z_DX9P`;*_v7yeuIrsLwZ5!&??MaU6e7ENf-PBO8axKgsqzYP%tqg&eXFd~$z03n>ew?m1W3`d(0al)9gcR=$#G%bdcy>n< z^X}R6ZDoUS;zc3P%e;W>N~uNdxyNBg@Jr4_f$4T$FQLxYXim-obqu;j;ia233}gGH zEe&1N({~p4j=Msi4LmEkmBb$HL4y-V$k=|i(DtSV@4q|-3DWYs*$O2@MRQo>Y7Z%Q zI&k>AskBDzhxod=I@-*m;I>>Iddp0OX1_o5e%n3ngLE2g-IFZoC#Pi8qJhg;vd@1Q zw`Wlseq1quR;c~pHnEzp|8cIQHl|o2jlP`;1x_ExXTAz=xww-eJj~si#=In5$zU&#EF~=ehieR zUBB9ie|QZ}RCFcuv>Csi`GEVryGpbxv;jK0u=TeJJ-vGsH~js3TG;Fe7YagP`(>6v zGx{uO1-~K{%p3BYWxUlV)pF9uS?0@^Sc%7>5Yz=kK*$Efl31!e=Nr*x{;Bl`a_B6Jk$g{*B1*A*lhK`KV7=W$ zNPNRGDx&>4AEp_w$#TzI-x34~E?pQt`#4M%o4^N$CfukkLnjc%8e)F-q5mzD>=?5R zMZ(PTSi1XIpu77?rfCWO2ytAGKNbu%OlvB*h=d=7KtOj ze8YZiR>UCNnP_)aBR>H zUUb~bTy6r}$s5i;E~$rZ=1M|Xau&78+z8L#1AQKr!FpGD=uxahYil#oY*om)nJ~`G zvLs18TwwJ8KmI6#q6gl2whNmuB~whJZ;AOF<~#GbcU;0UD){Cm^cmYlR}Aszo{sXS z$$thy+UzaR@0kXcs>#!B{xd#rz0@2yKkGZ{Pd*4; z`fYg&Y8WTbxCg}B?fLizZ07FqliYvjbt?!OcVp>a9X;;De#SSx(Fji7`Q)^Ukr2e# z+E0oV_#NzSJ1t~P-al`bQZ36hYdHt9^7-Pu9hQQ@=i#(Otm4t1v2@OD@q;FoKilz9 zf$^easr!n9-2G%V!85Ot7JD-;{9~r6o1~8IEA07Y7tGP$cUj((={aPl1$&G6NI2d3 zf_uG0K?r<3m+mmaoUP~7u>5oml#Uq$QJ+nO@yt#+Au9X<`)cV2>VJSDc{xj_0)*a{C{_uv6{ z720%24U*&P(MrvgM$A#?r5g(Afj6_jZL~JDXE4ruFQvZ@D~nrFSY~B^8Je@ali0F* zZmW4;as{(kU&o4y+?(9CZw-tD4(7&5T|ay$ql!t%REhqf4|#?Wky_$rgdz`K6^aVVO}hQ;JqC9vF~qFEt_F1Pl~7Sa;KH^ zUgtbN&<7e>?_qxQJQ?xdC8D$4QdqImo+chQfs4XyO)_8PqNUkyId{0>{k zEAs2Nu|4^*c@qErvr7uXz5CJB?doRtW6blieqI@jjq4&2CkzEtQNd9mz|C8!j%Q|_ z&mDiy2p-L?$9b2w1OL~PJ7JPW=SF3d3p;&TJ-5d6&tV`XdxaFdXMg99Xlg&Egp)p{ zC5-x0&2GW>$Q{r_)r2d#7q@hh?Pb~YSsEoUv_CApAuT+eGKoq>NyGW)N~rhr7Wmqa zgAJiZ!qC~xG&XUGIK|>Sc53d+yHxE=0vf7Oqd5qSt_IOesEKuWiDf5ZPk{X^; zUB@)|_C_A;Z+*gOvLo+c`$MkpC&rn%dX(h9^oFiettd0{54?LGlIO><*?+Eer^iW4xWaB+|16C)e)D z`=Kh$FO^Zk+}dNLGKuA_A8o}zr#}!M`Bc2gTLpI>I}Bd46ks#EdC~RzCAycquUdlt zZ#m?bEQYWw1#G%;D!0{O7DWGS!u17v;BfNKyn6+V+dQHZyqt&eLl3BFL~m8W>fvNC@sZ0$)S& z#qyn&LX?byr1u-jICzFuOThg@DLFSuK`>kxO||dEaFerH_F(r{Xjj@s;-~b(`H5M% zUY>a*>~9su{s;uauIHR?*&kdlHI7=$ypyAGN&^p0xex0@2g9g!m+3mDrEI%<2|hBe zb7;u9Tp2wNqQ0^QPj1-)3$x^S!_~}htEDBWZ{?=FIK6iq?J(^WTSn?4LuSDZHx~`rN zMINhdg*nXQzh{&bZ5pc%eM7(Fui3-s!2vq_xVen~`633&CQO2UzqN&xxjFReB^B|! z0#*Eb;|~On>m+S{)tEGTv|G}vKD?JB(@LL+BC@@jaNkQoh%jSw>xr#g^|>_KJ6>LL zL%GnXg7qT~!O!83$o?0ZblS)Rl0D&>^ZG*mX%T)Jeuf0F9`#wxez!l75&Y{l28^wA zf|!YZlE04|ur%fi6o`|#sVg&STa8FE3%h?|ywIv}>V`q!a6}O^@da!$^Z;X)eY3b( zgk?{Ti`AL8CbunSwBAX(U~CdXu}fNDbE&l|#oyDR9$RJkwS_S}AIEOcFBh}8K~HXDaw_%mxJib-S^@HRx-emn8=WK@4AM;Z z`|4yQox9*U7k@!hNS^kQt{iojOsLmKrDNmWxTW1BM6(*}$b4vK*}fSbHh5Op3v=Xb zNEZ8S&IjL++)dtC=nLIBb#!{{eDOk^@94LokGoTuGtug(#=nURKrVFvzb#uCS0pm+ zkT z=Fj?y$Lxnt&1N_LFUz|b?a$b)se?eOgw=$USJd>H7l#|B(0Qxby=&zLSnX_pbw@;W z?*bsP)z#RpsP8`JwG`jp#&V1Hg_AomL*d{ycCUDq-sg^Kkt_)@@Sp@bhQ#gEc6(+ppWi=>a;bh%$&l?Cm?rBt*i8&-H42@}>T;e^Kud@}Qm26zp3 zyInCHM*e1ug7{F$oE!PqQuuLgAoDh=cwBEc#lE6-khJ#;$z}Zf!01S-ekF!$`gc>1 zc|%Rz{lJ}lCRSa;-HJwDBqaeADC;yAp2R)nUQhpnzk!kxSP*fce3JKHCjzv03*e6yzdX@rzuy0aJ?Z=_NNV9e~zHD z`nHI}*^M+>Cl@|cDZ}C|PQvghj5#&0luLoM?>{?fky!=b|nU7q!QAcjj zwvEP;dvUw*FU%bK1+v!fg+Q$)tQl-a_oOs%ansa=u&)`k<8(QR-hp&*(sc;dU~HDh z6?m}wwfn2*vD|c)>;7%-X435%1W(8Q!N3`^nr>T| z1nXF?cY$0s-Dj^NE@E1a4Qqab&(98$BdWzj*IM_2HZwlpiW*K|v4gxx&;`q&I{ec8 z7J}ktaP#fbXuY%)+=!nFE{v}eVsQw@<5S`|-Onwb`P3YqHsd>2FGyb)0poXD3P;OK z=+FIT{JT75lwo=ay=7COc8|Ppq&<{IF8@lXp)%5G&*5J#ZM&PXa6+Vr53T&TWX93* zzB_{1s*@1(-1_N2}3 z>sSV;&cs(>V!K8-g$8h?x1LJD@`_)$V8ljhbib1`Wjy3lZP&roZageb*As+0m2|c+PaHhF z2g_F&i-V7I#6r6k*)bM|ZX3u?jZ?+CI9XUePXn&0G@;rnmW6%Sk9$(2NP~v%lX(2I zH&~*l|1-FpT}#FlQrchsnq;%-mQz@a88#E-F|@Mv&>Y{VM`Rd-C4u3S(?K2zqhF9?NCl( z>jb)Gn?8Iwu?8mW?T_}}8Z>zKQ}Ulp4SrBp5i9gc@j0x+1*l=pRngoh$wG8ev;IM_TzFh$;TnD;e*gXp(W;bHf z>WT35duyIWbQ2c%eS}g6XFl_j8V;P}1wQerFr!dGC>$P6eXr-(H5bsm55(?*=O8Po~b5nHty$n3< z8py^X1)O$e2(`n zRiF+&#a|1T9EYSo0B;;ri^srn1 ztG%t@%rZQj{hHCh!;W?&>F{REYpgSWKa}^G%<`i(h1qv*QHxiK;a3Z3O ztYo^}nFmzGQL25J|4t1jEZ;;{w(7vao?7gkRR)b#Gq~cwblT(FOE&9IhvnV_(aY`v zTnK0)QonE0=GT#uonC+DYr_??=(9MUw3Sw4?OSEB{q}vlH1pTEeheV~zbZ)BlUg*g zDr0%(NgTI3i!Pfh%UGR#SXSd8oS=OPQidmzTW*SI7*Q;#dqYzUg|hR^|1UlWCy#Im^9zTVI3yg_6Nd+tNJs_a}G{|h06Y?kiM{TEk zA)lA9eA1jJaN<~BP;WL8W{1k-uZUILWX3@!R;L$_A}VNvX>k+G#2Kj$YbSC%3Wq`_OPv|+$rM~_kO6y zy9G9^?;6WtTpAr5ahh~=`a)Y|Cmx8kqa)I`!TW3MJJnlCEfw#QfEaDYTtDOfvi~n4 zZ(oJ|VywXE<|*z9+@~vjl1coP0U%tH5?Xp3X}zBm*zNzt_HwJK`?yXn(~9v4?NUJN zt0$=S)f1d!-_s?XNtI|flwGw#-2qRaaC|*+-!x3}29vcj%MG3sVhZ^pT|4lx+y(8P2n~)X{pudVzIk`fSAQPHQ@4Z;h za&Q!|SLX}dz2XX&um8m-<@>~izSUevg9x{BlO*%(y5`?FSN%Ph-iXM1(A|VnUk{+2 zKgIlL))!SNhD+wzP$x~HY^n2z|-4zqR$*dn)>rLeG#dJvpmb7e>sqsaYjP)aCw~bNrA7t#qLutj<|0~ zcY#{f1}wY6=864R#JxIJ!XO15Nex`9poNRcL~uD%&UmNIxVo<|bvwO-i%QbNw_YDW zTo6Q@_OrWHOXi@BL=y6}&!J-w2Vnd4E}f?>fcY1e&2{y5`} zXVzbZbg?CfCp!ukcv)Pk6v){=zCwSmI4aRg7ar)r$=MO&bQ4=x#+V7VzJuVYk{sX2 z7|ZkQf0Cby4)E?}3mSx2(Yo(n#Z{-6r-sXdjnb;H=4C2%IDZQ08%vP!V0)FzapIDl zPMq_uRK{2QnipKN8_w?eiB7AZf~m${2s-f#i!TkN?X@jj63cMW-f)@ajFyt5aV)ob z)Hldg>;sb~R^qYJcu5VMw~ujspA93aX+dyrL=W0&l)_3KHOMMxNBzf^G~39KpUv36 z(YyA*z|Qe-BboiqEVw~6hbyuDwh~tQH9`MNKS}UiDPhp&O!0&5PQ0UuGVWdMLhgOg zgxM9f$gCdlxyzf|7L~^MyG`U(-BcKSLl^h&H~=ZzOG(T1+musfyD6rZKA)~DR9^i{ zQ$NL#K`TGtN4*5G^wm&)_E;qhU|QcLV?L0Q|7uaWl)&9SNt_!mEiColNL%J?Vjet2 zTy0(eeHwZA^ip5guPTjUgO7_Z3?D@m+Em?BubF`9f6ZtYU;t+aM?mU?uNb9_P}}>7 zJI?OoSC@_eSN86n43lGA&>*U@wSoL*e$~_J`7kP+^_I4bou0t5kX=@C3J(<-L+q)$ z;oM*d9j7E@#oIx|=)sU+QH^14LHIfO?+};jQE&o9d7uf2_dNo{PFjum?4&i(kVZP z2dfD;_cA|h^9@etg-FvfTW7QH@xC;01=i6xUtbUicx~n3VO<*I@ z0eUb7?_F8|MSDZ?{QVlS-LwzAf6krvGgQHvqkADXa1i)fY6{*_*XXp3L%Dq}9`wp) z6>u$C2DjE5)MUtNUu>rEf2xaW5tFCNbX2VOge+5%Gt&u>HgC68C?1jhWT;IOl&Pop)T#{};#G z_qMl4L{wyEWz^^WNk%BLWhQ&CFES!CqX;dt%*bd^RPOt{&nF`!dt_7^8k(9Se(&z@ zKY#Tg_ny!BoY#1^7(>R57@^VLUiy`)&FqHjx=uZ1h>zk3#PPkT&iM!4TIbD7%{P&C zzPgWMNfhF!-D1;wF84P<47vI&c_O|K(lTlzZ`M{rXqofcA5k z?6igW(Mk_PrOPl>(+(Wg4v?k|Rm0Hd8%g=`7&fTz2&B%w41P=|-CLe1_-PM;`awCU zxmyqPE~<*2k96>6d?C%3`hYE{Nyqp1X8xN0gmyE`Fl1+(awojSZynPYg~4WXd(de4 zhG~sYg^#2AlV;w9VlfjH^SrhL>syNl0|Cy#PAK=R!}sAGSwc`X$+gv$s4NHn(};$^wh!_iwwtz zaNrI*H6uXzF1%L5OzPzLi)9)`()sb9QM{2UOeVWUr&Vn+Z?`Qi2&tpOyh3cKPJm*S z^MtA;u^n4W={fxlpuJl~vX+)G;maCW`B{#q7E16~)fIMfpWC9A7A6i26`bmavI_?W zxlG;I9zGV@;^BKe>42^G=r-;Pb?M0e&iB3$Po6>8P}v8P{5>Fin1)otK3GI#dO8f+3yx9Gk9!OPd#x7QR<6bJ7&8g#X>u2#9EdA`=zHDqRvlUp#?1= z;QB8tXi|kwE2om4+*kHewx2fbSO6_CO_NuP0Zt6Nh zYscL_MJ`_WSwfG+g_A=(LYbF;oH~bggRO2VlDi@Uq_G20VRLHwfbFc04drC-`2ybPP=MS|hJ zU}4;f@0k9*ispoz6=yZ_OkBS_`h3kdn(17I`plf&xP60kNX=$G?c6|r#R~X!UMB5} zIKwO^tpfQv8LpNW@E*lsV33=Ln=alGOtqrO_Pbh`I$V$Lt(ySDR#kJq);)+Y*rnLI z_6OqLHmuJ{7jbcm9){o84k0%k;JDmK+Ax-LF$Or2<*!^>q=h!LpYIEkoQyGVc`eua z@6u@7zo>50By5{vB%ZL*!uS|ny5lY9IRB}|c0Osa&F6*iw!lu>wqPm~*6}&XweR#U z+re(G45rWCDh=IlgyRS4idJ=T?0Bi4@_o5wvZ0h9Rx>fu8!mm-#P~!tVc^qAP@D4u zKcA?lrmKD`hGZ7t{+e5Gd{r-T*D!sw3>yGfKIp=;QAU#B&a>Oq9m&Djdiee5Bk1z% z9xZj$$D^OLg^$yR!L{z+arK2N`nyYvFvr4P3YetAI``Ify*al%Ub;F8inG7dgniui zt~;4^a^FM>LUg69H4oWk&4rM8o%2w>RSNDQM*%zMVEM>mI(=#;ahO?)nJ3z_j{9$= z|InI{dBH0pGRy zl69L5HlgwgDKm{{ZBKB|48IeqnBT(>DYu0u+9qUX%MJFt{T)TCCersX*SP{xV1>#K z*dW$p+*2#IbYl%kr8?50KGAIByI1trK7G!n%wQ+KxQG_K!?5gHA=IT?!ua?+w43)? zn7cHDtaH%hI-?Hty}TM!`Tl(WbrDUPVNXM{zGK7@Q?_(~fjE%gKX({zfe-J;!jH*D z(pt_eY<+j0F^===yL^X#6Mxc?r?sURZ!I!Bmx#j#7~o6;GpcH54zXJbF=bO6;w;Sq7UwlfQ9ySpDgpFr{l7_|nl-YJaAI zed-WF*Ktki&f7-e@{VvZC%^~?ZD>PTHfK^87IIc^9E^M%O_F1h*q#w3+{?}H1K$6z z*UN=0eavcjQzgf1cTuU8>^N&7Wq19{9=-?_ekE38{;LO6>&-qmVN`fDf&E2s!`S!ExT{{qaa9{rGMwSrB}Soe1$$&dCMS zo3P_k3syIl&&mG!Qd3+yOCEEZ+O9Ok7kPb!rP1|ty=5MLC3mS~c{myR9+|iLA*y)g z0Fx~0(9F@C^;%F%pUtkq4fiIn7s<6m&ix7ZU!LaA`cW{Bvr5}lrL$f3o&diAAb0WqA0u9-E?HwVO0*?=`{>0ND6Lr%MnK0xkL_fUwwxsUlnCjcu&IOYRq%E4q2MJ6qC=E z;Iv)_Od2^%%nLBU`%`!hXkAbEU?7(s4>-yCPp~Kbk+7q=8esEo9?a%Bo(nh2VMUK5 zdgvX`|Bf;zE|c`d?Fn*R5|pbbvvGvUellrTDT6BVT}a}4=Ixeo%-yHIs~_*Uc4%A& z%v=k)_L57*(@wGjb0Wx!qjBtv=LV&}+U%z-`o_vx25h4a$r?C!sI}1Xj~AS}QjY66 zrrX-7Rxx};5sq}Z2v_#@7E_z_5rcX`zk_;wR;oyS56)v*Z}f>(sZ6>s^FGsklL(o- z`}%PGA9glaOLVc+L;tqjgoxrHkUXmxgL*5dp2}5WTyJ}6ig6`u8K&!67T*rt@`l0E zafMWeb0P2KdNQNt&7^Iqj#R&!F|C)r(95$4i|fqD>)Xd5b?sMNVUk3%^u4UM;&(F9Cp5JVvVxpBf z<)5zl($(~Iw)X55^6PCJyO$O6f3NkhyPP>&C*=DWlRkyqt7*MP(b~5#w$1^q8j5Ld z%5B=0Kd zXnC@p=tgPczogrWGwaqs!ZUMhS@x7p@VBR%qrPJ$$k}k2f!MK0j&_MlA?wL#FfWiv zik;ys^R9|e&i&_=H%p+^gPplO4*gUsg_n2hh`|v(oLiKla9(N(qiTvUDftxq`aFp| zxq6cg-1wYE?Dc@adtFfE%)5xBQkqjElOpDZvs=-hhyl67*7eu~4d=|Ep}Z6BC{$xz z+Fn+~^LHYLOT9>Jc(~}$)(rKIGDRypRqJK}iouZ(u_>DD`3pt%Q7svxNd5`WOhuQ4yoFY0oLziu~|PnuLR!Kj$>@d&1Ujogn>vcQEF+tlB;cnSRy= zmxKKK`#ln2Gv|(-;>@grKYy_YiHz)_y4YvhNP!l$0qx0!c+#1B(Rp6)R^2Vu?$BcD z*|Gp0_A$bpA>F{K;Ru~y@eg+mozDDt7NenyzBCPhg}1*=hj13gix=aCqp~{c>5_+j z>4DTmErJZW#CuckC(?TP8ZefZ;+S7<%&JcXvH4h6Xj{;~DN%a68jg%PHl31_UfyE8az4?b4T8 zJIlt|T8cMYyR&RRL%+4d;QssD7+TjNY$=W+E0<{F;Q3b+iRM$_T6z^~HJydy*8&uG zdh!3SXBzBj_8@T@&kYU!yAmSTJAmd%ndGY(#xBO%kxw>+-Fl}AFMrPknWZhRi`Qgp zHDA*C&y%q492K%?Zx;E>yP?+qh*7lmXlZjE?tEDy$WImtyFb}UUPf+g(uDr5>23A! z!G#sjIZ+FS@Xy1-c42ICS~z*&9>)gTtX96uXU*)4DKTnn>AC;tJ|7vb?LmarytAxd zB_19WLI*ypQ^@&up|ff@%yI7}cKD``&0lSybg3S!*xi6X$4_8pw`62oY8Px=odZ6e zA853RE^b;dLTL44$6fo5x-o}oKmQnEN?UtrMei@rn(6x#+7>H)`azqBeEQ!02Zl)_ z*|xhI2~5zDHWa5Z>CSwx;_u6ywoMdvx4%V`PJhKKJ@(U0@1BvFw|=7OXML7jdovAv zDo}oYG>aYGMy%jHtUH}gg88qmFnccVpEuw+kzpbUExF20Jmd^bu3ul9YmRvplZ53L z#?h3+1z3@OkakMd5O*bT{`J}|h5wPt zmzwA}YptTolQnR0!EZdDaT<>A(*y6ToNaefg(W)ZiB6nVt=`5Lwk5m6jb$>)#`-wx zG*CsTuhz#`zw^OUubHL{OT*+sQ_|z8n&|nNcYD_Vr?`0Cg!^ub@XeNBs2DkkFuyp~ zhdrdNT6WOQZn(ky5Zp+traJud`MuL|=F*r={AVSxMO)W{_kV4m>Ai_`>{J;$doY~$ z5Pd_7DgDXHTl+-QkWM&X>!4!6Gv2w%^A|FUAlQx3WN^q`_HUolC{MN?T?)RV#84iI*+es@r*0Zve;lkS3A?)dg2<0rj@}U|N)CbdHMf*U#x)Ars z4nfYNY!YN8#|PUiV0-7WP`gb{8frO(WgjV|zEyfywIU7D^t-@&{xf5S*0I@L7m=(^ zS~zaOEMalPfAF#C5B7I=r5CcTAcbE9H%vGPTQ|tXNo%w@GrcXC{_76sbG4)g&a;%d zcHln~)ZLyA&pb4tX|$E}Jh+Kv{E^5(Zv!lQw^V5LE7r{AKL2~YsMqx2chE5k8$g?9GLUejWpKDSm?jm z%310e!kM&-E`i6Q*VN~wzGM?|pN-6|AaB_nmUaIqysa{YPR~p6(m+C%n+6NBGs|$t zqW<*Jp=j~&v35A3R|?HCsh~By&nohSDr*Y5PL@Bv#k!doz}QS@_F~25OlNj~ z*PwU<98t3bu6EIe0vDc1$p~SW`-GEXn>e{P9eg&xZ`v7z)>M3?B(?|Q74$4`oIe;^L%G}uqbvfx>W{3YZ zeT6A=KGUzfd+pDQg~I78L*P&n=k@IFLmxc7BK+)TfZ9$S;fCQG>XTlEU!Du>lha0G z^g>&@;C7d(p%3&7tHEc-M-r8cU`Sk+gN>El>E2_Rq^?%N`Ar{z-8q~V(yIc;JrLP~ zc5OtXN*!Fz`_}GwbcOX;!XraUe<$sss(uE z(jV|fUGX#5r{Yfez}pRD;6#a*G;UQ0JGt_oOHdK#0(*T1&)lC>Axpv3NfsnZOI4gD zGr)OrZ^iMSX5c@%2wj~ILHVFbB=lT7s||TT=T%RDv@S*%?XetmVxQB_x-x0Z@emfJ zmrVw++ss>M4McK&_e*CJDI~On6&Hq4wdc1nSJ#w82~)+a?q=9+sjtE?v4ZyQosac% z4nX7lD6&T{nSDO}RJn7S?J>a|`_&HWBfm9KH$#0q)_IRGbw*oANZ?taO(BX2XNQx2 z58~OI`L6WS*u`KlsSQ?r=?E8_Lh1H~O7z@1jJbTdOKzJON*>))*)H!SdNI}lU$+Da zVbUM^$1e}{Rvb~h?#2uG-fLt1({TFZ!+M}+RivD98Dn-T@MUuuhSfT;E?X;!#$4We zV1E>jT^a$d2Ti2xSjt|Hm?A7~RFk^x+(6QFM$_Dx1=yd2C`J@?6}zeFW7P0dwC=Pa z%$FWxfYlqAmFh-TC(7AL|7l7MXf@w4ZjL_&4K->)^y62n~6T4dBm{+m%f<_HJ^0EYv={7*c*6U>M8P2wDk;9Jt&Jfm4U8;#X zz+&qb!lHFr*!1HS=iv;2iZk)to7$DkH#$p}n{eOPwHx=XG$+B;+dr^dMF3P4ZC9xC z9cJ2=YUpC%B>v($d)VbUFc=-cG)zlUa}8nlKKbF4Od9VU3b%c~3-&xe(&xXv?D=%QPfp@~#on`F z=_@UGpU(S8*9CFTWf(cY`4oe*d0);>2RLYDAh{NOWe07igJWM!yc)e(@P9H9-a{o8 zY>7}zo>{NBt67NWHf(`j0lmbnX1e(Hw+TcX*M^5f8u4SjEAwcUkrCewaC=n>&s(I? zpAYnK`wG4JB!roaLdiN7)N8GprFwx5Z@Qvu?0uRROAw3sD%wXo!pSbnuF11a0;I z6!=x+_%46pxl@_&z2qPMd+5$wJIoS~#pt10*m3Z7RR{0&am?V?0a%o32a~Ik@VECM za$tcGadBA4V$QjxhMcv7wCB}0sB$Aj8Tvy?ND-E}l<^e9HxlfsCEZ+ekTsutN{{p0 zgq7J_*s!HN%&<&B>F7{$UUN06jMl_mlOj`E-@7}d|G~X;0>IW)AEp`c9YDVrrry^T zO*`x0sxgznf5aGgHCs!1H1i`2;XUM4JI@D{3U-6%5lKh zGeg_GGGOFz{v6B^INdVLj=LQuVi^ahUR;22nD%LEX^NW zy4Sab+dE9r`+HmG!oL^kobUoH-9HcBul-2WxbELuM;rFIjRSXAHEE2_NY-AZkk*|w z#6g%0PZ~KB$ElCh!&M762kj7v+LeI^oTCsJ=EvImc=r$ ziq9FxE!xWW?#F@6Sncn^%5!~OtZU3M`Zc(TNKOxp-zGDVIni}ukZ`?XLjs7RZptFY2t|ETT33e3FLpBe70A;10k z&B6CDq@|63$AMyj__`XRdy*j)P5`TXe`t-DyY&`7Q`u+V~HF)cnby zHBbwpJ84O^O@XZc%TSU$FpjCz&sEODaiks2#?sx$f>su=;NCWdtCFVJMZpG z3qK~*gbaZtfhEXcd(IB;uL|1+{l%3xw{X7j8}V&_Q*4}I3M_J@j9J(aU|5oaDW=$tQ(g?ls=(zv^)IAvoP0E ze>k^h{np>o#&bggX=~m&_Dl_acv=ISM*R?Wx^vcmVj!Cu>nTRfF~GV>AwBxP_Xls#irWTXEQ>I>;tM2*-^lZM zNv!`@O&F4B3GBe<8aYs)#GOwYAEaN@Qm6hr)E5DgR(ChE0I&%WZLnf1R$8NI3#aHO+!5(mY zycGs~Tm;Ks<RSB`A-VpzhQJN-)C*22yIDa5j2tRP_+SV$KRMUWiZ=Ru?*znc>d2T z4qCaEo%Xkv0@BKup-!YQ-*PZpJn^l|ZU_EMjpzF2COyGxYasmYk&BTo!(r;+w`9Ty zIlf6%fvZEt!tQ2O>4k?2o4u}pPUPKaLv7-Cf1?fD(&{f=2-CtCk9}mvFD;Z^J1u-3 zv}d!iiwJW>IRfNro?{SRvHbz)jJzAk$M+u#Tx z4N^wR!JB{HvKE{druMXe|17@a&L|CGcH}MGZ*ctL&uiyuwl@8_+3$n z-~aStmy+)in=J-X?%)J=Xu%!oly8j8<*Kl!S1k?WJ7ia1RiSlqpj?u6Xiwtb3iui?=zpoYiP5b!K0PzBpoj^+-iFq z!YiIqb&|}csvZR2&t{;et|=W{bdu;Dj}`{ReZxNHYC_)$r^M^Bj@b3^L7JXdOPiMz zVI1#Pol$g^lv>8ISj~U5Pn9#6^-z=Mj0j*iIxT=>edV|}Jre>tJHxx2IQ;T@ELpMk z3~A>k$3(LZF410-;Dyx>w7uZLz4zM{)2@_aUCI}DmOo4kbk|0Y>e1l-!4|wOa_+|U zz3fsSTT&OjjMao?;Y6ojs0B@^fSQqZ70B}KskI3(BhiHUgqTxMv5!A|DS8);hh~o zC09@Keg1}h_&o)zi+IN8-Wg$jyJ_(5?{5qu#=_HWs#N5+FIC%7N`KMaHTtN1R#T~! zt8Q+<(_8wpQGPNae7C`w=bu97)OYk^31`cCpBF~n9|8w1m!jbfEn)hVYeJ>QUwqMK z4s>7nMqI-CpPQ~}!jtk>G~_7vm%8<2k3Mp(e2NiXJ8&Dy{w}8%UhqC2_d{gelOX5@ zdHDK}s&Fwmi?mFv#hYJ>;3K(}7BsvHw+-#h&be8LBkK5kC^`goes*BSJFDL=yv?j* z-3VN`%G84VVbH0|FuSG^_ca|+&dl8Y1vs!?O}Mj9Lu@kDL5EpumAmC6sRlbND1;ev ze+ZsA#Tfjt8`E7pN+f(IQQvYHnj6&Nzguyv-gvKaW@hmH&6az#cU&?eUQu(|tcd~6 zZ;si(Dp?IK%a{m*-TWarxD*pEd;zO7MMPy$5*ufsp`4kK8d}nJ!@ZpO^^}fD)5bq$ zFMyrpd~n}*B+JJUtB<~97x(;+4Qub>@qQh6ulkD#>*l}~2Lp)hR)CI?@0IV`L1DVs zb?i9k?KuuCw&+S>e0P<7Ru}pk=wgt`D`;3=NB65HU^^QRa<969G(_oPe=8f8`CClk zR65TDWxIoH*JJ_%Z*flLCHktt12#@E#02UE`}pnjb()r>{a`OUIs7A8zWNU9v(^XB zE;EN7-bPZoESnv^dV<2lMErEwlZ-wxS$yBy1pW4Qa~Zvtv(bY&L&s|b^e#9@e$Gf? zyV}Mn_e}2#TwmTjh&@`k41O2Ov6DxvvU9B9yrtBBM+wWejSy~|Ix&Z{#V#GEwuP_j zweiKpAeWH0k<{KJ2aC>gw*1^T#BMw1N}Tvf9d?feGb2@L*6jhT^TTiS=Ik0A{ckZF zmSrXO;_1%hXt!`|!4UB^f4A~lKatX4J(%EJgcixqVDV-jVl`LJ!Yc%2FWIL^JDk5R3T9^) zPz?oV4gA}u)Ozk{X-b2}T_u&LqlK=0@^ROiCBpugQ{uwT)|j(u9jy+or>Axl;%@zC zP}cV<36%3(xluiBy-#-1?1pMt(a_2Z?mj~sjSoBp_fszLap`qj_h|+}|45QqEyIkq zhh188*6#m);2f>~u&Rr{;(}Kx+Dv-^qe6#?p(}N<<3Kll7wiVr=|+-Y&>gO*t5;iZScuG_Ul5j9uTc$Cut<#?pnJ zHuh4N{rpc$`TiNo{bO2V;N}Z$7<0FZGqAXS`|Dm(@hFZxiJGd^cmArj!QcU3!S9MM zUGql^8z06BzY?Z^N}E5}ttmiQen6EL&nm$8em&t(O;2&#Fs`9&D zhSPF!$G(NawH40^UaG;*_us=w^_yucPnMzGu&!+DNHg*9I_~LOwqKdqNeMBM`XOXGmxD?yxDS)qA!=FyE>rem2&|BlQ#LqZPei-PWJT zwtnEO?{Xn}WGRmF?7~71juxXN?r)LyfsUvKNj>6OMBy%_SM!h+#T(OhkfT*?h`Hq) z7Bs}z#hY_0yB1gD0%8k;+xkO7moi*>_%ZCV`c6W^ZZpT6I%;X!4q~=wO0SP^WnCPe z(9m2tR*iTJv$t8o*5z?naCHUIh?!58f0biUcCyP+SKdAHiE~#I8QAaB6$f9{#UpY- zIZHqF)RnHS-OXyZstX^vx4$I&Ia~^8qPH93@m%U^V_R=qm4!Se};ww8~>3`Ee|6d-zgC()|duJ&9nKOA#;l9^vHsSjT`t)Kl zZdtmS*xa8Xj_PKH8;@kVwB9P~x!3f`gErt5caCg%k;*P#JWIPi=?vR;nPTt!(Gcu@ zkS-?;xTNi3HpWv`+{<^ZPx%*=Jv?r~?WImnzp=+T5rV#_6DwQt$HnhZTlm|~6t4&$ zU9KIwNV|(U_)s#0&J*5{QqHS=Q2UKGjUEGE{Ay7%vI|obyrqLLRigF9Ic(i8OK~xu zZ_RyUpyy#5P&oCI;H?UN+rO801Zm@hMGE0a<5mcN@Q2@mQUr%IE0`3VkGh9Vpf*+} zCeM{)VA}%Px{F%eX~dj0cFdvkTo?PzrWm3c2didj!h%Nz*v#1)8%J5fxrltc8FWRM z66Z?xgvGPqb%lxx4T~T$w-%QhJ_D!i>wu1}z{a)KOq!ldHeBPmtxE0_D@mYp67+G8 zRl1PvT28eazF~>^72#`-NMhkB$D>pFQf=L}V6CqrbrIgd=ElF&az+JKZ?R@u+SU*) zJ`W2920+@Vkq|b`NZLB?I=g<}OK`iWD*fD@NP1Y0q;&_irRqLUh3C8ZXZV*K)B8Kp zSKJG3M~d*=Hwuf^_z<67a@I-3NvZWb>e3k(Uk!tm#KK4C(MOj&0!`A=l5kK;1M| z$%CwAUOVPPeU>(kcXktBPz41fK3#)@)ODnb2OhK4 zjyGXT=USY$D2D9qqa#k4%Da5?pSZNLJNsNK!Vke_Fi|62uNiu zHTIj{R4gc5xWQ8kF|#`T1Jw3c`Tdm=teG` zzRIKr8s*CAl=3!F|)trGs_uz@n=JB3$C7J1VL}~ z!I$Tc&g{DlZ#wCUn^O5Mcdb8cU*is^d+SJP{kAa=e>LHnx)F{W{~S&v{-LJf@%XAG zfE?Y>Kz11#;ZYg)@mg5G@6X(;{HHBk_~S<&^V`Lt7l&x%hVjs2Ko`tdGX*@?me7q} zcUXL9&QjxgQ1vb&N$dG@_TlIW>a{l+!{6;A6QX8_$GGo$&?*(7_l|G8PdpFXv}>l< z{+uN~D}Z^t2&Zeo7N+Gi;gG1#tTuQFJUvy3Px{Yb8e5w=k4764!=jY?YNk^yZtYMi zL=FvvImJ2X5nM@6mAxS|IY0MW@hiH1wL9c;#(LEF4y;G`JKAw_C8nR8#v1QfiYX)X z(Ix64tSYeq^IdYhFYsbXt1aMgOfLN_R3j>LyTk43uQ+jE1x3y&yM^56llz+POSXsD zoej7ru_K%DXSR#`R#TkxGFGXT|5Y`_*owD8Yj;_@357W6%_pJNYxLjD1or5;LNTs( zG4BhlLytWQ*d4kK>erUy#<6Xf>D1e#B~Mp!Qoq1fzlo>TBlPgX$CtvuvQk=@@C{2R zeiR=5i{QT>8JblX(XcJ6!KI6ev`70f=(PPueKaaD+PNJ|PO2d`M|E+=)NOEN)@ZJ+ z8cA*gV_3ToFClZGs;Vh{J;#+>tj1wH_ZgLR~6#D=Ls;? z!iV@e$ywIIKFayIQ*MX8yEy-|FrVsaY?VGgF~VLd6UBO`WLDpHmy!#!kLwOki|!D| zwBy1?t{v$A&KBnGJuSY|H^<|9t*Oa4K>N?}u>VL5sSUWrRwm@ptPajFzfD*C z#7@BD<|8z-fbZCi2$%0WLwwM6e6?~X@x2yF?rO^rSE&j<>%CwF??2am`J4KBZ&zdu z(?O}l5uU%dgEtHKzgJ^7i>d5ON_b~i-i-{1I-5YEeh*nnKUn z10cek_g`&jpz9B$3lDqQOL`wv+5Uz7T?fVM7xl|JOzYQjA&G!F%YqSTArXRF}%6NS5~S28Ei zNLHN=&MV4N&d=gGrMw$0SHMlzgcXG~_XsS(VzpY z?%EfI`54w?NQOkMRi%r>;vqqu@=LKp}#szdcIX!E*Rs(;ilrC5pk^T4Bm^SVF$}hC~gP{R_>)5rnA`E zUlU#K{k4Xti|cWpmpWK|4}d!xiqSy24GWeRkg|<;SlIrZ$mb-J(;S)c}pWCeKX-h)*pKQYdnTs-$NR+8;D~f=YqYE z39Wq^2Y8RM_4>m+5SGOU}vl&PM< zE_V!}A3rA}>wJLxlY5IR-KSJ_oo@epqKU>5_L_61=c8xNpeEi=!m!8zB>C$$5w2JKnb~ z>jqI1>oID91^bvY%jNDHBfRqZB7}TUgW{F?Qpo-XtoPM8GG&1gPMZE*7-MV&7bB8! z_QQ9AvxOD$&1{dqR)3@S2cMz_Crh!~-iYNcxlP7!4nGczNb);H3;XscR@e)x;6-UOJ`7BP^t-=k2S3gk9Ady; z{w^hRpXgxT_VvmxwQ*zRQkcUjR{MN}aI3wVwBzUt;{JUk4Kj>F?Yd0Cu(5>{a-VkD z$y!A#d&_KpA+}7p46ZTrNPsA3Qysb~XY5kLu6S+IQP|ZXkN%w^m*NJUVx!*_5Z85g z*c!SOMr)XY{Hcbt^8FhUx+q#GZ{gW7T`jUA@{HK`U0WR5QJtQ7`h%WV<=@%*OK^$C z5J%&9wrG4dZS5Lb9;6}#o%CTtYUaUNe*f(GkizC3E-*To_u3_Q5L&ZEi@TJgPxw>% z*u`J5%aAjz{#}CY!=1#sVxH|<+XH5vwuj?Ge`BvLv)J^Uc4Qd;zFhXEFfQRb)j6aq zwL6_d6tNw}0ady<;B6P7HE%wS_ukmYJ)~}z(uF?m_R@X5pU|4S+*`%<=jDAt(@Y!u zupAe^9nTh;>>+o{c%GNf5>2gPjUA#F7%u=+`JL$7?sFLuEHkk8VDDSoFRByuWD%8jw4`Zg2<4;dCPk<_ij`*@P zk#{J*px3wYo6qS7tnt4F@~f*Jx*g9ILc0wG%Deb}ztmcExsJ7Z2Vnmikx`Eym=LcF__GXzskgA%a!>f;dUb`PCQh;``=Vg=GoqNg36q?d-0Dv9~EnI^@kp*dBEe3Om9p{xb`I-lV%71K_QG5sJQN zxqsjrd3Pn5?MVMb&mCi;KIlRI*E5IXVh}PN(=9f?xZK)msOE9t_CP96a+gba}fJ|M^<`{{w|wDOy?b?U>g%0YClrYT3$xmp31}YLy`1>!#PsagLk=nxJMJ{3h)at!b=rB;NY75 zw9nX53=AB_a+2#vD(_6Ib3X-&&TcTAcT=16M|SnmK_O#dJr*1HAea9;0NY08V%OMU z+FpE1@-NEq#)@P*<aP`vUhZMbTzhJK91#?TZwDt>Y#pTBseUy2J2b+ z()u}!8Gf2by4CW1wS9>&y^kNvp4`kmb-hVzH}9nId^CS>l(yak0$$1S_|;^p{i_>P zjjBa;4?~vt+uLOT_Z7rnya0iHG-1q4eQCmM#w<3)kyuCW4}9=b>Hoa-JQ>gB{uPF~ zTals9lUeVkB?>*Q)v)7(13oh=q#kXq(VS6SgIKD~;;e2Ha#$vv+!V$Z^}bGPw(Cn< z4m0*!d${;usR^EG_$8PMb(HP;hOY;7AWnr5q=s`4EZuG>T7C64$J^jTjVJW#TXXuY zt_T-x;9ca4OUY~Qi5=c)F}RE!4n26Ek6&^abE|g~&KL3CzldxSS>Q@*pETlZMNje( z`il>^PO&^EQPHaPV<_+87f-^P7$0)9iw+xd--hP)+65h7SfT#Wyaoboa~v#R1+S^Ef3ER=;)4Tl}Q!5?y+9)uYqrR9adJqBzJr3ik;-T=>E}F$aWk6J$rpeGu`7fdS$xsX1Kki z;+YGotNOd{`KO1wEbYL#j|^h;%5n4I(G1S-Cf8Ns*%i~_%9*^)SXbI2D%iWz6QS~~ z9Fv4n<*lITx`x!Lc`(^DPfjPD;(X*~A(XZ0C5FXnqwmwZ)a;)O(gG`Rb*U~pI!}!} z_@XB1dWNti!>>aN=N+`nV=Sp%0~uhz`AQwCgdZkD!GM2$ew?!*UzT4Jyq;9^F3m{V zV@8I!D$)ealhf&e3E9+rSuwKlayGv6IbowU2wVvjMO|T8Fz-(B3u9l`IuUd2YizlEv9dSGZDJjo0BII!|!p-*JL(j zz`ggQEHRn%fySWEG;UZE#&X~0?1zuYuIb6lxz|Y0JlY1@PtcdLT@}noCxpIlM{#~; zENN2A7lTbr@Y|C`$~pY(K^}g{^`N1n&yktuWLQylm3GACkQmm4LqF&-U8^Oq*pJU) z3z2PjSx1hJ(!=)t5imb!1Pu1zc?TT@n-FzSSYJMnE%LV&(so+FTD_k*k$c9+p570a zd~$KnWhc67`diZNfE*oFVra`U{+xKzfR{JwFulkR^oVyA+Jw5X`Tg6A(T=*fGB8ZZ znKkj!myVG8ypM4rappJJ>Ft^X<9~iI`pqwlGaE~+e_F!EbpE|Iai#|w<)ZaMIrrsV zp;aroLGiLC4Di-vR|4m{+~s-L=H(NZ{ih|O74a&h^MyeV)?~)zlG=AQ!!gJ8I7Gy35jk`@`97uB=a_kw+X9Y&;oOePf4bB?@rMBKT7cORW&yB zSt5zi=XnjYV@z*bEUj6jFU8Nk&qhCY72izb_d^eLlKZZj#uweg8%NEFTDvXe3ipg% z^qH$T+GRB?idK;_r<{fI+JAJcbrISI@?7@L65{NtgL7-u3y-mT#7%f> zt}4yVE+hArkDw=C-ovvy%!#I%mPjAy;p2@<6bg4kcvQ)|-=p}h)aXO>?)xw+o9$Gi z{cBj!p$G5PJPg}IOX=L9GAU!kF*ZH@8;N|9#11>GSKf8gO4Oy}f2zoZg;7GckGvz) z--+zDJ1yp^c0phD{fcN+^^(_N_g=>oQwwI$1y&19NYJ@J1p!#OxhXl3-6mQ>=wWg}>G+W^JxPK9`LFaNvo zo%u8GD&OVZ9ycZbvYh7ZNgCRVuOJEfMBi|O6q3^Y^y2EpZC zBpu>d9`_)dk9CA}{_Hru?+6Q+Jsp}{3?#qp3TEJCEyn+?!h2qylzQ3ys6@QD-H2S6 zeu)fU!kc4R+$4coHGVUKZ#x~D5M~?8ERC>xXC@QjrDOQa4^xh&_7uu4x zyQZ^C6K}bkUC{v|hj&Fo-9W|GgEy$x=mPxk?+~Umi-#Zu!WyjL-v|X7_q;*Mu52L9xiY-_a+XkWcmw?H{uh(#yr^xHKBR2Q z$58=?Ah(aMsBJ9Aw3xQ=gi3TTV9a-OP^<#tl_f!DNX;J!~*|E z(s{@A^uA%dz4um#H0)Joea>^T5)DKVviBwuU!y2RAtQvyEF=vT^*Q%*AF{JoR@$Yl zv{ZgipWnY;UQvC{eeUOauIqix8!yZ3_m0*T>zHk**!!3eU694NA~(qT9t(KeCB1NB zb`aMmSq@Ar3y>I%5n4lI$;5|hnCW_57@xfsyjPpxH`*62emEpF7*wG57LJ}-)JS>- zt7B2daj?A3vmA|ycs}9@?SB3kH~f+VwfsGp>tvZM-6{1rX3qk0c6caktoV*g;?GIH z)W0R2OmmoiG+Jo;>wE3bLe}|oq9&1H`K_25CA5g=} zu}Y+i2eo)W3*P*(jP$PU28-p2v9j@^)GkldQ4V~WSI7CU8tK<;2IpVh#ltK55`LQnSss-^UqlCG zrz>m#*Y|bU!zKjQO<50z2A8A7t0p)(IE7g3R}qiwilAPZ34(^I86K7xlH!aGVSnO1 z3}_!fq6h9Exz&uP6eMI1ID<9W_R1A1@GDU*C2H_ zMEWcuVVoa*%dHje+tvpUN&hlY zWne0?J+*-QGqezU@0(6cGGq8F9!B_d>6`5S&x(b!vzb?R(hkO3xJI`6-=UL^WeM|C zIFSFZ6Hlz1OqCQ~qZhV6E+-++$fWCW_pn5YS(llqBJtfb3wA^)h}#M_k#SBc z!qWT2ICguS^kwZJzWKHe#yvbQX#CQGQ7ay!Rr5Otd-8=FwMd(m-trS#t*1c!1$ptw zq64(sjs$RLx{BKYRWhz)48;5Q#9&g1a@X*9viKR)5)R_ihRjhE&M(H zQMP*QFqr*BP4wVS!Ba(L5*fw#w`PA}V)+EVbd)+OSk8uTgZ>Gt52%QWK@rp;@jQ9X zJYBpr=@~)a1V$-rXXJUF`0gy^H3PnsfR0!8OL6?57d54!wN|{IbFDt)Z41!)CUK+ zuHLkxDU6GI)hav1MjMVW2Ig6Zm2fU!gKuY0O#*QlA5i|hootsU=hI$4AX}nd4(8rIVfw)Cr@%BFol*b7%8~3J;CUf zJ|<=wf$E4?Ld=nBl+zta)lCJm)heC(&mJq&dt>GF#F@)8Y00@`f)*{tw3lUM`_BXX z1!{~r=BK$+^Xi2Ass+et2aQeI8cPz!Ft6jrgEGxwjG`GPKQsrcagoBtgB7TCZMaNx z2;ZZQ%XUV{^7{eurs5;kne?OV80Yz!vGAvjmF>Ec19j+=6iBL`hQM9(A84F)&1rY9 zccjNwbzBu2CirGg1-XI-ym9mobZNhSKD*b$6&buJsKQ-pua@DRUceqsAYQmduf4DL3Q8 zC`TF-u!ujjQ3uO2kIESGqQ5K}z9OeNoI^<{*w;4>> zop0j44e)05dU(w;$ZHGAVBwuRWV5=8=shHiT4*E)evG~LHN%*AR5b`$?=rFT8zJr5 zf#ivt5}q0I$g$_Tl`tkviQWC}gFbRfptQ6E)!RxTIKG^0VqFpw9A-et{E0BcUPTn< zgwauJoH=W|f9RdA!2jnkPOx@K#JqfaqPqPr+3%%`w}*Uk^e@zhq&X$HrC|vy^jSzO zf_h?~^o?+B7c zPg@K>y2uncjbg`Y&tJmyqwLQIFM_&L*T})KNi=!m9og>M_g*{Jmk^rrdM<1o%-H5* zlOb{zf!v-oXxG|6c3H5y7&lc6+7iKac@nAUms~&Ci9)baBWMJs7cA9ReR$Vcau&I;$j@^kI9T_0i$7 z`8nvk4Q?oU3s(jQ3ZtJGMF^iK1E1K~>I(39cBVUn6~`EUvPc-?Z+jvCCL{*QSJ zFGL7_8JaLzryd(Jf5WViO5~G`4jq{9BSZ|G3P+2KaPg#55PVz|yrMLaZ`CGqMvjKR z=at3&X$J|{N96p9P0_MBT96nP2=iu_pnFXzr01?DDJ-M0U}Xq(uAd1HFV$jv=pVAR zAOhr_lJIfa2=dZ7js(4}#D0rcL-CFHtj%65lUPy=eOBr6#;jA|di)Go5AToJDx%un zFba_)*jeT}O^==huPZOZiWf~d?|VD*!uN&B0R=c;SVbPKP~?+OYob;38^^9)G)GZQ zoH2v}@^~e(M2)@Q&zFLIOBMokx;CwpCz=)mC%;O#*h z@To|`>Z|w3-Ork2{%;@p?^~@T=V=f4X32b3?>{(|_C6-4q<+UEPHrIF$Ri##@?!82 zo;uBVAgm11!%;Ktg7I1_a66uctIVlPE11eWneLBHbJ>1dVG-ksgK4hBpg;=_ zJz#gX1~2%q`_NiNcxE{XTp16Oe>$43Usoy7?`@24%kRU-g$nS!T8g8ipONXwN<7pv zURL2*j=sdEo-p?pKT0ba|x$~|wW6b|baU?0op zlFd6~iP=MS+&LmpC|b-|Sc7^pPOKU9Ydj{zGT->fv4iL(mnL$6G1AY+AAir z<^`8FV5(RKI`q8|Gwv7OcNstf1yep}Gy6OD!)09hzA9=s=br)Tx-Xj**^0k*93j`= znS+#N_UDdkl63WMTs2h3toNIQpb`Bbhv^%RepS$=57bOyJ(4* zsIPc0JdaipldJdB#Y=vYZQau8!kdd_I>4#L6veVv$+ zcwBb&&u0E5vs@L3eXa^W9IA2ThC#H{WFP6)z;wdLgJfs_R%>;!NBRx=*3knT=Q4lw zBm<&yW)=jwu}t*)lf<$^S(qGMf=+ykgg-Ty|29|;hxzRmCeGIZtvc2PtW^r-HG|#KxRMm__o0R!H?|u+H`6u3O*h?(R6!`noHPG#-v1DrFVDQS(6a!9f1KVO% zGJIPRu9^H9h7K6V*D~GPcZdhPR8oYPpgUCW?p#@Z|HOfR1g;&<|xU3AUxOBLZ?}`VdoOo^LLoy zZqwH!T5CIbsm?NDC(d)@)3?H3<#t@}%$W2!T2R!h5Z?#5Kzxk`uQpK??Jmf{rpO6^ zUaeR@{;rLg#=7d$c0K@U?^+4+6#*I&3TV*m}y%OWEdWKfmvBS3G6Db%gd6;}tP z(Dbq>LGDWy9+ZDh#*JOTua9KB>lqigYpZ_NaAE%CM>^2Mk1+9Y% zgPU-=@h_-LTM7l6Dsj8bKw5gPiD-Y+z%a{j8S|tEUlwtX(PeustCxep8ITOLJlF zt|T((gNkT)Fo%WYW?Pu1h;i$U%e{+9==b~?zaIBv9qxH zwu#VT(jgoS`Gv~+-h$!7Y7(ELi584`-_`Na-%L|$Gw@Ao0AU14qu3VQs2C;GV_g-Dpkvx3*QfSu+?0sOz&HA2;}z zks~+{OQ&l-&X>(kMYVK{So4ycvzy0l?v;iK6Bd)qpl$p}Z5uo><$@&QVy7@vp#X11 z4~9`|t`f^>cj%z;u`<8Gm)bU*|6nNX+shY@Fm3bmy?8i1m4j>pM7jDeWRvbK@@$nF zE}MIk^SC<$OlQ<$Me}m*-t@iFn|U3W&^!U|f0)W2Vzb)Ou|@cJ))t<(H{J+Xv=2)>%~0qMUsvj(+lM5^6q+Oa$NYpr zl5Rwv^~LUPk{8XLFO#}>W#PX+|M0p>05|H|IR5#2_Kw@+BLwKHL+^v?;^SXU@coqu zIeA%+F3XuJSfBNPUAy|=LWA?Lb;k!Gnz1zR-mxG#F(aXUyRt|Vu9I`E$d!v7m|o`3 zJ+OMmuhi*@eOmK7jXc@hLFMhhbWw@tSK#g2KR9fWCV!>g4!-p$z~M_HWqYZur7ucQKI}I>OR5(CZ_kgg1WKn5zGSBOkQ-0d|~vN5_ySR{au~^+Np?rW(^VQn9ugY>fczY z^a4It&6dQmTvBSNIW?L;jaSpt#lFizVEHGe6%W$JT}pk)_jhKn{k#;5*A4Rg~tmC*Ua$5tr4W9 zvr||LNqBVqM&e(wmLwFb;V4&>^w8b}eF~LCjeSGmiM0}Ro~^)@XCFfD^D45+R|B{A zc9iX_Pfu%#-}?pA`ufS7?N(brok9Bk3$dRZ9>A*Al zG8}Wb8zh-7CZYA3v^la;8kZal5y!1@@fkm8cKs>HRotbA-DbnII72u%sS@SowfJkE zhq(yVR4l3VC$1V>`6bK~`|@^~`w@fc1WPtnKoP( z*pIe7m;+Y+HK^yqnD*sz{MW}Ud+2Zt!oLvsV2h~ovxFRA_XnRovMjKD7Pohq7o>J? zNA>n(E^hDv>Hhd)y!G8ww!7|}!T4-jON7v|*08a$1*_)urQtoyh~^SivD@E^v_T~S z+Zy*REjS?=E}i+J0L2tEy7y zVhB_kRAIq2OL}v0Fezo zB;=wp6U&-#U}qv{x!#eV%2;-*OGgTIHLB3+UWa9pXYf2zkyz~1rOkTdgwI885b{O~ z1Kjt4|BDQvlyzghSGFPE0i$8?RArI(O_%Mimd>3xVoxe}Ao3kQThSWRzs(VDwEPyP z?kquLE0pN~#^2>d!$F&Asm}}uqqSInLx)e&ii9bCH}S>B)g(bYPrhI!CZ6aH+mFX* z?O4{@gL+Pfral}S0o*oiiWIBKjZ9>Hl27E#+ z%YZOW!g|YdKftL)OX; z3{CsQS#%3wUX&lGDJnwH?#tF8$hbfSg%^%L+)h{fB5i$b*k=BhJ6j1ymJNf4|M+` zbomD!)HLJiXI6B>>I#Xvtsz#b+=6kN7!S&dAp>!0Be@! za0yzTWYPT$TEu^l?tJS5;w5d|9aJdfcsvz0{Hs8VY2D~{g)B0}AcG!#Z3})ZyA?81 zTWnLlN*_cY5t4Q!;F9TYh(@?8zxxsMzhyt?ZU+1m9F7;F_SPqy!O;t3P_Qcc=2!@) z)~<%bk9*_ja+c>96)i+vt3~D8-Rb04ZDh|;O-%c}3k)^K!%@b^u9_B4v${uc@BY-_ z=XZCAMaO=)xH1*9g=^gCBR9z0R#m(;)G4^3!(i{^2%UxShcY7uoci$W)Rd!%!XC-$) z!;CkxQ^w@(hC+^)HOvjG$G%hw5oWU`t|N=FSEV7%)SSjg-RldtD^aJlM3`oLgICyEQ9HjCK9qRs6+UhnSvMi{Uq+sMpEdmiMO`Pb2%Pc zfmc@+GZ+VHovRYGvpcV{73t8^vyu#nV!doLhl5k)c-ZTzDfa%clae))xsjXFFsbk- zi3n5|dY!t1$+vj^AD~hLs=V_??_)z^~Rl%zeyY{5`UtR9y4tGY?wg8y6#PwM~<7 z<#Hj8Tizyg>8sBC9oo3Mqi{Et+z{D|wCSol8P z5%lYl@#2H;}i35(BQHRI6&l0(p!$Sq^-GzJ@wIr`$C&TR&-QV-$@~Dj$obUsg)AGQ?jX}(-v+f{{_TbI$tA}0Hi@Sr^~cL*Z%kbi?kwoWcQLR2PGHQgU-87$ zRhhrQG|6f!d9JJ9#Lc)AXFGHX1Fq(Caivvwx%++S@&j~QYUA1Zkuu%ja%(mA>*qr| z`X3^dIjlploiPCtY@mHh4r-b-5o_}vWd3w7I(I>LZVtl;`nW8`h&P3#Xm z_UDhVV&50??2#(cSsw%}Uk-t-^?2`Nclssyt{}Ie23?N((2u)&^0lm!e1QEWaDCey zvIZee6zhngdLUWFa)`DK&$)xc0$`ncC+pX);#72X0OJd>d`+8BK1P#&%h>q-eLo4k zzfXej<_7fY-IK;8lt_;Gw_wqwh4e&;Kflp{`B#Tuht!>ag@NWb@YcU~B$}}?yB%R! zu=)>Nf@lhB2V}5$b%R^=(T=Phf1j>=mMc|#;R~rzc36BxQPz#(eYYHke=wmFo9_{g zkLmQ4hmFkBWw2RGbnduBb#5INR1O;8^Zd`8t9PZaW?Ci|y5HoM=LV4h%)7FCzOj&z zzX}@0|G~oB6nyS4fmXvh)Hr8Bt+>BrEz?&gH2nuF{$u&`eR|@I^y^e|nk^lIgS(n|XKD;> z^N%MPoDQy^G=}WgHwV{2_fTWmaWZ&&Pg3<;18au%;%?TbfwJNseDM2|AobV`%USnO z$Zyum?R}fv8L2G#`L3d2@z;f`{Y`N~$pkXha>T};`Jf}h-th;Y*hc??HW^B_2U}so!!CM zAoFQ+-dhqlI-TZC@{rwgZF-IPcvCyMdTKS-{NNV;+ZRqc4zA^WR~cb)w*lO>_F`db z$4}IDek-(K4T?}Sg>7)CBY{pgLjxrBAedIqfL{$To_;Ya4 zSpwhxCgX&6Wn{iImUJFw{Pw?JxWmV1!X-9WYjaIW+UQ7WeF0;??|v>Q&mF^$+0V4B zTTg`P=WO8El4>*`Zb+9k>k*CqJus#s8RjTG6q?KnaW`+sUwkdcYaM65mowiu?I-qd znB{q=9akb>T_12iH!zm|aYI?gp}0{K+ZdJxV2psKWrIF?*5wv;cw-|Ava%=;^WGKbKyPg)WMW-SGo!>M;0O5-2Gvk-mvqG~0i$5S}v`POh=VCt?)nYvu`CY66+>S{v2Q&F0-K zSxz}-IO!fT5;j^gc0|=X5_uT8cjdM?mF*9Kj?Kcl8^w6#(=`apUq==j%8L)p7t_C` z(;)ejHEJ#PCW<*IjAc0y|6Z?!qIdCG?^BAf!|EF31?%!Uerzs%7zj`D`oNO+^=R_S zi>}x2Lw2pdPPM}&Fwg!n`0Y%?u|}07Hn&OmH>3nx)}|Ak&&vF#3N6g?x8mH#4~L~D zW!Q4-Ib&4*nC(tK7+dnAe`w&UxENVp?5`fh(ck6xb(sO=;V^Y< z?pwk&_1^~L^i)KTupvb0g)!VtWO-ZGU)eQpXZBZTITxv5W$gkx!kf@V*@*6HEt4c~ zZNcnR#uSzM^ElTKTk|i&64vi_@<9UnxfGM5`>Tl=J9ld~)^g{4O+e*%I!aCIx%r-U zWZYj3ytDF=)QGzb+dvP!4Ic|#T-FWE6=-CmMT-jVlM>?$>a~OQWhI!vSmtBz^DUZw z`xY*^OwGWO_9miW;>({sqmLQy8@Zg)3gP||);n|P50~^Kh$Mxud;Cp;v}*^pnB0hO z-L8WGi(%2{TJ)N!OMQN}k;SNn77JIw&K3@0|EP+ouUN0a*L~ax*0EBjmrD-Hg~H;U zsTir&%pJUTgG4j$>#WVG(&_3`VEgBPO!vD5W|sNFD&~djcSwbHC>Zj_%!@ew+FIG{ zO)gdyE1OQz?1z)dZN`eZb!ZfsU>yKk3R*B#{XN-nz#NQD-$h!-vIBea$Om7>h+dE( zm1`aVjgfWeqH_saZG9wB{g~G=P=$3^c<^(VZh0kdm=$~%I3TjA0(`UmQ>q^|_=|T_GcaY?%n%F(_3`k2ka5S&M zSg|+1ea(Afx>6l)_WmW?fjw_1iql7rkj>s(D~s`_OSEu(-YDMJR2`q*%@nc>Y`|@J zHTGPsMT1`Hv5dJU&QXeivwstXsvD^|&$5v;JbFQTF3`c%r+#yZ($R3zs}$b_^(4O0 z54bhqcH)t(--H3j?VVHe)G%Xlrr^+`0N#8#rv9f+>-+B|pm~Rujxv^Icz64%imUui z(p4%`Vb)JoRJ|~otV;C;&*k!B`+wg^e1BzO+=XNu8`#JlGgsvmSeIG%^Vw4Oo!am@ zwgELPuYhf!GV3YOrWx6GGQZaC!FCv%76}I$^Mr-*fubdeo)2&HP>LWh$ngLd}Qfb!?yooWWcUYc*ZmZUkaoPXy^n=;- z@DC60oo0+y1yh*kDoMDUsV@Gy@r%TzbP$zS8ln=*^4tr2l(jaX7^5oAK=)Q%KDtH= zUBBAOxUVe^ztO^&DK(RWO~~rqwAzX>yRHjkE!_F)z3N!E`?e4m;{st* zexvhE4f>|CNTM*X1wU+dr^EdGdBgpB*eB+kte++4<#jAJsU!u=vtAdhgQ_n(x&BGU z5Vt;^-N$K>xx?(p)DLQyJ3Le>reB0}0}U|nHv8-)u#DmQa&%2qqH5>vk^L?iRB^kh zOqVz|NmV?$>=>Qs6fWGkk%Hzg+eq1!nS8+|eLNYXK$PW~=AWF2X0f_tx>+!pJ3Fq`LBlGjPQvSuHcpMT%4Sl09P zQ|P~g`HI*6gB*VYzK(T8b@(Rn(Zxldj&t%GE9CcBFu8 zn`q8>rs?>A7?9)bU&v|3GKw(wm)>$81kx%can+bB&{J3^G1ydue$I0A;~-C7#e{WO zS1*APecFVKBdVefyGh!!=sNjxRu#_`5%Q(k0RH-9VTbt*VzsyzIqAXX!%sg>ZsT3> z+^Z}GsIL@mDeZ@phl*l#tq<$kxGLDNj)u99-69od{_7w^hF&CPDvTNH@P{jsPJ=!2Dq_E7-o#HhBAsR3iC*9431NzEe5w+QIoNj{rl5GW2Q~O$_Ed zM?z`;>*N1sS;3%#cj|smbqW&)~P@0O^hdEohz3 z=CF4(yqKm;=5=V%6$+NZvL3Eb&-@!>Ke6*7K<5d+!rTz!6Zc5le&z|eA?*FK{4o5^+CWx3=!27o zgu=|V`-Pzw+0S!eC;4#73(}|6;@+uwL?z%Gd2FgCUOKo|u#Oh9&J`D7>!S!*bxM~v zW!<}yPd%A`*aoINufc+Z@$`3TFLL|z3c9AFMfec92qbG#aYaD~$=dx#NT2ote}8>S zhH%5uVP)RN~Ks|>>{{E=5sEm3-Hj~L!i5e=lO>^xIwWu=x$Vkv`4?t zU;)cIS%;IzGRA4?A(8pPB%#UJ%l8DL{Sx3hwRf%jjw#hZZe|qb=DYMTBgHC@( z&*QvsdPg4dWqV-A`s>0XzvZy?p@=#OUm=5e#=JVJm|tQXjhowp?Npi=%6fA+ukO&; zl!D)!I!J8Aa$?d?9Tyq3%68)q%qRa<$CV_n*8)@jBFw!pQE*Gq09`PQhi*NbPh6i)bpdgw5L)gEg9Cw?sIeFT_p3|8s@2psjWw8 zN?I`IKVld?IzL!8hu4_a;dcKrl93Stzb2&M?l3D-6`DXa*eqRstR&lNp)2SgY{0E= z!=Q8Kdtm|VCo+(0gk{4G`LuB6PmY@dL$Z5-Wrd0uIwF#e>Fq+2nZLSQu`4MX&RD@2 zEx0|WmU!(l2Ye>Q-|BRuNy0iKIP3u910+za4vWGKqc8-Xo8b@VI{hS+LK9{9ru@j_3Ar zknX{J_Z>bVRGi*ViSL@p z#*FPC_keN3-frLz`r6^+6Q?<^KJt*`T8K|gK>EP*8p%EIiFyp&ESt}}N44Ndd1dOn z$_MtERN%c;qp9JczhugDc6T-@3e43xU~EtH&sO52_2Wp&EHxaxUXkfnGa#TvL6p8( zPsZ+zkY-)z#AQmKq>0Picqf(x*yVU$=<3DRSYCtscKrkGKz(vuK|$PQ6h?h3^- z6;p>O@di~d$n^CZ7`{cBbafxxUQmWk4Kv7#;D_9nLv~`~PHoxFym^`q%9me|&FUw; zOEE022@Lahkv{B8OwZOVHhq;nn4zs~!zP$K%O)L2^SXt2Qk&MzEy-9?W z<@g3@{)RdIt`7<#qrv7)>2c!d8;eTxon8@&aZ+%Zz`<45Gby? ztbnmxKJ|s7g0Is1~^D zGW2i@hBy5-kpchu;ix^K;Ileh7+aKzdfrNWQL`7AZ?8eK;u6ww|0`)$X56;&Jn5yt z%&hUvg?L4I5A^NO;dlMj#G6Vcpt!{vOk%4r*1?hXTVzSj?p#LQhSv$(<}ZMxKB;K? zRFOY5^pBuYd<%cwyhh5jo{_P0SboH8H@DksD5$?@_l8EIG<1GGSElp}xxjtU#acY? zt$`Pujo^rz9HjQHLWj3wskAVh^!k=W>)8E8*Pgt5X9|9eV(dl-9g_3agRXD%;N*Qx zp}2s(_m4+$yH}hQUON21Q(nKabq&9eVQf~c`*K)Vr?diScmqcCYzL$3>4I@g1u7qO zpz6vN{JB`xcN2CPz6`Yh$M96th*jkeJz7DQYN?~~9(B^SC$Apx7nfb%PL|Eng7GZ( zRC?!e_6b!j{(h+%CR!X3UL;O}l@@haT-*%H!~)5e*MIOwoP_EXY~t-S4KVW0N!aV# zDWtr*fjcJ1^R*7OM1K$C`OMWJ9f?Me+${s0ri>(ATJf6g>iFXZWZ7(ugGC!HG3(J) z;pOH+VfNHadZI!bj9K<}&0-a?<#{-jI)n+sN^ao7WAZ!~I+fpPV}`@_bYs1~jl$>^ znK&eNG#T}aWei3u;S|&GtlgDzMn9Hnf`Uix&9$VzeC{6h;*F3XDoR)C6NrTP{BbH z-;dq!-32bck{9Rs?1Ox-Lg9opW4WZ3!H;c*d`qMzW;V`*g^WkEZ?%f3_cM$Jcupen zS5$C&k~=9pvJC>aG~=SR?PN}NHzB{_`VqE2! z56g&0^f(e0qJcV3B029ZX;8_uyF>rUJ64F7grs+@mtimK9C(ySG(Rbb%h`D46DQUo}sm|c=v;m#v$I?v(LpW=eufMuhozHPm7cS-JBfp@S^h>tl-?VC= z5jo5)KA;V^8S^&WC(Y5@av^bN&HfO{+*#Ude&X%x|0qeDWm`wuSs@X z16PUvrq48{(^u%8yb=z*YsTp0ztFDi16M1`ans#l^vi_5gx{r!M>P)1bPQ#aH0*a+ zows>?kxcKQhI{ffNLN4ChdKrEj&dmZv@=3_`jf4=-dWLUP)!KmeohrfjSLqQ9Q(jR zzdF3wvk{!H7?8LU8@yN(5AGo^g^ii)K4OwOU#^-<$N}by^VB9?{R^j#+lgKu6rHY} zwRc8sHa{~C3rTe<5YMu}hW}MSYveA{{k@`iND@k8nJ;kNJ2f;^nNB{emPD!D2X2JX`@_qLS(XMG)OwL?MWf-E1H~!&56QAmhd9q$wK#g(R&pu$ zG5`L7C5~A5ckGdiRYE`JPgrcuGO%GANZP*+GZs6JuX#gQ=V~{F1A|H>XBWR&YrI zrmdiPhbo1ynu~z+O+h(hH9ntZd5q@%#6jPS$&_A-yzzCGyRSRUJ-t5^?(3IhZB)8r z&cOn1yj?5yH2n{wG3q-m-w`BnGtVO<&!}TWN089`ZWUNv zZ@@|8YQZNpUHG}C0>O4LEy*+IFLts%`T>XF%pnUnmzs(>ky`vvy_IAr^V^(K)gxUD zoSO-3_gE569-3-_p=CQ3zK@kCe>UfZ^XgdP6eM)z(cboLz=x(aPKNsBLE_m@2A&oVnPCM0^bG006$$7>%alRR@fa_p)a zj$f4NbY<5?sLrs#*3=l`jZdX;oH2ywbt{0nwhZ!W{yi!@Qip(Ca(Pfnd7w592Q zuoY79rKcAEpnfKQn{l*K^(@Ha%wK}*pG@5R){Qhw4<@hYD`V{saJqVXIV>psjeD0Z zg7?0Qpqll&wOq;v3+*~`b*v_CJ?;VP`i_H}Lsi6S&qAnac@TH((=Zww6Cs<)N^NyG zWu`p;dO|2v>nGvmrxVFswu{Cx9^m$aznvawPlg9WYVcHw54?UPMzK`#c8IbgYC)NQ&@lHYft_yW2&6abc2=8TZIX3D&kkG z5Sn)8D)}~22Z!V@BwZX`+doOT@JBZBW6aMN4>j>^*?Df0SvpL3)rb{&UnROGn_&^V zpUro6hrV%%WEbmp{MC!6>uN6x3X^rvt&M%1fi;2?%eDO-+)R3`Jxgl-sAKWBv)lyz zEs*8fj>Dn~CC}cs33twYN2@!NVc2Rmli9qQ+@T=TlLrlM#Go8|D(^moJM|+4{a0)A zKSR}oypKOHeP}JoZtcxC-qS%x632PY*N4|ofR$O#B#dE2;%=$Zu=`tO+VW_|vRgS% z4RRh*A-jJa8oe1xO~W6PoJXwha>z)Tw*1fZF2)Vi<#&hA<&MY!E>X%Q(~E-nWl#I! z!aD+YZK49q&M!cx&(9<$(|kcq;>ZL2}WeU!jVS;KvB^LM&l4;AH z2^uKb7B1uDOqra<_8A@CQzMQ`OhyLpdbuHzcFQzPN|oYZP|A5fa&ZY6Yjm+s?=(dt20Ssj?xNS1=5m z=9gk|uV6AT8P?rw6(syyp$6|ymEhyw-{5oqU1Zo&MRBxq zF#X4}LPLDj(QwEdQs6NMZd{ZXWBX|GT{?#5$~$P|=0c`9s_>tuYT(ZDi-p^5$=@^GXx}*2@bHO=WMVzr9gzDWWCpW9qG1bJEq~(tS z(|#Ekd*&hOGbM!E!7_bmOAZi^@W*`H40Zf)waLk0>2u*(Q7LwqOovdljl?Cq13$)( zW&Bn*5Rar_?}6I=QInkca^)ToAI@jSH@sngP-poo}S%~&(?y&8w4)0;1 zg>T-gK>tu{xF=u5o{>Rx#rK|M)8?i0;Pyg6y}uvOjAWb>q{aVQ-XJ(^7qP$eHIer# zA|?s!XA*jr>*~k(yt5pKJb5h{_q%{|fBF|!DK3TT%ijEmLpnHSkUA`8p3D)3mAF)Y z5N#e5PJR|9QNQ_v!Gd`Rp2&%~c2PH8;fgsadFDsE&fb9_*oTzlRxn4R~p;JnyhW z2g7R2h$l6M&o=3p_{5!jYPTiPhH5x)Wuw#7w-;dXV@q6`d{k&FEfk8j*ovEn^kP0I zC4Tj8#(8?L3V6m8lJBXAK1V{RbVrz=BqpHSNEJSsOyLLJ(M95DPNb@3LXW&8ymey| z>3A7HwlGeDQ&gjqPv{!p-y0({NeKVs4hg*iO3>roH`&fyFq++ahE9biQXUK(64^sl@rS3MOiw;z z-hwebwD_?j%|YpF5^kF9OKxPnCH!~Xu!|!&7SE8>F>d+qdAaal zj0bPBiJiH$CxCFRMfmegMSPYYME{OqGv~TC_WrwqboJQI{FQ{o$&Y07d9D*bh(WQjK0lW%sD?a9Y~Du|_fE)ktA5z;uX zc1+V;%pE&Cg`amu0V};d1+IS&*yF)Ewa1@_I?LyR^tOmES6cEl*LBCY?79ZV_L?WGk5z(*F(tSOUO~#;|48dQ1yQYS zCrx=V9`dr(aChYb*`DmLCnr9*s>e6iCv=3$ zL#~!32-{o`<2=3)i;*d0<*qjLU%rqFH%!ekSYL?8r1rAeYjIH%hqF9TT~!~*VBTyu zm!Wjl0XwoFYB3dtd=YH9dGKIg3JL=Z_-X93wbuPM?$2j?`^V?x13TAr3`^v?GR3Fr zOPS8;!P)x%TcRtt0O1tv2C%c!f1Otx)H<4j{C{f&u)OM2Yg(| z19UXB=EZ5bOviff3OZ! z+e+BGn)ylW3P4L<6x#cjV&#LL^yg_ae#2I6#^VivUIThUniWOt*_*#Rbvvm}QNw#V zmc-=DR`5)2L!~WO$!;4hI6b8UGxg7KaZwh0PPi&|wm8dj9B1Ari%<0a$I)3wRnLDU6%!?FRP6o;K|0^eJ1I?ZV(lJqfL+-QMEjgiMIiWK2q z(NJ_qLz9N?Cg8GnFWMb965U>|2BR~Q1uIX-(n3uWIJ{#Oxf@hMbT?E%k>zvh{w5PC z{K(=Z|Mn66ce*rhpN!~$`#yfEMHpF1VqwEa6};Zt4F@zR!k0xB$WFVIlnaw!>>q#B zlo^6PZkL5)&te7tG-SJ?P6)X)lDhr&qwNxPV1D@peGu4&7WT-)c?SU2DwlO_U0aSnHaM#^}=<2#&(0dij#f9{crqjh>yGM`ad6l6PPh=oiv%uQ@bhJ86YctO1^DJ~SkC!Mkeg}B>m3#$+sI6Q^63$SY@98&88Bj= z0hSeC&TaO{f~}E1(I?SfJS|ZXI#h(*u7q#o>rlo%-FJzzZn=+2ZxVillmr=4Hk+1> z?*O}HA86kJ4?1`GAGpSw^Kt!RxO9XPOqDuJ6)zz=rm+re2Bzb!;vZ1~^YXp+9D;^k zT|ienXZ#t7WTdw|La5;(1uBQfkU!3*bgNer99i+2E(q5^EoTSdTj^&0Z^?D)!Df+j z=1^>tQ-BWn%R^GVIl6n&k=j12hL{&u(dfb_oXRb0(Kn4!?rOqlm&x&JpyfG@Z17f~ zlWi;ETY-qi#_UBMTO>q|UxWBX=2NJ;1@qHN2O!rBFB<(m4OaMkMHUNlgw4?p!L2O- zJvEiWomW}E>Ijj*n5fVVcPl~TrV;(Nqlde|csSoTH3|Re#*wehA!qe++V|lT@$^uD zbxQ-#K!g*;M>Ao*-%jNJ=@JfM&-)TDp}?~2Jy~|Qip^Ey!TsH{^UP<(?nf4Go5>tE zrt$vr<_!ZR@#hsOut!H1KL}aCdS(H1S}TyWUJ6=1w->xt$8t-2(sJj_u7DNkhBW!9 zDsH>42&VfQ2Ip{BYb`v~Fy$|;Hbz?V34F$DGg>tK0oA4?0*&oAA^ey3Jx0izFQ+;}TIK~~zmB2Htk=)jhpyI5fZTxpL z{z>}@q;!&H=p-x$eQw!G8PFSUjMrgxbbRe>KIZMN!8v@|sRash6VQf){nWxE8$K_- z$UUk`M>tXrq&HiU1AXgg(@$~HtCgQ<&`l9h)MM|~YCV3pjXqXLRsx5*gVY`w(<6Qq z8mldF{^k&*y^D3;*;=E2eLW(JZt&GkMY9SNsl@4YXrCF)xylzK?zjy6+HOuZ+DxH` zo=c06s zS8ZzlBO9{L9z|w>HYm4^F&@u!2->eE&=FJ2U=l^-=81ALA+rkV_TBNEE7a9UCmyIh@#XUFQmw6zn^RsR;EG5HY`F4>Pt_UuI0 z*pBZzpJfukNL3amkqw}${@bp=WV8?(fjeZ~{>Yt-a%f?g_{&E>? z?@gs!yfknZ<9k%}j2+~U4GmNi@xKr8qhS&1my!kDpMXAr{Ht z`6?8JF8+*8$+CWjH-87uy*sRb!>)%i)LLz!AgHGv^ta~Hua6dE-z6$g!Fp434-F6< z)_1ny&T?MrTr^5CRRFiw+t4C09XjULWA;93LG9_*DCm;{EZoYnFwA3IvAP5BjsmVG zE{HCETmlSbj zjMHM2CP|lI5lFLc$qSl0AK7XFTzFS9JbrG7d;4U`I0FJI8oyDMs{%GLR|Bu{pE$h& z4XW}bld+iYauIYiTC6Y6r>-;-%050oVT>ji{HP_^DxWCn*F%gzpFe5&7)`j7#b

>(+EY zP}*bab=8Ar>Hdb8a(({Zntmh|(gOYy7vT`*UlJQ83n$pFLpaHuO0SX-^(j;Iur*wG zcD=kPxvHJJaMK&VOqGGkJNm><%baer`U8{Og!Eg!ItmEuhrYD6yyS@M)b|$;p>Ky_ zokayG)t8-he~lQ_idB-VMT-@5&^h5~m!V^oV0FDI;k9Mxl{*#C9+OUk|L#G_MdBid zO&fT*v6JbxC|O9KvuV)VHgG5ntcRDNSE@O}bEOYq{JZ_=#d0ZZJX0BJzxE2=?ogy^ z&#U0*RZ05jQ7@;Fq{JufEfywja;2JUMnK=jm9(j$h#Xw60K!>;=pXxW&bd0!yswTE zzQl18{nA0V_6S<2brFvaw*a+Cn%sq)R+1hgEtCf`lukf!do%wPihs z4fWs^b0n||^XL{gJO$>6oQ0F8n>Xx+sgh%zbV4waIqv*HqiT!{OP ziXbtoh(u1XpwaQQ;5$!`A8TcdHcm|7T@8)sRo4f!KDGmrS%Vfo z`H9S87z6*_i$N{o;A@r>Km3-PyQqXi^GhLrzZm@}gR#s?mcLtDNOqWs(1rx~YO z#2J$3lh#q|jS`}p_V1`n2xHc7?1Z_~hwv?bhhn#9N+23_fO@za(`RLApt{HeYZv>Y zA?mERH^&;K(m*<;qzhbiGEp+)9WAv>2Rq~2T-oU&q_URr2{Vnz&V@7RIL8*azLKYv z$IAthSF7Prrw)Jo@*1r2T@K>achZy94J4q4G1&c0@S@LsC_hXMzU>)}I9WYuBStyE@ISr8D11)3} z^AZ?ZJfO23H1Pd>3h)JN>CzJ>)M?CL=xtrft7VNto|lxVH^MfJx&u_fb;5VE&@tqtJUnmH>Q3G3OJPo?M5HEV63a#Fw z=^ROMYCXIarXBO(uP0nU#7hZ|-`R(5vGZt1RSJ}jt3h-8_0d`(J12kt$z3Z*qixHq z*j`{Fw>a!B39ssf$<5W|bpoKSGS=n&AfJ5vx|(KgXo20Mb$JQHOJuH6GkC@?Pm{UF$>f?QYik%;C3m~{Ik z`4L}?R_tWolfy5_xds>Nc%~T~;&pf}Cp#|lVIOFW_ro7*UC8yw47Th1jShWgy-2Z) z^L(|8yR=S&Hl}94%(<_*We*(DvKCo>zjs%j-sOEXTDK7lUnJ36UvAMn-v)T5ro}HD zc)~J4S$ykUbE-L2o925+ikcR0!aIU)a7J^J07sOg!b4lJ)H_WGu&U)6XH}5r9yy@3 z;yw4SGYn0gEeHPM-NF|;&(hXg?J(bqv8w79(OZV~@b!)c|JS7tT}V-YA<;pD49Vx( zEwDuBg=NotM+UQGVDtQu=wIiBXsv{3Z1NlQODsZYb68$<?&^e#sV_q(Wqx1$+1e1kIeoWb@2qdu|c zvX^@ougs^7`XKzLS2#?tfn}bH=p(N}(#v`iCQ7qx_|%_hWUV}?OxT4UnK{u!_d1Z$ z)Wf~Waaph4L?7#FmWd{dMnHZbU#6Ib_-e%Xe3h#Nbf0v@xBZvfvmocsh<2 zeeH(CAR~U3uN&>~tB2|7bNOrUC9vbuCUA;eidBb2(YIsE;K@4;9MAM$p7k@joY6$8 z>3O+VUX_8R*n3j?Rt3M1mWTa|UXla(X4G$VBgCK4;$K^tA)QzA`1Ftr@|4b`QI|U) z?!yZFua_-x>_ce(#5hk`FHs{=gtMCqxW|7T=mW;IKbazil!e7yTSYO*d%hvt-*VX6 zL>Z2+dQZ%t|GU!sS%)hfce^INH|ixE8^ms${qBiTrNPIK(Fl(^fDR3n zgFWXQxPQ8F;m!__=u0Q3qkXApK{agOe3QBzX-3YBEoOghD76a_P^CJ?fr(wr>jwmK z3ZahtFwgrOX1hqFl?F1!t*ETYm5v|U1mnKFM5CiC(C#VBU&p?C|GL}G{8bRyz2!-Z zLkoE}tP)-`-)j);4-)QYn-Pu9EoO z2`EF0v744;kyG1!sH7$14{uQCcUoR1zxFmm+@v{t`EU#T;io3^<(@!_e>=&_*U8|X z--KM}Z$;Ld6ky-aT5gGEFcr-22komiXb9^M`(j@JPlcC=b7c|oyDkUox8;yp!^zZ~ z<`^uL`olob74 z5{wN5H#qMDsjybN6-9aMz{o}&-Z{4qYRD4~WLC)aoLINIp12oL~5(Yp(bb*>F| ziLZ#hS13D6Rm0>sdEU1AFM7>9X&JLO(4hm)w4I%u^8fna<%OB)Vot{ zEFn6gP=GQE!-W=6+0fMSmowT}_&(em`_k8;r2b%k0=??EC%F_AOBlpneY(bNU9Fnr8jq;YUDt!G??n4#^6B;^Q0 zs`4P|)D5)!hbk_PR)dlO7w(^qVe_R5=9=9k53+kXLk}CcU*ksWw-gfB>>fyJ^x(TE z{6K+>ueIMObWl&e#e8cH*IJQ*_F-=9D^u`TyO?{O^_$>XT|gQWSodit(#!eI>z17( zuE|SjkaIVvC~5O;KW5U;PwT;Tl`D_BB=BN(mTnYZg}?Mh(n*$SAluQ3^j+_xTGl-$ zsCPj1XYz7CnwEno@*0^fp^76}ui{vvTyp=H8J+f_0fO%<^G!cYk?xRryuaKdGGBHk zwQcEu6((!3-KOE}ewPN+pbeEtvutpL5=3ro;1)_d(!I>jsiSYHfT zyq3f7^%P%Ze6G_4B8y=fp(F_&(injVIeLRl>y6Qhc0}9xh~T zC8tHc^y74WdgM|HjO-ka$*^^(HA@z*SqjiUHbr?$7d&k!Ko*}A>4N5TD0h=X>EXrb z{6yyU5}X$5rcI_TpPJxgWejzu5bYdhMqE6>;NrK#{E9hId8ESqw0_L3#<&2YG(6l%WXjvE|yf)@N>1O-E zeEG9<=gV}o`+F`wuizW0(`OwUTct!l4=&>)e;pS45oRU$$X*k40^_PK&IwLQJ_eN zUXnWbNhWX~~1 z?x#-f%=JLpRM7*QhcaKv;cg<{UjU*X^T?32V)T?{zM`b#2hY;iJ~zO`9vOZ|kPVl6 ztsma)3dSE_OeS@<@$h$BGZM#LsB4T0DC>x!pe{AKQa%F~g{UAT>xj;j$?=)wVBSBj z#UWiIh=_blN{4(VotyqZRJkm_>B2Kqx;vYH?WaedBxutY`I4el8vF1%vzr_>Rs*-U z;;12^h?r@xe7%Yqdb8j-`gKYUes4V}JWtNjt*2Wd|I8&ipt_Jwu&n`yr;@x|XBXP0 z!*Wv7eCP??N%YC51juZ*#KZGq&_YLcW;^17{^hCl+$2Pk(&~`wpKxJnXBI??)X>6X zS~#9DskF}?7UJ2%sP(26Sn%s2J)WV-ey0carp@JdSYM^bKUs@HEN)>|zlMEzC9n>g zj&|ydr@51)Mc>4mknx2w&N;(c$Ab-+)zURhIbi!Bxe6JlD)R~(TQo(gg zA6njdh$~b~Wq#LNsCe`RTy;(ddLC`y9CeDx*P1R^skDK-_!)|@(^uZq;TXxZ@TBr$ zk0EqPA>H9(On=wcLboI43o6BN>1SQ2$UlQ3wxkm8NvWXmt`~{zyNAN3$cWml7odqU ze6FVMUzoetpBx)wgr73spiAUKA`@y($4!3>!~ZL!WloYP<%uhQvi&Ye&Yw&twJ^=| z&uR2@>^yRU6-@5gVv7f=XdrneKaP1gLw{*fZ3SJpqacUM zDzB5Iplpa9s*c{NWT0{fIf&6cICy@JC~5&O^Gj5=Hl1X3SHQS-asJ&+T|9?n)}-(G z49@B;f_ON)!2(CbEl2xau&hB79`q+~dD{iG{}c(DQ5jrcFUG&MUV($XHQ~8+ARS&cK;-)feDWEOb97~}!DmG% zoHz}=8KX&6SeD`Og6n9-oFQmh^>Enu_XsC@^*K#`r2(C4CxzN;-jnR@l^~UOiaOP1 zpcBjU_~Y-tkgG=w=pAJ#k%rh({z~vs67et<9vrpB6;X?E%ybJlm9Y*r%#fm^x5UFd z{}?3yaT|Ib&3X*IJ-Ov7o2f73$qZexfhei2r-vCocI?!>Ok!OPHma8UP>MPLn8!VtUyDKm7_P^@^JCP4laG) zZ2F;8L3GcYv2$cv$Qi#icB+DQ{;{GzY zH8zyK`7;MQsH=kB3WLEej1g@O5dYelH<@=9nP)4!gTsnns<&!<4bUkN;Sx<1;# z?trp-lE^MQg??iG;eCo;2#?rCH%zT%9aUAr6*p2)bg3+ymb*gk=dPyn)E`6Iu8&kL zCYWsQZU)1C#H;&QU?1kY8-G3m5w<(&(@BLBOC<5!v4O~J8TnRgkA3mL_c7f1^pU2DDRCNNVxl#w`|$L}DdcxV z92~LfM*RVQQIebjXsbz~1gb!X@Jg({El(dak`@L z)_5CwlI4~B(r23-NJUw z=4$3NEOyGR0++6Wx{7+ zJ)BD130SFaO!rGX;pa_OhW`TeXnsT{k%^EHeIGWDkFzR8hg1~c)XuQMxvkxl3eYKu zzd0V}!d|Apd6jrHT>1iD(WwRA&PO@>tOCNXQi7i0H%Wg-1WmE*g17!M{EcE)TD`v( zhE18k-?}D_ZLX?=MAIpz@h6bm+fra^u>|gWcNfi0X1u1e8_>ArdAW0aD&TKusqo87 zRXl5l5}clVliZ*dwEf8oC`|i7e?-b6S;HB8b=NgA%fN*;|JMl_@7aD#)rNjBOoPw5 zQrN5aBig}sJzpiIk*$pbb!5KT(4aZ!v_~mt{4?lbHa1R&TJw=;-=}0$ zwo3*s(!e~yMqj%7G~>~&IYJxnWRY1l6_Dckhkie*i{r|a;3#AK$k`dw%&d6Osk6nK z16QEwDl(uOJ`-)2x{ca?=z=edU2x{DA~g~)4#o>Flr5o%4>-ue!jffq2D($}lNAj> z&+en|z848lei_(r`c3CtT!Hl%*XzKNm5jOCO&-rc|Rs4=*;Qt0Q}+o4YbnD8n@Dc$h>=vuo@G^xPvwm-T`Rc0wUh~0{?wywHvTw46?AGesK;tC zy77EH%)2s%4}5bP-MOX+BcDa0phjH^&M6SKPZrOU)kl4WaVx0U2B7K;#LAJ}``#%HG6t+vc{!$T1IRsOkwLNeoat~Uf-c8bf6fqCsjy#j| zrKl=i4rT;I4(c95FE&Bj(++xasV%3}FaWJhp?H7W6yom~%V6YU%*)w{FperP|ckQ&Lp3 z;wZk8b%PtP7V6tMd^CD8G>l6x$17+t)Taa{9v(p4cE=zMw?_-#de zcX?xF zt8e6*o{^`rE2^N$doz_v*@t$v^+WykDZJK9jy@bC1Mg>q4W6YpRHU-`Acq}NvxN>3 zx!|=?hz?e(U~2_6AZDkzUS}1WTT~4VTMp*MeDCA3Myc|uHs^)Y3TDyJ=Sq;^r$z_L zGDxA4Jh+SqN9wNQY0$eqX%8Nx!XC$1kMi6`}^Jm>xIiR{zeozJ9h}ppVR{DxBsR3 zY369f{!aMez6Tde+R$dEpR8?`!_9i1P+KmoHjbUC5P8WUT%v z*?DUZMq%soYVhjP1+w6mG!5I$x|!DgrfOJ$dL?wcJ*BCr!;%anau`DR=S%~ywgJ@iA7aU&1-goTGye%;i>bD5c)JI=Y2%E!% zHGce?!+M9LMO_v9==S^Fg3&L^AzrnFPCT{}&t=T*dp2_^SMi5<*`)y2?Swn`ccZfj z%24@y`JhkZN>Dmjt*2<-6)SWx&I0TiL-pq&plRV|P^gyee7dTfoG>hhfQO6e@2)g- z41~PAX%6u`Wyp5BlA<#iQ~0>&N66AmsStmBB6dBx7>CSN0Xf^1C~Hk65llz|lSSER z^!yO?`i(re^+t1Q2R75X=Zq(L{h{;1TcIR3x){3j7tq87wMc)698?XJ9@IDHZf^zM z4`X<}vH-3&WF&uYc?Ku%ra@PnOM&@v%2;${2G!`35-qnx@<{R0L!wJLsJ=*;^0cXYBZTB|GGJS{C$EBiYV* z7d^vr+*&V{m^Yz__?MNyf>ljOw^;_uv3{s@jVs(m7sh}#>xGOvF9bPrd<2cTB{0@{ zE_HI7jb|9Cz!g7vT9n>TCZT$W^R?qWB2FWlQuge)oI{E}`gBBGGFZ%4!V50yA;SxD zkl&|{zE4b{bpy=v^Yu8A+P0Mr$*cvpx*UN{X9_AzU<`b^dvGSlTD3u>@^5;Xz020D zuV%hJ8@^T77%wkSg$*mCQA1KQ$%#*e+)8Eq-Z}^^VS1@Tu{wJEX)84y-3x&|5lE}D zn_N*XgdMLQ2_8NvMh$bAw^MyL`Nu4ZE^UD+pXyjwh8;&c23S|`QG7*nD!Dx?7L?MY zaW~(Aa$c&z$R`FUC{2^juMvXWf<@?R{sa`xX~UiBFk%KTNjYKqb9))ReOiRHlX7_X z%ktD}zYZlMr9?YzPU4v#Z*qrrQ;?jXi+4sH#(|6*xkG4#1~SXYxLr9ga?gBJ%kCI! zY#0OcQjv4Vi3>DuR2!IzucF~$3#sd}Dwva5L{+|ZB9s4=pnl0by7CF4E&0|WXP+e8 z9iW4m=MPTmc@55F^Dm66pDvFhx1SWoeoTa$!BddMMkTCLtN`w2Mb1yut*KwLoG44M zhaUfEg))B_fq~OHI`)W&w0yG`)oo3}D$W=ie^r3gS<6t@(=pU{WESizdV-2Fu5w4% zzx(P!F51yF+Qs&ZmznRQG>4W`>llT-50sXK}7AnIc(IzoZ z`uS)IT<=rDa$Z@&{rwN2sXH6Jxx##OAOa*$T5b66v0`}txh8N8*@JbLM9~I~G;kiTg3~wMN8jg3vhK^XXjMUOuGP(6_$~iZ zkf36Uy*JB4FYA7tGK{e;hO~gGejUAk$sDyE?1V#Jp?I``4ZX2A4N^C%U`M}C=&Oo6 zR2|Sj{=|;%ev=9O{yC^kn8G=mTZ>M_Npt5mMB$TJ%1|P9h>UZTq??qhKyG6Z4Qx1y zWPhc?sDVlNN~tPx7;xqNh1a>I`!rc+cQbs^5y$`bgNHI0YhpTcv9eixFOHp=*M4)J zLVfA%-Hnha@}fCWDP-5m3RwKQfUY*x#qR8EV7QSegga->M` z;C%%=o=`}&j;_KF>J=dK#ccYkzlof5Wj;o)iFi*!H?p{=1RB;WP}f*3`h7oRZrHS< zd6n~#LXI{(@q56fwI|USmOly^Q|SC_{u5G^!Ys6 z#Qfx*WzK$+4wEUlMbJ2ZHVxibgPKmUe21DOJ$~Mqs+smczwQJcCI@o!eMj)_IbXf0}%>a2k zPzRrXTk**2GVeRQmyuF_7x}cc5Z;B4f8z3{NGg4_97b`(si-PHd&lp$9C(I#^~~6 z6>4FU0g)Xm&VLcUKF8?!W@3;J*mN2y?C3X=tENk ze&2V4d(5hG+dB<$%JjonQ$h>W^sLbO@(Pkxk_2BDcp|H1p~y^83tnpl3wW&?G^RdfOb?xQ%cs)*HO|a4kqD)~CStYOS5YMU`S@HP^m^N3 znp^%GRO+R0%f0==3iU*oXyk$Je^JD<8C&xBg7tztmgUUaB_|U3EvF66Y*w%P3pWED z_+34hX{BBwY9&$IWuL2=S!Tz+S& zz~ng_1b0H@XzasEaGO1mLfKyQ>_jg(tRBrz^meAIb+Rxy?+n^i?Ma{PPk|%6Iu2T$ zCDdX}erx_ax+KuV*YBz^uTC=OTckqmX0uGhcLDd$%dzrH7;Nn>B;rp*d}hKh*va-n zTjYL`t@*W(tZKzyTlWIRlrg?>{dsh;dIIY-N{03nk27a=MZ(^ zbW^x-SH6)E(q$l6Fp*0u4M16JPVVwtL6$_HpufdCp(M7H&Xt})H}{K+z9cyDS4XPh zqYBNCIx!T7Cq_}3vQPG^pLoX4v~e5sx?6Pw$;j5Dg@zBB6#Hew{4?5u>67O+S5UuX`i7_1n{C z{}eJbpaOm^%cuSNy7*!Sdq!e7I&Ggm-SamQ-s&M7-?!H>kdD2)f7aCI|nda#Ip- z(W@EeU>cVv2=A>TPFW@3xOFJKsgR1qPl$N!$XGHtz?AM~J+p<~qxm8HVPdl<7e>vR zgZFx^!Y*E_@aMu-#5q?J-!V_&+OR65>l}`vn7282Q5qL_Z4-Sol+C*S^IYOrfBKv& zhGiy0sQ2$0mO+q%biW2NVn9Gk*sl4xu`S;?eH)h*HIjd5&U32|XwYWXE#hJ_3s3Mr zMmLq0L2-gKcAWejeHD{~vaIw$4_?KtUa;DAlgkB)h@}Ke`_tP9_haEzZi~*Z|a|kLL z5lAoZ?*S_H9~wKko2>p;3hv>jIECvKDCnjvOivRK&9j)kiIEWI5TcC3Dn636>lT_yjunbJYj#|b;FrAOoM*37eaFWUbNqgv82}+ z!#xXc;++45{OzcQ`rps!ZhIarXv*b}jb$7fe_iSoFM{XO7GpEDO_C})HMm<0I`&gw_=(%?eKXB1W9B8>a^5SF{F zN8cYP;;9p5;cQjBU}Lg5&3Py%spSErj;N|l`$?~MVc_{ORhk9mNM0ssAj#iL+C`t zpnEkxmEZa7GO0alOPl8Rf%rRHUZ>2NmRYkq-IMc3=gnejH#P-^Md;w8)>%T$#RTrn zC_&2R>ez^}&;zZ3!*5k+BHL$Go;bsuN$%!Kk8I-48{HS4lZmCD_x%A6pEuMa0$lL9gl_mvpw)gEuv*6eueCkOjdREXL-`-5<-g0g5GlfR)f}#J z!&~x!vVIEF)7;v78_=5qSxA=S$jVh=bjhtw(DD9E%l6EmiH9Uar_>yI#SAqZtj2o7 zS3N+%MrlNF$67T0dL%ATU>WCilA=-Plh6dkyxh2@>7X69mRrV{EWh3}HqPlOgL#(k zaev^?@i#QM)C@Hq=md*#VR)L04ISyE2wF-O=wE(t=BgZ+A-fCZx}|d|W2{AHk)OGS zy;1mnnmSB=GmG3}9RZo=D!@Vd30)#}6ooEfUb_yr!K_MglqE;V?egY6`k z{~V2{MJzL8&ob;r`mR_eZykEY`a9Oo4?sN=gK6KQzfj4Y4n#wh@2CG4s?7) zV}n`eyTx}waMLszJfZ=DSgz~VxgxVO5&M^U@a6MD ze6&IedwQ_Wspr8gU!_fLC-d;?ZXLS&p99K_*M_F>&x7acwg6>#U{fyeew?mjn6yBC_`FN}4gX9ULsp`BMQQWKH{jFz`WuN6mD@DPN4hRz3{nX!eoE z4*_1)|3(eZ!_dThKN;i+#UBTWEL)gH~Dh(QClq%yC?^RvPC4c zMnK~(G{K*A6aI14I_}4AJKnwgF*gvaPJ1sm!CmDA_)g?88vg4Md|dPsWncRbnNT@4 zlb>;MFWu<)yZ!K#{Nz+C3rSA60_-&`B7W{BRJ@k)rTg{xxxx`>uDvXT+`BY5t4G}L zfXN=7n0#SO^O{_^^|zYkk4lk{X|T^P4kBUnMm(+4{05p1GC$1aNiH)p?Id7 zX_lIh+CPXET#^wrJo`r9C1K8Ya}#vB81vTa58^VH0YJv5vCX?FBxZjs?CjFSy>mO! zJSSC{@YVsvjn$x0mk8V#U`+n7iD-am!oAye$r7&t$-miy^Lc51E+1CkPX5hj z4=;AN+P)08yxhng-z$WRn=J8@g@^E+)4FiXa1shQR7bX%{DEUb9-_PTN$9UEo6mjK zg7=1JXg=$L-+0Y{nwG4g-IZ7cdb zg3ae1CD3zf5v>0pL(^X}f8ZE78ftq0{Vhx9-Cvy{6Q%4KPq_yoURm(2?^Q04PQ$RY>5I5Op31>wYfbTFlyn!2rEnU@MM&tXzyVETszPN$JN5H_p2zHlxi*du>LG=Wj&tlT9TrU_d?WmB{z54 z)^vy}xWbLyUxAivQ-q@>Ly6Sxp>%cUAMjkt(^bkt5E=THF)btTgy%NYuS*`*u-rzg zoISm;EeHDgj-hL-(>a?f6)@fB377w2GG1@536)*8gm;poCt04+ejtNB{d@#jT}*+P z|7PM`byf88`3!z)K;qz8y1=-Jd8D=QhxWbncd)!@gwk`=ATNt+ykuc-M2#Tvj~^vQ z^}t&zP+@-(>GouOmvWhOgOo0=&r*P6A!F&GNCP^`ItA=)X5xIoI;8C)2c%}xV5ZyH zA`K3&E<)j7Uy$!i_qI=|7CgB*g+f#_ENE7y36IJIA6TdMhw&M-ws8gikL?Foq7_j{H6$&2VZhu%mV2_%MQ36_=&se=F0#Jg-|6SL2W)& zp&`u2Vm$K~Ibh4t3FDif%-ERs2wTUEyFHSBYV&f?%kep`38dnq$5LN(%hu^p?l{xg)y8$Q;RzT(~dv*C^8C)!7_c;#@d?Z31z8St@cxz+opT&4n zvo-kTkt5K>0a<{p*U*oHyXg^!PN;pkVvuoE`X>QCjV(s;{5zzxL<#OS{p3FT*wOcU zdSIln9J(i3B`6$O3I+?llCImc@rN))c&GlJB-C_~^RCt4@=T4lZHYt^H!4BrsoTiF zR-e{q<-u7!8?3X?9AzFU$!V9D)x*q25)Z`P0DPHiO0mQKTO~o(?y8B})h-;c-+3e)KAD|VdZ z;szLcT8saCHmy}ho6L)RKpkd1UhO1MQYLg zys^O^zK8JPZ@LiGGX>oft0zlYZ^$ii9j@{Bc{cW>)lZ~J4iBMczblqHbp=gYCI{WGwj=wO3+dbLG;qCGi&m#j7GCOm2yGe1 z2epomOuITT{2BDu|ByMYe}1A(t)fP;*P4my@_e=lbPBXVVfqTK*gAW8blu z@w<@3j4?F$a2>RH>f)v3IrpjCT9hgyiDg~JxGaC7&U!|Sxv6WJKG{|ZFO|O$zucW@ zzG^0aVQ(0@VeCMi&-XysZew15&m>wlR0b5?uAqm09#kimv9&j?#q%Ad7@sNyI>V|E zo+^hm&nv^F!UFDPwIYp(s0NGs-CWi2J}%(pCceXc_27K=UDOD_lauMX|6=I-jwT3W zT|y1(-=U8O6(R7zEi_tu5{)s>f?*w&*ggChH+Iz{P`_V}a-7cLMOYIoGAlVdub)JA zMAka!fwRcLmJ0lw5c#Rku+T(_8 z+tt9JQ=SZ1$8u>!~@2z z`DDdCUOI(7xY-Ifp8&aXwL+k+Sqf48*Xi+CZ!FAH2lp%osbc$Go^B(z&Yy=HsimF>CM9@c|alA2x?8+fqv!?3+Q{Tu9cL z@yLqZ4LxTO5`B0%b;)LVu8$ggenv2HUd`Uiu}ksmE^jRDpb15N$B}AE0|{g!Ft=6= zxA}!3C{TpD%qmV&5J*SwX$SO<2{9>asM*p22wD_J%70a&+Tkn*{QyXa9A@|Q1`sS% z<=bBQa-Uz0EVC6w1>O`ta@EFxI>I{kreR( zBT(z}3i2e6`NoIdBg?00;LSyHaP(OodAHPvdh|5I*#tE{`phUa?6(Y9Dc(d%_jl4^ zUprvbc0Zh`VL%H%CV)+T4KjTA4)rt7p3~x5u6c_s{qU(97QYyZCONDU=;@cj-sU^x zMZ|0zwm=DLPXH;N(L-ubHFUTr@K)uK=ue?CG|c!9-Tq`ie^_P1BV$`U%-s}8O^}C; zpPkS@k938g1%4lXiKZ8Cq3ycaAePh2**uO!dD3!_X8uh0FK<|t`v-g%-lNe5(JYJ2 zI*+>K_?9{BUMb1^)uR77I`2R#+c1pFJT{@Mb|EDCsK|NmhY)QIO^T)zm8MD=5h<0l zRMOD0M-k_J&V97Eriu_E$*N?P@8SRc&~e=F{a*KV{jLnK{n^PcI+%l#-Wrq4$6H|g z00o@<%LW>={HeIR6BAz-!>)=BzR@xt&wp&;rtd9)bTB(#dSAA8Ss>XrtFb!%lDIIqO z9|Oa~W^lPvLwwRhD6F=RqzmOoVVZZdC}dCtzl(Jnt;sw`9hZn;E)|KdRDI!FMY{CB z8*N-4odHwAa)lq{c`UwSNhUoDCCkIr@zqQR$h7#(udls{8*atIEBQUpR4>557vnf* z<2d^IYa8BumCgTsHlN-PsKR9>XX(qJU$D?vfEv$-)5%M1seE86F5_nqsqzE}U8jJD zi*~^i-#OIeDdPnl`2+tRIg9>#rGne)CUDw;qp6#AEv8Ms#!t^yfgy#zu*JQxTEHbqK(4wo&iwBmTrYe7z_x09X`usZW}RHClD}AC*%(oP*LA9T z(h#3^yywN^p72#}Mv}C5E@IGCC!Y_qT_XAlM3_&a(+u;mT+5uCoE6C}D@e!otOjVw zKSl<<(!{whe{$7MCA{sN+qluUiCb`xgHo1z{n~U-)T?_Gd$Svs;5lD*Xd^$3&25*J zO5(1GQY3Cg3!XKNC4OeHEHjvbNt=g~3B`#p<&v}{c*94CQ7kAp7nh3`!+&rWGONM- zsR}M0_)KK4GK!vl{uNi5CDKP9^&ydEflt`P5yc);dXDKxUJ7T4@?dB3DNGUVY;BpJ z(1IqCJ1ERefcuWQ-22RY> z&L^{XtHCe#DPs3uh1{>B{pqGA=6`5z2hAKI{r7V+C3` z9;3y+OUc@HH8k-UMPttYVSUO4xG%wne48puHl`|~Yh7sH4F8^&$yjG?puCCsU(c!F zgod`h8SbO6jV|0`PIlTWe)i!%__jEjpJ8*HiK+EJ&kO?qlc<1j=`9v?fmcs*_f2n0goc~fD6;ju2=lzOp61kxASil4j2z( z_phL)OG?qpdUM|l7jF~bc&Q9N?6Q#htonherv>7K%PYAD-cRM=}g}G>?>I^CT#o1c27SdXgJr~fej1P&?E|skOdi}-kfIh7B)Cq= zj+EUF19w9Ov^gP!voHK_RjnLfaqHgi{;6* z;^QT!X{gZ{&cm!8KW&f`W5Z6eUR|4MJJ~QWWQFMTs|*D1(In5fAJJl&juC&SKxLvP zjY&*H-@6GQ^UoBF|I-v-*Y*;+ZHc523$)SoNxUdC@DYE;s|Ldt9;K_kiQvs)UYup} zf$v(ZM?YE0N?PMCkm4Ch+`)nBNFKR@?a4A;w4U7#>Q8~6*KT;kZqp5iW^we>QEGBR zUb3k+lDE?FrPl;saOI>}`hxLLLWuxVoDHb|W?Q=BOA6kUo-Wsc3p5|*ur!!yB$8T4_HgpkH zXzW2pldU9hlPqt2^*V;DHNwA;enhiT4b}hs<0_}B(lSvMejaTB4_9??cK7|o=M7s5 zZNFTnm9~1=U@75ipWWvR-~GU$`xV6B&pw5dDaxpM^E!lWm_$3DDCcB$u!! z15=X!z{WLkq+C-2=Y~nanp1c0II_M6UOZ~XU2u#nuR2WUK1{*T&{1Ti>IL}yNLr#j{~P>qW7JQfk-L+TI^?JRz4E8Iio5=N4T1Q2qx#bX_ zno-P4b~FF&m&3G1O^3YiR7TtVL+H3S1~fJ{4QrL>5u+bIu#@c!3)hGCu}05r%Eo<9 zy5OJPBi>_q3eGAz4H_D6z%)&O6)Nt1b6b9*K(gjg6u;(TkMJSO;&l&60MYY6UesR)#A?%lNt>wZQ#WK>wL3 zyk(O;jn^qcYxmFeVdW(5RJpm>y7?Vl!>2sMtsrunw& z@anEC3bn4lhUP8QNS*aCUfDwa`=d`&H|AhhiVPXnRswTS89xTg!ZEQqRb+XDl&Cc@ zX5@OI*7`Cun%N?56)L@x{T=n7iv=RpUpzzxA834m&)VHe*62l(7ze~#6nqyJX-1?dafhF zMU%6^RaKYlkygXB)*W1Aohg+!VodLiQha!w64YKa5dVFfEm}R~KdP`%1r0~*QuEiT zeD>=Cd>rXZE`NRxQQMSII`%-{?maIt8*Q{@Nd3^$+$S9q$<@U}i17|<2ia0Jl-(G_ z#Uu-8+kj3y^H_yfx)cRV#7eke?gf67|9*PHuoF{*6~x(`9j#>k)nbS1U{$w}j`x$2 z=+4|jjM`=Sw==VG`v+-~^<6-Qr6}Uk{nD^>h=4jSy^X(a4~4ZaA96=tZV(@=++WzM zY0v2Xfyu#9bcoj(dL_CGyPX8$g^NnSElL?3_oPC}f=RS6O-7navKe?_<=UGzN_P(itZGsG^JyxjXtC%mO4RumGH4ix#DDO!>=_bMW=i+B7)z`!ULg^yoQXHv)sHbRU;XQG z^n{ui6SP?luj>x?ptKFOycdGZ#yOP!&~;V?6ev`H=4sZ+ekPRb<@tZpR701l zGlgHSy%E{@RAH^nwm$u&!j@&;i~G|nN`^E#B^6iuE+J#Oyuq-7y)WlRL2n0lYDhNj zIv`K@wU79w-5GeBOM~U(KEP8Q=F9yN!VL~`rg^6QBul1*h|*TJ3MVZ1ij_ll(6jo_Mi=L~=#Ak7G+aa2TnLM^gI3 z$2n>22B(c>Qn8%o&eyz@RTBowFBZMt&qI{G0EPdK^66U3=!exUcy3h}&HFEqzn`3k zaxZ*IVX`N=?Wc-*>4%~1W;OpUAscTDQXqPo!SH<*>$YCY`Y+-(QMcBgc=eJWY?$vu zPk5H2<>d(?-@kR>&-(89$YXqOC+yr2O}N3UownMn=APUgBUY9#>+|*PV4cNYfm=w2 zOe9U(m5CF><%#!p_Pw`J!c+H^pvq_loj>U>x;O`czqpiNZQhM?E9wi^-5gH-C9?O9 zi?MxLw`J3356(~^}@09%20g!S>Y8!HlX!*4+V9iq^M6Iu4WHy88NEe+L)IUEehfVGw^i!I+%pvAL3EY{^0 z^XVY%&IWGmnL2#i-bmwy?;y*V$M5>MOJtR&GhdRIj&*M1h|M-B(iW|X?+YAt+zc2eZw@mwweVi1pwRI4173eeH9p?tPZtgrLFII@_}`Ixyj{9Jy_=(jiRA@w z%s)psd+H6;d|*y&3)Yb{ztmA{{9>rnEa#VrSf{FS1ZTy#=iZP0;mel|h4aoYrEfGV zaevJ^TK}#Ea@oFJ+ojy6lbnWJJQB5YyfP-j4 zsF>Y25O%-QC&D83j2;@zot|hy2NYIe_s!RZ8CR9y$9jFSlv$F()~17+ifhllxjk()>u1i*4D(4 zKCxWYBPD9^)JQT{U?4hv@-|%1QNZx77~a1sgzCw4;QMzy^y&&*Dz0Q*x69KZ_2m+p z&z_-4ts%raMV7z1F&lsOu)CRtBDo%@h|aP~(A=m%mt4P%v0*l#ZTg5iJKbL_-s4%| z8GW5jiX4Iqf|L2@Kc4eOQC&EBd_VEbX(ix(pYiSi-Y|c`23XI@V^vH?fpuO4ZF=_`SGw(^rKQeP zP5hOylz&j;tvzt3j6KJ-3gLHJI{$293O*>bAPF}UVM|p%iT-+N60dcqAoueZJThT9 zoTyVH`aiwkxCPedYsH9<+(_&HB*L_6G~I&XHDqGb;bnSR%jX23fqvnd~oA z#?qH_VOf+FU0ESQlWRPfea+)sf>Q9;R#VVc)*^Lvtj{__zOZbdJk7gfBypEcqq8ay zUcbJDhCltt^{@Tm+KVaT{p+6hY2eET^~b<>K2U9ShL8AEh4Fen;NiduP-4DN!{lRJ zZrwV1yq_9A|Ltt=dE|{K^>GzrT6)qI2L_OtznNZ>$wd8|N<{nP z2xuwO#!!&~xKBu@kB2s5!0f$XXLy|kJ@3YKD?EkzUXLJiHrxN-hVq^k%joKJE!d^m zNWU%(b*v8+-mAd6?+b;ew$y{oWdXa%hVt)TE}N|g*&Nr8z1MSM0z6Fvq`qlyQ*@nBsv^S+hx-qzh{doNj- zo-v&4-=mE3-64GG~8Fm!Te)ALFI8utPAC3x#`?-?sPU@%~vY+=KFGUyr z{feVJE2!M5LoiiC4Xy6x!OP_abj?@RwU=s7gg*?x(@%g)gFHYwD2wjk)p6Gr>#~5NZ3y9V4P#$yOVErXv80~UUZp$JTH1xg-_hd7>`_^Je{hH0i$z4 zVZe8O$DSeTi}4vs6PFldSu+}^8%<4teduhuT)3r|&G=u~%lx;h_(LnPw6hYI=2 zgA8ePsf^^^-kZeEEQ#xs%0W|p5?M282ia<=#`2rXz-4VIpM^Q7dWpjJ5&J=Tp#nP9 z9Ow3hAElS)bmOEC$wH6ai|O;-6}ZdNoesBbf!VGCJi1J_Z=O$=&%*UlYe@9G3-HB4 z0VV%p`t%bC$1-JuRY->#5j{>6qwK_|z}~-zjX7g;8Jy;_BaLZ&K^2yqI3etv=c6+8 z#o?olh?4$V(Odd0$XV9Y5u@ViN$qU>Q@56&@^ffCsf0@o9f9-uHdJ}07?aEfk}#Fa z+$S{?$pQ0mq$1qfVRAL&9(+B`{r6suj=#YA*R0}&P78OyO6F%6<+z(~8x~3{CUs!0 zPAk<8wWXmJN|<>&8*Ho#-skFiREVUg|*T1D3O6 zn%me0HyES-hznrz+$L_2eeXPv7XQHKF`m@Z;tburj&+pmsi*QWFF^X3GO9%6!rN1m z=qAR;E58^;>>ZG!!!q#a7A3M8;>bu#ZM zcZc54NX@T2+jp z+6-0;%0Z1WXZXewT>Thdx@&$n^M)lee_$d1g=H|Kug{~w&j%2JL>cc=g}$4n^^6=m zxOW|iyuS{PeNe!M8Hb>5*H+dQ#rlu>tB@)g#?V}YI8fyo)a$Uu2~#E9A$5u~igcwS z^=|x^k}Mn<+8{i*pbo7<7t$@)SCBw$b$r~R)Tf8XEXu;H-;BQfy$c?!RYi+EaZnzk zLvOOb{VdjvHF(ZQSW}>lQ_=^4P&1vr`C@`^p5$|fE1UR>sol6n=c-WP^ay4!KTL4* zp1z%YadImj$oNkES8n06%a|@I9S{G8)$&evvhkR!Dsk`#2K#tLoLQy`y;;aOC8nzg zBj8z}51qoiPyb4f3gZTTg#rBqxbM^+{-d0bCbh~-(zRs7wiO}VuajnCb=_*tAyI=S zFJ#QasUf7_vPinyHwWA6`jbTO6lgod`aJ{K3}ik)@!B3-dY^Giaz68?GFX3H)I4tN zVoNe(qzblvSj9AnA=G#xV+G%OMJ;&~7`0pxzbD*+O=Wv%_T+Z#*Aq?-%rKx8?b+yZ zs6QESz67pEGY^BGE>u>V&?2U*aM~AOq}_ULiOe#s#?c32%(yyoGr-XL0VIU6tUAjGL&A1?n>z&X1-A+;-$uGpfEkt2pe^?!%? zbxs9%w#^3w`(hz|3(I1hpCjz`Z|h4M(Ux_C*sqD_6^~V;nRPM!SH$+o8cnodCz$`1 zwecfwrlH};NhFQ!PVZRm-lyIZ9*^EcH+FYmW~4G1Gpd6R{Cx}Gi#*{K%c(l<7NE|= zdBR?P$m`r6IHB2*di)#B8RXSsv(6hDKVUo2TOz@q<{_jxS%;5z%0$f{LXw}`kIZsl zdz8v*_!X`}Uua}tb@W|uJ8TZ6-xcv%poeh&^a6eX>n~X1F@Xx@@VS z5N%gV#fhtJ$q3$`7;R;}*!|YR-mj&6gN7Jau6YOX`wqe4a0PVbE^{C9j?#ZsO1SIy z0%78Tjr_pQ&p7hac={x|3DW*k#QDZdFFa;Pm&#^gebRcec-;lCEE1qy-e8G;NV>#!iicr(4FP0w>EYflr zM}66i)q?rXb`H$rRn_wGL-$tlROu}wk7v&*o#XH_!@K>! zgA1GHFV1(&@0;68*$x&zWil;Tdxj>@`-YLRZ)v~74?$*`3Qj$F2MiwCQ!YwYA}4j2 zj2g?HYMpnm+d-H7@H$Ig4A92LS))Mi^C$jb|2tS4<_)L!Ij~+fd2~N8TX^hb1f8gE zh)aI&<^LJ);!UQC> zkOF>R8afBhg`k>Gpv3x%J-&Gg-%T~9?)wB1&&p*~S#1Jv#r?6`qzHC@n96q=6{7zM zH*#!q8T1TeUAHHFK)>3OhCZyri;Oui?$H;{%AEcD7rlWMu#j3+b^PG(CH%2mme!e8 zVZ&5A`bQ-kViR-3Iqp~Z9lQxO3dq1guQrg?KU85vrL#Ey#(VD4TTMDoBO71q>JTSA zAx)h91-&*)lhm}&u&qKKqg+zCi*Bpv+ZEk7xhR7BueOk%ceEPw-;_iuXNWFqZW5!{9p_=j^H6YLxoPU{D!xT zCX>5*S760Rc2g!ppqDpN(#5#?_s;jt^UllV=u*6gGoJblhW}xm0_iS%L(yU{b& z{UnD}ZbJXXmHgbp^_Y1)mMdjEfw(|rG>CEL$6F1dRfbKdxb+!zu^S7*?*jbUm=7z= z_Ru#r?Kphz0g|!6fa(s*!PugKXD6R2`e2Pvy<@q-ff>8XVAkmxgSNfs$|P80%jI`{M`EsaLbn^Q1GG+@lXp zbF{Hv<4!m>Rzf!}YGHhGRT4QPfF9!0@$30Q~YY8bz2Gc^t9L_5YP z4!YXGf1e>QIrB6VPHG59e4zm6t+^`f<*dqz8t`nIF@54Xn$sCljjl3xsh@Qqv9pts zY#5eCR>eE>E_+4Twr)0=ldnY7oESfL`Wn#Nqe6=>6`^o>4cvGHV4>ZJ;=-ex`Sm1f z9r+ns&kdqqM&&`Lgk^tbe&f%%ET)OOWF^n)vdJRGcK>%M1rxOjFxFABR^`bE(4t=9TpuK-eQm^suB5=lYhxI4NDSt-mt*8RqqQ2%Cnm z{F+}hw>V7^4m#+HGtw7`CXOCU4-_?_t?YA};c%SNA~w$_?m6=6**DK$ zviC&SLDR^HXV18GgG?k6edoS;UUOa@e-Goil1+-#f87^UI~~m(W=!gDEJOFwmheM2 zhSF6B|KOeMH+12ciPVqvUHUC70D=2b`cPU*^7e5IDS5=YZiQKR+iU>YGF3o=k1-BX ziYaJlYS5v{U(qt<6!bDzw;qo`@1l|1!VoIHTyHY3Rcfx0+PRh=9d zpoBjA3!t&smRe;?uxx|}Y0o;$ZTi4Gr5gs3c=xj;NH`E{+^sQiPxDf)~>%!f4hSO0?TQKpLDV2FW3`WMZ zW0T|>IrPkoTKg8_5ZhVA_fr{c@=?O@vA*z8%91Y0{En@rN+de9hLbx`h+9wWge8xM zk{gpX@cj7Fjwv#?PF(PRz$S-ND2|M+X$$oW#d?r`kCf@g z(}idmRSnv6>mXW{aaQB7Z=O4K$x5QuJmvVK9m0ueUl~VHldkIWCQjWd=x1gDwEvj*6eJ1y_C>JijlE=~&Cj7XxrSzz3J92rCsY~`w{;^joCiw*rmy@$eVJ+)H zz8*nJ+$Hq2p9IC@Oo&YmV>&bMvFckRc$dF{h8X-pgU}SXciM+0upH>p&DmT{dIQ)p z{qVfCF+U+;5}k2LUb1A?C;B)fgezWdF21AG)OYuMkfV-MM_mLL&m_Js(O44Gc9b+s z8A_@d!?u7LvCNShwd15D>xSk*M@~7vb|UjNtv|^;2kK84>_tw#LgZ3+W2z35pn@m#(V*{MFJFksuK3HN@{GHartz0>VjrmxpoaY zNaxWZW492aHNC9AEb_D6nICF}IJ#>QS+rM`G_nrOG%g5k4A!CtO0sZ3!6$g=H5Q)u zHR8hw54ag$lW66e&p4w|mOk^z1Hly5O+4oVZ@+aBbzdVZxtMUfZ=UBb$ii-0HxfE^ z8@b!SSg+r9z^zAR{O7Snh|ilqP!S6ai*?Xt<2z0>`2r1RT|86DpK(!3=hM>~6?o-_ z9NnJM4Bc659*!^LbH+@f@meCBuNOv^#NU8r>5QALdm2)L=hBqlJt*_Vi;Pf-7A;LE z#L@Y+&{Q&zNL^6IuiGDT%_B|d0mkQ{MIx@nRS6c#>53zl+lU@iSWug#O;|QrOn-F7 zQ62dlY`DCW{0e>nVV4x~_VfhEG_$CAY`-2elN8;yb{IHA120*; z;64vhqKj7D#u(vgPQB6%M4Ad%Z#0a5`Z|OvO=Q2Lu@Cz+^8`zl5lf=5s(2}_2PsKz z&JprTPmXWdl7;rG42V;xfRGg$IB}H~L^Z0>tnjZmX!jMs^WB{Pp9owP|@6xOe*vVxGfG+Ev0{&tZ7Dg5*>BFlw!_n7%w|BuRfM zCqCmkk!+D}VLg>sNqI;tUAQY1n?#eztr1BuTQ3*y?EMVaOF|0%6y)R6`TL=1P(7Sv z_g|@sTH(B_!|4u-udGi*kw&}g!`z&4V&jAAydcAzD!gw;|ELs_VPH;w3JUSW=y~Mg z{xXRFql5=#H^b%^mb7~CcU%*oLCh>_xTaZ!7&kT&axV-eR#Vi_`|c0n^qVqN`gsLj zGLWa{*Fqt*OI2c0eV2rtT?ujyPU1@eWt?e&1|9vj1wS62L;S+_(ip8Ts8gv#4o7^3 zHpZO1+`ow1AiIWEUX+s9w!h=7kBa&3e_wFwItBWuO@|DxRmMDV1>f6gKIUHzwsi-Q zF$33wtE~W~b56sa&~5ZoK|9KxT-e8<3hqipe|!ra^WTBRJH~$8ewTZi>Ov=tmzC7D zlyXmowhNQaRANrNJRRQ8llayt<2^|QKmKnEe@ma;aJ_brh7EsVSDXrtId{G_uaXn{enwF^yWiiC?xe6(7WIB)Ov5#K%k>ouZRK>Q^nl^}ix4?ifva^FDzk0u&50 zf!V7z&~1*tFmO>i@YILaH{|1`#R**FPlVO$1sHyJIN#fS@FYWCV(48$PaO*3W*jgR zdp>XF65eRgU00g1%JLv-Hjkv8EMH*x=mdG}Ka{*xFLFN+WBKLfQSeD0;nXb^MpEsG;GQBH>N-rJ_BfS-I?luXGoEJ<}mbWvnS}e&q zZ9w0ed_~)andI#aB{F;hV{sq1g5Eslo?sbCM%WWL;_4@4TAiA+K1KZC{C+?^VM!&UCPi{Xf{)ANPR1?mu z*CX*6j3QE+Hx>@UmY0j&Eeb5HlyNyci`Lm zpK#Yo0neJNbG_Nj_ld38&+$9IcgGk`2sKzT^Cr!9-$Isdmy!gOjSx=`=@xd(J4J`hABD>Yj^(b#RPcGL zKBNAX_q?)f9_;LrN4>&F{PNa?^!^VSi7CB9ij$JK@(Wpb?9xmk^I{wMp0A4U-Uh=| znNoh|vm&%R+65k7M_|zv_Wx=w?z@dTEMpzJTcx3Q&i@d6#-Y>R^Qr8{^mH@(zWsQ@ z_j(akn(}Zq>rqc>O@@S70*pyN*T>%;tKLsCQhhD?JNcj}{9zS#%-gR?caPGQ`N}iEX{KMF*uV>872HD6r0=i`K@`lghbxfA~Hkc=i&S zTvc$5EAt88m_U#JmX&z)42WOe))1qk;X;+5;S>zC=%PgU@)=EjbqK^~tJUM0c{`KP|9!58l`Ve^+Ru60Btb`FZ=r00mmlV1$Q1wRaU)sUBb zpj;isdZ*GMa~{CFrAk=&p$LxjdLSRkO2i4LN!nWpw;xk6YrG-3yz?jtDPa9a+&CCB z;yHgVG#&GcBjNe!@!-k4H;YX*xTK^5^t_3j~3Wh$bz=XC`(8^II@7b*(%Sf9WC^eGm z->$(kqR+f#j~i%l1H(e~xZbSLp8b`0BIP6hRwE38QKfaRr6@>!Er$WBje;|FWZz37Hu!T$t{RD6BD4<4uA_TnN zN}XjGZ}8blQX{28$1FwsCM!h-&1r-IO#ff?xSR{BoI;)7c47_FmPM<+3um@eVgi4g zzdzfP9KFeyPTqI#2BpG`aegQ!=NnHbfCBU-M}R^?5+ z`>ZtFjzL7y=}z3shvK)pET0%4O=Z5Y8~x)^WR%QaFgn4$t4TJ{+Y9-s>?bx{deEoI zgs64k`jPq|_}-6L4HhsT;CoT8#$H<`FS!veqRlxWT+%gjFHI~F4P9TO6L&=JBiWqlrB9zBZr{d?Gm^|zy{CWM6Kb4n*!S`#qNB@0;{qIP#a4X%S1o+vP^zTHM;At-dB|v zIIN?N!>>Pw>^4LCyfp(y^XzkC3@gtiil`$F26d$zYCk9k#ZfI#UNDYE*!QrG!q@OI zr-)@76fnAJ4A;BE8!u?YksmVo-aBb7>v3?hJ4*w;=@P|G4Xj*Q4As8B`I3W-(Nr^& zlw95bC5)lEdqEJ)atxrMA9Zm+*L29=r^~-fW(;|Uv7AWOkybnsNE}B#<&T`4%n6FB zFgfrXrCFOv6w_hmSm%@cR%f2GNyE6{nMAay2llc)4#~)Upm0i+^6rc;y@T~&G>(OO zV?A+~~fqh#vv zi(L3B6UmT-2W0N!IxXe4 zNe=gHAcG^LMaR_&ald6Z%-b`NfWH#%6W4G?MMm^{OBKeL^@sQuO0ed>uDGVBs!;#V zSZZ(8h_Tl%vktB}`ec}iB0|i!@RE+8^%-X!!nX{e*;-Ase*GIVq7`;Ro}d+$?@JoUWEfrP+@}UoVGHR`!4g>~GQy|4pPG z*39c`b|0>XEukK#*w4J-6wx~+$Ez1+pn3HOGIqKGkuhLd<1dq7@;xP*A}qjg?*y=$ z{EXZ6XRi2QL!?mU-3h8XZ4?HjwTUukzT?gA)Zq3P=V`k8JqTca%h}xz;Lr^_dbC;_ zi+5*$iio&TdC98s8U7m(ggO9?GbPSfLsp1&D`l=X7E;=$r+uxXN-B`DU_@ zP7KOM4fq3Tk2ApjoC0q8STupoOr6o_U*umC2Mf_s6!FxX-JT3)wvwy(k>2ILTKnXQf znz`chuJpBeCm#6sAILnd7Y-U)iK&e3nj5l|JYhbB;g@sx{{ox%!BT0cuf3PBZe&<5 zr-nK{H(^}j0GhKT2d`L%Nc(c^94j88xEe5?RVW6y~88wzQ?wY(%W zI+eau2;nL;&BUu^yZi2^9;5|jHXI{wu13=E@u?UeIf@*6bp?EHE8*4G4p8qplj@)A z#zPOvp)U4tgikJ6PICLq|VgmN8E;Psq+ z^mR6SM?QR#oIhzuO{yrGE}ua1*3`m@5(TV&DTKtyCiKm18OdkQZyg}C0VLRc|ydzY5*Fli~tBQBci(z4@0X1a&y-~sQiHEW-EM}b8 zMQ7PN;)HBk$oxV=gD!aHGmbiB-$YgYQ;?P#28-B@wd(nFt~Uqz{X!E?iw@!!)W-8~ z?^dGErdT>vq)V2*7>TE!w1RfLGEI4rfcqiilhJ(mK2@n1J#R(oCr~V#oxGC7SZ*Q-^U(UK#efjix&G7q_0{)(n z!jG_@NSC;pNXWN8PC#T?Y)>^W0urm2I zMh7`sR=sI&0@FI&u!~Sa=o=f7pIAjZ%Bc*t}-36pc0>@ zjRs4-9nd3|LyMAwqJ0PV(eU;*to(MCu1cCf*L_yR5e84-&h4dCBTPziyC;EE$I0~lclW|rug{vIS@wxS%it4K?c^{lXuT#X z+*{0VdsdCbUPtM`y?3F|TLsIWKL^n=A^q+ zwQ?prlMK2SOIveOFgw|uEWOF@+P`!$FmFB_-T&!MQDG(;2cCmi;|j1~8S3eC=W?bI zBdNi9mcf7J&+8A?1O4MVIAuvG44giTf7erhw{2FE%HlFe;25i4b3dprx1x`?WMitpmvBBan#U8k8Uq6Sw)d2_7>OkSFfVaA*|k3GHs>o==)WKcDPCh1N-M&7ofSJERkYrSCWGH6)yxmSn~8PJq2yJ+ZfG5rJH3p?t!l*C+fP#a zPXYYlUujtWc^~;%KZlqG>tdBbKGX;N;g8Qq!Om+ViR_9ku&S2zpw$SWw^LaDXe+8$ zzJp8Cyy--{bc|`0f#0uhL4-Ez6rK|+db5b5A*19aKeyhXTJ8I|dpk_UVJ~~QBi0&p z*~J!|(Hu{%Hb>ImH&Rgc+Gz5}^9rP$Rl*Mg-GH~8Nh^*pUZTa1zS%yFbyIGra)JpJ zS|rj=8BeyDi_UxH>_589@dcAUTS3{f3tNVi5%bRTO^ z($s6g;e|4udovZnY{yV*v9x5vvEN{zvrcFfpNlhO3_++iinNc>#Mb%NqNktx(OR=A zJT*C-)($ubb`h$mzWfbr-E2TZT(dC2!IQXJ>%+d!0$jB#0`45lrqPj%Z)_(`);W%& zjXQ5*i9!}GeyX9HKbc{QEb)`%Ux+I-=zc-}|#3*J8)*0;AuUC_pBf^s-e z*TuiQnTm4{EFd0P>%sey0B1Tx^xaa|W@O{L1=3`QPd0DRq9B<&rw5AOD-w0~JUuG2 zj*IhgpdPF0e9A*C7w`Mr~nf=|3Ki{{vH#wU~>cYB-uaz!I zQxss&>uca0G><-iE+z39vWHw8eNYseT7{0rqey+&1aiGy87nr)K(9~c;NdD<9yS^7 zoKgb0U5#k34Io9G>)jC!qitL`j#I`s|T|57^YH(&14+ut_`Fx}0MyR|in<{kfw zOM(aSh27KWXe`Be_Iw^AVam{5IN6S;2gXH(+i&`))f)lS6g; z3KrI7VC=AD*k)7?Wh+%N>d$7bHy>J+R*ks|YP{T3J=mGqjvA-$5MRdA81aX7S;j9X zYDsUQ&RhxGiy|Rh$C8GqW@AcaKO!hdCO9S zu}U`DnaC0UpbR*7m-SEi$-zXrmb$7)ONzZVgC3Re_A%YqC3RKQ_R@%4W?7G0_v3km z4Z1XpX>qT_JtRn~6gD1bbFbq@-!0X6a0iNR?<8LKDs%_Szr5&>BaW}iK*Br#Zye;H zmwEWIxE)J~FMK}oO?YKa876E$AdwP%!M~r849LQaZad6#2fMe!N>zn7xleBU4YfX6L{hD8Kjrl`7O<_P=EEM~( zJMY&sg^uSv>E?rtc(8IGZT%U*ulF^P_{@@W_~-b99Kd0iu=y$6SRz9sF5YB}AakOX z7zpYtC#8LO8i>}cr(Uyu;)K;rpsndc|I0|jwYNq=#I#$`%$`%F=Z_QyZ{+A^6?w@> zy(9Eg$v&?AgQ@uGb!q7JI*wOp!H3ePSr#LbCdQ^<(cYf5ozTk?cmG<0wsygSTZm2I?IntB_=QAaf{hBaMCfRzD$E!w5$=_wtEQw1mt3qnI&9p z9!acg)p6Q+*TUgY z%W?QK1?kEqS?Ir7p2!(n(ar}&xa5rlN~}*nx32)VZwcpm^Zs)b8}V<$DABOm<9u=Z z7u@yDpSFbQk+(OEu&D7Lyzo$^&$ZLANY0bw`fPv&n-o|U-~ecNZ=~x^vo1mp1=6)B zn@{OseT!9JV3~a_R1rlS=DeR<)8I(w&FUu+xLAvxf0@WFU!ov^pu=?bm?Nb5a1XX^ zDkATaocT)kJUl12?thZb!=J174dZ0*6_HU=d`eS`@;UeONl8hil985%hR`4-5f#!9 zX=|%*k;iQ@^Kg~FLc-&tU^n78{ z`UTV{rwm=13=2)|e!?{N&aMtU$nU6{NE4kz!j~*5iRnDX0&8LKW9@Y?R$E9_s-=Y4 zPT^#jb4+2{pma>^kSFWe?oF2Upe1cqfu6j-YH23EJUSX?9V+3zg=*u6aVPoqKAHRv zSCR05my(P~nnEU=RmF|_(!gq`HBB>TjJ}b!WRK%nE_JR*h`km<3arLU)YvyD&_@vz z7s^mOc2B?K?FoJC!MF+j1LsTY4DYa^!y9fIlJI>?|CkjC?!mD zyhs#Y$?>tuJmwn{5^_z8EN)cAWvdoIPanjVad}uYD;Gw=V{Ucb{Gva?lV0uR)%~IP z;+9W=EAtm^oK(&_bbP4oo+41$t%{=?-h%35F@2LJD;Nj=N7RjPb8k-PZkjK&N!SIdAIUbav&g*{6y5nRlZNGf7oW=md53Kpa+O*z_=xEHYt$(TD$VoW+4vqEQ0ECmak)7!^uHW z+`X5qPwiV3x|f+0+TGI!4XIY_-oO*n+rz2J%6$A>zk#&5lz^6E9%u%0pWZM5)jp95S^hg!j#3cR}BxG-sQ1iWQ={H@N1cz(c6 znqj9Qe0o(vbar{elnr)8I=9>Zuf2pb?dAM7vUY74ZD~!%d*76a)#h6;FP3!`eN}@_ z^L5m3l#Fn;E(#)o?(n~-bYS0&-)uLWGbfktGjF_1B)?SCfIb{7651X6NR$SCh9`_S zZV_^$cRoL5)ru0oF!I7xmG=3?et)nE2~aNuAC_6L?4t_z3Z~L+Y~R=B6b?

%@E1 zK4a^f-?p10UCEst(vE2h9*7t={lQ>r-(?gf&EY$H11Cig;6Fw5?9vQo8VaBOc%4 zO`~S}^W7IkfSUDCeuj|!}frOB2G)14~c(#=vmfl zdAXyb_dNG?PQ_s#ts%c56LQ#{D9C@Bt&PrPHjc;(b0_bjW`DxC?UO8vw)o0HPyWb> z^?j@DJ57q8N3xla>FWNeWJT3Lay)_YVUpc?wU>D_I&qw-9NB4E!neIh#l?$3o7`W@14)DCKlpmt!X6r z?-v-N%Q|g0yF(9yOL5T;3`lGTDUXF>!@4YNRkH{CS>~kKn7s>Q&)5!oE=?Un|KZ$P zZ)#C>6h2K;!wDlk_vVk5xie1PpOwTpT_4=pF7N5J1K`?{Mm2QO@Wwb5;?_8tj=UmZ z(AmfEY-s{xaw=k7|0A5PHDlL@G@#y=U1GV|Bm9c@e{iGwYTEbc5aQjTjfs7$;bK55 zzwtENmF!qY;x+_=iwygH=AC~Yx{)@0xP?lJDrE7sTl~UG_U;_~0k14;A^SD+NX$RV z#g3XrEtYp+=;3JbOP_Jv+v(p>X00cc-Ls9v*LUN!4fn|z6??vRVj;R-4IpB971B0F z9j`oy2mRk#)X_E#>ldhy0=-eN{HzW-y+6yXPI$nZJm|o)52M9$gBaWByBrSg3g+z$ zUFpvYtmiTNDM^sK$Vo+BLz7jDNt)P)bUA8ax%4rZu29JzuS>_>msE-4r`_Pamu1s- zYrs<3cvh+pPMEm9Fd{IxO_~>m5pWlw?GQ{GV(UJ zbmuJ`6J$+-z8xXIU#Vdg%Qd8EyyE{b&f!A~zV|#I$@tX@Rq@=A!O`@_Y*h^Td)(G7 ze>uN*GUI07ccG^(+9C7rK>YTp4aTl7;^R-`m|;C!5Hu-Jd~` zWqz$Chr!9til#+mVt>|G^&W0<8PV*XzAO{`Ty@Al<{MeJ^BA{opENCdSB^R+0pcDH zjAM;F`o0R`j~4~g8KYDMwcwBB`4KOuPm&a!Tieb>P0^r6=bLcGupOjsXBaIMXP{$^ zDp{9*3ntkr;T1bgNIbok&fG2~_!`H6k53W*>}VIhzPnGXKTJeipDN?Qqv8B*tNv^^ zCldUOWF*Vxe1?z>O4zwR4b--6qtZ-EubZ%ooKaV$WOW8M%c+symr7x92;+Ti*MQ>H z_H^A8Ss`ouAvm?LMf|q>Gwv?-7w=x^Mn0TT!?m`1cuN29+fR!G_mwh|s-1o$*IXTc z9LNDJ`F`|iZYGW|wIyq-EkKLu$of1_m5ToJ=R)_O3Rv)78Eu5=;`BfhYBi&l&GSIzXAgx81-3I9_z61g!stgU zZS>*xi3F z3Aa^2_jwNDr-rTkJ+&(2C)v`EE&HIqi3Zk=t%C9hW4fR-2fu9#AZGRh;qpKgoVWi7 zR25}W@2P1x!%LHxj2c5jYy^C$^$yPTO@LW{6mjwCi`=Q`l~jF12ma?ho>MMLyx@o%J?KZ8xEavqdUr^1n(2kWcT`*!X$Q{n<;CNT{|?%JLX}- zO?tiO`TTp?xFBW`r2Z)5MzUPw-D?N<27_08kPDl;66GXjHB(3}(@Vz&<-o3E6X*bT z*O)c%09moVlH2Dc66}{pk+ZADOFmX=p?Zud6ueTQc{B3xU(6C1GTI3SJyO6DPdl*? z8cx3-YDUpy#wF^QNG(lO@nAqH{A^f8FHRHiRCO5fT>7X`iRHe7R5_A-P?6lS8YV`H5uh`lmMH&}Ny?V>kJ&pL|h$Z(Z@g)7ty#3$aT2tRu6zp!R zVntvXq^{uT?w85fuw^1~vxz0Erf8x@>RM36xBSU@cW~dz4^SUA3w+ppT<-pPZU^%u z9Mb7PXP5Du@%@=J(Y^xL;w1XKxdmcUf8n0Dl)O6_OWh{tVf}!uBca`g5xjaazz=f`ZxaMj7K!0W{t}DMw1gjBr+m1Y3 z7`V0f3?F%jc_4qq_xc#O>K36!ydlZDkk8F6V$8;w6q*m}5N$&>>^l4(*Lk%MH6K%f ztGi6Ou+QNj6D5y^>Pz{}%E46Wjk=(}shV6I;0=$*+7-QVk%69lXx~pwSp6k}Jj)8B z(^%$fjlUj=AD0ftJ6U%ArV$*Sv6gzhlNS0OyadI&1pZ>kH*{uv{nRi0$(a9CFm=j& zKEuS27O|cv zxXn6Cm7uz_z)X1k~N3X+9g#YAe7HeOnF7Y^4n@XjYv z@x)4wSXlQgqhgg^QSIF3_gt7gOhfL$ z)+$tLI07%`%^|+>nppq$ig@)qDQb4R0@WH!=}yaiU@EJQaHJactTm!Xk1{Q>Du@iV z7yu!HHoho52RBNKXrHn)d|t0hEIy2(mqRIjd|V2%74k@6nZ4G1Fu6o*MHwQ&epyjPf`)}jM`4L z1Ed7StIx>re$)BN*#$UjMkvwVtxU9&G%#;VA`FYyp*6<}ann~5lD%vaIO#TGK;$Xd z{pdWk-SGwYPTIpMD;L7YW_gr5E#Vb-H(JH~>itySlH30-a50t17$diqJXz&S&JO*F z+s{Rif310Ra_CnaTsnmee3lGBOs`N38vviu;^{@%zc^mw9E@1FfG!wiAq;L2IN`up z@@u{l9_gCOuiP<-PFyS!bo3M@S8nPPuR_M>&(DL8XI<&%Vktp+!}tiZX(W*<>0> znU^^HFgduZic@Cai`RV*^q$*Bu3Gq7e<++^s6xr}8z`i&g5}pGu#B;?n}3}Vzv>95 zw;p!lPx%Q{`-ClxIIfITwH$VwWtqN*Qo`Wlsbq?+Jg@cRCK@zJ$oi)WB)o$44n+8Y z^kX$TO;^CPPb*kI!W-_^(MbF+~n$+o_T9;J62we;|93Sq#Z{}(J*NMb!+(x9aH*ZUCIwo-f@c$x|D{KzM?eZqyyy;eEm1u(W|k%YEG}eWoLQ?HlB>&0v!86noBF5hZmHmcfhXXfs};4Cl@rQamyk2<((v|60jl2p1X?Rh$r&$g>>`w#5~o0AR+MAj z+i)&!RX8jRltbywz%Q5IMwi%&7$;vz!f{bxp=VdLL_@y!+%_@Q#3@(K!Iuxmc>~s4 zWSDS>JPH^>F0grNw(H>DbK9*>N|1kY3tR^ye{YZ)7XBX3n-v++#mqzX__~rrGxamv zVR^1=?S-&QE0`w6x8j{?F@%v8Xb8&~_A%{G7X2&%qN#vGHxGil0aNLSav34|To#PV zY!+J`FTtIq7rC2i?&P>g5#wb>@>3-Bd|`-4xGS$L`S8Gx>?E4#m3$9;!wl%!BpwS@ zTu9>L(J*_jD$*8T#abvjvTzZCX@_T7ziUqYh$waC4dP<)X1+1O;qL)3$u;% z+b031UTJ{*O9?Rbt^$gW6mdc4yy(g`oj7&*W3DRl41e@^6{bH`V%#PJVmx&auGlR{ zCU+>&E1Q{4_;MS$c_|Pc-(tC>lgA;@p6MqO+c5p18_}55#@jr*f${6#!s6{|(9C*{ zmTtep)x4a_bYR9gocETy-67^=*}wng8)kI-_d_IigOsq@{T0y~J)Lj5bPJFC2p}D_ z51BPZ16`Sq_&4a#>0!5VALHWk5(0S7xQJ{ZoO4_}{i(^=_2e#BuUN=0=kriE@hBG& zeiBr_$z$s>Gyc;>H@a%DoG{Vw6G`g0$Q_)Xf)m4i$u>PdVj1ug|BjC&eP-oT@!t%r zzi&i7-rWNwlNpQB!W`tE$1$(|A8d}k4xV}osDYM+;Kj>>lHXX;x>X+EydA_VvU&K7 zuSl>trYxDxo{46*`v@4!gVZ2bYV%r3XsU=M+jqqj{t3#)^M6gqh{1hHB-@+ZRkH*m z>!EbMJ&y&y_5ysbBdVKO^nyyW$64J=R^1;RNcx}LF!hwGjP=KO_x zSp`gg^g%rI&MtbxOhLGJ*^Hil>p<5tFX&_MDli?egnnb^dC06ZGTT|6pZYo#eG;dV z2#Gu?VyrOTnE_xGtxCtn3z#sw0hU~N!wviES+ps`h+DEKkvd&##Kj>+T+iOqY7gtQ z&1YGa4jx=@s^KfkIyhMeRIyN2m~$ta)SSJ|jn2DAE4RQj< zpAuPsPr|~9PumUH6)z>6C|*Kpzvkq-O}LGR7|Y~b%2mflKaQX>1Z5rEq9xg}I0hyd}csRuMk;RLj2k=8@1yT$Z3G@3Za6!ec zXoZYI@7b=kuL)1FJJg)>VRU|ig%B|2FuB9JtWrW1v3i?1lt!+hZJ)YPHy{(1q_SEe z0}J899eK#T?MZfxR7FOu=BsZQ(s2t#f?0&JOx^UuZ?;rTfX< zr>b*kopz8!Yv(8D=@r6Vhhcg+VQgBEd+>1T}EcZ+j9>&mos9aQnP z;^pGI_|_zL&fig%7^(S_Z^g{39Pj`N`}e0;&Znc4>`Y>BWe&gn8B6o*M);U_i8?>( zj|~rOq3@E69i#d|2~Y z+|wl#+Ndb3csYbBACBNw1X~u#p3s1vez#Q#ztAe<8u9mvqT7dE$HeQ?$*hWjp?`%k=7$FL>fyrGOk91Z7OFoC65kf`@p$qf(0MwH zwE1b^jRGAmeZCYuu2_z%Y)g1q{b=|*Kpkf*G=hLebSdisTQIMI?7+itD%J|!YoEaH z>TlFf`!_Dz>Q0uIY@}ME+vwZg0{_(|z~~VQIJWdD_ceJr)qK`R_>?CP&r&Y(4XY~A zGOmo*)HGoCXU5H*)YPk=7&&F*);+sO>CNpRq{?Hg(d_l--<>hOUTyot^Ami zmH2(XCdutz1M9{yf9b~OTu)Z?5+^5^ij}}Qn&X^IzoYNSI)32VU?ONq2?il=$&7pU z{OrHi@x|K!5@0Mvs^wL2*w*v#yjz3*$1-s#4W>k*VFk5cEsBDy7jozNCDI(9My&J8 z0zvx%RZGpqZye=B7f-;Ma`v4XDbH^l?m;is$_n;JOUa1m7r7SpTs>&qOf+x#k#W^O zuwu?Wa`|^2b&&psg&xkNO6@wF`=x**{71m#eQ|VO;2$hd&xhyr^Qn7MD@Mmkv7M4U zsq$s|Hq(-OcAY+(MZ#naHA#1eK5=3GOtuDMOvQ!N>${W?aPpb0}v5yVJ-)~#exak)7bo3B@&xxmeln(cDo&M4OGR`VfWzeOKZBA<+#ILPmo=vU$}gB7nptiD4BL-yyVMAwliHc84^lV z>6m3VFlNkN5KANwZKi;SMyqf=ti{`%EqK4;FYnaHhL-GR9P(>*kg#DHy_O^;7(LA- zTZugXd|WE#mOBvL_i|()#3bNM9d;cd=Ad=0amrjj-N z4-w0JRqT8g408%z@FBkGc)0!xG^tI7eJsn67W00| z3PQ^pj?)=T)kP~;~j%!8t&gZ23_6RELE)taM8c4IxbkcrC1zlN3^I0D& zx|GjCo1JE)J2Q>D7*L2p)-QPT$CNx|S&xG)A32wUvNXTF3?tKOxZvU8aLQQ*pIn#b zZMwG5HgAz2KBF$N+8+f+PE09Eo38@Wi#2Hq%h?SbbddCU5JtCMun;b&pCDBUL&&q; za;Ri83f>)DLHC7qqt%ngFnTNH-=t;Wa?jVCAvVH&6?OdU@S|`N&-fR!L_*GGb;(|% z64=9-iaDis;ge%9mF;T959i{@08=#@xG@)$TEusjYZ84bQUcJwssH}p(; z1$(TT#ltj9&~=auOg-pE9=v3Cy%kM`^m{vBwpS#$Hmgg>D1S26O9SKbp1|AN`ZS~D z2JSpCn{ydnY4uUIBf8p2~B0P z{H(gqc-A`;KHgL(CHkuP{^Teww|)R!xj;pb`u3XfMIFKVH`AgQ)xiNtD9dlQV)5T} zG8T;Kv(5P!9=e!ptgZxQDdrE%-`P92w<_jfso7s(0$@?an0dG;tQc&dnYspXuX?@C(nppS5|(F|^0xyY+HRN}iYDST%u z^Hl5UBgRV;k3G`#D9gDtZE7OZ^=iQB7wcMjejc0)H&c^At$6;&Dx$owl|ONs`J*^< za$#R5{5+zBoBmXAhY#9O-ELXIJ;NM=#&FyL=DUtlNaZVbZXz<9yV2<42a@k)&s%Iy z#ZxDONpZXsnc=H}BZ9B?YAoK{GjLLzIT>+w46Lfw!KN=w-2MI!`FY(rm{3{E$?2Ye zV3upRqV&9QP=W`I5oCq9iIv0yFLDvtx9|bWT@L;kNOqk2i4MaK67@6rbXy$@+_jjK zns<9(Q=kH7`;Y7Ou`H|kgIoJQ?A2I0S*OnsrZ?Vdlp`UG^HX);S>e_-)-;K|v%|M* zNJeNF5N)Qh*qyxxQL=9IK|Rxp79J-pd`#gPwyXUwY%s}_*JSK_Wt?be1J?u##w^Q4 zN&a!5_bWMl-M&Sm6K%xV?u^ZJZ7_zNZ!bLNSB?ri1IyGNfm>%Ru z4rS-%7fndPk1MOe>C^{Uu}uZFHLJPp>1Oof-7I{dU(MBP|K)-|wc_@&*W^UMk<{5k zB;cJUGXLOoQo%IRvUN!?xzmb9Sr*{ASyIcq5lk?g>Btlf{QQj|%gHx6-QhB0;8~mc;jJ6dcZ-QnbQGy>~vBzy1q9$R8%- z-NI;Yu7x09l}KdxA*4NxbqZwLz-Cu(I(BU*YB+y@myLz|gN#hPYthAt`~L(-KgJxG zd9!e!r3n?5iG=UNwIsF6O2F@pGK!>&VeXe5G-!P*YJW^1+7+raHzXff>YZeNsRizb z5`Gyf28*W-^hLx^bZLAFmE9HMIc!$6Yh+o}?Tbj>axFY}^Jd{U^L9S!s7QFWT}!fi zvp@N;mT71knI^_G^S|z?s9fYsRz#aZ(*z|fJ+KSn?Jv+PGy0=gegP!E{KS_ubYZ2+ z=ic*t-z5cnkA&;#A^LmpJKi-szUj=i#oo1!g8jYpQ_&DEQDwc*k5%0M0eIQ;9)hrU;2GoGlKY*&Z_!`~vD z9q<@VY%is`ElqfGpf^eRyOD0_O2d6STOc<+8fJK~|CfJ1xh}6&v@2Ft*jj7{C#sWJ zHivau9SPtAqYcP{b$!t}QHmI}cJSUNB0Bg3x@;vg%39pYj*dy z8(&67j&k6~CSFJT#i8VpoD{k6P#woVPJ!i}+O)$>!2imu$x(NJpUbpxqe?gTHv2B` z%=WNzjpe}6G6Br4C}Ow}U$}eqBI$8y0l7~M3ZnLvk8LO0z z7Iv+$r89#?LZg(n#E&x|#c!2x9sdYa=ep77c73tmhIFuhe6Ct8$c7CH z*hj_|&PAKixn8+AI`INb>RZX_?AI;&R^};QtU8?L+%vVZK&p;BD@f>hWu%{#OX8rXRP(P-t&Bdr5c8`+rfqq1sWxP15F}N zfZ0z1H{_M@*7BL$`kV;bvRpx^^NQo2Th5>#ot5xpcLV5JGwyb*l+bKYNFrS1dC%#o z==gOWNmr65qwUmi{<6JLw?>twvK_AK=@uCM@D6u&j7QPCl`K{pbc)7&Wo+aPqe1)Y zNjkKw6vI3G`2|xb6tdjY3A0~tr^J>vT$dG&S==V}wYRyatSivba5i}~=MbT8{ZOTa z@pTF+c#EejQ-7uv;touPh7x()e)2mvV}B%_dbuy|+`ou(n&`*x)nk1+%Qy2!ZnQw@ zs?!-D{ zsurDvD<8{)#=Sq>F_kvlapOIS_ZUglm@jnMsb*4tZ8}-*!*t^xS0U`eSnBGTi$mv+ zCUNUBxs{FAP}`{is>f=R=@r={q!sRzu&u@@O z*xRKgsV|6vR}E8&E-li49>&Wq)`4sJAdZax5Jt<2EriO%vqbmp5E2{5b{{9i@a5wg z+Vq3zqO=rLTzTI5PAM9M4~C|ZI;6!|9hH(#6fS#iOr_bk<3*E}WL$6wgmBE~zpxnc zOM=-RxeXUPA0s)_)aYHM0vuUpMdqCN3Jb-I!}$#$Wa59%lQK`(xE{(a;yL^jtq0d8hy@N3SHoxg)`R zl``sFj(|BgFVg;D?9OG?3Q4y^=}7i|9iMm%rtXP`_DDrMczFirwR0)0-`G}cTjC=nqn(@G|&ft1F=5pe{;n_J=*nrhj_rmhhS(I*KI~`AHa=!C4AETa!iw&lLNp z%1=_n)HfQGnBJ=r(g(VyuA>eUWCVx*7Q?WKm-rWf?3oWA%xBLXN>rIAa88>vv47Ie z_Z=t_5^CGYkHs~xot@jOr(XjDs{k5%wH4JTY#}{87qvC%SbsyB9DA1qm5UYdX;nMd z(=oTaPF8S?Tm~xrIj-|dIjU#t@MC=ZhzHw;mXEI_A6`u7uf9x0hn8^S)Wy6M8??~# zS31Z&)TIt_h)!-|vh^wlU+!t5I9(p@{kX#)dXRw%%#Z1LCIL?VQNZiRtqOa1j3MXb zgt9sH#6v5Iu^mLh$czp$DCrxSK=iS%S3z&~Kcs&OO zJq*6B0;3$m`Rjjq+~jBqVdm^U>8*%+M~yA);W2i_hy*F`z7maf1|;-6>lDa(2L3nQ z=}&WMA@Ipr(q*>4F!1s%+;(>a8IY_&mcN(9>_~u~eCVv^96Z=B1!7KDa6>iv7HODl z@151n4h_H+C!GsNsNChH*!?$md0$CQvmHtLt%_Ghzk=J(ZRqeI>OXP;!7cQ1% zJ%-Rr#N+dLiQh~OR5>;qdOAa&I2K~9$xWD*ITyw(XME!ot2sTR2U=`!3Z z;~6x28tY2#KNEP1Q}o%-QjGM~=9kQ+uyhjhU4QujE$TM(jjo)q!23SAa`q0l=U_6< znzn%C`Nopb8EQE2^gg)Y|BAom%y#rKQsk!kBq-XZfXV$B8;o_#t=`C(r5~K3ynZ^h zXDlqU|8#igB`q*Ru^*0XmnG8zGx>v#On(q{kg>tW0+ zzVlCoejCTpr?ojawR9X&RmtRDL?q)hhvwc4QDV6kF3MGajT05<{7VHmZQ%fDo4W`? z7-M1L*fE9NgknNqAZqy<3rt-yJQ9 zTjy11VtM~7Ar8H>ddt;L?1aByXT|g8Qa2e}(iD78eudQYD)`|1e0aZbd1>UMP8ShLz|}x{^t+_Ex#|(m)q5GrT=``I-r=he%ytV@3B7i`Ng1370|!$ z4$g^NLW2_;aoVmEg*}kZtcvqn;1P^Fd*-{m(i6*jRa?vYhD*oGO{vrHOHVk=);PGpM|bqVT@tLgAPH z!nvuz!-|4W>ccG1qGsQIp?ZD}Y5x{QC#AD&@{6@(H~Y#T=%xHhvjnV0-N)_|G~(E%%kYqhWW!N zA#x^kcWypzN!md6BvipM#+i8~9Sv7!45dR@9_Qj-c`|2=srdH7Wb~H33Ln}Hi3RKN zX;>P`U0c}6e;QGNH!Z}4^X^B3Yn2)X8Edu9{>4vc2|x3swYv4Gaw^AD&sDV*D!0O2R-8=Ed=CUBvaSzFN|!thQD-& zlauq6$>1Hb*b-z9gLMZ|3&_Qof-JC?s^nJ9>|0d*`hd7+XPTYfh`A9Cg^nxY8K0B+ z62Iw5tjA3yyB0AmdeK|hZec_JV|w)zo&U%@@fS`yS|oT}xJtwt6C_rdni%=O4W6_p z(>Dum;IV%xVDBk`qRaB=@-U3+4%kIKp0IA3vULR(`E&TL`>NPasRMEbt)K^)=Q)4k z9dc-$Jin%`0IyH>BYi`)$fz%>=*2p+JVdJ0<4-#Nc_dFP%kFYa94(4`smiV0?MP2& zG-A{2l@RmfBt6kkg&zW;aO1Jt5Z2B15kbG_U0cK58=jjbnYR1#+M1L$djm>Rq$!B zA|}j|hyN-E(1mwc7uAOm5c%*ocaLcox9!Tv_YouMhA@%vJXuQOXw2B7jN$pOAp?fX zPo%^4$qD_|?q$7WeZV*T8eaG7h8>MsM01BW)`x1slcx&wrllON>r6A9G$%Q@Fpp9uV zL#E7yCkMUhN7j9*=^{-?QXwzR{9|(K$HC9+TKM!*1+#vnPnKeQ*F&2`f;Id7&8;Qy z_@@$<2fl$r%mcq}R~!0ipC<-6%y(L2Av7*XA;%i#kO!7ZxUzO0^f0@=vfN_Bt-qjT zT_HaBEE6XTu!ZPhR)m$<;ek2-CI@>-(|4!XbNE1C;-|2Ygi5R8zt8V`yD)BuGqGsF zTH-%i1k)F@ovHW`NGl{!M=K3n6z2&J6CU%m)2q-|sDrFEnGm#30h^=_a1M=&>F7R< zNGCMfcH8^$Ltlu5Ir;{Ym6M;4kH`DseXklweA&c1>!zdQv(;oxU?_AfV_Naz{kk7@2g;1s74J~k%w1YCw5Xw9 z|K7Ph<|<H5|=83fu$n8tUH1$kA z8dh!UJ?Ce&C}Y!$Ls0c~IJIWEgL}HF#Pg-8_`rr_e2|?6eg;NFAx#5+hn?U`PD{}{ z|H|;a*#dE=BGY89sN$rb-JqIlNK;uZxbuAu^qp9y{qJ zOpo3%2aq4Pl$daI4!t;DT+l#itp&kO8HIb0@wL?-B=o18Q4pD_SmeEH0ryouj4oNKi=nxOu*;rx+%z#A zcoJbu$|G=(`MZ)!Lv5|zyV0MIs$fA^mAbMJ|Sl6f+c6DIX6Go^-c&$8i9WeHy} zE(I4(v?9Z8LqY8k%Zco9hMt}y=P`fqR(u!aewk0_kI%vhNmIb&(QQz>A&)UbLT&ea zm_XOXiUcQ514(GI0f9JnKTUcE4=UZM*DGz@qr*es&a(yM2c}`Vt2N^pXcF61N*EdE z!k#H}TD7)@^}GFqDPZ@WH~Y#cm6^2IapmbMw}CC@J&dIRSO zUS#MGdGeL{%#U9`3={NK=>nfj^psX3#}C}+d^q)@rkQ=Yo3Ce5_17$$T%X9*A>}tO z?Z6|de&Vph@1gmy5_ZgMgT2Ei)3@W~gnN$9$W_g|+~$O2JU(y<@k@*)gPv<*M@a&F znfjhjf0~AMEy~3G<|Od?tbpq;szDE%abem&+LaP)jfsc7w6N^q9+I^*FW-}CcU}6bL|5$#j4e{c@3HDI`U1N{ z&CSMLuk0YY>Myr(c`MGWsw8h_jHEl*{sIkUBv&{G@@|I~YP%J{d&ZVr`8E%87D>n! z{cLWt|5f~bQ-*kIYLWI>6xY{rLPvJCK!-dgA|5O|vIgYG7n*zgGc4leVe3t26Lyx@d zz%37D$bhqj{GczXIP~=-$Ya^P+res>AhXxDvcEC4-7gYC-3%m;M5S#}dqFiHiZ7P-N@w=?OAF*3rbyNV<-`=6Mc&%$th zJ2=^DMGm(r;j^3Jwh3;Hyap8sg?kMoGWHu;pPxD!^CgfnNuPQo8KfPxO>?>^2f@Aj((eiAqiW0 z*^J2cKEr1p>CGGk*EgcBFCno<7K%SgCu2xiK3p#{Bu0*GKXoXHJ2|YK4_sD`(^eR8 z{bw@$d>EVacl9AXeswRFZPam-lQbWVgOfpw6*)E^V$$~mkv;FUM|a7|j+fIrB(5i@zl*B2IVm6OzW1(AVlr|?*z z0QR2Hrkbufc%;u%Quk~;{CKWZl-9kND;u$kDvs`lb_V8PUi^f={X7-V&YBJ5^I{=; zmOO4dGf`}M#+CYgk`pe4H4`U3iCgu6?GEnCN$$?9C-G*gIKZFvCJp?=JPkK+>!8Wx zU2r(;Xi~>hcB|p(vXk`nvEQimOpc87nNK(T%fu)73n67c>n7R6d^MwO#66ywyUe4j z@!C+5@W6n)R#HQ~_%bN|wwR7E%f#Z7giO4lO-^l7Lix>$A=bv6>Ue*}cZ`7(`C1KX z?rRs>OuR1M^+QA>S#Nb=&1CV%?5q4SHaop5HqA4){+ek3M7!}GbLfifjnjUj9w9%X7wlGi(YXR z-&~3sW!7_U2aeNz_Zu1WVL#ldJW1U?bg=#1aPCRlduVY{Vm-Ef_wUs^s3D*6F(lA>~B(z#w**p?Vg-Y4hf z>z>WTy6M{FgOAmg_b@`u+jCTf@mZ_C7WpYl=P+Xs@&tVzgL4fOqeP^|r~nQy+z zJo%4|CAB*@l16{#gLSOxY;{5ub1=+~Sc-Y2fM(d>0$W{U{3I!zx9>)&V9Gount^4r51a)K$aX znmT^COa=zJY$D0~!oY)l?=tSj_iFE=!D(0=szYq_%;^HJDvasVhd4ZJfbi>#(Nvtu z4W1A5^Y3>2XCA>Nt8C)Nx(+S!QytKIw!iUaXM5}q2ypq2->)kYip5przVaaQc_Q0c zR3C+7S7%cTr#5WyMJG1ldi`iI0wY(k%z=c9~V2$?#)3buS>EV!cMa1cgPPf;58-EQrgc-k;HnuMktw(VAuCzF=88$LRuiEv zEhH6OhA+p?^G8~=aJ_*NS#zIdSM5ZC|1$;2(owaL*vPm#19L%T?-n{Hz74zYN0B{# z%qul43%7pmN0zS21-Su~ELARxh%-w}CUu-9s_GIShHvR)9_eqMaQnys&>O9Q=U*Nd$EdnfIW{XQOl<4b-oHK+3F(s+B|ie| zNmfN)d^Pi843Fb?^D?@o%>G~3X~gCgPY921FCodG#Mko81AuL7qDOK9zqG;H}FN9P@vM}^lX#cB7m>Q#y1N1U*@6_Jn zX|BZ-#sIRPJP^2{&-yq;(cv} znKPL3pNhQFBM&t_wWN6uF4ONZylX6ve}|SD(}l~&;LHajmflWDgSy(`jLlDlF!xwG4X~l z>D?tdpUOMp-|oQ^oj7~nDirqzC$qU5ZV;Vt!jI!dKpf`+bq}3CQt)Z+2`P*BBKJ-#F3Ag;nr- z3TLs2OJjy$`(XwYqro5nda;mN4Y_Q(3sv(87}DSp zH0v{iG}1_8(rXADaM5$TYcjFO)i6K71;MYcIWeL z1@}svd}6^gPp6aAcO%B7c7zKNdNg6|5%64pmfikpNNMB!Ay4bR^vOm^n}2?WD*r&3i-wI37gcn|X0eGO#& zHCr&euu^!k!da<(*1p*T*}9DxePcf%qCQTVot8r{28G}rois>F)gik9hhe_T2zH(K zERVOCgi|x}rK-vT`f*bOjeZznq>}fFKDr|)`Z%$~)iI0|LuUD!3#Br*(WjhpoCJgYq}(#a{0 z;IwWVe9N;)q3#ca9>r>Gxi!BxNmm7JhaGT`&!rXZHL;21_1Ts4pnB?xYp(BwYERzj zrgjZB9?xQLZH?*j%9CLCB}!UW#e1K>4aQSvlc0p(*?Z6H09D=QG2egxXmw&TJRW*N zS~$9dYL}!5ul?HK*^ZoFv_Tj59r+`nw?ZB_NLQ@$ErFxM^yuvvCHNJsV@WY}bYk*O zwA@`U#T-fD_iJlh_#qu))3s;;&(?YN6xpWXoQ0c{33n!W3fI)$QlrmhVe9ZkczhJs zt23){L6x^;!QYE_uhbPSg4bhKp%GP|y9uj~nX`v4lc-|C5d0h24T?`0D~(657ZNUp zF}J*q^y|e4sEI9=#z^tBI+^$H&DjNQIM=Js*yo<FMeDUJAa&so7NT_Nu| zp(_T3eZ$VYkM-oTJJ5Abku;HO1s1&!pI!`vqnxvmHEGZ-$EnQzFV8NuNF&3TCrM!lv&3?!wzY|Hh@g=y7dM)JlHdm&Y<~8f^uA3XE(EgV2 z@aqw_n(yif&+Ww67X#6QvqxU>-Db3DU#8}vA@Bd4j%Is53;G8X^3^vv*kW~Wab2+i zB^~mI(`&U^=&>Z)?EMP1I(xxA{tmThB5S^}I=8H$TLrSvZ=V|*8Ldy5R+>0}$1Jv^ zkE+~#$}{Y}M@t&TE|R(yQ~auv_1d*c}{yUuKYy zlz4!-_TnDGCD(-NvnkS&Bbn66Z?E9%9Sgk@IG=N-8a8!jJfEx~Uv|uIp82)cE|JZS zrOh)x;-C>(=AVEjo`B&_nVw(jfVLBdK?&zkjE!gqllJdm7*tKQnh8)7Fo6HeVq2-T%+vlqpOpt=%N)Sd4GcE z+}pO~jx#hdzCM4D=yUy6C@@ihv)^lJ^`df|Xz9Xy_`8^ApspC1H3WBZM%fQF8J14# z$vg{{G|YGso*0rVOrMZMV^Uh<_E(me#r>iwwwyD!LW8~3zDgSQYa#Ep4{YYU{ag8^ zXLYyD%<{ZKK2T&Q?%c5hu9c!PIoO74x<+huUL_TcI*+M8f|<_51bW`NKeC$_p`V^M z`2{b89*gI*xKGKn@Y!oH(g>4&uPC5*IfubhX@ZXV24t*!?|Cb%E!(}9zmw+KiDo(P z;E16f_1;nh2WJGbo5A%o_e28PMj5hcIgEPUo`6>#m4U-Y&TOn)1WrkV8C#P|+jH{a zi89_(@BS6KcyA5B{w=BSa23qD@mnf5mP$u?r^e}9!64nyB(J~w zq0_=eY?APsUImXq+sCum2hOtFzDx&O_?LnHHEnv?$b{!D1vYrKhHMu6MDTJ85+a@` zl>Unxn|1g#Rln%%-@9nqu!EJ9Wzx3KA^6Nc8J678q25NvoA0gD+SidVYB~-Zo-et? zU8A8>Yv8!+UpP?6vu^`m2m`Gh*x&2vyk{p}7#^qzAGsE{dU*?M>dw&4uBHBQJU7wB zhRxlVLe2vNad=cdXzS=xr}HPkWjE(+uTYhZ&FA8O*XMf{gj}RIFJ8gnacxjVG^WvS zUJE^3RN1`GALxTsp@2N|RV*3OiY~gif2R$bFDQ6{ufDjtgzNCS`qZDlqiu4`WIkGz zw0C|4_PD*0rPNl?Qm^qi_frNC*EwHY?*v;0%wp??sK^hp3A$W5Ax+TlARG4V0DV6A z;W&Py*I1^3uf^|D?o@@Wyr3`IoGyW^o4OP>_ZpnDUdMW!cZF}`+9{2ZmakCA zAG7sE`QUo={g3k#2Hpb?*OtsKe9N?OPB+RZoClHWA5ECZ_IT40+;2K4NQf$%y4*_SKa)8*|b zJ{@d@XASkKPWvl-c|MI*j8T>6wo1cck9Ot`b4;Sw(|xddHD{M})T5@3>{Ss0jABuwUa-hu^$ZsEPfaZ?ScRBIDRzqMJzoMbxu=p#Hf8w7WvwdfhU zFEn+VcF)$7`{irG(mq4j?8$m`?UN>s&h}#udG_ay@+GS5(vqHSzf3u7HL`1(Xx7e< zB(u}-Hrs%ePDrCLeFyY?eOvG~9jEj$+Sa_!Pk2zy`$<#aZ_Q!0f@d^(^vn?E|2zgG zxYjy1K^@;(xU=JN8uI3G@A0SCO`)+p?-|!zhqoTZU}I?ooj$$;w{1vfulR3a*(N*u zoaX^WQ?)5(PG`6=a0gT2ta}f&ENIH5{@7AW1C+Hw$!i^)d64tT-+sa6&-bvG0bC!x zrY}AjZi8{FRpr*(V(|IjtnAIMGW9;t8T;v1!_O=FwC-JZP+i=PrG!az;$0M!rT!Df zTN=~T4SE=9JXAW%|3A&I&=((QdSi*IA-PrFf?{9ZSAt5q7c~usQI4>%{{=d?*a8I` z6O814bIW>HnCYa>M)13K_M9!Crs@MXxesC9R2?B(Er`t<-cmkZWg-eMR>7t&qOzo) zW3xUJ;802CD-$pzC75YsT&DF`hGE&@1em`?i~hV>-K@{#oaP?sy074WCQRBHn@|0o zCBS3B1V=g<(AyjKLKA;rF!x!xe{d3e)W3ru&IO&USq8ht2C+~@Jta;~#<{_U>@klF z9X&T4pWXcqEP!(W8rDJ+UwxQvI`0B5hpnS7c^3V?Onqv?!D(+N+?8cUjxkW{57`1wfr1DE4$L?q+Huimpqkgxd zf-Dtu=~^qTp20KSy+V0cT`2Fu)+A&8ooeE%&rPbN*{!By|;!+c?M{-z>eMHnvB1`k?5}*4Wq_z zmZRZ4Ncok;qPB6?P;?|}&s)iMUFRKAubgm7WH|KE*Q8Tw-MNP5%Y5k{9a#PddUQV_ z;qj|98D9y9pOr%>v!uN?7Whl81v8t?_1<Wm+ooANh!IhgJ64Z96QXjoVkf=;!oGJ!rE5~dFXZ{QBD6l z#;oi}Crf^VU$h2W=9@qkZ-(K+yFqYYOM^Dmt%BUbC}vxpOty#kZ)98>_G5{*{A1)> z2uLx-38VOYj_xR|?c~XxW^tY5X*+S%Dk~IHb!pYpZxHxy3ajKkz3`ct_+Zb@T=p%2 zK5p{ChiwcntAy(h-!?+q#`f%Js)_RIf8RZ&2OU`O1#>!~(Oc+vJYAZWr;tyVwi8<~ z@uNclxiJe z2I-lUGwYMEYECQ+k+=psRU3^WJXtdDFIa9`gjF4G3410aQrCxps9U-Zb4`EHBZpmR zl9bG{UtK2*>4}4ihr{_0ZL%NG6PozyMfJZ)JLM*98RNwQHEYSl-x6H*>!5o6PYO=t zS?soZnH_)Eo8)06URq{@C8?_N`H+KHwK6+<<0mCq6>`GihTrgj^yu8qK9E1diG62W z3mtM0&TBLX>*v?g2lE(93%02XK(y-*np0%xd%sTd$G%dl~idq6CDe4 zgx`Gmc5Dc@Lh8bZFIz@6DRbR;(v` z-E>rmGh|-jGPR7IkA+8n!b09RcVT#7Gy7}qmvoA-tb@fa37#b%5-9#vG>nbth|_qt z=D)E%!kL7B(jERi?0ct!cxcN?yu00y{;aA3yJAZg-IeR)-c^`&;wZSs@yvC@+2(o9 z`n9CzYCGYY_j9Q;XGe64u7nvyk+5~QHXT#>BFud_gLwq1$wg;-0rUx#hLmz`O+_Kb zPJM_GC1#ZRwGsZy_$7^X=J)Zvh~2C=i#k9bYTyME5yZL9>`aQ8GO} zT?L=UnQ;X$V~Pe9izULTg_i6o z=jg&Bb=dHcbAH$8&>aUIjB*HOi^tW`E&o^ObI*p|>C5{Oc30z`yFM5~x@2p84yLy2 z!a9yrlWqT7gI_`xdZxaQr$6uw-oCKLxD%$-dT^sKfV1VFU@rAi(}C9K=D|$9S1gS; zz5eSsIJ%NbLigg!(W_W`hh*wF)ft~VhQojy zZK?$iu*;v#7PV<4y9ou*&@EPS?)it$WLMth*8yMcv7oqK7U(8&e-z)> z($%9|ckVT7GQ&>R)9kGWaCc*aR9K!tOCEQ{SDSO-<{V8@)$R)|H}Z&<+An(i@-f^U z&_xLD@tRCL+rsT3ybor%svKpnDi&NAD)r{?!pkHR@wHt5&g*PQ7*#&c1Vf^+wMcsL1hWz;kVtH}=8!wox!JTZ`Ik8z@-)namph zs>{1Csf+8Uo)sok^1aT&RD3%9JFezAj){-1;@|GMET4NO-xZF+!qOnv-k)cDl)>P+ zC5HXwpI^W~|BOK!mOfBZ9{Q>jrp`CURIbta&KfMt;CDlxM1`z2R3R4cw8GQ~9a4E$ z2K#$VX0f8G9KSLb&wkmN+dd|NI_ZtZHKqC}-`Ayqy+Wa>x7tUUOwzg<*n2f!cvNJj zJmH}tG-Xta#+j4<^$CJ`-*k!HRmgK@Da5|Jy>Lgo9x1o~Z1zTW<6cw8Lo%j!`z##3 zq>x)V-op`3dW%^F+$(Fv^GEx&*`Ai1k=3ON{Bj3El!g|iwf`y@RR**BJQHU%exeYf z`=7K_Uyp{R>*AS{e(W9BWK`C_$JzodX|m20YV-=iS!1+Nvy&-}*S-plpH0~1T6KBj zybU=1fGOOL9jS!xk%HBL7&iQ*8MRVVfh(7IMWJsprRA%_u9`#8pr=nBX?i$x6R;NA znzH5H5>#`zC2VYcg&vO%!Xwr(*vis@=J&n^U2p%A&NnD&>C)bK?WZ@i*VQ4{iyjcJ z9nR`(xMybm^X41toKLAVAfW|JQMm)GuMru1G{l;o3DRr6w?|$!5mmx%@ZuSMKe9jC zJm(jf=8|f554@OL0b5S#(&D!Qpp_%5n4C!-=_jDw>p#MbF?G~BvlhehTv!O7^Q{U@ zME$YesK(iM%6oYb=;Fq-+be0({CU{rb&l|*@B;NXz`KsGn_z9zdrk5HXrrml)(52$ z`5uGuI2Pvj<^HRQ{e=rF16Tpyd&8zG#D*H~ffi8d;NBjto-kr{4_i{3z4>5K8!K7v zNv9pA|6ys@G?@8~XPL)@LiEuk>^}GKPu^bxt6GIg-y^bUmy+wN52~ThOapRA^$~Kk z+cH<4-!B}m5UWGq19G0p`OZJ!*P%f6YG*z9Ps+ftuMAnkXqi6o{({TCKf(0^zaO~- z!}`O6*%2Mi_jp?a|LwZqX*%jM)i@o1r*$2%cTY14a2PKHO=*-A?-jDVRw3rZtwdu} zL+Z!9lx>z;GD~0Hw|Ki6;W?l4Jddei5C@a5on|HdEa<-$e6HudkZKxuAMv7U2(gTU z@k_O7+QIKaQ!i5Y-|BK?5Q1;gR_TJRv)m>_A#OPT5Fgu{(`*YBoNiw!b(q9+CArl& zUi&A!;vBQ{b*H&+b1Azwt`)s7h=MVrcS#RNrqVT@gFEyj7fg6ANlmX@cv2|vee5eG zr8z@we?Q^nf)2{C&CakT#)$p0cA)W`1+rjghBUrE_n)k<$NQ-cxXp-j*L(B)&aV;7 z>5&E5J>LuKXQ)eEy2aDHkCmXmvH;v)XwbV>HNvZZmaMHuDm_}=3SP#mLk}Gt(vx&? z`l}$8FrbcnjSBGCdmCohgU?Lgder#jgKoY&KmPn8v~1Cpojj!~TQ1v(3+F8Gj6WGq z+FO4^V7xUNc^Z>edkuK*smgi|&Y??_+CoggT)4W#i1#g;;QkC-_K5Q_rf8dszs5#G z;&pxcI`awm`e$**R3%OOyAR!0u44U%ULxMriZ#Vs;2-b2d-JhBxLuvaKDBD3Ly=#h zP48Ig4d*_Y*7Sv<^%fYr$dW=wTj8iGHKxIH_kYaH#WJ^25X^LG)3k?BHfAj=%{3$U z_G#c6Yc6enm`PrxJ+bY&T-ef4m&zKwz~t*dHo;z99`Lggg55oZ1E&i3y}l2a)-1%y zn|Mc$g_@W@*<149cf%}qb5VU-0A4QQnF5n%kn`P?wf>kwBh+T#{E8l+wZT;BaXeD! zb9@JL=ksL4HvW#Y+n>dLxuJVB>ND<_%!_T+jcQ*HQeGVudHKa-OHtFYr1rnMF)em5+=ftZKb0 z_i)^0avwVpBi|TcaF8B7e!_d1jh&egoJU$|+=eLX$T#tjdA%UA7D5 zBko9BZu5J=$BtrsrWXdE(xQy8a+vZpO5HxUrRFUa+S=_g`)pZZFFd5N~&#Bn&1-?u|UuAND@k&gKlWppLn^5a7B}y3z1~ zCTM!V&bU9I-LE}W3{&9W9(Sag9SS+Ahq>sGZiBf2s`9{7vG{akcJ?^`9CF?0hOZ1O zKvAJi`!@@4ctsml(wIT#Zp6dnMSq0XBkTDcvk`m6cVkg$y!UFdxtJ2-jq``|yFXuKySW?ZT^!56UST2ZoI?hk?lKqGm!v^S zJlE6aY-{#LzS+vVLN2u68QE=;tx6*OnRo$=;VXz^^r&*z2I2QLE7mfO-{pNfi@P)4 zgP^5DzxP)*bHiHj_muPQ5}x>K$hw@)q`_n6rsr<>%2}70_gjF?4qv8Y zp)Ma@u>u@lZIQkkIm>Gex`-9U5AonZ2kI;vWA|ekZ0ty$f$H%OtHqyCaYUEO3lbnL zVI}((S4n>JS0YQA#d3^&5}>8u2)20?&xrX4;PnUjQnqP4 z?ReY(wbKfqbf-22j?sWO_HEcXmsA>jp(DILqYh{P)21Nav(VISx^s3N4LkoH=a||u zcYY7eP*D;4YYfL^7k!e?Tm|p8E^PZR{#(-s!8-;EJ%z6qXzIQO=wxJ#;a+CsdDjT~ zHMC$ikLFO#x$bbIbS}hK@Mmj|DW;6DWp)$zJ$;&mxNt8hH z-$8V4y^780d6ArkcfvI`Tc9w6_jNA!hQ^;WS>&chnzsHAyxtTm*)PbZ?%TS-myLhn zA@8JEtZ0cBKGsSj_?&OQ*h18pT?&p%bZOSrC(YXXk>T~!ecW;MDsPay2XH^Yw9Z(T zbp>|s(xG4LePB=PfvmRG5Bjq3E7VtY5{zCZQ}S$Qkaqxf+M^;@)wdA0o$;2u_+F~K zU?JvT4#0rn24usz@dxLbvWs1kDgLG(+E47>)N`QBS{&WH&p$hzOs%(SVC+AC_QYRZ zb{VURJEHSp(?SiZAGbmH=skhW_TkK#JT1}l)*0dJXMQ_-Yat$t`;Iz|KgeQkIu7rX z%kJ+_q=p+a@Ri*b-YKR{UC(a^*OF*Pxt(Z?&t{09yiXeCp(W?*s3QiO;PYz+bUAEm zvkqVPKq2oM+C^Oa%?gXT=H}zcXAezfTT@i!K?`r-&zN1gYU{7?JpO+;@}MF5Oy~d2 z%JAkJtIg45`fsxa9*WBsg5H=av;B;ON;hW)_snQ{uLxnnfix-TDbKKs>LOnF>4m<| zd?#Q16XvaQWhL=Jf9L{VuV+>&tx;Es>-^pN^p8FZOJl_KNI_^ zi077sU~R1d^(syRrvd}^U>VQ*gl@&$K4xGsVYo8j_(35zeJ{I_S57N92l8pFBdp(l ziM%VP1B@Sd5CSAU8oioxLFNHVaMF|;PFG;f!CQg`e@`C~t|A&47>VzBC#h|Y5)3DN zmedAilbN48-n1JC62Fxz47{7OPWmQQ^vSCNP6m0gt7CF$s{H->DXgo>%68k6L+dVi;7*?k5JJ`Ib^SoN(rC@DOw6RZ zsuXBb@kf|`op+47s)#*#hj>Axv&5StwJNcNIY{|&{h2D z#k0FFQQ5Xt*Jdxx#HvaPtIWoc0U<1TeFnLFT*SGI>9EIEhgenw=sZ}+HXY#amE5D= zbYs1`f>HO+1S=N)g}?m9dc7=4C_B`amGe0tQPfrJSoR*?t<$A5ZoH3`-&k)q)X~hH zgqk-ES^PNOKmK4DUex*mKeO~`_ddRFkM?1eACsv!a?dB<=iBy7Aji@x@TcAxPxJ2Y zJhk1zx7tdn<5#Xf40RDRhOI(hb7RUMtcDv(t=L~aC!Gpa#Q|!^K*_&LV-6?5oEv8u zd^4s~En^^P)+5QDdmR%G@f)koZkSl6O{pvOn&*6^gQh(Hzz!JmZJXq;?kuZqa}lGo zA7Nj~lK%G9#h&i<(gm(jY}8N_cg+3?Zv1~&SzID)-?NhWX#A#-r1f~tX*Tn$<9&Zm zb2%0KFG;)E8(p#c_e+{|{3sip5zKVr`MC|EXAJ@(Qu;=|C^V;Y@YK~k(DG>9K~CetJtx<7b$&5H*{IEg=gkD^I2_l z^PEp>*GSL1x4`U?vC_Fx&aS)+aK*G5Eb@)1)msbnol+}JUZRk#zFLZoM@nG~*PmB7 zyoA(S>)1lodg_#O5+iRkNJdYx$hIHi=y(a{e$t@~X&mf1Gmz=MX(1=tY2%hJ9s+RI z*7`^85c=8^jk!N_#C%P$`+=d-h`kE=oL+13YE}S_PB)_a#qVH*YD+e4a0=OsosZ+g zdcfB_Q{`df1A?kSIJ4$Fgg>`*@y62Ctai(1T3h`cIt-D(s!@}-4n+!0S*N`j>T*tB zU9qeGS%D0l<+B@kF3G42?e6mq;@icL`1p&oB|eSP<}SjX^7?@rso-8r{fyBB+^V-Fws&N zWYUp2ophwli!KS{y4;n%@%QClA6&$SE`uN~WW2bn*5dFIaa?iw<fnJ$`g z!Rbm2e0WQ^@KGUm`lBYA+Z&0gWhQjZFb9r*dn3JRn?g9QFV0B!fW4eCnA>|4+&A3L zs(<~aT}2JBdX*P*Sn!_CELa4Js%o%4X-Q`}V|lr8ret@9>z3B7#nT41*iu7Ho)vix z&kW1Se!U@wJa`vX)13DltWKXTe4y_Q-V3Z#M~*$!#9*^-?8tS_>Fvw2JRiNW=9mHb zp3R5dt9!G#aXIw5%_?k{nkjfMPo;pX{jjFc8Xbn2(Qa`T_?2rjtIbO4mwOXtxcEZQ zM@`ycA1O3-D(U^<-B@)l;{2d+kVk>?Rbm&e3mP%^S>|-MT`_FBc3gT9kVy@i%kZRc z2Ke;SqQ5o~%{kWhS-e*J9L!aL1Wjbm&CMZlT4MGKujWn@qcj4ZO2T9&SV*t<Yj+=u55U2pPbIrK$!>D+kFS9g&MK-?7 zXSk{y37p?x6e5jxcb3~@H*wMUN2r=+P5Y-C;7KzT_H&v-UbkCKY#a6yHgNBm;l(5{ zDqhK){eIKARU7d3=Gn}Of4%|#{JT$bV2%#w0I$@CSKgk?@PfJ=bSDBL)i(+bTY*2Y!h2Nk9UH%F2>SC8`j2C zA$KWN7w1hHj;H@KqPcH#;HbANTce{U4-VXczZNg_+&A?Comi}evFEI?%1)myZ?}Z^ zgX<+#ooupFnF1ABb6`Wb5fzwihdMi)1=iIu#Z(x_(GIH+A%4fBo6 z$#_8<>}&N;y3Y5ytX0^NRr8x?`|0a-)S=5+v`uJ`HmBIjU1D@;Q9eHg7(#bvJ77Sh2LO4D(k#=W{0IMIo%kz?oJcN7ToAOOtPxCwDK5Oxa z)&>l-F{YC#oFlT0`)7`)(C!~ga6wHEa5gekc3O5=csh3nI{*gsy~q!4Tvtj~8w#oY ziYl@5_E#4{@HmH4foD?9r_opznf7tm>(%+|lj<&MDoMYd88L-MZq3?`G&>Z*zTG z-X;d(8=P6^xv8|*zy#I)z7;aVO_jGpZH1<+lV46bO|g%F*x+cE{*CL*D|?8;7Y;&4 z8(r%3rV$RrbARJ{4f(~#CwNY+M6ggQWVaFTaL8~s@uIIGoeJL%d&lUo*|(CYdzB%k z$zE{wIQNgGnL~#|p)4YzhK>!`4KK9&u(liYsC1GUHt`C)CaB4Ifj`h|wT>ijP{`LppRW8+L9oWYbGDK>{2Xg~zLjg9)9*@e zsxFgD*)aIvu^)z9<$d=drl>JOVC{Qo$|sN2pn2mhVc`$%yW<(9+nfWd^39Z{MG&Nf z6-aJz>7>@RKTZlp&_1V0YbH(P41_SI;C5{PCF_ivL(;OIyUUFWi1`u+d_1Rc45`TSwM-_qLcPeyfa&$av#5iWYu15 z?6nM9JC*mSJhH(@e#Z2vWNz~gf9Hox$vvJyP|I1+^QJbnUKA^g8o8N`=bC)bS68t^ zcsOWyiOSB3p3u~7opRfpG(MKW(CM+#)BU;Be%L0gJ)Hx-78*3EOBA@Zp3VC2=AGIf zOtDFmj|yd^>;Dp_pZE)MKb}WElOXhXX3Y-ryZ<4zp5n#jA0Tm{HuZo;sLKps8fA6l zed{*5Rv5CE${b2rxe@(LzJWW}Bp;~6fTE>0OPEqY%WMbY9J$bQ=8H=dSti4<6lYB1 z`3^l zaPtpRNe#wlo|l+q6p`n98*HdQ3@W_)%+$9vH1#fx-mEHHKR5}Cy+fqH_RjM9w4UO- z=tns7Lwg$k-5QUq)?rsTgW`UXrr0O-CuGggrS@wxo3)y`oY!5ez6I^B&t^x)rBU{m zmgw4zfgax{uMcSh4}Jn0a7A-Ced__MDgE>z{r-fNj~W6VglbZI@U+PodjE#69V_b__5-v%Al{ei9J1~hby1H7B# zz>+&kH1qpPp1;C%L&apJFd%Akx!NChy^Q#O5M3u_V`H?3?!j zhx98E7IF>BYtkpQ+v6sBOyGXn^rO%?NRMevNv03$&GFZoLGXajoJ&z{z~FW$dstCT zaT&*8)Dbtfk!Ps?EpCY>6K1hzK759Mti`}2eMwrckb8w|i8n5X;HVi!RMnt_`hCzzJFw zSUMir`WG5*Qzo=e`#LyfzmeAEGMel%3d7C4VJl~F zW$f^6*5q|us>ptE9P)2S1VK?&rBqbsKS5e_MR{ zPE{V4ce#0ocPh@ND=mC5|7JOua#q8ed# zhOOOVMLFT^u$|@<>C8igytJ>4I942reKs1>z5bs;e&)vZmUA7TA_>Q+wSa$=Om{mE zz}qoaSf^`9R-B*H`L9-C4`T3xm9KQCWg8fro#2Hy~> z57bN3_%mAi)LXo+>W>q;7}AsHn)t@OHTTo<_ss!1V#K^-U_0E5hON2->qD=w!PEGS zIOr%C#@v-=MHkTv)S>y4a+~`;Tn4Dg zmOQ(mVz|ijw1G^0?Aqhe@!hdtuMR!!(GCKhR7=BFU7<^~3eJ{H0O!?46#CK{Qv&SR z>op4b^GrLjTrCC;xEfJz^jD}IEwTAWDrvp{IrLcK&oW+IqzP*Qm%Z5n#=A8+H+wFW zUi4$?EqM-N#cODAnI+ZfU!kq8tDyGNcX+qYoFW$3<6uFBedWHjutj!aqt_RhK1`P? zc6@{>k?UAKXBYIDe5qNVzuhH)Vydut<_})av(oVkps8!G$NW@U`201v8mI|l*C$Yh z+6pjz(+BI9s>ma^>NW57o%oKLeBMsneq;k$#2ZjMqf!{@V#Z=eWl*0vo3PcZ-q31| ziE@$IDM9DYb~aL_73q2f!?1o2rB4FUCH+!}8hZk?dUH>{XRZ+UX$rID?{RP27>g<| z&kCpYoaJ3V>_olTGSo|Pps)Qk(9=qVt+hy{#Z~L@q;43THRG9`;|H2&zI*TA^wM}V z4!k&yvllLt)w0KM>UlOyQ`e*YjwIBUdax1v`+sYzn;3P>8sl^INvlxs;l^gp(x>8J zOWdeChyCU^Ya55Z*lwA=WP5=3Mzz!xz2Amlr(b3y%((|WI-0Y}#mO|EXXvD{H-*c4 zS}8YCu<)gL63g0OPFKJPoAh~`d+{{YdkIWP-U~@v^{MMQOAPBOvK>n`WKWYuEa`Gf z@X&OYy_f5XuOf`Z!X$I*w)8$I*1nfoZp@-zw?|^!g#qAi#J%Feyk>nq?qn4?2bkg5 zc7s?ppZWC%kHGb$8VK^Wq22nNBe#e5VxQvQ&z*MSl4Z8IwMJErNJv7HojKVT-b++) zX&lbF^b30Fa*cNq?*PhjVBIg>pz#07;K+M*$Pct4r{^8;L60fYeLm+;rrC*Zi-+Q* zBt5EqUeug{dRVFED@cp14 zzZ+^(=X<%rA=AywmwN!Ngu01S^24FO87kMm?cMB?|8HC+4feT(sVhR5=g=(bY#4;0 z!I|JRK$FxC?Sqv5bD5EP1GQ%paZ6&ZWV}C~bY9*Eo4jEXr1JJVWHm!}V)VL=kx{lkdn`JI5vJ`bgL7gFfj1uHz9xf^ai)}}v0 zotpLesq0ncb%n{zyZz0<&hmpIH3xx}iI&h(|sE0y1 zv~AyJeLl70FWOi61x(9w`cX$_J)*F_pg?lx zzR=3YZE=WNDP*SUQ+Pl(XlG&1B9`aU-S}Ogb4wSDO?9bHRjcMXAK+Y1?q`1C8&^B# zx=bM#4bc}5v>1WD(+p|dkz0_-dmg7RR+ERmj=_!oi#!`|$mI8@6NVV}z|T{R>9k%i z__s}!h26YDpI3&$i}4dd`=%icacGN$`L=BQ7M?r4?;w_Sj)8FJp%_~QKzlY?GNXcTP=q#ZDzA5rxYqKD+Dc*nNknS0$P6H3|Rj% z$M#xA^m_r%i?^+j=5Rkl#$yLDHslN3=iDvZXT>nT-+C5?4b=M8Rs3|UQJN8+KnaF} zFnmQK*zMA$7WOM3y2Su?`r20tbu+`ulN7@3Sk8`a6$~S4-O#W`MWzY^k$Mc1w(*_h zryehWI!m2do}xQD578LK9E8dWyPS6>lP@9XTs>vvcMiMMrVM_cGL2X-f4!D#83( zv2<89gG&De@y@;-P!p<6ZV!$?W9Jx_=lh#BT%U-IpT@D*r>f|&wiV_MSI5aldQ@Hi zNO1h;!7_^YY$@z3s-;`wUMJoiyjT-0DyFd#P2Qh!;1zaU9GTnU!9}Y2xExot(8tFo z^yti#SkSxd%pTRJ(atD)+}i1b5Y&_J$!&TI!?$)|drdhrRwYmPRd!L@qT?)U>Gl(2 ztp?+_b)0qcNFAGc`i8}8$X4gx;ozqwg7A}TYahO2?K3xVXm1lT&N>UOqCV4bPNfBv zwitJG2pn9_v*d4`p^0zMIkcL7PRankNp382t{yopZjCKZ&tkKbYI5eu2DEn9l>*Ny zK9e29l?6;{*d`9D>m1x!bn-G;|soeQ|o6z(46gI141)0~i#Gk=O zm~)991=Y4jk6>h`2RN(WP*qfqz9qz2JIh;N>5F~Rjl{Ozjx^|35ws7hk~+omXU9Ju ze74gA8r8H&d%@D?**<<$6`4J6jj=zxSmm)g%3YWZp$Bv^lyfGRch(Ts_K#-j=Q#_m z!a>y8XNw_R6Ii!570=aj&-{6b-W`~X82StPU*ev(Hme|giUT_|s+c^N7~`EcRxmrM zhT4zN7O$DQu z?{?EoXxHQ*NE@%k{@!C0%X_(<4$Oegy|k$?{hqLTS|Ib!=bGducX7O01e6aEm4*8} zVD1nTw!ial(z*NqL-a$L-G_Agb0P$<4^D@T>ojS9)e$gzFqawpt*6d5vry-5uC&-b zo&xsgL*j-)h;=fg(?8w`Pc?1WK7OO0z0Y0raV>=47rJzEw-z4L4Pq1aH_)ugXXx)@ z%=#kds`*r)SUMV2c}Gu2jab-_HiSJ0Rg-U=T7-H5)t;)y;z@b60OI31pv83qn&b3d zxZkZxD$#J3UzWLxmpMyo@+t1mnX8LUp80-rn{tJQ;$zOda9(ak_Fo=D{KqTo>!2T0 zo)Ce?<1euck1DFk{11y_u0v3<2DOOk0(q~dvUaAb@|VJUkp4AT`qqW-@clf*IX&|5 z`=!>DKG*^`-uo+^;ydsUG!*Bq`USx&ct3d7O_=%DpZUM|P2+~v`9(`3%CIapoaruB$S<-C#T#*sXv5#H zS5LeHDe_q6+`66u-|j`Xwr{1yX_=JX#~J@P{RGY4dNgPef9G0Y%ig+tri?xru%+)o{V?p$0T^Szj2a*(i<8N+AocJrKG4KggVANH%Y5aOgf;7RsM- zj)U5X--pD&%r@4fwyFj9p+96fiIsF@%4MAU(4X~PbdjEI9fBjzZviK3ZR)4H4x0L# z+VlIx@V4LKrprtzu;*1;bZQq&=3c#T;|(eOt_@yQR7)Fn^Br|UJCUb4;q^p4TGRPE z@=d9@gYUqpr!(kh!$j=xDF>>ba_&u+4bA?^+ZAavHoXGgxwR0^&b!2S z$Z%M8!wnytQ<0Oyj6{plp;CB`LjD)rPP9?kh{yPI>f_&^@NlO&%WJ2Q2Ojx>qg2m< zX=h{QqPX*d>8CLEB%*>Q4Vr?H$*0*LDT%iCR?2%7N4^&xKJj20)e8AtpobVM>k$X?qC?y1ER_4B zcya?Hmq+H>x+c)4=WB7Brva|Nq)RW{PQm-b3Rd(wgRU=AU`fPBft@l{{%FVhZn&@J zokInw^-;pkm(i^2KZV?Khlj{uFk1B0<-ZFpY`VAZ7_G?}{-3a={TJa5pXc`MC!YW1 zCc-A(sg#@mT7gEa<8+Bmt?7blMPndVPn|-wy1?bLfvm7=HMRVB17hvn*xFOv_i~Ff z?L23*XQNf+?5lrq%yVt&_A$;WEix4UnS^4u(I)?MbRK>+zF`<|@12%5X-N{LROh)L zDpH8ZCL>$?tZZqJLRR)383_$4)%%?LEs2a|&+Jhsv^0N@^9MMe)O+st9@q7~P`mCv z$<5Jc#ay#G;_*m05?v~>-e4?kwA~_EwRtRa;5}PWFMrZdBnlcUxn9EM8L2k-LZ;Sg zVeSA+cwjM*y*i*QF4W{~Pw}S2(7{O@J6@O8yws&*0^Kmow~g#Pti(QZPeGh^Fbo*x zNe*x?mFx4h>1yOh+AvO8Y6x7@o_zt-6x-pxMqy|-^- z58D5MH8f6_7Z=#&!>=C&1#b=(;)>&w;GA+D@!>l8wP)6np4+-J1DhQ5QTt8?1pStL zG-$>%5gK$xY;UH?=b)0aJ!s|gp|FT+-d=GZ+&@N5g}btNd%pmg8x_gZv;ypmod^dG z+Jem+J&s6?C&e`?%*95^bBkKZNc9L(xRo5c_((=k);OyT!5W+qw9ne*(`#$t5Shsp62>6U0AqE_q0 zIqrZLX4`{giw4^_(@|_m*Q1_0eiIEJO+2&sHc`K^jPsD|k*e>4@y8=s$yo={X~$uZ z(|3c=cPiL)-;-1|_^`4mN}~Mvx1=Luz2x*`M`^_;2^m+V&z@FVqh&X17;2L%yx_N| z7C(JD_i=Yfxu=EU$#;pT=4iH7Y{eeW_QIL_uZ4hV1!%A71`%`qko3puXf(x_tbJ$6 zuAa=tF^7+lXXG6rf!T+c>Zn=Js zj5yhcB^7nyULk%*p0&xhAV!M*FZ)5Wl^e|EIoho+sZ3Y1=R^+PAAX3$Pnt}Qt=7eD z1G<54qYbOy$+dh>9cay}JtRs_6K9;Qm9Yyx&Zx&85m}&gemSeO&A{B~5wKi)6TxpP z7#*{Ygd|L7>w`IGb!H<`nlWAY?-6H49oR#*%2kuq-E?sARU3%XZWOZleaD7-)7JE= zCNH*X;<^KM#CPHvmXzDdx$(L1Zf1w@c5p5#o|p(W`wK|Z3GP9g9K$oM2C<{NwaM-+pTAeGupP2t-bFGaqqJ*J-VK}NZdozl+>{0<2T8O z%M+MysFHZ{pb`D>_KYOV#Yv?9Inuk4KVef+7yPCr2R-Lj3xE0ZKjC}>yj&9=R79A3LoO6Vp zebhvUp_)*!aSF?QCoh`(tb(ztwiivaxs01nZ-9rNbwJ&T^IcQUkRW|Wc5zc7-m&Tf zH|@Sif{hHN`SL-so&0jITKskCE-B&qbMrQ?Gt?*4E^06gQPafaC=K{8&71w2uOfcJ zFR*saH%T$C^Fxm|!dN{oYJ6J<*P3(2iH-&vXVcF7INc=l4&2=&r~N&Yt!TC&td4eph%z3`nBz0|_aLDsO^ zeITOoJuhY9aiKk2T>A~;1^nt_)OLUq@&bq*8fRL2h% z8_DrkN$kg=Y}8%eKyu~vSz@@VcVZj?o0ftPAfZ_9gl80K_NaN#){Yrb55}l2c1~rhwD}PBE6`OIBrxty8 zsyEN6;de||M=H??1|`k_-|G2;gekkT%Ad+&Qfx7#hjP7~*%j=k5(aezCP2CV!TRMU zqE)2Krj=!3Ls&g2-NLh1c>bgQudk9#I_uawH7AjA%wbu0GRb;Eq&pReOh4H+s5{OO zw7_uTW#MIXE`I%*0J~Ik$;-a{R_=LL0Y??bHRF8g1m-Chp^T+ zjRN7NI+nYik?m)CzvUXF>gBL2sL2ls3~`l4ha_TWr_dmA5) zvovt8>TOaSzLd3?Hele3U9jVL#2R-VYz^A>4+?}hA7jFBIRWXDeS5*=NG(M2) zYU?F+E%wsDQAEb2DW3BiuQb#{Y$w;_@turZh9NEZ-W}EiYT}yF_sKtQuxhp;zVx_C zZn!H58k0rrF!zN6T)+PMw< zD-@~!OnbH~ihp;`8`9>L!@<5x2XAhDM3#E=W!>*FyfJD%berAF&vFyb553u?;(&gBM>KxR%a)x9{CzH1ibVCuf{#wclC*;9tn039JQmwY?j}zYLLV~} zFJC5IKgz=@GhIB{&|SudXMFxuUF1wPf~rZR0XxsCj3F=CEV1KWSBIJ$S#94ZXN*lQJ7u-K z5BG7*eAP)VPDmvu`F*PIjAluI!34JDKP6E^YC=EsOOr6ZKOFnRnKtkI33Cp1!*^SC zpe0g{O&jPacC2cFpF3Mg$2!iPSbmm_owkQv&NarKZ*~&7<#9qy!!^uxR)AfDZjjVf z-1~g0UGiv{FEi&o_T>|lmit@4vK5+W`cn%U6{oOxH3e})#|JpdwilV1YvJ3E>4a`_ zW|D$DOuFR`?^54Oo~Rp2BfLh+>iL@&Kha$Jf_UZcW<7Wv(6~rx*UN*Ud6^al)oR1C zTp#v)nu?fml<%hYeUlvLT4KjTtuSDa7k#v!^P0BglH1qxn2~%oZkP0u-B>rIso}iE z1Igv5acttMMx1~B9XU0xKRc?;eafS(frAH_s=vJ0m+Rk-DXI&JR~*F`?+vL{SRCwM z&v$*+k4S}%E_-KQh!1Yfg79$_65q|H(z{1@%l0rye%9C}bvnr!cwacqc*aL-Ju&(I ziG(cUTr9(Gu)uQ=(>SOsew0_G56sJW{tLIO67Q>RBo#fy{J?3#+RgBAPCRYB&Q1;pcyUM#l(Byoe5gT#Qu2V+U?R#8xG;``u+6dTT7W z95;c=-P*WMc?)T2RAkQ;v(Y23gUqQ4CF@*y?|rCA=6h=6efwvRK{Rf4GD$KZQubq@ zjAKA*|KLcMXRxt<94oSO6pycHhrAjGcw^7?iVrT3uBG!?%(7Or=!}McOn8fo3;5XV zFKM3ho`mIV;VgL-lDWl#b>&(YKmS2=cFj97i05mU@Mo`M$OdL{xD^W>tDxnNE^7$j zb@+2T90?xbm(Xh* zSUpP}4YGn{ch#PzN}}SOc2Y^!OBR+oNZU#V$~2P}|NX{i`G!=L+2R4w`MB!(S4&pilnaXFAa$rfQG%2SSoWC%Dvl=FK_=8_yfUwd}#2HB1LZ_Rh4 zeSf&nZ+G{Q^n-j>>e58QKIXBDqq^V#<9FmxP^!@Nw}1uL7r{@im-69!x%P>PGR@@n zxNLmRbt3<2`>mT&ES^|EoKh5^!rB%WYWYA@ktS2Rqb+bwLWsU~DNb`IMfHFQ2B7 zEvEe;(Zm=F{9NJQ{DnnJ`Lo($--~L#Tnqlwc{X3B92D*_W>JLmwMKQqjD=^(xbFti z{N;I)-q}fPgR3@boZd=m`l4VpEC+v#SB9dyshq9K^ZQOKlJBp_vmJw#M57&MRK91L zWG;VJZ~xbey59N;wd1>E-vivUVl2-VPj?jCHg`gg@2zBRjT**sUdYeydsyzCdVFzu zDdf!?!^R!v3^6k$*m_b*4({W*2^Un!jaPnbqOp_MIMkmWh_!(58{DTnQWuVwVN7=)Hf)B9ShAxQT5f)mtmHkL zt3-}|i}0dr&*-t zs!^lodX-6bc5@PIq{g(PrygB?q7LIyufdpztL)6aD;RrqGFXb<#ASy%`m1jt?=6#= zb!AVCaa>Qj+)EPLYhK~Ft51j{?_IaNFh&cT-Y_aOPndDXQCwrxi{1~gfx{LGV))V< zpgz8+z}T}8-v%#$yPsyCcb+Tb$3|tVq&J)-fGEf6adqKz-7a$;-JCsi#SRY(KM0;Ea*oFJ*Op ztQXH=^p>Y@%pJkagYWT-uMm>AkQtY@;bor~kk97XtRClZ=HCu7*rSSAc`RwS3LO{O78msO$!7-y2|dd>0~-bO^adPGT3&Kq{s!hh_~u zY#(j}zcnq`og`j!x|q@_AxDYwcV17hQpPbb;@qUvKKW$S>I$J{c{*NS>IzdYZXr4! zRk2VyoaD@y%HAu;iGJnskoG4=*fGLMlpYMEoo)|c>1YGaNHKv|alZu(?!jp_HKq4^ z{vm^IXyB{6k7fFq(gXGQWZYq}&5dLc+xf}PI}kc|-ys`0^G$FWN$$@jY}J`O^eZeN zZwvcKy)9O{v0AJDALO&imFqmDTx1^EMpy z<^T9P@=)JRs%+hcq3J+CqMv4`zHi=;a zpamB@E6}h}Hq49ff2N-{rR6V%!wX|=&e(ZDE{*KN^tTz}H_iZ9l9b>(&@&U0Q#?R^ zY&Ym-rHc=XCz5{|PX`?@<8kdAvj0{%SyiNiN8UJq+)*3$mG4fk&*@FSecMBp73d;( zDS*m*#`M&?;IZ0|M8zysXv@e%7pIwEd1niGdRY|*DkaPAs#DHnW8x2W7%qTcYjKwhT5-N`*@p?9lE8lRm(#8L#D8M@xWA==D+;VIc=)BakWchJzbnCj4NI!8z_3#|*wMYX3 zU#60>GwK+x4D2YoxnbY}K(j=#NpD@+jjT*VvLeDZgoIKPB0!AsY%KvyD zLKNsQ*EX{08PAq6Wy#7fJVI4fL6(L;mR`kMmn+ zV|gIWIA#GOQ+Y;GKYeIFIE9rwlNZ+wt^tLT?L`-6^F4Nd1*&{y3;6BR#@!FDlA#GM zthGj29O1DAT;|vj=Vb;`=MNFG-FuIowP^UFf&6IM&8qu2iQ`)XsrQf}Fo|pJYDVb6 zp#pC@Xx1Ni`s$k`f&UD4R~4w?W-mIgT^nzXzQ*$r)Y+9qd{0&333ucJ$@gj% z9N{v844|>hV0;65^lKwO&vNa}Y|hiZ(M_g@Pvkz(LlG);qm#Pui{C+hRGCs+ev_!= zIrX`joJT9_u`h%3@lVY{&|7?0vU#7GG-}cjNz9l@OfiW+GtboF;iI|CCFC=nF8EIR zsFjj4jXY1S-X7FK{n5;gGL6INz!^ciQfKZG%Hk(CNJrR)4f~CZ|w$Q<<1<$ zH?!fIri7?us-wEWHu7+IGT&(!;6h0RiBef0{G5=9=_9U@P2)<4qn;Ih_}~q~NEF)m z-1quOZ|b_p29o&=%VF3p5VjQ+jI80lzX>Vi`M4gelHaYiiyDwK>yPBh(k4`o)u&T# z^k!@H_`9a6H#I8@hOZ)j-$k{`ZmHi?Rm6US??eBKN@TrrF6Q-{4_;lYps|-87Ub?G z6&qEU^aal@G1h=5Z6iq?pWjz8O(IyYXE#io!~?GaY2!WaZFub`-5D1k^E!>Y`UjQn zyn=f^acm6tRIYbWpe@7^2D@r-24JSFp2zNMMfLYFFzgB6x0~ePv;YlwAYV%y_UoYc z9s}}E4_U$MZODs2`YY}|(Z8pHp1xY(y>}H`@}d<@dwqmnetN8e@2+ooD9}&oqabAv ze||Vm@u_7n%h|6W+TBfn62m4xlhP|FpRWq@YI}jkFatb3!7v14WQu79(_B=Oo?;8_a{U9svEzbHQrO;LMN)!FDg_;S`$E zrp15A624n@X?j9D-z{TP%j;3m

P@9?6EUyM*g*xWoGO{7zx6fpZN;6YI0Ug0JOb z?6X30;hCG{p@oyQacK}K%rRia#wPe{p*5HnWe8)}If{+e<}_uz9W1-7gLCe@B}4xk z%L+}}aLLLuuy)@YVNP!Wi(m+!SDJ{W0q1YDP9c72HY~vA3eNi>kT<>L$srXrtW)nM z)4)erwxDvOB2AfQ!?IWMxxn0<*2s^5`e9mVul1VLFLh&aD-^`*{^@XY$O6A^@2;SO zWB@!i=R28SI#{=D205@nj`^EN@vTn-cDJ;q zQ)r{PxMBBVh-xh$UfjdD=ojY}-yh8O+F!*SH$6CJry$AIzleJ_Uniai`*RkOoVfRg zDP6EGSh)AeQ9S46PQ50tgBj=e`)H67?9()6NBCT+v0aHS$~a5BM9!r-FO~J}_frk= zN#r52smE>MXkZRTt=9#O_o?L7Af5+$!hp!QG%u9IMruV%2b`5m^m7t5Q{CzHakU^k zvPaDWW?-nL#9|}(40uY3j)yi9VyBKn)pN+PF{#XAc|A5}#X$RpG0bLt4j#Fn3n}Fy zQBUG`Tg5KKsN9>K=h~0mOM>XL=N2#_Kob)h3}E$$Da;{9SqyS-gfrH=i$eJR&G?cM zU3qs4Y*?X-$Ho+r1D{=4yhRocNb-Sx_(H;t8%oddyrh5GtR;do_AvD(so@WWO?FOV z_jN&Z+`=KSlzXg->kOgvoewLCQ4zJ%n?QL&wWP|xNi68COxI+3(GH#wyyQ+kIoDmC zy(`N^CwCv%J2im(;op79p>VRlPb?cUzk%-)l)+!>$u2eX?@p0DZ21+*68KIdd!rh? zvQAy_<$r6#8Rpb4I}S3Q=;G!h?@4r)9<$d~5kuQAL)i5$#LwMaI(P0VS>HZoPc0tH zl0aYm!)&SAC#)RYOqR5lkgq{n_|wuswr{_;M_JriuSG8$EtAY~bP|^rnbR5b^=RmR zJ4`w!4+mB>3-3+2hq`DXyuT_Tr>gi2WwnE7CnquKw@i-Y*M>`#x=encqWCIE2X=CQ zY-)%xUe@Rfs}%EuyS#Tj(BGXNIBNsd)(YY@g}V@Xtf(L~oA)PbtH9RaH!)eKg@3;9 zmhETqNinXNYYsw!B3aq1881FCq<^E`SR&tv4V&yvy?+M7?^9aXWvx7TC3&*mJi~p_ zrb;+GNr?>M``+`b7Q!G83)uTz7v+<=hIX_HOFPdnd%GzJ&!>{dFu>ds?{a=O`*$sZhO1j<90{_c2vmCz}ud z$Fxh@aO9lLQ1e<4ZWZTaxxWeAxY$Tk4f%K9(2D%ykL~21*-1vhRIm6wdDEhd>Nj;@ zE?$(CQ*Q?>uem!=Ezen1KsZiBNqrlsi-+j#UWOd$LUS5P*Ng$#1eoy#aVH}wVbICPVHN0Oph5Tc}4|;PA-Iv@Wcg)=+nadodUwwj!`cMN_`1u#EStL(w zJd>F-_s&~ivZQ}g?11jo!irt*$cOo(S%I^NioUTxlhcJ!K81KQIT(ty8%WzMo~;%& zTc(E$iM@~-%&OCRB*d-hJUW_K|-jHpx7Lfw} z-poAj0#*^WY+eS}U&Z#LU;I+Z!%2GBQ(YDAs3Fri%ymS5CD1=-1)EPZac0>X?5_tb_f}-}cRAztOh0Nq zwuTJr!Fg^$a`3k!nwhU^#X8}ZY(JB*As5{pS3q=lA-QG7HIw0~_e5OB%9t zrQ1rRGR@3EZEak%c|Wlqib8zYC)_FT2mK2KvOiG;i)WaTOIyaV!)8k2gsIllW_g-q zc0VW4)X;-|j<1Ey{SB}$=X(rI`y%Ac;(fcBDqX#zjr8O1tR5cuq=*CRExA4_q=+bXcVVwLU&GXC0k9Lji+523>^4T09(ns{`I5v=FgO!KZPi?!WbK+W-+q()UcDq%pUx03M;+X-u_uJJ`?Fj>WpV3X9a-OQ z<>e$!2(qHZd-dqp)!i}MUJ<0f8-*=B^6;}tG!&{0BpU5aVI6X8Rl zdtxAa(4K)M5v3&Ynv^Vf@(bnP>(e9dd)Sb-oC%QMk1n}o17o)-hz%vG>LtygoTqx*h$c$i*bdG)yxrE1t{e~o zaa`N%bxe_GD0s5FZ~5GD{|UHqrq2SOOK5t1F2pApL&#UopG-U`%lp_lO2D44EWmj( zuP>9zxl@htR`8q0R?eywI0dc=c#nyAe52Rey{-G|eq7gxX}Lp}U{#~d2s zESNm^7jz!5rgKV;k{!I}e;ZRnrblJ4h2Qki_+2SUwx|@Gg^M_MjRf32C6Tdmyw9(T zB>xz~rnfrq@?m2rna^wcL?^Lf`f!^3sPXUw9w4x6Y)Rn#=u8G4Erw&df6@TbLP+d>B%7w_QMgjUgtfn z+Hw*dBF|V>7WTXOnCuUlNJbXw;k!yV_%O9QbI)@W)r|Vn$oZ+{QHc(Eq^ZIxUB(9M zHQ++$GH?iwX7SNivGK<1^9JuZ)@0J|g7`~j%^5vcjm3#30Pp9CV#B+NsSA%kN z0l9iz12;AvAloYfSwj=o@DHBKAvL~|kq^^x`gZPpi0TjUpc9?_E$C*KU}0;MqgXn= zKkfc&9YikB#rXkhvK~H_-})g@ovu?pN2YGplg?2qmHf;5Na6a2om&o*hzJz4=6}YZ zx&CnGDkEc#t6+n+Em0N5G2yC`SZ3ReN@kyx`0;1;A@}|CsjP*nohJBMK@Y0K>V#P_ zd@p)Joo3u_BZCY0U61SK>j9o_8u&c42Z^!u zWggB>VnF(ED(`Cvn+mjW=`~Xrs5gy$daNksByfGy@SR2X`5njnygL2QC<(Sys-rxg z9}jprGK~${_^97t_1s*q#s-v1h+d_#06zdCd3o-|RK$P!(^QIiL$J=vq$t-_d3F9e9RyZh(wM zb2vc-jl&~JmO?Dcb!)_R+*tGP#(K_M3w=U+!k%ZdSe~`Km~N>h>*3vboi7|`L+ii9 zLC$m?^gQsDoLi*JuJ9Y^tNqasd$mmR`_)o3;EZ7%r_0iNSc`q9hQQ9?!|bcad(;}C z3Z>^n9*w7i38#8NnqvTas?B@gX?pZf-!kr0;=9&+HgrXS9;N9vc*;i+=D+Z)PZM(rwiou%@C%dTZ}=g$3bLio}cTuOw8zM0^2XS!q8QE zc=xdjdFbCFteEB`mi`=0RcltjiJv;S-ppLamVC&)RBPwj(2TaD#4|=056`bAXO%9p zQfDKaHscP#M^6Op-WM^*gutv7N#u{88s7GwLrlFR*q{#1liBo)42t#?25xl{b-RzC z2YOdR0<*`+U;SXpUJX{tZ~Z=lZD^0)^~B3q6Ei$MkU>ey*$A5k+)#TKl26WJ8*XIa zq!$4DI^_%C(Wj+Qt~xWCvQR8A4S$ z=S3gyM(GbbnA%SZPk#GKrgtCBj^($Z`u;26kW?kCI?Hgt`|)s9_)8wVQ0@A!m56dpN zgJgJjR?hV;SLb`v$e2`e;*uV=uGfT+Qe+nb8qoQAIp=tB-tVWYc&XodaE;tXX7hLJ zs3Ql-D*Z@y`eGZ(IZuJt3de-U8W(WHhDYSe{?8;i#~A+%8vtXcE3%h-7B0;2rgJ~n zkfVGiY7S9^w`nU_r%gLnKqbtMmt%4*x!8jPpcA!2xsk2z@2_@%bl?2{eMLhTUvE z-y;?EA4&K241yqu7E)Kvs$A~N#yhEqeiP)WURbq6nR`Gy60~Thn>T%2p^sN@@~nz2 z+DtPv6G!g}f>@gXGOR%ZFHPk6ed9KD&cb<&Slc6f$LG3M6N;|r(8Ttu3brHD@v{)S-|;i+Pcj0F4x&+ej?j1 z@%L8wFI>9Jh@M})hm~nKiBV6zsfNTB9&$~>u%XYu(MBjp4dof=-ZjwfFcxCdwXnVB z7#Wsq&wOLKcWk8%%|J^DlJ?jd0^4dnEVfAF2<54d_Xjv3B(6l2zE)3qNRAzz2zK@y6| zFZ(EVv5fCkRCmET2PO=;pM@41ZD3{g5AxfA->J8Iklw_S6=?BipnMcvnfihEPuvq> z&=vaVZ)B49ZFqc9BeYJ_XN4QM&nrWl?p+@S+p;xK{bY%ZA$jMcf*3G=AGo+R`vu2m zBHeEdK8>!h^okDRkN!Nrqe(~(aS~g6!suj(h6DP#82H&rrgc~6^-y!Y9gWgGM&>1J z;>*|7Bxuc9_UcX@u6T6;lJ{h=gjW~wrsoiNYMo5Fn5bc=(Q+AQ?8~McJn8X`Eb8JZ zNEbMX(-Xp|c2p%S+so(iNtQ5_)d(G@xz}UA9o1i5PmKO*;3D&CvM6miTl=~mTWT_7 z^}MckKI&mOEa+WK5<}E6BQ2VAdr8<~l@gvS*Uq_>zLHH%_R>dzQh6oQM)SA1Q^x^xx#HeiS46PZhkndRCEdb%;ib!53p)NQJ9o1lU%tNw<7Y)PE6(&@ z=@|z%%~MDQuTf?%j>@vOrzyANykn7YXy`G4-8hd=vR{)$!JkRVGh@`d?F(zt6xsea zeE06=OBGGOlMo{X|NMCV`6qi7k!Afgc$UElvLk@! zti4wdb9XERi?O~Ex`Oe1y%sWKV+br%=S+A%8#>}%uwc{9y>Fv@Y3S1R@Zk+--agfW z^P({;;q|;mq{iJO<=ZrtZ{QwK51)zA*}1(gk?h_U{UE^(y&t% zAFB5uw<9L7`9w)Hjq5@G^gJuEp5i3l7kp{if;w38suw!4Hm<7q&pVt(C=>T zBx?uffUPSdn-?5liG3RI=$q~E-?nh}H7E~Fi38a2VC0R>e8zm^PEvLaU{W_H(U*nM zk9#d)VmW`#Z<)ii)~QT8@!$Wq6ApIWQFLfO*S>Dhp$Ef~z+i(8a?&x;>gLK;f6T^; zQzId2@@t75*8=?eol!2V<~vXO8)39^Ns~Zdg!5oTsa>^?96AZOOeLd_R-IwUL639yiVcj?Xgs z-Q1wyZ#dsI@%Op)$g!~SfEGqPKP9X4dGWbux78jB4mL?bU7B%Zh&e6t z=)-FG9Q1pgFKwy}f!-Nfc=wt*{LB8ZI-x4+`hS9B`6{GYITH`BTMN0~W-$0h7qpw2 zL1tTNvO#$z=(O1#dYR55AFrvR&VWATU&hm5?vI`{VGMnezLk{Sl}M+=gv*#SD-&$+ z#APdZn~@>7#BraaiXJ^@;RHL&xTn7BO;Yo4A?wcbc}GR3!V@(noZ{Lo>uEh;bm9;4 z++CIDaCwm6v&PJW*Lj#ehVFmF*@Aqo{Ibj()*p^x`rX>md0`72O4DbzxW;>_sUA(= z7Y6+}6Mmn@UGk+alx1&H5EF9`g6+{JzqennV7|5;JdJV%37=VFLwreD+HYa`SSK<5 z{TP~)8VzrM=-_<5C;sPYx_zE=mD}uTpFYP()o^|SVby@|PG-U&<=Jd$axOkMngEBkA+Mo4zk~a0 zENg(7ANq=YEG!|2L`V$u?WIqqkCNqX+m@T)xFtQ|+0@IzOzw-{l%Kc z@{QJv?YMc=oC^vSq&fDJ4xPDN3wBVZ5W}p z0IHrJ6*fd&<9>u@QoW^#^!j6jPq@|LUw+?$8t$FBEuk)v-$^!S&Ll^vL*m!f4BoZk zupQ4}rhy#0Sj)3$A0|L=NfCL;Jx%YePsy0@?Rg5~;tR{b%GFnryq{tFS_K$*H3X*X z$%(i8y2<+XO74B``c*=Gr0bzoNgJcPYr((#zI=WIZ7S(O)L$;XsunRs;q8J%Y7u>Z3yKF5yS8WABXQ#2J%jCreXXI#*MoQ5F zzDw-XPYPRlv6Qaa$R3RW#n@Mp=%WVGc#kbI4SX5T@*^9#{)*%Y z_rjdSaq;2w*0mt02Q(=oY-E&zN=NdgA zm8UhC(XkA)3mO3fyeMhndBl}}HxM>Dp2e-tM&tE--hHCXWwX-f6rnQOnG+X zeSI4ILS4xE|u#-zHgJYb|~Ee7wY>x+@Df-h}2aEoiJ_AC|ypwC5ItF6}xD z9#?Tjft)5tLOhvMr;6y&{VNQ0S0NvMXJgyy23$qU8Yp z^zgOA)zBc_n>6waZk6FqqSCr>dar6L`CBNFDlHl-tNA~<9{$PP-*8Aip1tOpy?Fl2 zT<_-u&+F7ND8EeB+jov?!w1LqLTH^JJnEN)UrOxZi^>nOgY)yFyuHYhd}DTq_a1C) zIBhZgNP2Kx_qDZ_@c73;f5f$yKK+V$w?*I`i1*%4h+%gNS(!#UGl zil-Mvf_dmQzmW%|SmWCdTE6>%@KqPrEBll7^?wEZ^-kiu{BU}%DjF6oH^4{pd%%hP z*37NUQ5<~Tf#!rCBgJZ3SbC?9T=YK2!i|1m#q7&)u_l8p_nr=GN^ zYT<(NIwBTDvy3()%z+mqHe#Dlc{CUMdQXJjXOYYsuZ`M+Jv^u!*SX+c3|-Of3Dcm8AG6kcYQ4a9U#@aCsKbj&!xc z@`ip8{5@DWc)?Ljv~;FNfDXr}m911n0-lTQD6tU9U<Mv{C0UenbOZz z8=zFs#ZN7I@cV-?v*dg7J>iD*z=?C@%RDuy!jjvPfXI!kuUQ=i;VvktKFv&0GcaYM z1AIQSgE($f!`dU1Y*(DbcBpgx#$IPynsiQbexZ|CS3~LOwmPtwXNDUJx&k$<7m7D= zcE=<`>aeq&{N?wWdAjAKaZ4(jc%cEOJMM)u^Y@R(+|G9(6Iu;vdb&5w+spYy2Op9n7c`iga2fYJ2?zDd zgNS>K3NFdmDAUqBGtS1lN*!b<&!}~M%~=y;`@$eHn{_df7h|M`w5e5Hn92M3Z_}M= z`Pz8UYvMVu{+;CPN<+4`Rat!Ys1!cC8j-FGV(@so1sJ@{lfow>?3u8GoGdIB6n%Im zi&qDEGy5PhzpjOBNk7ok_2--`zK5?jrJtVPlKkNPTl`yR`e%wh)&0{AJJ;wyr$&>| z%hpjmw(&3A$;u?t68X;dOB$JaD2Ywycgdj6`LaFy@Ecz-hR@l3jOC$Ps|Q-13Ip4S zav`1TMc1#Qbk;Rn*tu9iTx0nW{J#hV_^-~t`3o~ojRmDoTKLHKB8kv}9r!Q3KT~?G zBK~+@1EZZ)h}uz}#W0`+lDqAKS=)5*=%7oo+iM5k#Un4H)GMt7C29U@}$Dj5T)QJCG9-=+WsPNvDez&i`%; zzIn0in|d2wnkz>W1NCKh(w(kG)Yfh^&!o`A6Dbc!)!|`mB=0lJ-HCLY=}L&@_r5rl9uWJ?oQ>qY@gE}>`gi*=qWqlu ztWPz`>ipkQC(Jm}N#^=C2!porY2K@eIJ7Q0d2f-vpZ-;e;2|}If|=HTxgVe0|{zX!{f!jWt=g+^<8lAohq`^ zcB`<&ocr1WBLOCe#3E7yKkZB;i;h$Fd4D$A%u|Hlq?csSWCy8b@9{ES&CmOFXm(Ol zw!=BV-%~1r3w1o)13Y=|!>UDpNx{d_?7>g2Wg5fa<O;+QhzF{>7(D^yrWWHtgU{uD368p~Z(oA%8sA z0DISyVMlwhJA3%OJLLwX#4Yq2^&khS=X3}Ru?J@@9lXcyrHLAHOm|E+YWOID@$^aL zY@#8CFC}33p95RLKU1e*5Pj#qmrS~CjMA{K5OD4`i~L)UqspJdMaPw_VW6Yqw69=q^`YhB(B zqBYOHlM-Lfc3Z6t+a+sQX<8eeI{Fs0&&#nTyyk~r;`wOvdx08gV84coWWdQlmS>`KKMEo74+#43ZNKme_L+UWky&zq5s^{&eJ!4KU>g_wR6>k8^($ zR=t9=@@^Q>Bl+jZb+0-U2JHoJlQXQG``VsuOM~Xmno!V14RbSwkoZ{>S@mfp@sEuQ z&Gk7anY_|T?3c)WLqWeFy37taTo1>`r!ia|4Z726F`Lnm=J~{h4l`Twc zK>xi5WOaVJYcZByqtMsuArUNj9>Jwx^3TWW#`OS?OD59D04q3gPZM9;c7r|X5p2G{ zf|xo=neKGkQKTU795iKP`b12Et>1L;o98n^TU=Rh-7I`2PLXB#eQh<6YQ5VjySG|g z;u%lkxGTU8)XWLH6RRvPKCMQNbbga`@Ev~r3S;{C zfj2$YTNi&Ee@0G(YqD^ME0_>53A~6undz&EOWcx3&f`t2bR_2ldMSbSZDm&TP!l7T zdcff&vss{-yolF~=yO{Qp_pq_kY~5eN{NRtTMY5Ovmz{UF=B5Qs)!S&l|%SVBO)KZ z5d-hp!n%O#QqR71*gP`|7JWL*)ap2|CPRrc6AqCRoDo-G>AZG){tVqmM#SY zv%xH2Gw+j6DZ(# z_d1~B$ygY$Rs&-pgXDzRF}1vFoZadHrjHvX>&IJ3kH^oI^j&4fxjIcaE8m9ZuI$5V zgPp|7qy6doW5Yo8C})*a>q6Py{%pR1s`#pB9n`K;ArHAO&P%5gKK0!N&V3D#ez_*g z1aWESzM<27AnV9TvNBv1yQdD8-Cm2hzUY#lE3KV5g~WU((!a|iNUo9ri<(%EU;gLl zJp6Kc!!X`_+k1!7&_bzXG~VZaL`jj*unG~Ph!j~xc4Y6!ri@Ah={)aqviII(XGK#* z>39F$KR};w&VBB2UEgbN8}we6$uv+?T{qE;{z!I)`btgShCcUc?X%cc4}3Q-=EC$U zCfvacyA9(pH*-r3x$T2muc@K(I{(@kd32-4)1mw$xnruvUz=IM0Ix;tT*qI&a-b6Z ze^(!pi(IKAX4F4q6iEKpwHiN_=lbngp(HM^J_6cGEq)1G|L`yQi!tXY6($_UeZrqe z611#YAj!_+`9+Y0tgg>{<~zZ&NnMy1>TDJExl-SA`^mB#E&eC$FWG5yoW1_+ zz;Ea)fU&er7_z#QFAkUn0sXd+>A`CJz2h1(-Zh4`K0M3m6m|Hr(@S`|)>%~S6ixFp zAA;2&)Bq#H`Tre`3VJm5opq&$Qk%#M%)nC9XeQIG=Cbd}#@s{mBjLTWgyyRkxN1WJ zi%K8mtV%9)rjy`>@WOcX~*c1KKjxyyHW94-|x59*9`tAmcSDq5Wt~-g& z1Kg-;WjCSwc6pumv~TCD94jF`_pQLj30!;kT!<`dA^WY-Hz(O3@8|Czn?m`u zI(Q{0lM-Z?RbT1{-P>2PDUmIhRe?F$XFzS-vcVd4rFSeTsrhOcs<+~1F_HHA&)!ZRSWoLQfZVedSGLD4qHR0{a13~ql zGaHFqmya<4v??C^`A`#HuZ}mY=hxVZX^mXv?JHP*HI>a8<|H1LDN=N>fd=vo@)s14 ziyx*jX>dEw4a$JX^8JG1$ULqUs{}(wRg<~`GalC~5ZwN%u+%?J;?WfW)Y83%v`*FH z@iKj=*twYLy=vpW%Rj>3*9z=1brRo|D$>Psd&1Hlnmq7+fxOPY@l_Tlw62i%_Eq0c z@pd~^=;-JVfwl@_9Cf1RZ$kuq+-E*044_|5E(P<&c&~3q&N=q>mROS$MwruMb;pU9 zx&c?&d7jKnzA9AQ%jZw0xIt-1Hd$k#&Z}dFlY;cIOb=PXs-CXYV9s&r&pFOwPoqHk zB)txffieGyK8vS=e+c>easMA{P8W5;?1VryerDS}VxhT}!S*J8-Zlq}#zwNiDIy=3 z832b@KOo2FYVxbCBgy~Fv8ZwQGbcyWCVO6GjUTH;{Xr-4_~uq@%HG-xY&B7PFnP!QKbh=Fud1I@=$1XlY?9hAIysnAo=B2@L>p(Wrx|sL> zpaIEWu9AUn^?aC;HBHFc#w>_b2B=lurJ+PsCT<3Wkvcr`c`?zOt-=;AEkeIx zAIu^TBc%(~_`t+aBKfeGO~c-xeo{1ToxGkb-U>1;m_!;k8L~^K%=wblR$y}Gh@gyh zI1`^q(-Y3Htz3)Wn)8%+o=akFx7v8P>;SaxVZyoCBL1yYA9jAy}&0^6}%OP&!YI?ZKb_eYzVpxzj{u zwPTxVYX(c7wd`1@&T;xW4r|*$7#nh zS7}SKqfBE_wA>HX=558TLwsS?`Z8hl|GRp@om#!`25}?MKWp$$?r*Kx*v^%mu0m(0 zcf#LZh1~JsR7gEkO&Z+r-O=1kM)m2+He9ddmT{dRy;YCQz&l0SbZ>aTSF+l7I2)Q8 z)3$$ISr~e*-(Pp93zWkk4`;)1!xdqZzXx+KP!bb|+=h{AiGH_^mGXhDi6H6e1b=Zh z)ZemA?r)7oR+yQk9^&uE6SY!f-gWCBpf1j=05vcx+XmA&d$yB%=rw*^Y6jD4Is2rG zd06&uL2Z938$BL1oW3e_@g!x~)f+P=?iZ75E2lHJrR{u1dnRoCxnJNv^LSOh8tD0c zA=BnN^XE{^>N}1_yi^g(miMA%AC60X)1AcwB|-G)!#dcnZpy|v4x=Y`inBOSZz63k83LE?YV(bo95Dw$%Cz^YiuccJ z)4e;tNehNx@0!+$zIXAa-30Wo_kT-_&9zv?PRt++oC#lN1d$E9G`Q=8jbvH$3U>NY zA+r8-ApVjHi@K}DkIMQ(YyDJaTcaRenrT7*=L0LC*1EpMovOaggpvvR{Nhd(c;aQq zH1|rxu(=N*#nqH#zc!SqJIJJJd?dSLT+5@X7s8mPy=;wTF(1{S3z?yN$WGMiUvl+@ zL5cxv%M?}dlwc*V?UL=zV)#A}%Bl^htbY%#+rtX1Un#M>k(fo;PlXl*77-mi4L&dI zth~0{KX2l_{-i_5yg>G6LNS+i*8^d|H8P!=@$9C-P_JArY(#e1A>SYxHpmu^Oj8y2 zX*GdmNo9G}3e3qGr$TQGh=Nwk@Ax(20(szzdAK@7{K0*1XsoD}_N}mzt!i5+?cQj? z`dn+~bhkaNsc~n0P>c0teh^)(GYn!ab@-@##!$GSAFKW#5v7-!<+c4>InKf>RjB)_ z%@CBN%MXvcKn`cCvbVPi_{og^aLG56gd&@Lp+}_L>ss(ZRovq1Nj?6>5QSZSvYSg| ziAk0|3$knAvyfL%Y@Nw!(T}5&*qQcw>(qfc5IJHCIq+JI@146z?txmLQpD%YG=TGwy@kU$&SKcSSh~aF5!es5 z;OYVWVA3Q7R(aP+)Op}Z%hY}oMdZI7Y3v~3qmr4?geKl|b0s9JO=F(1Wt`b1!_@Db zh~b(%Z^%}1={996>WX>av&bhu?<(D6-A$HOKVE)^eOXY)j~p?eZ$@RYZ&-Unhxew3 zjUC|1d-QCsQi4slMzK<(c78YM23&mmR)|}Bkz1N90^@ynqw3J)OKxnF_wbJgRr0G# zyTYy`Sldyz)@!vdEUj9}et&A=YuZg{K@S_o@b?cN*_#IR$GjDpHV=+a#=oxz`-po* zn}T~_B_#Nr!u{&h)_BnSVguRz4SB^@)FNUww-=RhK?P^AjG1I$HzOW-Z4kt4b!7B6 z=D;2brmr7vCnH+WQ+&e$QdLD(aki0f3I7O37R+ZyV{yhjE1?BTlp!}=le@c~Cl8(D z+3W@FJbCMCXl&mv96<)!R`i$vM=a#5G-k_CxAvnvn0~ulL;5$PPA|zA z$_6ZERd(&Xzt<1g*jJI&N290XjD)VZ(-W4|tMhjjWhBmg5R*D6i)X{v!!a*EX_RR` zf3Z&+{%6z}bX5?S_3c52M+_AT+;CU(C76agq=TQP9)En(98`-;S!Fin*9Uc>#r;o^ z0ih1OcI+Dx`RAjM-TMsxe%BW+5781tF;#C?# zUuo7uqrWLHS>6?X{`@8MEJb!xLKk}f$UhRDtjYT>drgL)+reC?81mBcN-|+Zx^US1 zG;hf9fnmoll0)8_+}S&pEIf)g&?wv=?vJJGFw^bp936fz%>`nWCo_XqMRDm9O=>$} zW5tLIsEtqRLUWDRK?Q0HJ1uxmtWNf1vusPai|ZWtxW7ue7Wwu{KXT+6oA~MaTw!to z@d!98Jer2N7$vc^;r9>_4Dg%o-5mz|1Iw*c6$gCKrPoZpOYh?CwfsjHI%=Rd?a@t- zM=5`j_wW^0iutCqNuW}Jnd`{S*dDS;p3}PUB4*f`7{Vw)g*pAul~ zu><gv_TCRHg0GU_SG732_mOLCCe*8nwX^$i4EG!O7*0lKHDA145;!$_s$#1W- z3PgUP6W(Eh&ih4G7V_nt{2?59B}dEj`R2WINm9&TVd+xTblsjpk7h1_uiXu}c5W}& z*VUT!e~da|X&-vEZ!T%eGUQ6pn$Z140SowH%LiJjK+2!*g2Vk%t{6QZEQ+^~Fs$=4 zhi@aZ6DKf}XGPrenklH>>@6hiMV+&09Mz0^1klTfE4X{YG|V~rBjWx!xDVCsh1#7S zn0lYD04G%Du$dQ|cz(iF$XY#(wVpf6-_1yd*Ny_|S&DwxLp#ZgnFH9#`ATBP_;Fxv zut>U6-%)naF;?Eg7yhW@w+|T6!kjFYiu-5v#y+$x!T}trHTj0)=zU8Y$s%3b`G?+j z;7`|g!mxz}+*K_JzWw=3JVNl@Y1v7ZM_99m>(O&G+7dSIRwXT&n02T}U|irTmVK~= zcfMdIuk-(BI@f;cLto7gL*|b*pS4C6Mj!WJmDiQT;aZQuY+a&X_3(Ud-8vm&zjuM% zRG;f_+)sQ4DY5lWFwY3RZ!T*SNoqdU|Cxbc>+8sl<6QH}br^m1dpl`I)?X*od=0xN zu=v@H{9-{hBu}5urp?3eV{Z*Q_^>jpKyHuYjB>J~+ccKr^^Z^7kp-cva|Ic#P@sk$JT#a2Qo@N2Y2lGK&A2!p(t8*v(Jv{Nb@$xLKmea!29& zWuZa6KJ#R88_Ygri~K?FNazx;Ep010%a>j@hj$YJj`i!{N0;@aZL$#I z2Hw0f77U|r1JdEgTYX+#(;0SLF=rlIvERFHO)pG5L844*xn=z!m>+{Y>b87-)K>~; z4`-8o7c}??*LbpWd^G!t8k>&D-ZWbAgw%Bt`VAY0QNP4`=rqTKN4&KGpXWb?gLwNs z`o@}mzW$Hs?a}0euf8Ll|LtJ2HaGEIg~x!FMY6M%``Yw>o&0swGk86s&vQ zvwyp@JD-dBa{W~3NUf5doNp)_rhHId=Rc;PE^%uxd??t;2<~b^LgHwkT^AFX;<*O#k>W(>pr#?Z$)pBwdy{^8G zwh8#OUaQiLj-S4rdEqYF zcHS`hCeIdD>{AxUEo+6nQ+RplF5KmYY0v{Fq9CrT4)3UtkuUcg+3VJ`e1~BmQgX?+&ZhZX;IeSo@ZATB<6Wu|Oq8dh|Q`LA!|2Vm>vc8|H*kR{I zhx^2k%uRl>knvOH8k;Abtog&p9uR1MO1O``hsQT-n&#{RlQXn^#7t+gbX*+$+V+V=&D7wZ&pATg`E;hP zf;;(oHQGoG*rt1^p;GEfYc0ZIEb3JXQIGQ>Ae3c2R1$@gMPQ`Y>Sr{nkiWMd2)DxB z;CYz=e^i-Da_!oMlmcgQ{P{R~vT6YotU*TEGY@FY>&oWf{&uH2WiVM?9?^b=Qf=U z=v>U-|DA_SNP&EtsL3Dd?;;j|Da&?O7WW#&fXTwe(uIx=GWTVZ<-XTlbL+TOFBAHB zaTYsVgId$&{pr{h4sZ#3xgAH`9stv#{9tC&qmB&yFQ$bwckPbIukz4+a9ibyUvF7ZsbXZ-(k$e`D|?pzRSn8 zXjFwVl;O8;<19|9ZpE_z^aX6+m<{0{_X`s=&+~z6QP*+mFEQ8d$}KyOgZO4`b^&$8 z5|uFOKjSB9w$b9BZkR)o))F>!sy?qmz1fF6BjNINC$Tw4iz-^U!b?Gie>icOtdoYY zs%IjT4d#YA~O|7DGeXdT#x z+L)Y>7VLBuv$uxP)#ddNncR&(De{85kt%E!`WLpv*itP?2RXD?hd1B+M%KjbVX?QH zc+RAJh|-Q?@opFS<7MICY<-KUF%2I0FG=oo-8#=%ystBzIs{uoF6yz9SWkG-HI|Jm zLOy(=E*;$;`+4*-jEuFVErZv=Kp!2x!sQ#eli8D{-I0hF+sYv?*MSrtHk5sxa8!PK zRXXvDAIls86W(lPaoG26v71gyu-wocM!`>8r&K7@)5t=9|3EtD0b5`IO!A{652}O}r^PQtoxV6{yB%Xyfj} zdmnnI~L>hX&D)5fS3P-cS8lOj#{JIIj5FPDf-k}B|@Y)ZNn)N-%2 zt6|mF9Huv=ns?A(m?d5%2fwNFMBH=M7z1magxMdD?djL@8`3_jokjPa-qdA~Atm+b zPx<@>&Ig@ih6%`*%hjUyg(702h`K=?Moc!YW2xCq{MOKQuwYpr>sluA7aH9`J^mT# zjy%{Ur4I7i?uU2hEW0pz=bJ6;8>1}xzHbBV?!3Gb`G;ZWwWx;>1rKlP@Rst+L{{p= zE}-tk!Z#Q?t*e)+Yud>4=B<~ij_u4=BA0B4lM9_P!h_l3jCO5c7~LukgAJHJI3>&y z%7*u2H!h%Gpg@tHJ|!W8i_s7GQi~ej+YITK^?BF#m=oTn##*Bb`F+12=+=8U(aBfi zXCo6y_gza^G|mMxR>spR%MHY|(N8ulccwh!DPnCsj~pkVdwOKD_t+2gZm^@f!(3qF z4o&VA|Aky%HJkbVZsYMn5oA!Au(0SN58pl-CcOMh{+4R-&fC+-|2ZHhM>~tBc|6@Y z_A|-eq{&~O>j7>W%h>PbfB4)gP3qm-fbGY<$|o;->M%AOH1}vDqxd_io-~}4Y(7eUcO=aC= z^OnZRy{<+T#T?eTUjsHK=!7~8{%09A6*%ZR6N)Q0PAVB0HN`1YNhX!s5r z){ftfTROf}(h>$&akkCfrw)!A+!>v&B;J#}0;y-BpXld81TfodvZ!pP7mnz*>hMTzm)G)4;_waM}|KoQJx5BrET){%f;~(!>g58KOB=Wfv zKmHSj3&UN_9(7$>*wYoP zF&i#->J_q~Z7?gCqb$yUzZ2ZQ`$;>wWB&5!p78W(2xPh_V7`?HJ!Usdc!BzGpQj^f zN`5-T`snk7?52^q2Az$J-u0Rg0!5m=U1nEBdZ)g2(2eh^X6{B@KSX%c{D?v z_nMeWq%+4cyB#Xxj~V^wurVj3&vrPA!97ON>+SX6wZnvGt#p8fHNS-Ux3Lbi+0!92 zJ4ml(SO?fod2N4I+{ho4)o;ywxqdPQ?}n1X8FYG@ zH3S{d=1#S4@_TE4%>D@5rcXUKZLIkH3fVqd-RRV{>)<6<=eNo~lUjQxcB)1qa!na5 ze&;}ZO>kH9<%C=(zw_HKF0LF6e@wQqW1F4D>91zc?H_{ShN#VrEPKgyHDjNtiZLC= zblT_d(r%cS)I72q-FLv7o|TyJCS)XzJ7B<;Sfg$;=oct8m6HxdH6AC)A*P*|GgYkZ zR_W33VG(*cKkIQP$HAaoHH(?&D~R^3U8%`BO+gLkg7QFL>YuR!=3PY1^Lh<9`A?UX zj!+ZF5B~_E)69rrMlJvHY8`xElfx|S^mwFMAav3RV#AbG#U0ZeXyK$A(qZ^Ljl1bf z`=a0VX+<4R4fr9i=Xpu!bHUs<%TGnvd!XJp=L!k*+rUyieq$bAHf-%WnB`x06m@NO zLdynkFk4>F4URieg+trf$APH5yoAq&wH>5Ll*NB~3RLg8tQ=OMXS};E?e#ti+VKAS z+wnSiDZf*0P968>P7?Em_*T-~44^ck0yDgPp}$O!xCh8loBs z*OAw)_s$B~L?3qfimEt4rbLA&s$?7LB4Cm(^=RJ=18?i`xB0ioFef!OzvdJ_KV%5( z^$#I`4r=h}+ZK?a9vN&I`Z6~5NuVY%8_32osmyfjY`K2s@M3eGYttP}#vT>c;q!bc z!hxP&-~#<$p>D^zmP|jC%ycKV^HUk6@bZjI_-t{J>vW8Vd#-;;xH9Ui8tCpUD_xhM3jidp2Sji?sN|)e^PoHFE zWPZq4_TFC(oh@4Y`hGi!8ki8+?9mv-eyyy-^`%X3N0QGI?7>$&H@(=2MDF>i`#CoU773L`tpcPz=nm>SyE#eH~gFl1KLDVw_k%#Q9eXEyHU0}RardIIu{B8 zmq_DRc9Xp>oF=d5x6JE#d~XYS!(~0|^AEqvYo&D6X9wstQ;YlfXv%l*wzzx$-0=)P zWxf-VH4C{$d^)_h`9khl>u}lcW8~^%TUJ|9%(s_2L6MUxxtoTwZOC9KIktw`BBSQg z`Yv?)7aOMB zOnAoWLUL1CjpfRa!7DgHm%?Z=_KN|3-DN1OYjR+Y$UC~$5l*AF?jSpAb@@>j8&Dn3 z*|-Wl-n2{?-p$@D6wgE*e!M<4{HzSpJy@gmUnK*)rn9vU|G1}g2dpp86+Su?@twmR z;PjGua%oX_zQ-sD*2I~yJ*ZueSB;>GRX<5CYVhu$E_w;>6@$Ct%~V;DHUz1%kLaf> znypV4#kzw318wdYbc-`{tUPx*H5p;Rnvxc!aqp9|ChmM1jSm1I+QC-cD{ur{cA`QP6betm&|?>N<`n%N|@E;Ko)r$$@Y1lk?UtN^M3IU6){lUwv~C{o|6V9(o*#hm}jfY=Y8}9 z?H-iHBF{G4%8V{a`XOD5wRcB>BVAkRO(!6yD9o!x&M{E5L?6nl23VtYkpv?%Gra#H zLdXhMCu`!DW=;Xa2Ys3QYF#dg84P=0C$NSG3ZhKQj_SSC6pU?9w^JmggK}3uYk?L| zSgHvdwRIVos)<1-s-cOPA)BR^hq`0~Kas=y@P?K4-3iFZy`);E#}Aqgfij07%+vw* z51CF>cKe2OZz1X;!U_F(#*ofmSjPir{DR$n=h)DNnERHhPmk!GMUI{(ce-+o)H<$b zwWiH{x#kv_)G(M$<&I+g9?WIi=?(iHR`9zCsx;kvCTqtYwK^h#PK~jHeovJ|_4A7K zN;zsHv6mirT%UgM9}TOKjbrF~hqQ(|vzA^(e24KU*s;7$S~8=nOu2HKROf9cR(Q0T zzcqBF%RYFpV$=ba&5xj=5uxxJ{RImzca_)nU;QOwq_HYhkCTx4`%Ypc?!>CCw?J++ zYL>)%@;ufmhXU?-EDT)!3?olcF&AcF2Du|y#%7{d$R!|=-d(nVyguzGOER1-@6{7+ z%z4HttnI2t1y|fH>xDVeX9ry12kKXIZu}y-U*<5M&j0x3;pf0Qhznjj1is?QBsjAE zA2CwW;=3+qkfBpMu~VyXk1;Zl+BJSAZAZ0uPgyTmg2vC-2PT(KvwWvIKIqyV=%jmwZT3cu zhgKt4xv7K9L7i{bI*8xdiR>$B=RVj=zjsa-K7B-v^piyTHsdkaJ7bQIwiGVpwFw{4 zw;QxaO3TMK6TQKje3yj=9G{WG#_w(78M_|9>-uTzSCo^uxo;!Xrg*@JCCImYd|1A3 zZ#u6mo~fS)^KUPazVLFCl@%lq>$OH~?DsnUq`{IV^;^#lU~T_uMrojdBW!ok=Kk6` zP-7Lrd=IwqQNv%st>AaU=>9lMer$mirQ={d?i_xzlcesT9rFz;=3A!sgsX2=$h|rp z9&;rK&J0__vYK1?oK$N%#MG9>VQn9$Luux;5ikq;mQFLZ<-PigOcgQ9rW(dfo#U79 zfHi#33OG970Vd9}=Lu6$J8;98Rn6yoxw$vkq$HA&YIxJx8VXm3Iv1ig?cB? zBEydx@e`#^FsJS+-cq~qUkMISclfyAG#h{C4~BH0k_t2!YjTy4Tk^YVs+KV?NGK*( z#*|kKSX;=aUPh09WgUrrY|XuU$AT*k$`gE?#poMRl#TdBnpSG@jG37AmcEpwVa`Ry zKxO*7T$K&OcQ&EMkiO1xg|0)ic(TbIa?U7-ttw{x*rDkVc0f~V@<-stML5%4L5@K; z1<}B{4}H69n4lhlJLIY;n)M?c{>b$C$SK{x%*TSgKjI|DmpIdBs(GX)LsK?;OPzG0 zS0>Y`tK~=hil9@>QTCum84r-gfJ^W$^7NT1PZH9}vRP5A%vn_|9O6fxEY6eHnTHcc z)7s+=AYhNNX00>$>-`jJ&?9!G+L`Y7)*3Cx-p#bQg( z@n2mg!j9wDNZb-+6pvg+ECY}sjD2;ob`m|>Y7JL>b$De>Z>ae+nQ2rgioSlvwC>Et ziqUvOx36-hY31ucbFmhm5!65~%DS^oHzi_P;#Elb?m#qk&G?z%O{C^sx$pvi=6U>? zRTDyBCeh(e$YQc`1r~+*+STXHsjJ2hX%X@#O^FN5`{PX;tV}RFQVBKZ2CUc$cX1Uh zu+{A%sT!`%huR(`N0(=^j0962P`Huk+DsH;%aAc%H3SZ&CbBNs3gW*r_H@#DO`$V# zZ&Zd-div%HXzp#mMJq!XbKQu!gPIup={xkyG9%@CYI**?%`o^9-crjQ#jJ<}VBV?^ zQ<_j0tv3wn%tP1_sj9fYz=eMAaZ_4x&RN{>gVNBKhBRe`K6gko0Jn3mgiE+H`TEC@ zo*i(O{O!=-|9ada%dX1GwF{iYnVpR2yQ!n$E9U5pned1l@6;W4K4O;ghte7e2!?^099j+nu&tcL4*;ojE$KPVR3qZ2iYy zDl>T8O%#mPW&F+V1b8u80qkqEc)#vzI0kJ<9iYF zhi@FGPaW48u$Oo68=Bjl9x&M~$*l%CJzFq&4Tr<-#NfD zXLaN2xARh~nizSG%nTigj8ZG)3@ zJYWd=OrO6$Ny<<7Gex2-Ug(`igq;+P-#pJI~H}3x|x}3#p@>#B+7+uv&FIsORf&rIG@9ZO^gcxN{@W zJXM!$uh!*PVu!-6X=~ZBH!VD6gbn4rZP_o>7;iuBPuow9fT_o|dF=r`2)6NLkB6y< zUk`qR&b{aO)l56dpQj~OQPpNk5Nc%#MB|2`mE zqZ8PdbM3s^cOU#bkSo0QDBuehxI&IbEtzj)$}_J-LQRzlo7^97ov~x-hpoSeR+%Qh zyrZl9mf9BZk3T_;arb#j%x($xjZ;miWsxg1kHCJ_`2o=#5X7#uD~aW?hhWKiKWXbA z#vjG`L6GZE`0muf2aNAa-_{Kk4u?65b<4)mW|ItP3P7)18Sb)>Q6nwG9sA%O^qpTG zsXV74yXe~}?VY`xZ5r&t0}>U$Andzvs-=Xl`Ga1t=$*u5pa%E;v5F|_MYDj@nAwND zsF7)&v;=p0*A>Rmvf2iSc0}I(W_$P<{81S59QDRCdeCSi1?c@ojXN~d$~~=iKaKc7 z`zjJWdYRDdd5&9GPJy&O*NDYc4gNb}wLJSn4fl{M56q>CR$Y++s>8o@^o6j1I2QiS zgul-02@zq(F7C%0)}Bc{XfNDf%zvxRyFP9uDLZ?zodpuHy!%Z^`|Lo@6d3Vy(#>S| zl`^4hgR?lIXfExQ69Peg+Wh8SFZnI?5b_Evnk{MHJwK!dxQBUrp$Fa3*@s3vG~m@k z6+!WVE~|FMze`~|*iXDj%Cyz^p}EJ&zA?+0eQ*;$`Ed?RInb9K^3dal?hXa@&9hiV zrGhy37cxdHwS*=8kWu-?pPDzXfL(*JHV!w0z$OE>H%v{u-}(!dR+y13Z}em*->0)a}@Fn3_!6KHF8zMAph$Sh6g|~H>@XpYkW)E`8dwt z@dIgIy&<(RGUsVSIzijKFT#-w^c2UN(Ej7jl2^#7+duUl*>AR<)%-BxotB>?-(JlY zs<4MY)a57~kaC3V&V{{MP{gP2i-sXi_0r@}E7^N-uUs2>Cg(Sw*WaB+Z}VUWP(%BQ zjitiNP*|Cu%bh>kgTXo<7L5G2;~l7X-6SFBu^%48P3ZM$TcB^VE?<4@DKX8Ju+*m| zyz~7@@ajW2S+GTozaT5ghsR4;>tft7M$V)E{%j!iWBp_sC#TANtmA#_`R3_5^vlXj zmUf;{~eY^ zKAq{r{^8t_Hgg_5f1sKyJ%f3y!CrD7tBur@x2|#n?-#Cu_|QpIc53nG1p4 zG2zP^{NZ;{Hx`d|Z1k2v)GF)%A?T~UP^tshmLFwBp0=n(H;`*)%uo~c^tu9lx?COH zFl*+{?lZ(})D*T~9cPmT>F}Wh8Nx4cw>dC{?(=*CUG%zf549+;8HRNpZ>cLw22u0& zW}>=En|t=a=SyoLn{%Xz4=uu6d)&{QAA)-Rw+hsu+ye;iKz^7Nl3102Y*Lc4c+_qM zEZeX|dfLQ6Rx&b)n0zy2p@#Lm`I;5AIk2Aj8em>kZ~*cy9HIJ!7T5ix50#P#cI9$A z|5@=7R-AY*{F;V4+hj#LpNt1f2OU1nqL@tTYR5_xO8JaQ{ULgQgao4gHbNs5pyyg< ziTn1IPIk20FkAKy^(R?A0rYhB2vF~@&9?*?z_N=TEZG>Dx0XL4t2N1QTBegYYmFk+ zt=R*qYDV04cR5+*rpjInKFbf~^nqC}*~!r>k`N z_|1+m<|Sv{FdHQ*ryUmSrZJx!Co%7@8Eqe}0_#n+xmom6^8IZBn{e(QAD?j$rj9uv z#Np0!Np&7$$QJB4QLd_0V=qzOk(sn+?O_>hW zQeqJsF|(uAjDD(ih5YW?e8ZBb@@&@fgGQW8xJVWuss6xy#x*ASBZp@wENJN9tquLD z<+EYJLVRZ}dqmTy0U403q{~&a9bm!%Q}*X7`dDAN((m)~$obo9vO)J7rMizYm|CO* zZ$95a%v3)Mi;kA??^mY6N7tPsu(O2s+P#{r(;m(GRN!~B3aI;pJZbl{&f=WhXu7Ch zBTOD)z~hr#z-#|kLGLr}Y};IEinjuco2AFM1}Vap_8g{$tlhJI6;N!5Ie^IfZC0BC zpL$o4ndq}9T%9HNIw`Dl7N3qtp=(EVh3uEwT;WDP5N}OpUw$cy=5gk<#B)={U%Z<; zcev6u`dRS2pE{qsxrrQXcVw3*sfn}f?!mn(N8WolRf42LA0hiTHhc7aGE9q)Hy>1smc<&yDn<>y8-md{-6NdQp#U$7jBMoFetk zy-2pdP~$fuPmx8~EBbW$&0n2LgBM}_*n`dnJp086SZh3&joqyvjxKegZ6;cR)F1cl z=wHjQT?vq3z*jI+yj2>r%|q10Cm$Q&+e0&=`c6mo)9QtETV`0a-VTouX;>H#>-5rX-H(qec&MS$RA5^9yv$X)qfN-xgq<*LX>m>AA4v!9`qY zVJwVRtCvQlHFLdNo>Xg=C#%SC7I()))3X-C;fjVXPut-DiOA%CH&h}%wAZ4G9!tn2 z7!oX~Da9$Utf6!Unzc7WqZ>lD)x;lKCHfCLQ;Lo)E z!^?0V_HL&E%VOo@Q_-5UI|UJF^d6Q7^})E7Ot4*swH_ywFh&PiY-s75-% z^&SR%WYre(^iG?QgZq;auTtm(#YM0s&V+aA@CUOG_Us6H%2J{N=z)|2Wc@7-UQwwF zHg3m|UuwvAJW+=2j~@w=S;%FYuSmbqCHYtf)RR*w~--t|sm0KGc2g%nIiK0v%a=DRLniyk)d;H|Hrv|u_j z$6NgJR7HCIlLyrFK~BPfLJ}wQXZ;Q-i_s=4;eO*1>0Os@vdw$u$i1uj-|G0E^<8QB z+4U^d8og#e2GbSAju4OEh5IWE;oJIf=J)@65%~pfmc18l#-gw4tui%^84m{)QGeJ} zM#^>U*y6jz{Pa*i*gIR5{I=HRf5qW&QDH5+H@Ah~|7b6-?PpL&B;|wYS)-A#3BSeF z?uO8@z?~&vPPECgTjT0MZ8S(hG6do5|C)XE%t@OSxrT@cLZ{WWD}_W zpjx7i`>xj2_K-Sp3A>Zr#`$p-swgV5I{bFnq*&4{3pWV=pvBd@yd>IDL)evYWzjS; zA2j`?Qq@WM{CT1$G${6i{kom_J01%&f2CCfBx2s#rwMdtY6hh4)8|q5y2G#y7R(uY z;M(c#wDCwDIg#C+%f?Ayb6kx;XQP+IH4frGZz0~c>fC+R2Kg;@WM@?|c7;DRHq4hE zx{s`q=@V(<$woMK$A~NKc7rRgY6Ml>zuD||r(5C`p!6-)^IOW0vwI(lR{hN~8+}aL zn<{R%IEhE_{~}VF1^2IM@nhNw@PB4s)lZ4&HU@pz365mw|9Zmp3t`T_ZLG&3XK`VV z1+>9?DC8yT@T_tl_+U!euB+$|`ej9Pn|??g0R352?$k8fhc-qc_eoa*dF%C%IgI`( zQJF%~MN)_P5w}(r$@lHkrv2tc?di~v+mF#T=)oBu2KffFSmk{MaZkGoRa&SeB%$Z= zo>dUNKV&6H1p{u~-2zg|jhT_Zn%MVVGlYLLBS#E%WHv3Yq;2a$m|HM%9!_5&1GKLR z18+Hs?WfM5_uK$NboBXtx~dLb9opATj`-a3i{E6>0L9Uq7_#CqPA z2~832g?V_(Uif1Iz3ycX3X_$@!|EFHdcFm86^|kkt#dPY$oiu0u|&L|V>o z1}4Mih=0Fhguhx?PTTqE=-o>EGAq|qe@=LG{-%_ zXdhqserAy4AHJ@}gf4q+z)n}8K33{Ud+&_^gBu!rUtkAW?J$)6>!gfYk$bS^(H}qQ zvpk+Sd=kX%MZP6|)75?Vkds^6g}#Nz;uy4$nguL^b2p9o2j4‰zOZO2=1;ShS{ z&;eqD&(-(IW-!p}6f@PX`)-Gk@u_8Gso27(m&K~c9fDSUnjFc>Hqkw z+EuVXKSS_;je4*X3u$@f6Y#QhcqSc%dF$6y=>cU=D8PQ8t+9+4Y5B9BGn7TgtyxfBu|#TX;~=v*o$%b@TdLErp6TEo@>+H%aTOwEl&Ps8GKj84v4?^d7Cvili zgf84L9(D}X;cUu9a(J;F%f51!tB<1aKNFr$)#0V}Vc@ZF4U0={;U$k8=+AUp=7hHc z&uPK5apFjrbwGzl{5A#ItKRJ1brtcETQek|nCmwNpMUKH30-Bs7gk90d6Ps&)N+*A zrYoq=v6O=SpfN=MrXG)25)Qkzc4JN!64BDQH|=pJiR`(7yyd+vaPYc}jcaY-AW@>D zkPp_e-${I2-mWzj(LhZ^w6 zi;*zOT#*$b|4KS8md35BC0@p;fsAs5jpvuLMDZ`5(?ddkW-79O2T^0()S1={aD#lj zS-i=qBHAB@u+z07-`ki0M+fUjRShe7-jy&&TN4Jl77AifFDbpeIaD~Z06kONV(G7= z8L(@pA$Qa41=}+^v2WP7U;6Ax|6I-^w|f|I=Ud;%yPG$K{ohJ>%epx*W9v?$2Wnh8 zXA|i#8_V9`RuR|q97K12%9CEXhq=|7lWFh9MlhLg%4g|#fpJ{Da0hitj(WZ6zC{Y~ z8JPxIW7_3;9~Mf#`CQ*i;M`|4oAS1Vk6JPZ3RJF;sed*3?s?k?pD1O*%@5jC5mW0VelX}wmqlfPb+9&f+o}XlgL<+pk!s@H z?@ysf+lj0~J?HsJ8Q}kI8&fNG7E^yOq+PZQ#hfr*u3jmHR_6h%>WM1;{x(!?c#Tvo z0Pk4|y=g1=p})}gz3Zkrj0nC6|Gu!m|{;S~-EC#cn(a4!G^rR^RZ%JR3Vc*p! zgkDQFqFXPU^Qlj4A=KrYP=?ROID9tV{5VTKpzd+gmKXARUNB$e`wnM->P{=RXv%5s zu+9f+rix^thXpT8j)h=>36Eo)#e?%>>A^^Q=$oq~ru%5oQGylj_hE5Z&yx)G=paQkQu`N~OM|=6=TEo5A=D>q4*Nu=98hBy_7(Ga z_h&=h-BIL7oI2Myvzgo;pU!gd*+`hXm>$W+-a5}uX6>6!Zh9KBrl0j(ZJ-fV3|qmb zzjhLDW_Z!PySu~q1a+S6rT~Mq64~$}|G2u|ZTY_4&g&u{+;fS%o@<9_@drJ2%5{%6 zsE>_KT1*>uej#?3ba>Mp0$+_+va&6I__2Rx)Mb-dhJsoajpxb;xk;>v6CEs-5~70h&Suci|L)Ci=ao9F&EYZ zLH&Juwhnvs!l0q_`?mu`WjOlxtBm1)Zsh89=3Hrm9;79|5qiX6Hm-^~)qbE3iYGO> z=c#g%<{ZZo>)N@m;W~KqBwhIS9cTaHOQ@&iQ}{IuH4=YgL1T?BOTe4{q1i*J-LDq% z7IW=0#+pK+P8zezZQ|QURRd9pXL*rMVizlQTG7oD?&@lBow$oc|EWJ4W+L*k7o%W7 zFJEbFayQvY$NBO-jOP71uI^}0_cX6(_v~@LZW&5%8z8557w+?~nu2-X2$nVC9}gc? z3%d$G2+2L(=?`q{IMp(Xq|YD80is*+J#w7K=u5%BlvYWA!g zy-UxXXv8a9HXb#E;Wb0)i2RX|iu;hkp=MyG1<1Iak!Di`xA+W84e{%8#*|$x^dVe=QyKXXA{8ME210-VEgQ-;MQUe)iq0XPq zkibplWM;AEH!ppx+%?Yu_nxmqEoh(V{b1HR1wN+eG5N9#SgEVL7@2wsJ_bmo3!Dmg zU-Y&VzITU+C!HKC9O?RXqXdmKiFnB>mX5lg0%qpA{QEg4$d5H;9f)UkhqzPOrULR$ z!H_3DZ6v=}+!iJ{*ojAL-oqJ7?CE@^#5bPULV9hDU=0b1;-lUHG_IjgTKySwkcwkz z_ox;~KX1f$i=I$k@KZR0cO|)1?)2P2#L&hDeES!5_>_8(&4pI(`JfucZW_n@_0Moe z*@aMSe~IiJs>WsJ=MwW(-s~6hId9Sv=}I$8C_v4v>s;?H-J|LS8F2tN>(a^8D_}QG zwmaRn2Isk%7B?8I1h$3!*r!Tm5ihskS7b*vEHmQ#?-8=*!9`&;Y7(3`CDMo&BVir- zngimbaPS9Vx7?J(gK<`LmD>+#7<%O4g*$!rb0B@;Wxz+NYQTS5$BIT3o9otV`<{HbO>R+Ru@`9H=fN;2FK9Paqw% zH66TjFlSh|JD67Mu>n1m#roh*sFX1#|Bf~AfU<)SEZxI`<%{@}ectd-W-D2P`l7q- zW1!PuILl8)j}o}i8Ra*nWAJ|T{dypMd{UpbHez4=4GU0je=C^gAnytm^zGl%q(>yq zz>zOV?7l2EVo@tsE;tHbOoy`G^f-?<0eBfEl8W9&{Kn~MxG=Lqs6r0BuxBiNdcYdY z4`7#yi6-s0n3w0FcIDbi3u+!00ZUG3@Mod#yL69Bvd(e^*~Osux>Xul-J|kkeR0=3 zufjZ;4`03LwYmM-8RRj9z*t(09Z`YjHTlmi4qf}xS=(@)Ptc{uRwxrCd`{X9TF~9i z$h|z!;!yLc3!m4nIK%I5TnKZnj3z1{m3j4@t;FP061#$D*`{@gbZ>PwIjSSA+^d+< zl_#T+Xw2W2ctJqiQ6WVRJ4)8M)62I}ua7x+BeP}TL-HIp4ClFJ#BDHg5rt7c7x_xP zWEeE$53xI>#%mtsc4=dF6(cvYGLb&}^qG7`uf%djz-`}ZRx|AvFI;3y=l0iQSGDne zw9}pLHW>>i$Efn2m9pS`as+#a+)IttL#Utd+k2W$Ax{^kgWOLE%)Y6?_j~LjTUWOT zE9C6OeSZ>Zo7GBa(9`Gc#Y3Rtbuab{IlAlSf%HW81EgWA8gD*f2rqNz78%&C6F`JkGZsS9{w;4UK$UQmYlJv-0rZv3!h796VFC{Y3-B^Y_<*Jx(z`z9_&Ej z4f?PBP2pE`ID1m~kLO1I1YMW+!bZgBjXl(9;)^J7yRX5w9jWT#)!j!cuBfw^qg;!VB6Va;x9_Q+KtrbbSucRuBktFqeM zcr^Cn){2bin{c@UwxHLTC;05K6K$?r(u36sAUUMYtxkO;6_@9*8PEUmJ!&N|_|AS| z&&d+5*c1TQ_BN3Rb^3g+$0VrW@~n3#et!CN>TcFZuA^tO;*&jO#U!!vQ@?q@T~+%0 zyezXQMhsJHNl$L=2ddq%+xH_Dsr&#|S0*p&%a+1iTO!pBEaDo^2E%RY1u<$eVuQh8 zdPOcs$Ur{R<;rw=xg!NMe(7;LFWePonK23Or`|SsQVo|v5>(&7|0z_%Wc8ygUi~Z& z%UBKpO1Z=?QHlE+=Mq1?2zFwmqS#w|7!CeaDE0Y)n&-$FwC+R;gvmDXI2S{@Caj8m zRl(of%!}T+B?BjN@g4cC02h1jV8X6eE}XdmZ`C4L>!&gvk&p~`*Igr$B6WVJc{h2R zLRbkyuiuem`XkB`c5GMS0hUofbFWnvXU%>MJwDqJjb!Yc`jY{(JGQbCoZ-h0Ce!9#f$;CS4)6To4?&CkSszU$ zaoA8By3z56bQ0>8zs7h`AB#bBRHzoO&Q<~WW_6Y~0(BaS>NM82f;|7N%Jt4L(r0@* zi;73x=C~|q{o=`DRB=Wjey&?Iht(9J2IjOAb*@ntj$`In!Hpn#q%s{A#OU$aqk6)V zTZU}!CnZraUY16^F(NivjXZV!QCO9`hZU|Xu%`;=+!iS-(U$LU- zx5@sZ?>9Fd)<)Wclf;JG>Ir0ug$`SWnEXP1 z3SAn!5;m+ve$sCQEIV$+uAqiw#_SN9;C+A``eMLWS6aiSMQ7Qv`;9#Q+*kO#=Omkh zo<#Yd8uYY=D&$sT{vl@Z{>QN#o!iMzOE$yE^C^PsJJh^APN8S_JqERhefaGjap3Y& zmwma@N>mW`~$ zUBC=$x~HZe{MxU`#bd9@j7OCD9g-Ip9>35v!(~sE^Tu7{p#0NN`03ioYZv%*@hU0H zC1P{TEb7-I6`txDa$BPTkl$?1exdhaLE=DaFrkp#(lp=+pWDfxgj>QC^dr>ArGm!B zon(%K5l!w^@vS5soM5a6r9FXgL1MbBOACD-TIrni$r7gL4%QOH4wKVZxO4_JXZP(JVH5u&n49Y1y>{on?%k*3yCW@XK|O@1ntTx2wQ^T9*b< zS#0!v52oMkNOF7wzcM)s*2r(e4p#J)=%-SZHG%NrJ!V?&9|q|?0+@ZKg4i_AhMu@s zC!M?mb&S0R(d)^BD4(XmMZ|53jhQl{YJ>~DP@*nq#!AFVi$bYSQ#y?B(dFw0Tf)v81}yQq zlBgUi-!;P*FSX&{^1qUiubv3!E*JCdi-&@9@isEbP=|j!JsvhA#+$cUQ5?3~i)xO! zB|ZO9B6fBgP3sK|=;cw}c;pMzG4V?sAyttV2b2UVf<7 zPHauKravDskV@r zcU4)UGycD6KVa|bE5vEOGGDE_yK4t}s@jly{*CRL;c4~Wm8)N@B4!PG>_k=*56?BG zpE6f7`U!V!w%%0P$^n+WK&|zD75Go1zTD;?PgSpl%!Q)x`dSHpIzI{6z8~b$4^2L> z-%*k_(t_Q?eU0hkRNAul3vsdU!RN`2hkQrulU4i01E%+&V`k|w6Wj;sM|)GbO=BVb zrz*F2qzrEQfy@{8RtJ{7f@AH!y~C0V`HF%?;8=)x1%8Hnr`kz!CPa?C`i4BeeHy*e zuoAZT8}Jjwqu^$xH4Dal&0eoCdVcc(;{L#ZYod>5_nNaT>3b`W4{iqM$2LGCKog5GL zXPuiFPhK7kdsGKV=la-G9=MUzg~O}8@s40_PeaN#uni7~!>@$Vq{DXL-&cc&obLfQ z&yQtK5@kg>L-evO`Ybr$j#9=-hklO4&e2C2{K(ZCWK6gf`X5X9eU;Fz{NC1lb)IV< z4nGq!*~$;d(HS|?q>sH=fg|qwu7%NO^G8D*=4`+1ZVBDidaw`ZyWAl!M_rKnhWBGf#60h$6k$6w?VGHc##iiFOKzXZF>OSuRpRyzhULOsB z5vw}+dBKksbPp2tZ$`}DH;&E=PlX?k^mr}imfWl`V|`J7a#&4D&DIu@`fm+cgGs? z)1`yJEU!_>#(U5?e<_tQlZAZ1UTm%m$G&Z60oz-7^_zR}HXJc|AbOTFnjz(c2k2w2 z!on+ux_I(6=!w&hO`{(lTEcsI9lp+g7_8qqiw&DCD;8y0(G6KS6&bpy?;VI9jX&#P z;Z$|r{7My|(t#ODl*ML;Pmn&+j>yY4@Nerjz~4Jt*=~*+&WUL>t~3zll<4rG1BS!R zv;IsTd2+Cj&@sV3q`fam#OVrz5(RI%aIHFDr=SM4@v1C!9PZ}YwW-|73gWj9HEdf@ zM<1QRWc=EA!HZ4sxXg>WmTB;rx5q*5#yL!ByNu|Z*Pn)IX$W(oFmpp;4E58^fV=fN zJl4Pp9CsP8M#QxH`zvE`Z=+!M_uROwvzDbokwk7B5jIPU^_1qTj7JdJFVhV8Ul&e|NN-E_*3O zd^N8bT+Uu0ZStzTT0GF@Aw7b3kk-X%bk)j@#M9cl(&oXcE*w4u{jl%7OlV5ZYIeQT zPF!p&rMANz;JURMzj{EW3x^l4_{SFoHQy?{YsX-)#92b17JdN25OIg@e?!5>A4qr%mcF{=0{8Euuo%Q+G2Hnx=|JW z%LMShj+zRKckue&KkrYd*?4}q8A^8^h4nS2eEi2!;^wH#R_NP{fqT>FEJy@T89lyA zXC%b=_hS3-4j$MZMlY5eAeoQ#xV@JROtd@AiYGU67rba|tvJaFP=or)REItSRp@_N zl|LU_O$76)EYqfwM`vw^hxsW&M1OlxC`+TyC)L6-nVy_qm;^>jDy$7Ty%|kmbeQ%p zas<1;o{sGS5kAY=_}4c4xsEmDF4`k(z!^IlXDq9Bg?ZSi`qc0m(dzEYrUX~=*acHy z`IQ0E^(i)$^Jb=yrA(g@ohIJ>Lm!%cYXidq0P*+YaJuP}9sJvcIuj=g*rPL+eeESL zh8&Tn8}sUfJsYrhDNm0EXH9@nm>smz?+zhXt=Nay5fjauH`Zse zv(wsn>r^MYYpxaRMBVR!dEwNfVl?#Iq{%bpSVG7VHx}_jPTUYLPcsL{duyGy6DM*# zdjEYM%q-L4<2OGfafjsDE6tNUM=}QfejP^wLbZ8?^(44r*_$21JMy9AdGzMC9pnyr zNj%nKkE&4>GqP>wP5ad7RHbDsL_p8ZGzp#UsR-8sbvRf3O^*32Vh0c#?;3RxR)!rA zrhL1|-S18XSw~qYdTz|GYRv_^vns6LOx&~N&7;(!iI^6u^TLBJ;BK74E*<>M^A~H= zczro$SAp5%u@Y*6KK6+tl{uYQM`G9eva*HpVy3JJTP%rmLHc>#eta@?uO0&A)jvLS z_z*hp#V8>Fao5e8^Jv5JRQMUE$JwxfFkrbEn}Qf)$|<0Bw+l(4w2|jMybE*oA7xij zZS`o0>!_&T4E zLsGV|3}^VcRrLK|{F`-Z@wrCBLE<)(86J}ruRgM&<2!OH4)(x%;v=B%CF>#HK!e}e zrvaB)UuK-4EEZMOfyFyJa_Jp*yR6!TzLst5KP~R|JF93~k5S;5sLglX7!G=Ye(bf8 zqF6n^o|+H-F0IA+Ga`l3AC}(qK$ad~VXhB@mgq18+|fK;phtBJD#($gYP>%3Cb<-n z!6Fa0al?Jvz}a*FBgpmL9ylJFb>f)3uZ$?|<4%=ds|(hPC8Bv{IPEtg1HRnX;*+2E zg5%rt*o(f(V#rx#%$zYMrqi5x^d~u(`|69(c>Or9*f$y)OShA4h#!pWqq=;f_ueRq zLv5t=*{IvnDTv8u1dgNO(+%jqHz2-m*{~K1@p%zxpnVVa3cRZ(aY83TV5R} zx<(f41LE+xIjgCX&sUObq0OJvj(~ipOcodWi$7g%Nw@vfW3hVZBiJ;UE-(p)6gSNH z?WY0j?gX+8PZh*@55Itef2a4&Oyp*J{z0AjQMi+A#tTw8k-4hE-Ze|ag>|cGT2Uex zJnP1ns)WNQ6+3nd`AHcy2ihwvnfS}=^OYkcaH#k+n~po^>&e|=`uNwvl6lxoA89~m zPgaF>8#K83vU{ilpUIA2{l^cU+TF#6&(O3N&2`i1=+au)B4@{)%jZE>Z*As)GuCl^ z1XW!8i>$NK;N~kW;XABg2k*A$rWVos`DQ?cggA1e#|tS zaYw5;z+?wV?+Z4SAq}a--rj(XXl&$1&-JAbKV#Me?(%x|jHE9uC77k7&OZ;agccaf z?#Cm4m4}}9>i5Fz{dQuGwIRJ;GXaLK#q)95Bg~kwVM~Hf@h$QbKv7$P+(Mm$T5cp< z>YvHRdbIOv9xk*l&5B*e@4rhwlAe?egI|~#b#Av6Tz~7v9C~5~(Kbce^dR251+^vq zR_L?%mItK`n1|WzDarjV&pw2n;M0diz@c8_i0>pF-lxZuEuQKz8(^D_1#3iJZhE8-b=4~(jzb!`;nasP`sz`3 z-``Fwa{UW>$21|}h6>LNDj?&0CNO2}+@#u}bdq1OG)c!^Y<62fuXk$$+YSfb{&6BK z8K}WNqt>)8)`!|pmW3r}RQOmwb(p<%J6qq@!Y{6U0(LzkSUK(u_32+|{^kLXsXE^^ zxtOdEBW&^m%qy@@rzyd`U^eD0gbf}ENz-Ps(r&UMGq$CZ6LTttSmK>xx(~GtUJnOj zG`PExHjE$Y$kt{mi>E8DCwtSwDcaoCRS%>)G?@aVEBxe)Ov6MTc zASHvv?$zfFH%iI-zfnRya)XBpCO}Y59Cjbeh?f_5(pu0EF0YV?k76R}j>Q>pwMmoL z%2-3^16_6)x$&2CRq3l~#-v87RcXBYxAgh2QEa1YBUfE~7M>gJW%j;jx!Z}!pfY?*&D%n<~)TVYj6Id9FL0qfaaV*A#dcUN5wuM(~bdr%Yd zcjJ6|y3z)6wshm|9ev@E@#_md$giflJJ2gfBjJn}auGGiv#yb_@L9^DMb!-$e8H2L zy=dcKYkX+G-EM5|ZHZ{~cs{LL6arH(Y4GFj?r_;^AiHr8^@rKrDR)&NCcSX47wACa z&u;;Zo4TkylYxN_YODn@ZR*6okk_l4Y;#cNo+I+RdQL}Pm5A*M8Pv6YBRSIGUAb!9 z8ZvIBKJ!0}-Q0uC>1Wk+){fsZrQH|%Rvh3D;=^fMw4v(h0`}?TKi+Ws9SjPo5)>EM ziSEHNbo82NsPMtPM#`x!OkPtc5npwt)0HJ($yXU|KIBIrNJ%DR|2p{1-d1$zTRm2a z@5>zgBSR(K@?kjD;~y2zlaJRr z1%oe$c?M_D#jU87QPbnAQRDRAe$&?jGeA1WQ+cC<P^2s;$!&>E3VF}LjtMf9bGkQMH?a<-A zm`y7wYZYGL=NDK;(HZA{5&b9)KJ=9p{Q9zj)xK`wNwfY!_>x(y2kuWt{^>?5jr&8} z6Ak{``7tTzF@z;v)#u$Nmy?i+Z12bJy(^WEt|IQ}slRruk)KcPN4IxwV6QP_r0skZ zO%0OZE*3Lej@iJeMG@Ifd!h?sw`5q0jI0H2+;xWC?0;_q$420Sb0 z^*(dqi;Ftxvm3K?aIS(%CQ}b<6D(>^orwcYqWHz!EwzDuaOgflR~k-9HagdJ|^ug{kS zxn+x3udsi-Rj~>t{X^f-#4@h_U?#}T_(Sq?wfQI4sgQj|hRs6Fz+3%A^vKgD5*Vt+ zW1QSzsdX|NyXy}(c&ty~Kayj;kpuMD=12!_bAtVt=b&-_XV*OU5ah)>YS&@r4I)*E zKgJK$j0M|#cesMH<+1We`oSbbScSXzabb(-v@fY(cfyd5()9(~;GS%Wsze<2+>d&> z6cLp>_B?a539Mw_g~SNVEjPw|yt|t4=!q&HzWD@MXgZ0RZ&wt@4Gg2ZR~JiF+9hHp zUqpWnZiA@3efZ;Bli+InSG3V%pqln*r#xX|jYw z)PbxtqORQpQmdxUHw=16qO>yEKJ7NHG-fx1zwlxYuH%`4_u1bCajbqrC*P9d)y0#W zFT&@rBZ{8ckpW(qU$OIx4LrM~%l1D|68lV0ry&cC37?}`xi{#abcjzN+a=e?`Ry`T zueX<7xQ2ZeKCy7qXg4`kugMG7N5eQ_7<-egDBk=?yXN^^e1FHY33TCW19~jnkT=#i zLj97DLQW0#P_J~P&Q51Z6?Uxmb8jJQeb%u~)RSB?6=1XWaAxXrnwJJofnRH{l4&O0 zx!=acVAoV7e9lF^hsPqiz0n3do#aH17-MSR#LK%Yqn@YKk!n7Qgd}s^eY9X^;TSvi z0Xdd>^E;p*^&$gTxAC28{krD)2-MY#ShI-63L%h<^Wj6HCrn>7kR7d35~m71=&Z#m zHsX)8GeIoF--S&Dq%xcxG+SpeIf1h}mT=-r_q7mg{G- zN1r?R!=nGs^E7<+9P!zEniCF}uc-67WjY|87R+246hw(eJzOp6^xk_E^T$GEsj5pp zj9jM9%MX{3x{hYyr=`8Py*h(tM<>A+uFJ3Q3S*G4|U02zV^aMSZF39wR!jNEIq7)p=UzBl73vboOyiCr`YFJ*sA@!l$wJ z;*q8dTAc6%Uf$B-zdS=gV%a7b&O;q+V-$@x{!L!u_gUm)1(_3e>T z4Zti`k31uKbVz^jR@CHu{A$Uu$wOFVo4mN*ARqQ%P?n#jP314`)#Tn!eYUoyk?))5 zOpiHdGackBEaN88ZJQ*p2z{m%dwWBe^*FXK;17@URiLrtoiGWtc6&`t=?=$_m#OjWArryKC=*L(+xW@XZggLX75g?;BIeGUMEj!; z=U<2>*Trnb|M0o`MLCfgs?v(Ac<;T1cwY20rTyG@L-0#&KI-=CuDz!x=5*bhG7Bn9 zCJ{&MN7#QW76NzoX5V6PH<7!9UiH{XK8H#8_c@cGukUB3oY%}ooU(aOME=T^NQT9F-1 z#~F2F34Q3&Oom|Idsf*1C^(kN9+dy)F5ZT8!D=~{jlAV4EobU-+6iWwDf1_Ft)#r% zm$hmuhzBEY!|@o9j=NUCugshPcilXpGEqic=QxTETpS`KB8L#Gxs+BIr@@BNhCKAE zA9z{xWMMMM6GjJ6GNy>!vQe+x@ky6_vrT7S`n~vS69af&h55!y?ZonZ@-#s~3y!Wv zpQiC?a=Bz8dliQqh4omPlwB;9B356ubtzU)w!z;E2K=VEUl-r9$Qkd*c>#3%DOvb9 z2+yfz9hjZHgH;u^@WU%#!yLB=78+|O9?OxZ7koWo=QGrhTb(1TCIb6|xH_*jlSV)2 z1xjjK{P=<(XjwIb$zxCGPLn>=^HEMkD(*xc<_1vrBkRFTMw2(z>O^@d>rlDVdNKZVH zh~ATi(pAsB>5g3Vbru*yVx2al$#&xDb`vT}1+utGl@IiNOvZdjXXB=}@miz(u*Y)% z^OMu$win;k4NMxP&ALUS&;7Fo zwKp;*$Jd}n_uNGY$k@vUx}D?$mLV7Cx`UiU3>k7crpx=;GZ^!8j`~nt&)d>&s`g@R zm&bq4s5XAVlf$^v!`Nzi znomoZ0oq5dl0ScYa`Wpc@Vn@SF#EVfY*AcF?+oe~_K25A>;3Xl#Wi&bqv+NCE!ad&Z;R_RVs6S{P7G7KE$v z2QN+$qw6Uw7eDjljWzUOR1UfFdr+mvku2h5q0i==Z$f=YFWP@fI_rbl)NXpi=q-!B z;DP&&>_UCG-ghBu3-9DlF4e(_UYCTj)u>MZMS8tH8mx|M@!m@>64x!5ktO0C{N5Tm zX=xpv-CBGxaz+1f=6P2;_z~>*=x3tOUbvy(Ic^x0G={@3>=6H>VhBI%LYZ-sf@pWT z1>}`wq=l#j-7-Uwei@k$ljmbkfdV6@b$^8Is1sOdyq1o6kOcP=^tf$dcvpT)?Qn@$ z93D+aW*sDM^K|&LPYw{EU&8X^4f(r?=1{)ync#w5PPOm5Q};WnV2=2F$>A4W`oj<3 z{_)C-`LO(LiV)D(UVJiQE$w~n2{dKsaG$0ym@%+T*x-wuV)LTu+Nj^eJz0aV8(|0i zPpo7)%S`y|s$O6Mn}xoJ{|Bp>QT?R;U}U1ny((Xkkc&guYc~Zk$o&LpRwPUPnN8)$ z_Vg}%zWstb`WZ7Isiao8i~ArMlNkE$Ch|l-@O+d?;K|={EO7iE-q%@)UP*r^%tWu* z;{9gy_MC}u{gnnk=l+_k`)$*h1uYcB~KRI)#9&mr^Al*>zLL4HXdK(L7!Jz zv1I)IT5ZvE^yM(Pj9jJXYSfm>domLhdGXgcbs7_#;GJA%Cz>BM!?SWXoWxA#mYE;P z3pE8M{dk72xH1o3&zMA1(>1xp%GfR)%eko%(RlcBI%M`v;%Fe@KIfvLXTQ&E|BPR$c1kA^t)1su(OJ9+QZNPb{a> zL22NW*Nqo64TYn}Etxv9B1@F zc&5Q^I9>2W7OtX4xIohYlCJG!Ph?y9h#Bvpqd0<9;r(}>mJ*d)=m`b38hl081(N(8 zSR(QXd6U-Cg(g;TzeAHx+Z_TUOJ}g2aIsJqVNM20xLb6kL1qn7|F@|9lOI9N&7@S_Ll?W$O`)Mkn=M>}-+4K9hRzen zZp0NgVxM>ETQVF(e$6ulCP?*IuDurTxn>$z6~{AnSw?hMCe+$mQ&^09#=#R}sESM` zy!6!Lb-DfE?ul-!6@5eRE^1Tv?k2>2v;ns=_(n2xasC`B;TPx6hPJgkiTMK!9vL|m zVlND3Ntj97dp>sQI@d_+Ozp*u-KNm>zJ@etoe}r@=LR<-z6!JPPWNS>E4{tvEcx54 z!nX$f>zeJMQ`&g)t4pBqc^G?p@H~HDxER#F){sf_F^epAKBSGU5MCh$P-n~OKg_RN zHWWK<7MjtrM6vt`;_8^kt~7VdczBwEcc>r*n7zCYOI@lgmh5>9S$)08?h03)5VZ+j zz$)QEtwem$vYc9mgu*=RU;f>b!ftC|j;oYJ_qCREa*_&Ba7Q2UPgh#!vK9Jd8}h@? z)v%sNi+x8eXvGgjdLgcwm>8&X>HKqKLtYANdx$wOE?LwxH;24&^RDa&Uf;#Nv|L6_ z%U>&+vN@eO<8H;dY6MlB-WS$jUU%3ELzvgPfECW_oG4SG>W7Tnb2dOt#;dQS$sSl+>_uG!IR-ui4PKHE3sN7Bf? z<6uq%=6GD}20qtA*w|LwhaT<#ZX+X|fmprZyD}|G$%jkGy;$zLOqTYLVZ9LlsHJC7 zZL4GuP#2eI9|rq#EtpFvYF!kj(oIzdiEFktcUE(RdyXfW&A@K_-~vm4d(VXrd$8YR zHg+1ese*`E!Ha#~kz0~k>}8?I&5oo&;tGEu-rZgtRGLL+TR(-)$uZv22}5iu)9N$Gi!GQGn#RE0r>BJi^koDdo=RWVOW>Le=4+KW zfY+Nyrf&R)m)9%P|Gb~yaJIMfu%I5hC&JQgs6%`Fj^v)TVheK0cx1~m$nI1jiRIXZ zoj47ypIXai+MxGSc>vWIWzCc$@%~skl@9KOIXP3Y)AnZ{xESfq_WqO;zYox)|K%>8 zMvsi2y9Eu~wj0LcxjfkABk?^X%LZXri~6|*Fnj7mvJHD8KDEpO{dik;5A|kq|E;7~ z_U$AkTkQC>f+)JUs74CDMxKW>S4ji=RoQuzc?-HopM7 zRFq9i(r{_0;Er5z`|3nGVObjd(Cx;HHlVI!m?bl|LJVIrl8$*)L}V|kR`%IqKz{12 zW)DozM?C!crxo=qbM45A5W9Aj!WHoB5pKD zqPr8?;qiV6Uv3l&qaffDWk!e@%>F7;|Lr{glNoeLLaZAPLb6)33aG88P?=2X-H`Nn4u_LX_He zb^~`+8P!?Tr6dSm_toYh#bcnz(w_}7R}xp$xzW-^4bq{wOLg2BNYhcHa}sriF~`i{ z=`(F+mW~>dW^)>~MIZy-V)os_S0vdrgH5{J#t$dt!<4cC?5&j+A6qj6Y=6bGj4T<^ z^&-$feNAEM7UaPcV`+RJobAPWeCuQv@C-I$$@4-QWYPoafPcp9RIUrpezyr`?MM?wy!mh6ok(pChQftdJ$`|B=gn6kMSwosOn0g}X)7#7O{w`V?8`o*#y&)&h9N=l>B|b8-N@nZSD||TF|czla_k!`NlO~e+g9Y~uVv9?&fiE)oCbHu z4uL08>1>5(2mh@op%?$+IUa<5oX;a^`owXt;JPlqFrWvVP>5uC_6lN2a7UN!rTcaC z&|OiX%Zl^i%o<(3>fL3cr_d=Z@U<6Tsjj0wW0K)_ofcm`Yz!RM>B&ZAO2j8Wr_ylw zLnME-CRZ_YfUFC}>^l1IqDw8n_u>=bCF(j-tu3${R1NIf)Oecv82E;#wE&2vrUvUBqD)}osU5wBF%c-^i5h0Umy+H7t?@80MSMNg57?)8Oyxjmfi_#!WsjXw>a)+9^!``J`}9kQki z!;cy6#*ap>0oM(Wh3m`ESB2gg73?25(xk;tDLH}fmMHeL<`4hlp+?`0e=j`2Ip4I? zlJ31Z5tLqN@xl{zBz#$Kw*GJ#zuynLdaP7QC~|!YZf~h zwQ4cwWtcSvE;(v)c-j{>4{>LgpUa8yM%wi6!UXT}h_~Mgmh_ys8`X8%{DJLvvVVj; z)6G7^kDgivHFOdgucOV?3+Ht8*=>Gl$kj|@;MA{7Y4~J2zF%Ql*PQ>Y*o+w7kctV* znFh|`;^UsQOkW8~3^ciZZ)HgT63noPLtQsOJyy84Rw#lPo=z%IDV%$bT7(Ra+bR$T^>&Z&5z8Uu-A#Y*nKl z0=1w7^OpT&DoMuZ$&92ait4wb=;!Ijr7^PhqQUKC>a(LA?9BD~#@eA>9i}?CPnj|= zh#t0=1MPj-y<21qacg$5osw4mvZfAp^^Igt=h}%z4Qh13DNpD)hJ9gHjLbjj%_=)2 zqKVUbIwsEw9-*FDbMu%k44;%IE0*3z{-l0WMGBROva^GzzGMTOKuwy?NmDp8*NMqu zw&C1;va~WzLd4$<+z`ms)_lDMOvCw=m( zL7Lnq5qpdXreiQ;`bB{rKRmG~)I{sDJ~-QZ&$Fa;7X{M2PML2V@Vcv?`Ved5^Zpe= z`JDl5u!wn~$+Nm}yYodEu~5&4hAz<*GWX!Ft#mroipqrZS-QN)%N05TyRkpnN@8Ct zeY&~KnCK-p^6dWA@bb}Kre=iLFZv6Z$Lhfe+;bi3H=}E|*IFxy4}FKzs8M&M&B)nW z%$`9<9X6z4pKW=o7znPWa!eKVDvc$c)VlpF$?j0$)*kZkCVV{`QPsxfCf$@XE8&v+?MWq zp3WBGU1P%6U>bO-FEn89^DGTha8zH!Za8*wuTQOTDDjfewAD`3%h#Y&Qet46gBE|S zeUlLbH{#f=!B5zY1q1sGX7Zkpwu+HCJEMC8Xwmy9dafZgccItGvx=oI494!&m z=FOz$k$*@wzK>H6_wCxB?kO_nMOW;g?CGq%J0rd9{A->oblhA!O95u~i z`MK@fYmAgOso5|RgV;}f7Bx9J26kfy!MonrSAzaf#m{nL_wKrM^_2wglQ*yr(b<}Q ztlbTdl=S(AN3G<3v=TG2Ky2pw1OCz(T5(w&Y}ZC zxbzh7v3mt%U;IfX-PPk&qZYyST?*_>F7n1tQt0N*KZz1{bS?|=1^y_F*)96bE14M$ zsh2~p7&T6T18K`jXK-AF{LCdqi2e}3a=*!oN0+~V)#V^P;dzRiY+V5-P5|t+mJxBu zMdeLGg|bT2d!T>E;(i(o_c7p?%SXb5atrnpcb)q0Lg=&s#YFv)O684WBT_wk73-*N zEDXaYCVL-MzXb-y-<*(NsHS( zVekS~?s!}5^8V+4l8F0O5VQldcvlPQ^9!L*{9K=h5 zpGH9EaDR4XqM~?P&x^{Osh4iWGbQUY_WsjuWjI{Vr4>jzY|Ab?_Sv-Vu7-#t?h1>wVY(8D;ThpdEFMQza`9t53=sNWbN81)1H5XDU_U zzdSBE^wjvy)uaOquaaCp%rj}NBF8#XS;K4WbeNt^sqZG@XOH^EyE$Z=ngRQDw28Cr z5-Qu7&XRGzQ@Up~&Cqa!YV5hFPw3vox4-|;$!Aag4LR02nXNW0y%+--3YvUS z()BKVW6?{@R$Y=!_x}4v{L#0rGHM*qAsKAnybhic=SYX`&}ZX@pnmMxXsXaU4rB&v z@b67#umeI_@fdkg9`yj3xBhyEquIaa7;FP=J;O^22w zgCcU~{XUO{_0WS&LM*yNX%5{t{SbNjN|#%&^?+SFPqWxQ-ME*n9UO~#Axr|N6t#A#$))I>Nfj;+wHI?*v*}#tXW&qx$D>lCp_Kj+0%suC z-6XKlX#-2;|$({p50{sx-NH7IVe#T+yvJo#yTaS+1%)A?phDz7Lzbf+BTy>=%2I8a?na5&yI&gR zQ+AQNUu=2W{#kJS*_%sZcY$jRaTg@yh%qP;^OwDP2JBVpJM^X4FEGF@In%=6M^aWirpW z-#jYcoPN}nXUm$=pL^Gvx?pF@vIHeXw-%&69l5u_Va# zB@p}8lFRm71DR`9SG+*I$D#3QbfU^Cm_D%^@1qb3H(Yx$t9}x3;;JwjpHNJiPODTF zZ!_td=P}0id_spUG}V0|ThJGa)-1F2psCqD+&6miE6EM%@ zX7#2DpAo2)Jr+i1q-=l-S?C?G?Fkmxo3`eolK9F)k$!cN5HI6Ko)vr?6ozbP6nV}) znj2}55DbqEke zN!ItKo7@@6yQ0Du?D<0cr>C>EI&D1rz$qxr7{G46R_D6yv%9jnrnsXXDcYaj@zWH( z=c6~%AdVVb$b{;PhI~cGAeh);%Ca*5$I)4bMb&jtobGN=5s(~05R;g@Hy8+_h+-fp zSb&P6h@fK75()~oD0X)T_sqE>cDJwHt%MTRw?F=WpLu+TJLm4R_FBKCA?5$JXTM$#M~U5 zvUDiubvNdp&xL``)*$wp^!AfAZn()pTX-Eqb9IOu$G=++ZgUK|?E!sgQD`xr#pH9S zH^jjMF9^H7>G1FGF9_H7=dciOnZ#Vnuwm^op5X3J-u6^t!LZ7yoJ3rniraQ<7{J|AEY}=fszkD>>KR2shVLmuIp*zm=)rVo$aN6M#BB50v1u)!aZy{W5h{Q_KxPpCdy0tdPc*gle*mIcY6rR ziDa+Hcb6tAV^hPQz?rv+)9z)2s^&Yv#mSgYdv#MNzWi4V9xRjg^)ACF-xk73-Upj1zWj5gvY`d*b9?5MFnLP0BUr(Z5|FBJHvGf&5Otk2s^pLLGQc zz05m1eHUi;p3JT_|Kq`?C*htVTa3(nf9(y>T1Al$Wo3gqq#ql&tj})D;EU6oG->=F2D6`gaJFo&fH7VGL z(et@b9&*S@k#J(M&~V3`9Z{_(E^8p(m|4c`$OkfOaSH1Fmcc0E(qGH-g~v;xS$5NJ zzFgG^pSr&hZ<01u%=-Q)|3W*IS(^W^%rojE}#B&Dx{rlBIcf*tN%BL+%p_md%oMB~FdW|AH01fmd%%h?KUQ;9MSAts3{M!Q27aO))8%kC z)a$h#_Fp&Pm#mwG0jE@$w-aSom71ZW|4qSuu>tpcm-vJ&#lcUZ^zvr$ zU%P{R$hvIE$!riF64TE)X>OZ0W&(YFDSdug{~yG+q#VTVFbE>f+a%@RTP!L;93E~y{^jAAoWF~@E|Cg-R|eY zPwsI63-6EO^0nmMN;AQ7(EzL_YV&K`E(uo$#<6R8op>sBP;6gvFR;~DCOPWmVZrMb zxY*c{KW`Ze?1KthGn(dv=n?p1w+dW}HRRg@I>8tBDwaO=C$~{;g1}#+mhKzTF{ZI6H{iWD8K0rM20bWh&f$1jY)mh}Tii#M4 za}OPcdnYdg1HQRKU#H#Onf9gS)ZMKqKqC3TmqNTXkGZJ1?-(2Or z(QUJO264KcrpR&jI3m1+=3(@~NYpAf(QKC7z<(w4EDnPh-L>>dhJP z^oww9TRz)Dd9i(;rna5u{q>clu~L838*dc zsd0uiPD`*BoX9h#u6qmYCRVY|{iw64OEXNnX9Ck0`IGgD-A%gsl=d1@m)(PLx%ExC zFU{vgbEe}=e+%@qFz0us%VFS^cjB_&lov|`ELna`I5b6@FK61&OKX5|SraRHU>$!O9ybAm`i*z{>A1Z^|qz3+v=tBb&<`DjW>hdglE7i~e8{0Y;Dv7ckM0t^nD@IqZv2(Q;= zwI$T;n`nY@GpT#;fj0M!xGXfB$!6)K^<5gg3_o38Ce%a+DyFI|7jCUIV~(lyd^39D zyY2;Skst9!o{q%F8D4NaQJ4H(cF=Y7EVi`rFSop>M7xO^v6Y^;r$%PDMt?l4Z_?+s z26qHStR1VR{fp9wWvF@ci!kyObtP-WP&PlGX^d{+FrW)={$$F6XqFgj5slL`qQPUd zE{}7ygU>@ES%!+56m?LYGEn~lm(bb!F2)SchwOy#rDpt#-BY1gu?lbAZ#&Oj$oF-(ODdLoxx+%z%#VN!&mN}24l|^ zvI9!Ze8=Np)QNOrrx&j>BXKdQjtckw!nK=X9TvRvv>Lv zceG1d4;H~j{PO+3ZA^d|dsnID?r-oMc~gkFuFue6w%!P`tX9>LpzG z#qBAes{Wptv3h>^LwoGkhq79A#4G*~g!eXUz-O+_uiNQCo@O%h?eUklD|+6htH+23 z`1jYj(95ww*g4FU7tNjz(Rr=PRWHWf9aWd6WPXiSx%nYTKXPZRxT3uS!*kDJZ#(cr&)b$`PsjA zF!Ivt%q=w@qCtx;qiOR_&K}>?e~F=j3C?h*ntg z%AB9m8xG#ve~1ZmZ<4EyLZgQ&aI;B|KiK2|!?snj&BK23XXUN1)-r|}k$<4&rx}jO z>;+b+%`+0N2_b6&nU1YYTK;|+zB}#+6^r%xrR8H_)SF4{#}Osz#*UuYyJ}f=D(Qr& zAEL4P;S!LMPOequ2uF8zVI2-=N-x!QP$yF+WKA_!-1@C56svf%^j>xRNZe64zj!6f za+FE#Uzg#>bjr)zFyQ;kl}C7IiCq-OSO18)V0m+HA&5U+J#fl<&r<^;;zg4#iq1*+J$dQ(zNYi_+qAk zxcfXY16QQtF}Ff6EVbaRTY^B>qdikD){wgOYKMykSPOn`#)?xrOoep2DE6qdj=zt& z3%R4JSll3br?mS68b3{-@~9qPppgo{qQcme2o345^HA({vndAfP{x1msyK+pJ6-#%$Q@Zf~9_k5io4C%;N1)Mj0Q)hJydpM#z^Q8> zRFKDJMxuvX{WgH@q=7cSh089hp)?84JYe!M3LUtPW|&y#3)c!81U2A z2DJGhC-2gf>c@4)nlc^Xb{uhFl7g{kj}sUG=`<+TI?L<*`Gc&!>Ma72>)Ja z^OTX-g@ONNGgsQBjyzP3Ta?O$YeNDRkh`L7hEFdfcDH|Lyf(Ff*$2?~pBaPdd#SLH z*d0@JI>GiA=`6_XFYh)}1y2sC5!30J%pgtdOUQWmM*R!(CO!~GZnILWo}`?u)oFO#Z`DsWgr795+yhc3TC#1qS@yQ|jQ*I>6RATkz0tUJ$PIRGdrtL(Do)bbX)$$v=#E=Z(tHO5H13 zng6)bGm0J%TSlk@Fc-;HI=P$rq0V-L#}%6V&i;C#!zW|dQdhkWOMJ%P2V@1AHGC75X(RW^*@TP5szfD=`AK#TwXI%oUt0N9% z=KMCj-9n_fF}VN}?S2ZbbmnKQ7zCfy^V!O+t$b`_C)BZ0W$S1+`mO1PbOde_~94^`lfBxjKx%+6hQqcjN?eB>Vt6U|Gah7`(;Anzy0q@+6qShKYil9P=1RLZ`UwtN;}(44lg zG8SF_s6eMCBOX584eo?&Vv|Xq+1T(0rfA2oRPrhqCs^XX6}`Z#M4xYIe9+d7IND4m zP3d2OQ@=XG9z%V;#3H^ei<;4(B#qVe$NwzKtH+YJcHFX9ys1+P`IKeo+1Ux!*!i%Q zV;WM0wl3Brxe04FnJVU%sR^l?UhGZ5cm65r1U%}ok}1iz0f7Z|eo_5e-k(7_l)A2&T15EhqsLgdl ze+mI+1uR;#nSV1AVJ$JNwh*VNLqTdAcQ^ill9aeA937Szh_0teKkPysH(`ZP^VfoV z7WIJ{SBd99yf0qT0XLkn7M@xeDT+^+37UKeyOL1Hea=3BTX9vy_aJ`GZzWu1U<$fd zb-0h#47l(jgrPvJupYzk`m3ArCVKy7{GEkM4_n}mou0f$mvJy@kS2RXcfj(+l%4!_ zOxUGEjQR`%h&3){Vfszn;qDXIw>ONH(wskCT^U2;17SJ&s|&-j+t^>zNI%b7UVv-+ zxxz2%M!yg!!yAgTr%mY0|4gi*`np({@21ZU4;n+4monD-t){e7zY%Vo@DpzNwo@#A z`9&U-L;HmiAMSc(4ZQl3BbL+Ocle-})~kfL7o;Ji)${%jI-^Z$0sAn8a#Gu3(XY-6rjy@$cP~eX+nmAHSQ2xiqbk}? ztP#gjmSi90gSu@PPmE|oetyV*LiGiE_R>QpT^?OQXW&=CjIuv5rK8*C{Hu>!$g|xI zU(GaQOX+;Gy%CGQI}ksI@;k$V9ARC|PK_R4$=}2vy2r&QdSR}LE_F;$*I0%Ms2xpZ#ajQkSL#{tF31**w#lT_3l&&& z>@g50gFEv{5NPvPG(YYp4fdeV7yb&X>$UmBjIM3ncGDg;az|@Jj9fZ}nUVjh1-$V4 z^KLNkh6bN+Q!fyng2jzdlZswnf={!vv|l{*_R}RM`Cq~8mjiJT zwWLjXcfjUzsL))l!<8FS;s5@aHzDe=Rkzp@sG=AHDJ7vGwpa!-xkxP=(SZYRsc2Wz3^hab)#PVaPlKUUPR2 zyft)X$)uTQU0Q^v6V?f}%FeuOaw=Tz_LkkcQqTJww!?`?&mJe<_^ACR`eucR+CQeXg8OGE(>lK2rbGm@zU|sI;#2B7W8NjqUs!P1NzHQDA zrCm(n8C6{K_ZXP(^5L|^f}<(r)!%48Rs3NQX5YyL%dsZB+ty)VanP16A>AgteH^Zh z-X|P))=*5mXDbBE$!09roG12c56T5M#ah~@=RC5;D~5&;97o+ByB-Q^f5x%Fs3E-^ zHU*u39FQLyN_WP-h3Mb$7d%TRHrl-*P&E3BcqNN+@$qpO)=L%ssp#>uwN5bc?K)=q z21^7enX#xvJ@LE2$G{^In1!nqAW?4Y|$>TzK??(gFSpG0C)KN;J` zkdY5imQJmt-Nc^qYR5GC&LiTmHKY`hrt9(f{hgt@t2ax^qaKP^v=^?B3ERHe@jFq! z1mF3W#53JU$G*87bA5)u{0`)Cnl-NNoUiJrA^Gm^ja`=1%a71m^r=%kJxhQYw1ZpM zRY!>hbyzEGv$%W z(t!C9cy^GXIO_&^#*}8`y~09xyOz#UoxZTCs2wX2iHlX#5%ca_3;7SH^S|BaLH*-{ z3Y%UIJVclB0>|%*nsg5LO;g1KKBf?%ti$hpp8;;#A*?n)LsE(xfnM&nb`Zt>k*x=gy><3<7s{BlpF}ye{-a^- zG2%3iF@qOJ+}WwGwAZE#g#SlB;jOKWLi^x%dBkE%HbKjm+bpkya|7~3D=V4w&%6-B zzeItOKy2jfA&?ju#1fxrO1u8^MJp>^;W+6Gb9RQ{)3qyL17)2e)U4p~3mv9RIm+)Z ztC562Q8wCVGsY0nb4ZUq_@mJ5+n<%)3P)y*`rU?|z}1$pCPU*ElAGHL#w zUdLlfx6aUEm;oO`9_@hG z8q1`F{VVW|@i)O{y&ks@8V>`17BH2abmkoBfq_P5Z0~e>_c@HkfTU5N{YjV4aB+b( z*M_hKW~!3;IvuQ^`Zti1c42y@9Y!432^sW``|$CV@b$nS@ytM(^rC46{`@ZsP6Zip z?a)cEu3smXLB5Nxhvwj%?OTO0D#X}tlDB1@%Ewsp(8jLd(dW5X`_fffbF2%-IO{_7 zI_l5eq6Uw;PG?aLu9!rGzX9D z`78W-t;?@|^n*Da7O>g(Ecn^vuHdS?OzcPJ{H}{#aGz&)ST{+V>*@Y&>&}Q-qb6y{ zZbARYS#raBPKswE%Z2^VEZDvpTfRuhf{!ajaXbC{7mS&U8egcdL|327Uk89mbPQ_= z|IM$2(EFOs`900lkvh#6N0h|Foj*GK(@P~df7gL63)GTgPdtD>VPV49b2MwMoz>P= zZEj@2*G0~RiSI+i7pv(#6+agTR*V3Mrv8O0KR6iGjdh5kzTE-sQQ0#!FjkpZE*ZY) z_G&#Oxf^l&1LR>R*7`m_%2-`h$H{MQ3cYAn341iBP0uOWMLM%>5uRMSPI!^+!bgT= zz{FMW+5X)PJYUuc-`UJ(Cf3B?yBJE}i6-20CNAY2Gl;%6ogHx_zubW@P_Sx?2+6L} z{vYa??Vbo*{^{|AvNxO5ymwA6oR!3_=em_cs4SRZ93A*XFqqrl4Mop z(24GecSCX6nJ$nSK;F4eW^njtIQ2lOOWX3B;LxjJ`TBBKsjHa=hO{1oM`b>|@mwY7 zt|+hmLE7fs2}PJ;n+IRQjJf});V}Jp2lgURL;7{z7sC>Z1oumtiuv~)gm~)ZT(QE6 zFVS{@d*kkjUnu8WNh~H0YDGGlK)Xf$M2Phn&ur?cM?-Temfkube-kg0z8x;YZHs@w z_$@~Kii)ZQl%AjfCed)fch%;k4yX~Cc?4T_D6e4j%KSMFKmV6_d=c3;J zLMX|%;MZ652ie~CZ0r*aY0+tW6g$}nR;|;y@!W;*!1j=$u8$+1Khz2auYW`>4CE`j zrH;PcOyR^PO}R>=VP&`E6Go6vV{RrYJ6U4>;C5V{dQK0mtQVK+ zQBM3+D5^|6F34iE`3ag0WE+;Sfp$&&vg;dIKzBo(4Dzo0RmXKTfv|P0A)oKN01C#P z5YM*~XJ$+h$}hV@@4d>>w_TnH`DagC^(7zazfd$P7!8x|P;dJ>3z)C$!49<&+o$ty zu($UY&K>pUVXBp2Qkx^%TFNBD^del`YZ#;vPj%O9+M8MRW=3B$q*aHyqHTX2p(vfW zXMSO*C#`@;ZByRQu|4?K>apH*?^7Gq9-ZAT3IQ@5ZgAm0;p4a*HmDtWL`_y<->c<< zlABzSaD8pt*?w5E;<5k6!QPxJjtzXhVQxh5089Fxf}9H z_9iX;gR?Cf>P~xhI^sA7^0XMXGR=kF6?(KkExns%?Par5x+e_Mq~l#7{l0>J&z0TwvS zk}LP<(Z-o^dg>~<_UuOa4Csz zeyt+5?_{@;uA zFH}d`p!6Jcvjz&6c2kE4%V^VWMm2TeU7X7yu6~->xtw%w?fLln_6TCu8S-ZBV6a}| zPn_{&b!2e1!{_8O?>g${(1Gegpr#*%9yYdCZ@@2c=WOaZijU*q9U3 z`;kSP2R^#1G55Tv1>u`cRU1yDc_~Q?w+&B(gZhTN=fH*VX}Jm;bP6OGgPU@0yzZH%y z4VL#Fnv;lopPMM{N3+YEoU+Kf;3v;#}8n_|`pS1IhfEnZA81gDO)A36Ccj;!k3C#H0n@Wo;o<;8-m2*Zk3Uth z#^)XRZTkD`k1iFz9iaU02V1PR^@Chx%9m|=Cq!8EW%2ABpB&?ZueQ<5{7;|1T$luP zKc=v>Xk{tn0^$VQis}VZh#|0O0?uDq3e(7I*YUSI%+l+^zK_t9niR(PZm&#mBhI|> z^>0G2qEq4>(ki!}U4?u93?as`9^Wt^0ah6FVXoAb{NATOuFPtX_o5j-WAa4oGYfF3 ztr;Kr(ia3(Gge98!=i)Ta9SjFBEHh(&MHb!?Uv81Y3CTPdl5?91DMJ&(h@7@Ks(dv ztjt_l3hgr#{gMquSMuPsP;N-}y%1K!QO?vnoS0o5*wdGqlAfj$&d+EkyqGwhd;Q94 zo8iMY)$tb_UP0~0Dwar{GCL+{(Js;y@^=#NIx-U=Zve9-ePdw%Slk$O(t!>RE$SV+@RAZW$B@cH|E;bobF6n$N}raQJBtf^1>*|lI+YX{G(GL_zjRNMx?J37LjfcVbh(rOIQT|30K4o z8N|+7H37xdogrS6nB)&!;oX&4tpE5w{N*&QHmznqotZ&q9r3#N1eipA*ST?Tgtyb| z*u0)HNo~(66l=Z-*3_pw{8<8=Td|1U-P^)DtNY{qPi8D*JH106P(D;G1}@ebaQOsJ z_?- z-2?P_gRVNPo0-h^Dl17i{5sqlkRyidmPxH9tFiR#6L{oo#<40DHf1WYg-2*-;XfbM zdi)cb`y24?=KvOd&SIq%ja)0&3~%Wqv!CCI5Baql?w{WshR&pCd$cMH|K69G9a57v ze!B-LhS~D}COIlbp08-z$^LGz=F^uffW1Rcisbl{-cMbKYjZt-(;X!1NifX&PJTT3 zZ$9Rq4VHg?BlaMzY0%i7_@gx*)T*c(cY-GT-w(gb*Hwxr(ZTCca|I>JCdjregg5?6 zn1yN=?#9Yt{okqLRLbU$8NCpXb{h$aTaEZjo4zn$M*wS@ts)hVw8QQ7sev2Sh(j{D zC*Jbj05iVZ@IpH?P%JcH1^%wmrDZy}*!z|+s*^q+m%N}Y>vZcj{T&-iu)Axeu*%z! z|CpHp2g+WvlB5QHbH6h_n>?Q_uqQ9>qd};YsR{0HbosU|R&6tU_HiS=BU%RryPT?i zNWZB&k`6``CPL~R%6&Lz!>W0z%=ZFy1b-~S{Y#sK#bapi|1}CaQ?|77Wh;Mn)g4FN zR%N5f>nMF1gs!f>;1;FNJ-XXKY~vs{Z=RZzHS`aht_hN#pn1FNHyzZEIu7s7`ttp| zHbLFf<<;r5|GM3AF&gCL!IEY}KIQR9aHSb?F3lk}#)){wX1}l{L|f7QICX)3&to1w z_B`W7XYy&j6#LR0c5AdfPAD^kCh9Ya(svM7LWawa+Ouk}e$vi9=pZqMZ-noe0Bi@Pl z`9UdMe`v@DT=WJt-EOSOQ&UP=V2btYWy0aibZ)nH3P98{#kx*rJVUopcvgE#WTY<% z_G{30@KD%uLzm}TB*JZ{-t5#U4XG+34Bviekni`QS<5O3BZ*o3*2{=L_3?pyy^NR( z={Ek(JyB(`LSTuSe8)^>sJooUhRtZ^Beq_FvY7!)f2c11;G7ATwJB`yWo4=3%;9)G z$w(adgjhy-3$eUi5jbtM^mC^Z=8UxwV3)CC=yzK|x<8DK-dV?E zwco)0=*ND>R?KtDQv9Jq5M=nK)>b zCj9A@5LlG|MlADilOo;^!q*>;3q!)KxWAV(m?y7iCECsWg8dipatdchb7@y{T?e0; z%VE-i_T2K~V%UG>qL@wZzFTgKsng009#kt!E(d+^s!7f1hLOa9w2MG(%Q5hBk|AG| z*&eLGi(Mmq-s6ih7Df6Cp`kX4wVr?FAzD@}NwDV@AC|(op3}u(+9T8rS&T|X!@;WD zkiQBV2^Q2dtC_DUja%0XzxU7;{Bzu-+mR92zx_&>JJOhUU1bYqlXTe`()Xf3ygda+w?M^B<@G|?A#=7Pup8GkDFQrpSxlKszDGq8 zHqrB4G)$LR%^uKlE}ey^{NYy@>SDv`8u7D&c-oB)xMbJ_c-6&_*HwNM%%?c8-*apE zjM}c4<5D6Fol0Jp@lzmaXd$yc(9FFS2V#%yW~^H-<%!fM;g3Glo1$&NHO#zW>w)3S zlYEsar;RZEx8?6T@c>glJEEaEoe+qXE$PG(r^E@SidkEzHc?)U5lrJ zqoV_B=W4+t)hB>&K)HOgvJoHnu`l4aL(Gc1@a`7G+Zfy;HqmTc+u0At6zf9SQyo4$ zTm$s3C$av-XSnEj7tXunh|3CO(#W*6sN3Z!Y*8V$@Q*Z5+VW2{*h883v@9IT{|WCy z4LIM?8@_kRW~##)dGAe@*eWD5cHwSwV{y~eq(wnb;7$|i zHou${$tzb1W=AbqX9r6@GkP9W`W_Rv?RS&9iCGx4-vc^6r=FVp-fcddQ|o?n2iFdm zmi<g>f%!6ey z@7U(R2CkXmia{mw*&rX<(dR~@{XR`7d!om^ZnlHD$5Yu=bz%m#SHTBGd&I)|#NU?d z;{rt@)Pf-|x|~Gbl6R&#`FVmqHqJc`8=iONW4mmHO6`@^ zG@n=;M#oK|*u;#?IJ-RXLpl> z)Zd10_)r25)X$6k&1KS{(k1wWvhHTfl%;-ieX&8W=CoHN<<#~@Vp`}JnDx+r|DlYV z`YBK5Ypf;pw^GCZ`*7Ah@!*~>Dq&4lmbf}VCIuZ>g2y9=L;v>%ynSIb+{i%|_gX_5 z_Q(%Q&gclg$#*^E8|Cu)uY_<5W4wY!>64=lPrylzN0z0 zi{ylPV|KwNYg6vAp+(s7LYZ|NCX+n3t;6tx*>L)_0e_=89iGm1VD98^mmkl@@RDsp z?_)N6W5*FNFhjvik6H2u*>d=L;)OWwBWZey0GxA37ydq@dv}Z${Ga_^@#`Ny8~+g2 z6y=B)>74KNb{!60{1gm(oARO8GC;*&iA|*YNUv+zsH{z0^XCnC=F)!f_G&h>+t*e6NxY2gkQG2^{S)d*ZY-i`n;m6 zCI9$i0c>4zOzgaw`ZbJlQ0b`$yg#YI=bjFLE^~&kYbC$=4gHQd`N&)GiwXT3$^y}Y z_{^$(^tch|fa-Hcc9}GmrgTF*czUj2a7LTwf1C%F0Y&V~4iBE&X&E$TCW;q!yGea5 zb1>@aNZ46u#I5Fp!sq4yRz5;S%Jp)@$Nn<|olPmPL7(4e@do%}Zo#j9HicJxblB$c zuF|MVL##b?OXxyA&*tQ8@bPtJPv5yoXRnpw;RBVz&0-UNb;ejIF1f-AUe@zn9c5^o zNj#sfZjzBbbw5$h)?D&Gx9)2XN7QDp%bLnk!HBR3z8cjAs^riL+U9$4ky#Par@xy(7$G7wLa~?iknJtPD387 zq~CSYkWpq@ z4Z(4&F7MC22otZ3XPG&*eBiI{nEfzEzIP_gX?@DjoxFfogN*saS#hx2@4L8Tv76L6 zFBvassln;V2Hax2FPxZO#c~s@_|9iC7^z<4uvIDTIqwdVG&dGI(8?#EQo%ORiu0VeXlVY9PH%V{tN?_?Lkt?XN?$xb)fny!gWsCr@-28Yy#h@!?f48oP?+B*`RSvr0T+6$P&<^f+%xZqw&wh2}ifH~}_T zY02Nw`Tw?jDz+vdc8xdV#c%xJy=cZRkl(fMtUx>_!b0^P$O|@J^2R1bFgc15j2fA=NJ182Csnj>~@T% zOUz zq*mVz7f3ay|C>U+)d^APvS$noH=}&nWIL$y@M0RPDBH3{9W8tK3vP>T6rtBuh5!3) zc7OQEjaQAsCw+S{Lt?XBYF~!Idr6~rG~$(KM#IL`V7C4y`9&WG;IunBf=!W|w7et= z^JlFD-wozmox6bDB}4Y-B4qe%}>UVP;W4IAYX^jxow`0nDmER85v+uON}^^ z=I!kT&RFwu0=yrn&#!3KwP`p>$>g`Oti(f|>x7Y%(fi^y6^=by#FjX>@UjJjWbig; z;WJ5=*st_L)M59Bn@H-h#HX z{qZIT{@`yBs0wo=7CORJny6($?44Ue$LqxO`<)GH+g#Y9JH%daT#APtRSJ#z>bSD1@MjOZWAagju;P_2H)%hu?L5EznKb!Fp*XyBd9@e)PIo$|py8M@*h72snCm^D zP^UZ78m=iBU9iUVNOxhSWgYQ{Z^GNiRjicWJ5gop@yh%t>K4@JE2qx@y{G+HFVK+s ztR0Nyha2Uw1%1>yY@=QQK;t&3Ns>=s_)rG;OMXb6{ zGyf8MA1bN?m}Y|xpMzPD+IKqJwNP2|8x@QEq>;FceE2&kkJhoa2-Y4khE@{W5AVbo_PKA|0b`*tRH@U;NY>E@#(PH1Sslo8ZWRaAvcWm>XdxIBc679+gt&ap^Kx|Ms#t&qXF3oxGHEOBp1# zDoahaJyGBJ-07nUZqm|U!|~YbG4P!jYu?%RQ19!>dZ%bfKE#nrFAfmgds-{zeozzs z&!~Aix|!SRCZOpaKemY8m1c{VV!7T3I2&!q8*h$j)8tQUYD${@gf@NVF#Sz8I*mY& zs+G{Z)0jKtIKk15dMxmUt90b0E1Cpe63YE_xW>(IZJPWS%Iq&1xdDebEElppJAlX*e?vSCtl4kWb!CNxq-v_N6s4^xC}(q7EAK8um}{ zxJ&*P^1TRKH=uLZ96;K!KB-J=>-exD&+Uf%JbY-gU07Uc%~wwv1rN#@qc#ZgUJ7vM z<`XfHW{ka`5PdcEz?0_cTfcSS^VbCSRPm3e?|cqE8%UF1C6m@Y+JG-dJ%e%EOnKvw z`A}1@#2P6hd7vr}$Ie!Q2|TBcR(ZR_6_bxzuyy->ChVoU+u`pIKT*G(JritJm+pnX1L5H zQ%IpR&|Wnc_O4pYx<2sXM`x{uh|Vcu8F?M=Jjugc%BD@E=g@0;SX=IO$y^o5b+jwq z)k+HtqO;xLNDykg-2jJlP58sUW)O5ygN+^TDs`A|hOZiK2`l~e_^d5CZJPYc52U@U zUxwc9>xCW5z91nG7K-*@!??(YDH9U|DSuEetIrGc*M!E)6;6jHvsZqaQu6D0*t6#md2kN> zemj+8X8j-PaJ1sS=ca+o=(jk7p8up@Gf-=q8q`f7O*_&LYP2@9B+DN>%t{{(?#HlV z()zxnxZ`^(f7leS#oMp>-j5>zhR zedhiq@;f!nz_XjnK+0cq^hew-b!u6x+eDVCbAT%#i1mCjYx3$&b z>`76~%a%zijH)p2LlkV@sK-N(%z%hleOW6L4LDg4gm-eeP*tqOt2XMu|2tKCg*Wp=4Pu164`6k~?yLTi4V^1yu=O*Q zrGt~k;KNr&;xo$2x3|y7PHM#vILnl~b{j&TD;suXx2E*furq!&YA<};XrzeFcNVl= zhq0qgcDzS&Cx{EbFFspD`-`1sIE;Axt|oeX>AW21781@JZxh2|Um}JC+?B`C-=ceF zKK@%^g%6$2@K{j;H~hcUI9^?P)XoE=wk#EHb)Zgga~E(fUdfiPZ{p1pe?d}KIP0*A z`izd7;fFJFSl_{x>rbtKtjd!nUg&1o%~6Ld~QV`ASp zIA>(c|ERk_Wt}%0LSD+x$~xFXB|wO})WYrNO~S*v0ZfTBXJ6%V%FB#^LRUksb}PQ^ zoR7V#Aq_A^RCm=CChsL*TwOHge_jb{n#Npeb%v^Kx~%akz3;}lF3RvF8N8yug%2P%vj1;l7H-D4`^LAoXu0W;F*KHAYi#k zV8$OhlZSd@!_!?b?XW3-e?=A6A5~$Vr84Qf??!A~m;>%ZsY@au9cG9QEci0%GxhoS zY{GWoUxW>>dN>-U98|E8%1->utzqCd^5~q>+uWo^I#rz)=VS)Bvh{g_a(0vrfo6j!Rb>$^Yl&jd}2K>&gzU) zzRYLSd}-(VJqFK(YQc2UV6{XC=s9c#Q@#I}s|Ty%w#qHyIO?c6-pdkkM-oI*R!%KH z7iN4@V*c91%5bQ_xQi`9$Vy$#XN-ol{<$o~zLhswcf;<1YHaraH!0FM7I*jQ3MMpH zi*q}Hw*MejY@jAR(AL7~EkSZi;w1MNZHW(EPe5sks`OfIHX7E&h#e^h^xeM#omc0B z>l7n?-Dx5$53prL^!%U5NW_{t0iBCo#n*4JoX00WPySB0os;WZs$zY?%BPe%|urZVQXReTWg8wTGCc zhtkk_gBpyDH|D$V213ZtEi5Y3g7=H)3@J+r#C-aEqZUu}?(YwY6Ser2jg7>H31n9i zWzvBu8?mU;1;X6*cn|-X5YRfAefgyK~5PWkLvCXNkBy%H9>^Tf3kcYp4 zG8aBC`>=ft8j`=ka17b;Q~rLeOgedL7M|@9gj#;qJl8A)j5^w|VKkdL8TY}L2f1+C zTAMfd>q9JcJbl$|=6=(jg7V`4w)UhBcTLJ^V^03KL$iI)v8cMpSnNbzR-Lp09N|_B zS0haL=4V5o-wJDXNSC^(hIwOMUOQoRlCfgr2IAZo3}^qkTJw_I9pJUiRdLi@SLuei zCBBkT*Ob0K_p8i<_J)Jlx$7EI`kP6(rtq#jCSNA`JS)KCC#8w>|kUW|m`_WB2?e<@|H7A^!Bo4-pFyIGtox$^}C(|FTB~{JQ z!$;=>g!}oHin%W|g^y3o+4V0iJYF#cSy}-5IbJ61pHYE7u8)9(T7AyH#KRL!WX1)= z5xN?Lu6nwHaK!H)Zy#<+Cx*YI`d(~-nr|EQ;C7xNlk~}ENE(*?Prn) zU~kbz{I_?xV3Z&ztQFgYxihWU8Qu1L?d}XPopwNUAT1@~SQ>t|@qr$hI-K3<3Jo*T z*`^JD`B3T`t;(tuw~z*MzOxsG@0tiXC8Q0S{1*QE-jV&^msm1mBVLHB7g}DDH@i9& z>JKks7vs!$Hu3xelDmkfZ<0U!eH!+?9}91H>hr)~J>i%02uA%Dk`Zw&VwWn(Uwcr# zqpuh4v)K(EpN;s~AJj$MPl=@;p}gvmjktby4pctX zKaS2atg5Yx!i01qEg>M%2$CY4J*S9>V1NMzf+B(_7Gej|VS!Q>Vz*)|ve#K#?C$Qa zt0F3*$TvU!-sj$P74}(st}(}W$7@}F7z zJq1`uo{)e(gP>Qx9QNaA6YqA$26xv@W-lD+cM%neK^OfYitd%Kuj#>7_r9!r6J;~^ zegVyrY}tl^4)X0v>)Umk?C(Z=reZd{`*=vac#ra8hYPTeh6h+**XCe90Qx$NW^;Z1 z@~dmR;@>oy?QNZ<2M@wfF)tD9_v`RMhDP9P=g6!EQ3rIgIi_uyFU)pO=RNJRK%=OT zo&4&}-}G7!<9NEL@tk&)bp`k(bRpPwZVCpZzfGH)*M8;)zowpuv@&$txL$bBY{(Z> zOoBswt}xG?jePPtFYKMah}Dp8GkkA6M&zkOvV}G`Smpo&*QT?j-P`#0SQS)i+bnw1 zY`<-fIX=HK0hD5hmusF6JLW2}CelAuOUlr^dyBAnqc*n~Hx`!6%w@ScE&P;(eKfBHvY}qFZd;@%I%kXwdY|Y{=eS| z^@hJU?ubuFyU3p7iB(DZ5Kg}@{a6K9^)#6^HK|I@ZJC&ren_^A&ipMZyHJo3w=`+7=#0yQ1u>Fn}AND5$UY(uDw8E66nxj$pyu7^r*)C@(J7G3< z(xvuVv)g^9%*p$I}P9~^(mCBdIf8!?q9zy)XN(M_^Bz2Wd zn7n%!+=$WORTa}9eL^o*!&D{553xA7=BKPEp5A52bI>-u7f#=2!uOkofqT6v`|lt1 z9~}t8**~~2k7f^_Mf$LPSRtE5d70xIUx3ftVD>p!i~jvw^3qRdK7SRZo?FME+GjfR zZCs?2p9`=dy%Xgsx7+60e&#p-G~rzute{`` z1<|d9_^2DrQFW9N%pIr0KRe_@-P?gIhPY>KTPER?iMM4zYh0x2s6w<+GDrLW^m)D0 z5U^eKN?a^BOGDPjV@r?YLP3}of3d0yEEh}I&>_G0>>x#q-PoTET}w>1-R9`3E5O(r z2Aq#6hPci3qCWA#RQHwPgfQ@Q)lzLrfb_K)FYOELOEm`@V#8kc@%$lgq|J&6p z1Z8G1iT0S04V&=D$1=g;t{~58*dbi%^WjleVY0-{mTJv7rvHJCRsQ;_Yr`}V9|1%IeQRd>}rA?^zv{Bea z+3+9zGvG&EK5M>i%6r+&gmeXeap^HEcF@<11Dp}V$$gC#Zx zD98i@Vo9ZU$IM>4;6aNXw>aDZDuUX?S@cX!vfhj@zfccHe_g)DY(C8Nqh75$lv6ud zh%WE932!&*a=S&*pts@x`)k$6RY%(59lOKqyPC74u`?V`Ez$;sN96T7-Vxp$pTsub zP>>$&_zY{_<%sT#dVI!g#;&`cflVg^zOo_{7Owjzrrjq$;k81vFjR!Z0lK`uO*CYC zX0tuTO?hTSq(!pwun(X$*19CiRK2W;9#K5 ztBmtuM6Mz`q)K_xALZD$s72VhoAl(k@vw1I9{alLH~+aUpk1p!mqI_2jIkJSh35Qt z>WjS66%H;Qz>+(3kXC=u!v8Z6Vn_pjJ<$>?Rvd$Qk}vNSu@4OTRMmS0yGVguD=>xr ze}m%nd6hi1oq;f-lJ09wb5ZT$eqpDriu~YDFG1yf7Q=N${QVOz_`B_fxZ$;vWUuCp ze#`XX&p7&Ct0=*dQOWGtXyUX~EXF^-4$4NC(ab!ff;89H>R|e1jz8DIhmdG1Jzwv$3pF-h>N;Zz>;kg-`@nhRCaEjFA!K*T0 zr+#ndLj0MC(<5;7>Yp-yI`ijS%*Xlzy|8z!3HP2F4yK<>S@-|n&9NV^@}Yg%s08rHf*S zSiD+vT!=5HJn0h$sBTI$`JsGTV;-r*!I^R~oTVw@(Bwp^991kPWm7n6y{ zvZ+f2CJk_f+j|uytJeaqIdHn}A?-}BZXAn&=3}6$QIB^FcZ1K?o=o?pnzTnl9~Wl? z31#(Wa%qN6yM}*|xX_=J3qjsIOst|E%EXuoT(xXCggWT*gSN>q*{Bz5Xi=4N>%!3L zsg__)@AUVV$Kr&km0%r3f1Xe7#6Hz#_>}Vg3f{O;`lN{1J=GY}GA5hK*O7(IQq3#T7a-yHS5?!I2j z7B)KbaHk}wDElWaq3=;zNF;XNsSW(M7T5V^4F6}H8J$v;{QbYf!oRuVkrU*-xxED^ zsXd41!~t*%UJNH+w~E&;5o5uz7?=Ai!a&L@Dx8T1@3<@$IH8GGKI?++zEju((!lp; zMB=kP0pLgPviZ3tl!pyxEhDIR(xC-@ugaFadhQ_aJE2B+6mQNxE9mhaE}5_-Xs_7+ zv$K>`Sd7hUJ)nSg6TL?dg}hB;Sm7RGs=K;iulaAqN+|*TsX(X6WG~js) zhC`=PfxS{tl4f4+hT}srf;~b=({t{RHitLB1nMT+aMJ?x$k%$CeDB*9S|gshDQJJv z;G=!=plX!^vu<*ha-%BI#iLp<_A=tD6VgFgb&dIiQa57HBv80kBj(fH0Y8kx^|#c) z@hSPV3!U4~{JgpUc>go%*x}A*@dKUtmHVx+p;sy_ryaqU^a7B-Qe=_c$OD;INetdU zg8Nn-{=6mywqD6&ALCkhhrpg_{Hz1pI*NWTs!3S+%LlH}{z91H0{P{G*c$TQ-0P!@ zAwNQ7jpY67b;lZ?*BpaG9>iUYE{3D8rqw5tw{2i)CGO~#4>hE9-}ajbj^$SDC}r_t zHZDK|!8x~StYnrCKTux-vcQP?dfI`GJzk6v&x&EyL0uk^HWaMlP1vcabWS?@ zG`b=G)fy%9V$p)5~$AsllW#QMjP zkN4hG{C(}VEV9N$^08WiuVVxJz4o|b?M{*L)4lcEQssOvS@ahf|prH*}^B+~I@I^R2)72K<5j#R-a}oy2E8%L0 zA@3LN1qUYSurl%w{8{Xa(|s-qHc4tc{`9~0-l!+^zFV)n6>S!m3s1K7lAC7i72cle z#CjYz;~%cig^m;Uh)d5pOV2(nz@nF4P|!<pUBdz0GIgr@Z)v<`PKTHB5AQ zL3<@5dS=eioIgT`Pw6VOXQ|?UDM@~!HJTTiOkU7AQ`lB?mNFdsqsH6-I5I?=zq@Aw>raQX9CsCI zP*n?TNXwRWS?3@>l(n(_oIiKmiAS%fB#rd4=tvsotdC2u;y(}2ny<@Kdd0M#^E1Ex z;a=oVIPv$b7}1lsmn#S2uefnA@Te{yF|8ALUUg!pYmB7-KI-7#P4U93Co25-sBBpI zA)n3Y;>m47t6|FFDdHmXvkiK>1f9c2wflPu$d`U|Vi4OskaPeC%H!C~44x23=R@g0 zOun-L)=@8;rDOxk|EjSIr048^)ES3-zbVWO*5D4i@?fHx13RVdLb<0Zbj+$2Vko1! zY)%Ti-gKI+Tj5K;$3loC??i5_vs9mzjL$SQz}-fRdIYF1W!rQ%az-21w${Q&>$Zry z$OC!Z#1>~RN`=qGTD;)D0yr^Ck+nFxNV3OO*gxx!ur*tUFI zN)>i9iFg{Tl5wZ6FIXDta)%HPc=$D%9X9SD={(lMLnlIHMYo72>}!i>&mDuxe%3sE z@ES1roLj$k2;D=KSL2S7e7J3-%eyU^2v3VG*~NFp{P&!(khyEE?D{fw`Q?3q!jbYk zW_PzU|J*kee$IF$j`~6VZPfsr{8S%0UeM-GC#%BLu_;WI&Upu$9Mt-9NEW=!g>;+M z7^$Ox|6Gjt$W0lrHtm-akS4X4ka zL!V!(8w9)j$Rn+<1R*vuR!HBe#8KPO?70)%{!aRX>4NtB)R{QymF^siY;Z;WAvxt_ z12b{KjuN<3Wx&g|!$7p`!TgCW;6KR$T~50STcgwY(X1TsQ!SC-arwpS&%aU;TilKO)n7h?FjU5pHfnG;-F&b~n8q%Kc=K1L8{vUl zzxpcRbb8>YHI_orF9Z21O>g0}Y&c5{vF4)^ zs5f)#Em4v5z#a;=c#ZDT`z~qnr`-$Sg=K$M`0NZneA64}&RH+pv(H7coxc<}95=^3 zu7+IU)+mUX_*P6FL>}E)$@uQ;apA0^4nJb=4vSn?u`kPh@(ZD=ShlP`yLp!Oq0YAG zOHj`z<%YcW?s9lq!9+Rjtk3_c!aJ{A;p06;>7z?;e4Ku!Zo^hOe?BMUdx>WI)dqZ3 zWp}uf-JJ!Ip7YGr2xT3D1;^8-a?OwWLVSe@yG@zIiwh|?M(2D6?NF>7R^waQ2-r%R zt=XH@_H#a!b|^=mMc~2i+QQ4*&QfQO6ukMh5?)3c@{n|I=(Jjg1-x{UPBi*sLE1&( zUAhJj6_ml{N;c~~kysGjw&NYKT!?q+C0DQ6-+sw!-%?}D^BntbXu6?kd*Q(U);@*QQ{F{(BPY|aqh$vqSL`Pwm! zm(*SLcqs<%-Yyg-689!%1ibHlh`Gf&@pG1R7B&18FVk#%AdPfREgg{POg=Tq0;0Q3 zW<77INR7P}@o`F#n0lJJBl&i0z5N_Ks`dEyTUpTJ-YUk^>}}D!6c6oDgtRL(f94JY z%Yj*J#Fy_pEyM|bL`-30NpG<#h{BB80J!3$&4tb;tl za-zK5`eOLRx!8L=v2+4c(N55SaN6k@9dn0~!VGqr_CZTmYGY>57O?|m@uX^d+)FGu zyAtB4I~K!|O-d|({u%D$;ES3cONE#t`dkW|4keaFta)k+-{vmhRa9X?^T?kQlZxRv z#1UPf!+no-gW3VnZ2fa($+_A9C$0;TrIWV#^t?T;*EkL*<2?ArwY%ZQ*_HLP;#?&2 zd28^()qK$3tjm91oeY8FtY~PXd_nPIbgQTp7MxU*pWWNDJu@3v(UprY20-`cpF~-k zlXP-*AWqUUfIIs&`H;D)@X<1f-6~U+y7kP(VJ?Sd?sQK)a&--{9TaeBoDt7Xnhis& zn??Cm+Qn>GjP+$I&_&eZ-vba*o~>syZZ`3QDrR`*cO3Je&)-R(&%%PhOj(PYUQmVa zp1s&bI+IhLZO0=%&R}LlY>mB(zDoGvpWB z`oXnlfvm@V;s*3~M9(@`;h9=GZ*$87$JP~cT=a;wqsm)EGQDM z(o25iKN^44=^@VBv${rlF;JB|GY&I4tvt%n9*dN047lTfqJhaWz^8P>gssNY0-c*Cq^ zcq4KNOuDPjhuXyv6Wg5KPg0Xw{Cc9_9ZO+?wSjzOfRE7KKbG~qV9XaJIe>1)d2#qj zC&_!QJGOi}Q7}~J zwdlOSSrSI1V(*bBgd-Pp_!bjSDEqgH!L1*B@i8_0e`YqZju<#=>@nh+0J}sZzD!sN z4Wc9h`D$9{tihO`Zt$d&lH{?u4<58STX$?Tb#bmpMY+mYh!3RM-pU(Jckp6=x~WU? z2_~qY94vURHIt|R?kN19b@nByBVTx@1lDUNh~HPyE@RIcyn12;1l-Z)br&W=o+Ywf z8EVp^s{`=Tdu?ISLuYB{We(R7x9ePht5x7N)T>oPKHxi6( zxBEg+npnUdRk`yX(WP)SJz9KxigbhGEUZk4hd6Cr4!=TScefF2{Nb`h*gW`$_|lSe{-1-<*I5UqMQL;ETuazJZZh*H25DW- zHrQR8C#u~e&+4F^_%iwhtj*TsX$Ka<%N0#x(Kq`1gymTBToDW@vor5&3{}rVn$r+;_#6OJNY@>6*s|TL6IIdGV*Mn8G>7% zlb+LEm%Dehf$|(DcCU+}^dHT%e|nD+9@wbx1K&vNBCcT5=hNJ6pdY^Iq{iCloszVF zIR^ix{MtX_mFbOyQeufe)>M+B@A=|ypP9ieL&!h;VhC!5*MO*Lz%LE8gAFHCnaxJp z5h!-WvYcCj<5zXQM_vGE!k~-)LP6ca1_+&sSmRW>e?;pGnkJQ6e{aF(9_%ff%1N+I9VfbUR^08=)e2nv{ z_qZ*?oIM$)CM|?uto%W9{&NF)hh%?YL-}wv{*x(Rq~QY5d6&e1Q`D1g*A-2=7{k+B z+FWb%66kPe5VIGF3!yg`PpRCODP1K^BXI?qgn1)F!y z(xdV;d=*~>Eys=cRmx}hg%Ed6i8L9fU|jg?q7X#CJ0H0k*kUa|U-v-Djxo3dct;rAF_{=_^CA}lglm2NA~HMBu_ z{u$BS%US9j7mSMLDNs_O%dd~thBQ5UHtI0tTj%b?#-2X}+fkZ)*Ykx?HK%}SrnvL- zWu;&>Fj{OO-`!W|Y;1lQPaWU7JS{2={@(-6KPXB6m3P4*rxavYhLXo4FBlVh?1r!N zOz6%<-m8Zy>~9mzPRDnmiw}7O6Q~z8axt_S+OZYHVtxC3ITrNaA(V>LBhx<~e)t?= z)4m#Tm5z~6m+?^a7)g7^4@1xl`W20XyN;zU1beW$gMtZnP-y3&g z()}0E%Sw;Gzn%@h>5j13pY}d4m*daQN)SImhwpM8K{b=qNqxPEUvzcFf!R~pph()s z-5rA3mOY@J_O{{KRuJ;3A3JA6-5H9?xMh2`?1ouaIg8#Ve5AspJP&jV_w{Huc7qUcPM@E0o(0!`Tw-IEHS%NH!Nh{jWNou(CfPUz z6E|sqZxXTP6TRT}=X7>qWE-!#sgJWYwu&a4JRTdIFwcc{Y1Bbey?zBeexbrT1kesE za6Kwq{wpjzs?A#hrb0_?9&@T~;o9TqypgN0?JJz6Wv8d$ZEZgoI$Dn#P4|PnD~7T+ zca)`?Vq;AC5+ak+%>3qw6ONpA99BQE;w|dc;N3f~zHSV8_QtG7*N_63;;hSa_D_eh z!B*_@Ny^Vgnn@7L=|GVYf*yO8Bq~zddw@ zaci~tu|rv)6+MOZjJ4x)N{e7}SpCU&cj*qEkb`Rnm%?2iJ^pM_KbTVI#|}5DN&6Js z@y=0qq11ai9~4&zx6Z7P2PWC@;664G{_=v@WGYuS)|72EGmE@PbRY!)FtZgHUkar7>Q@8PvpU%65J*&fv0T-{99RK zd-kd|T1{F$LclaTD`7`31No!}0qq+8y5r=@taQTdLB`OkOnX4>r7*sAAoC^P{-7T7 zQHJ+rk7>5AmzUt>Sr)jyuRH%ln$nWv8ca^l zCJmZX@!0XP&^1?|<9mPT-{8f%yi%8z_34D4H|R|T72m=RN}7u?S< zV!eM+SMqiNms(vC#)NC|S`Q64_$QmCRJlm2ZtceD2PyZNkms}+`SGGkIFGk$4n z7R-IVN4(0MB`vR9Olay3LmYMa+L`^p)+v)^xV3W2k#-pL_ly|tO#Puni2bId!05rc z+^a$l`n1}y8#9OnC+)_X)jx!9W5}09`RM=WXV0GS=3~-V!^Zp(Vk+tOhvIUvr&|JO zMC{tPMsRFtaFhJtoGoW zDY+1Nh4Sh5vtapCTekBr%~XdtfzIn^@|G5Ua^#Agi=0e z)Nt&zMh7-(5-V~_=l0oNV~&EtKkcBkqY_}* z>9H*NQwz@;_;AQ(w&hMM4)oAE+IXJwu% z%Z1Z=c`R=NaoyjfV*CPEHl!ov$X1qO1E+qpH9GuHhxqo{{?Z5~DJ>xoC#TE`?m~L_ zM7I$bey9ez{G%*9xI*-9O$J-(nOAkiQ}1pGF9I}q+>9mdJ%eqwE>c)!HEvk9L0C!e z#5a3q!j!ic7$!IJH_v5w`${G&%6FDL5~t(YhZ=B_c-kN5bcavUbQbmfA2-i6#QR^i zh?#eY&+PAt5eul}xq^D$i3g?RsLKA|NArANH3s%<6-*y%@jo4>wf7AEm_?q3BP#$S~M5ZXvx*yColdomTy&^ft37Y8OD5RBqfat&gY_4cU8#fr^ln8M#9^yP3+01@7&(l3bS6tv5xc}={dL;+J6Xw zkvUp?{yZHJl0(>Dn(e)k_TaWIE+F*Q=ABk$!y%g~EG&h32hJv7bZBLL_Ag?`-OWYY zjis<}jV_=1Is)!{`LS0)>e8oK-Ec-<522~UbiT=?7@l7xJ?C3j-Z#P-`tH3YmR>o{ zQxw8+`R_l%fTfyzL^I7%)DM2gRZW`Mnu6y){Fd!mLp<2nJoL=%ja7!me5L(R7#?rR zZqW|w>%ZZsee9G_@l2CjZ?J)RkBis?{+s9bX$AW(wBb@4{XrOdVgAhin1%w#5$PJ8=vgn4TG-famQgD;bad5R!;Y_UI+H#!IQa=?nrsM(K+qCR6WSQ zcdvXU-n_O$m_b~-d3#e}DIRARTTk-v9_sk0Y#A%==`8*GI1=yH>43r&@OM3JygU+uvCu@($;lq?Pvbk>aKFt zb328-J3FzMdxpG9p%_dy9TMLg5$C*hCH5WU32*3q5n?n3Miq}?Ge-U4FLwK)&GUES z71CQA4~;^Hh9r2btH;wSyF!Sz3k#f2-6e7EcyH}Op$n*Sg$+gReB;!F7H+GUhKbCT z{iDxU`nM9Vn2!dhHp(asO@P_KJ=ufBN|MU9Aaqii9o%g)oin#bq4co^x^*??{r9`W zf*+b}VYQP~v)CPP>E9L{42bzNe@XjnzlE|V9`=-pXx<=PRnX>_H>Ja_3ujo3e1Tlhu+Z`LuZkzSYr$WBWDuhMC@Qd;T=?pS1GzPdeh08C%4hyG~MAojcAwG!at5 z^my@uQb;gYWl@nX(mTr8WwBOa3Gtj~P^P1Lb{;$anAr8DVQAy0%6H2QA&5X{p54~~YAp_XisL3xi z>%!k*YAEIh2ZKjG%}YhP?YjLuM^4}0P^|nS7oJcz zP4LBR%6X@;1=J(?(kT(YZ>g-`P3M4*M?UVjR0_9=qqS_+05G}g$2NPbNqqu5G0@Rn zSbBRJZ@9VyzT8_O=WD-l)wRvANpm$Do7}+f^bbd$jV(g;8%@4wUN)?@31ji*f zX3mzh!RK5V%ekP+r#TkErdg9&$5YCZW%?YPaK%`x?N1#{-Bw|F&!v!JrO&TLB!QE$ zIn$n@CdFP3!HIjU1m`dM^1W|^+UNPtlyPp(@M!nm51>4qxX&G55u5mZ7h-E{UJiRd zk|$@rn)Fo2#K_(EWeWF+k-L2rVZb}#^_WiFlkT2V*8UQ2l7=&0Hv^TU>xAD(p75)F z@Kj?J8y-cO0_|>){%oGu@`Sq5Bzh({18g5_#3z_k!oV%3#6k1v&pf6EHRicPNsf|K zx?>=IzICo{XM?kJA(@`T0g0g4QJ>eH>k0qXd68zTF1d4STpueF^hcV?J?lHQpY!|w zdhp>R4njg(uK0Dgixj`S24nh+g3NFoe)VYvba>f|h0yQrjAabEOwbVmK2px8Is73X0>4T5c+=LOtH(qFW zNKhBe*&$}cJ4{{-Mu|Jc5%kP7y65BB+1~K@y$=6t-@kpfPkGSF?WQ>3^&4l!G&*yN zJwq|`PYQH>rq6pC8pHigUD}j*Q#NY3@%dVF01ffr=7yndK0d2cM3!nifp?X>Cg31 zuuSoxI5&;-(p#hO&leqdpQOpVyV|zrtrDmk-HsS^-XXbSY=EoOxL_X&onApzu_hnt zkPQxReuzqfi&R2+&lM+?;PzMg=lXF_6t$Six;F8}Gd)pHK9yyUrhZ}hD72*hpl-Ir zd+%lsy|?#c6DvAMX~e|tnVT*1|JPMMbmMN}L_bTGIo*Jld?Nmn-$C)cF?G77l%b3` zL6aY7^InN#+cUPOU0e8-3w~&C_)g3lPF(lcczmfd9$IvC`Q}xQ;GpKr4pYByk8j(B*89x*0$1M|1M0L86DDi&U9ZhTkVqS5AN~H!2?o!M4FH4V0w$ zF)|FkGb?z-O!C$)jK`k#8zDASlQ&t}!_Fq+NbGWw?ix_eG3vH3tPgQ`-Y*5=MpqUd z^yM}X?d<9mKp6LH~B5bkKf}dc$pTj^T>cN zo_S0`)0mGfo&w!#ZA9Polo5L}3*9gJfnlRIuYb`4M(&DcgXuh3F|`wpOYJRdQ=y&9 z6i*!S>o~YSB|r0lmCzVHqh71fMbdw{5&P>E!XhhTG`Y+Kr-n{UMmdfN^9yjo_X9$I zA9eXy%`o9rP(HJ>ZshZ}+u&pKJ!}Z=2|x+(19 zE+uJuX%aSTR@HBzd+6-d1!$(b5{mP6c=3$^@F&!lMGNY5XYoe&S`T67p=o?&$uiLT zxI+Ha+>9SQZ4EXylBm%r@n`wr*f-#}uwVwwDvo)ua$h*Jr!)V`@HDI|YLV5~l7{0} zh@~!}SpJ%3s-45Yr^uLCeAG?m9*=u%8iZ;U;tVTvfe-zPnd#zYzW1Oae!U`N-*naZ ztM$dOZ}b%AtKUI-9yT8vlT1X%X!38bE5pSzmqM)EfH>``kgd^)^_oe2OiiH}@RBr~ z83yuMw*_Irf5Vw~kQwh*;SGBlE{nDIh&u|Nm?s*;vRLA+nUqjwKZ+^&s7bZVy^U%lM6~Iyf9;BLD3Dlb;GO zpsdOOHuoWA*h4(A(`A6Dam1PIUk>(Ka?zIVhJ&AO#B-P3!K;DvXSZlPweWnMV5wI&gCHtBO!E^GJa{4`aUQkQhbz5X&mBfwPtz93qN&fr~mjq=k^1JHjfu2PU`x7ANWjDew{hq6kViqh<-F3J9=jRcGe$8nLw2^Fd1HPHn8 z-`lg}GtY3<@dHp(zFasTtHza0v)cOy&9prE?p4vuw}o(~v<368q( z>X-(9uh9iAJ5OYp_uKfsU#d7rF;`5~a+O}HAHb%yufVvJ_Gt9~Nt@X$TI!M~A*UP% zeOH2y6Lt6y`y@E|Bb(Vn6R%PB!OqFk*!4b?(H=eqD@+4nWTZCV=jRBY`b4nc`^wTT zA1$2GmL;=O?J6&}*wa4Se<`7^qQS**aPk4s#l%JGd#fD1A9;e#D9Z0VO@tv664>=H z;;Ft#gpmGvqR#}%X6lT^$;soPwpo*F>UM=^`3@}hnx-`Qw;}#=j27x|XmUSs1ymkb z#tfI~a%pTKeCg3!JnKaMu~+3d^u=gsIH$wUcN-6DuLZI9PD+wPDB#_eS-}c4^L+6h zi)LdtLdkYw6J?N(y_*V?(|y@`TX)p2ye%}VYV-285?C_Fg_RAYGudu4b}FwCHcv3+ z%Jj2R+IE+H8D+_v9xQ;Yr&~pf3i4y;%th5HnjnD&U)9AQ=JlDzO27Q$0RzpjY06gd z0DY&vo$HPxohE@em$GupRzdJ>6;?OgMH=t68MCMhERghp#{M&*rZYMzRz5x#~ zsDv$#=hWYz@9fKAn=w1A5Mo{Rc*MsA;FMy+=H4e={aGPq_#YJXW~s{y%ff{{yYktK zevN$VR$J_mwueonyRCvPbsOm$!k^>X{6QP}0gp^z{mdG8%Zy08GA>uPtC4=@Y%?Ad z74g&)ecmuD6M|+piEBxFtomDsnYUD-(1JK!iG!i?<0dv>4c!yH>`^Byo}HrebD(!W z?6oTx4vp2~<5y8OkcF_{^)AwDl>?aK;tIt-HTc6HIqiI7!!#u+BPtm$wN}=*{&beq zn<;xpK9cbbI=n133QDf}vc+B1r60TKo_N|rn4LY1#}fP6ylI7evx6BQXKD*)M@ph) z0_UBo!!c;bFCnL!7N2LI2m8DCWt)kanVm2dkDmM^bKT$~jb2=Y8N}c)zGcXZU&X@Q z9mec3?R~yH8iS{k8-#Efag4`wg(KUG*`l^z{6)Ajx>d?pnT{d<6IKbeI~Fs$6&<9m z*^4kGz*Kxh@An4n3Y=KG6oQT$aP_iD^xV?>m%R4_4f>*-I4e(1K34X;_v;Vpsl_b-QA*lY}`MRg1jcmI-7fs(Mf}16= zSepXjVrO@ze@tD{h_gqxeu8jaW-d1;*IM8|>KPwRXOzY!$QeFW!<3oOdIlQ8uvqQ z`^!RKdN!6C8iJW+E}LvF=iA1I<3w#Y;azl)eC?7W?Rt*GbIO9nXTrRBTf{e4Xs=ga zgnlYMFrR!%p&z2#^_=mK|8o65&iHoQS@EVfc^K|TV3+9=Aend_ZVl!za=ZiUG4M3c z{yqRDx8;I^q8g9*MA@H7dF92dE74fT2+G_I8H1F?G zuw_w{(L3;|0$FQr zaR$D53eyW$kp6^d;Lprlakqi1w13q>l5 zh=1B-774>Vi8(W>w0+JG=|bJR zenrssH$+snBAua6B_4E*hpm(!uTC5X3&b8QgDXk>14Gbb>YU(e@~2(8Fb>ZYZ3NW~ zMm&@llMmi#G8u8R_uKel=epa%63Q&xeY_HSWx29ml&$N&atoT@t`P!#yYP(GQdk`P zfmx^<@%i=B;k(azv0xSXZ@VwR7ppbF%36~LP78!-)a~BYpb*sC^!P>EOCDd@nFZXV{zNRs%vlG8oCj+1`*-@a&-sToIdk8Cs&3n++Z+=O1MKP;%zNr#@P|Z(4qP7hyoAk~Dkc1ca!n`b8Zmhn`f7RhcUx!$X%B zh7SRoReo%8n7Z`vhd(~G?7d;Z&O62^=Li&88UqaYA zZSHoW0Aefqv1#PbvAZ-4i-kY3?z987S6D*z7on(1_sWQs)P=oLmz^F-I@r2#IHtZq z(7LF})0-TjctkOC^7zGj9O{52T___=eb6f(l|gFO0yZn#n(wz=4Jx+2^<7C17gki_ z*MCc)`lBA-(l!ygvH0z# zlVlo3Y$Zh#NJ!A-_m7l8L-J5&KA8A*W!X3}>w&C^cqxW$m1sl#rcb8maEH&yuzLIp z@lQ2rq#+CNMAwtTiKX;Q7LW?|Hlt zHVwWkDv@?w|7;7Y&+>qSJ(Q){9x-_I%!RrV^3UY&TYw|u$3c*xCiff@2%1-2m@GwI z8f4&r=XC_(;|+894HpMt-w|`x^2?a7Kd=sl|2JOjOz-qt9k$}IS#i+kGtCl_^I>4W z5SC1y%xs&{sNYvt$e{Vt;@tx5xMwx2TV=z$q{hJY`<>WhH)m<)u}EB=dRd4x(&WE; z8Nt=qTvmA3kbh2D4O6PJWp1i6`S{bvgwO~J7K2`V_^$P!`{$x~lb)GcdS)_)(wTom zn|CvdZuj9I>eI@FMi;c!KPTRz^KHfRNX*zX0q(8P<^D$I?Q{MLl{4Hsa1i!Cy9ZVh@BRcuINKs3R@kA4`fvCI6#C<4?)`??Jok`!*^}>>u zin0%Lh^1pp*{Df-;E}aHU&Sn-|4RiHn^;FYqEKw1xo5#4>g;%u2Yu>onL#Y&yyjKn z$G zdqlkDLS7?z6;5B|1Xm93Bi~kz8C8gDPJFvjFunAL&jTTNG|t+ zsGn|ZH~AzLtNd}%xkZ9Xs20Dpe8c z)0B38jv{%6qlWaxPr0*$OKETQH7^-sE^h>Vj_c|F{V7JlBQX`?>VJKQi^P)s7UsfcA+7n(9}@MULoCAuS?mo_nsenXX|&q@87>39`A>T z_kEvx&U2nFqWAUZ1hl%O4#!EmWpvO3Zcw_t%fWvC?!& zw6%2&{2<+I&x7$W@1hxN{AevD9Ld7ms|SQxi&UGuqW$HWX`#bD^QSXml)Q$zJW`+K6u9 zBHn!V^(;K)rwV8Fw7B#z1Ue~}Ge_B1E;RMVJxixDEz&BiiWr5zO=MuFN%MA@35?hD zV!;lKH?!erH>F7!aQ{9PaB|tT;|W^i7rvB*l9&gVW2o!x#aKAp zZ4mo?QdRmnZHOGtQSCU7*Vp99cl&`+=Dg>kesJg5S#ieq6a4(8QP_ce_%>GRJUBH2 zI#2asWlgHm!N5g$@ckcII$;huk=c08z#9$Sbot8d!9XDJoek#_u~fEmpz*=`hXXRS3_?fdh4OSf{sU{O-ps&|K`?_&kQ5&!1bc+BpZN zEu%f^>nyq7>Rgtpl$Gg^nuX@V^q~e#F=~FqpOf!+swEF`^aabb`{Eqxl8${q&ySN4 zJbA6d3rjY`H?wi9i;1dan2{=<^Rqt?4mN))-qkk4yV(Z($K-`Ddi7f|w$fV4{+od3 zW*!%2lYhj}T!5xo8`&nuHh$oS5y?45v2rEKq*WY@F6jt27Ix0 zsm4_zb$;k7O2>4@~@Hg=$YSMnvKVHxxf@hZ62jD4%F?FnE8=E z{P<-%yr+0toI!i?K*u07wVDYViPPLW+YF}swq(U8PH??zfjDqujxchsGQamN1xnYa zvBdly{NoqW3;27BWuza-s?WxE4%6Vz8!fKMLSgdYNo*47vOb=4L6u+y*~!V2DLOs~ zTS|9Cpe3IlFwgg+D&;f(A;y!j)nT zUh*Ltw$$xoD@^tHi~WZ(0l{MSR#V^lj?K{#tkD zH%jy1uEtR@jIZ%MnWGH$KmGrX0gJ%lkz-c>&vMUWrz;C!cnjiMk7;ph!!P ztF$>oUa%eW{cRxiA47hnx-enwJxy*>nGY*BuV?P$4gaQ18B{Yo#3<5{whb-BmkMEU zgnA4YoS6;2ePnF=b_HpOyAK9DU*_JE@b+CpW@55h1>7$(~O8psDGsW0%kTZ@)gc^5rhJ&(m5u+#ZCzO7tN% zT7z$U&;`2mk7k$SOt_j-1+=fekBscK) z>AvW!)JQy|25-N-241$#Vc}1m_)5zP=z8tSaW~rimJG}h>IuHtI0&uJ{U!~MCjU;_PUX1a z?5JxCzkJFC@%s_k@Rv5y@7FoFdaXBZOfuk8KZU{LPe!adnr41m3}z2&7QS55;QLnC z!Lt2Xtl988A2?ABH_eu@Iz<(p9<&aWyymchh5h;U3p+t{_HEphMEbE+h1f4C2i62@ z^Qr1_5aMaVZqiOGZ3w{6hs=c(Bi*Kif8KK5w!!u@-#x?#vnE!u@o)P|5%Y)QW* zZA^{!KFCu@}mqRsXbDMVi<{ z&uY-8yFE1hQjjckCt~dHvki9lsUtEq3GH7;!er_oHq#vrm*WPotIcYX>0WER`%@4) z^)zlOZS5`BWTx1g@mSSrm_2=-c=jq`n7TVKFmwv2CTQ@lvsZ!H8)WM@5g&148irrh z7Ec%hEIYb?_1X*Tx&)&q^2O>`~^W=4tSgx+z~Q zcHt{3t6<*c$zmxzlRxd(;i$@Ku{v^cH@^o;tH==J$F|c}>C5 zkbis+dv{%j$Lmjq+YNWbKQqV!`)L-MJ=O+W!vF98*B=bm&S7aW9i-X)b+ADxUCirk zE9HA0!J`XaKyiTv&$P&d{Vu=6g}Yj~Va7l-`nE-Q{FOZZesh2gp^l!PgZR#c*^qzc zu!w}W{IQ6|1$|wiQ?nL-P5DD>`~q0fA|=V`oB=kOrpl_~teeb^92S17cW0JGJ-F}q zZSu^t>cKXW?am@RZ|(%v%9{KtVH>fjrOQ;V|VoTnGLu9qxtzbAAF`OvEpUqi*&9< z?|=^AN!{g7-X}tYl)*xb`txFiJXrq7RZMTNmP}41;|lY^5S*aJ$8GbHYcg#YD@y;F z^}=ceFIha{;lG32ag=TYRA_bPzZ=V-q%5&<`WCuVM%UsC-?h-Mg?y~k=leguRV2-P z>%?_f9ePl>{8*)_?e-|S_WqKC1wTZ;#n4~RM8Su+iJ}m+JgX07q?!C;WCmyQquKc; zV?M6B0xJKty5Cc_mCRTzmhDr($&J+S7M22rGd_z4Ol+iQ73)y#fGRBPrp*J}C&2lt z3N~ZuSFU)>273+;V=*-Id)J1b=VsdTpO8MGq#O7bdb5*aBUdf+#~$05&|OoVD_>m$ z?Ur#Yoib6CN~*vq`r7d|gbjM`TZhkvZG_5!+Pr)3iLi6rASQiPl~kU&JawJCGbSzV6d zE3H-LFBNj-+I#y+l!0uq0Y-N1+xUj~6hHF5IkFu1N?dl|*7@M6YRYV%sY;!rY4@9L zAv{acYwGJdLXPJQ&HBt`K_>X)Y$Z!2{Z&U@cP!m#1VNv4xUOp<P5_X$w8g$P=oUf|j9$u(5{;U%es( zLd`m}f+5tAv^E5dtu6`{#PRWET_Lw1ot3mnyaGn!qXYKB;$vF;dO|i#9#37O#Ah-0 zba+xxBdYf#O?cfpw3Q8jx3nwnO&=%s*p?Xo<#EgbJt|I%MKejOb2r#JpgOcyM7D)XBQ(;%1b@z{UAdHshd-1f+sB$zgL3QO&wC^hvSB;WJ9XOl7?K*2cPmG41(&%1-i`f5TZx zs()#K#~-H1+Uxo@X~fnGeq|PH*1PWfgnl{n7<*cLPk6ODlwis_C+I_d)s#+iU|&Nx z3t#b@A3g0!`k6Q4pJdvZXU@R^gg-h`FVd0^gCWAXKRZeu!12=rG@X_xd`Zycqt0xG z_LJ+`k+VAd+NE5Gtnd-v3@7h%{}LQ@Jq*qdq0Zdw`LO1+jOCC%%6_gto@!m;UQfE0 z>+9zrUr+&_@g{uMeS{-DbXe7^zEVt@fTg!?2=m`)au?YaIBRXkvSO*Pp`s4;j4K2S zN74+;&4MqQx7pg^-FS#aI`|vy5G@W_OW({>QEPz)RGcGzf43jJPhZJy^MCyI#~yfo zP_?*Gm$WPU$TPBWHW*%|K3vN!up~v99geq=;t$s0%e5Wgf<*fNXNhvZl~I0A?ozQ9 zwj8w=TN=rW-76LM(oLfCRGYtP^@C*7P*%5JQ7Vb+gF2hMWcGHH5qep`XHE^^SZ~Oe z9oYu`HYPUiIZV9CyE@!ovKCsXyJ5a{vb?YGK5m72OA3=nefrZOzj zXHh$FP!eWA6F965bEF(TbDDxBU!`7K40pkr7C%PsxNmo)Xmgz_-vMSjCsKA{+N zSq5+DJ2elmfGQ7fwjjBMFMUAh>%G&$H?GQKkFJJWTV}H8c4uzuR1HO!uN~L1A|IUL zdURj55lZf8lLl`J+@3X<*>_Nrw2S~V%j|{6yXW!Y+qS@p8|$0a{50lo1N%XP-U)HO zlC9MK<0yvEo+MGm-LVH*@P|BuOYW*l=OR{O@VI}nmebVnTDBfl{(7S);RXjkMZl1O zM(hA#`1a0oaNpi$>b%zCk)*%P9hbw#PiW)kcWB@%HyLwZr^IjeCS5`9Y1H&qP@5E92sVjZGB z^AICbbb3_D))5EvXRUyayNn=bp)OxyR1CMQCa|SlRVAjk8ZXw}mBpyrO8BS*kG?cR z9}h!5`sPZwedxV-_c+Z-t5j6-Z4`Qvjw|e}AJl4XW-nK^al1W~t*RBs78}wtd`Q5f zeLbLLq#jRED1rNWlIYb!88UzCaLhe>D01w{Ge)ij#V&u2<I2k7zx zyGFniPiGdkSxri;vBTzGAOv}vH2tZjjB3h8j#^;C15Q_gLrSc8&)Nn9SvO~^_i#d|1y(9(Pi#M zVSSW3|MkucM%kq^A>}B)bCr0ILw$t7G!wpTTMu2QzhTdPyYQn!*TJJh`@~EI(waVA zk27-yK-~)szG1{f`JUhJGtHj?&Y05kw3tQM%Sy%ZsPbth1dh<=;pF%1Hr9%*ZV-8g z(m*_WAXBIuq|7USr_1;J={J7y;neLin>x!DkjK{J=X$*37XhlvwRyt)si5&|GTUpV zC>hrcMU5f_*}i%7Tb7MSWuM(JW1u--rZWKc^wehK4;|)H-uYl|e?6!_*NGq7oe6h3 z_GHKWY$OxUQfzVEDIA~<`cc#?^e1LN`84};w>_)D{F)N;Ce7y^zj;_B=s?m}b*|*; zB%k>cirV>=iTbF#Jx$cxCGv$0fq3&S&6gcIeE+`nFx{miOQx)(fY4I%KPo|l0_~Hb z^P%lnDyyFGh5x54;H$Zm3ATuQ982e+QKc(vdaT92S_}lo{{mQ|hmz#6&X{6tQ)Mr@ z+BAvj#{|6*J=iST8D>l@1NA#6MJL*s&s3M_QKcR zZ^WSqG#hp1<6g&TI6_!KjlvM<8s3jZ9Ox_kxQb{rFHzX8OEY=X7CE-_@3J1(wA=`< zTZfDHJZz+xEu}cQZ#WDK)a3d_^Wb*^_3S7qO8vVA;F_Wp?k2UQnfITMrTZ(ODA<%o zLDFaB|}f0no=p;`>>PFmt14-9@e z8-CF~yfd{3zUQklrxMbBhwQ?<`yD_czxJ;ENzj&_&iq1LD8H@{(i}a-+>7LE&P~Jl z2L^*8@dYvEBd9-NEYm!wD9M&sV_B=0>>%y=R!1F%{mg#zSCnA1P!|^X4CJ> z?#g&%<^~XYiL!L!E#!IltH(5RrSNfB!7^ksI@?Mv7k1%PXGOGGug!N=q(Q*5&tjL} zHqyKJ4H(c%4H6Btc=*T3@ZfnltNZ;MAC1R9$^w*BY4LLEjxjX! zWtWdPaF@Fyv39g5cz#jg-AvX%&ypCX+?TWg(h?k)T-0dMm2_(hH{ht+jWG9+7GL*n z3QTq!#7=!zm16BYF!qAIaN)!}er;_bv}$f>vYurmIShBSarXmS7*{J}lO<(tQMUnf`^{yEggZ?(UJoBjtQt?ycb)U0 z6psyG2QwdN^Cb$4<-F~o`Kpqe;TW74Y9XxLN_+mtQ9|Y4iEMS?XFlb5S5)gz#i9v& zk@|b!c;e1)Sm^TIY9(N=GlA7qP(SRsHTdW4J=reOb+=6|!^JM$aP&nz?xeQ@4x7CZ zKb;|6Vm5W;ZEh6O%C-5e{Ucz)-vY)Ted8Vu=GeV?6q`iPXFqyA-$i*)jw^AjNnVUFc=z04`S*q$sa&^r$-55J`Uaz6adB9`_3QxXd_tWsVH4qKVmxcI`on*XA)Uk8 z)8c{o^qe?_wljCg0y0yZU;cE}+M z@!CgMXrepUc7rP{xG_N{)fX+7Tzcw7AHK_~Z_&oBq zxUzz2ic-hcK#Z(g>Hc{ybyq1a!n5xxU?1u9{3-kQf4lv1+U+Nn4Z~LNn}TXAUD_+|se^$ZF zJA2FQXl73D>V*Ru8=%i4L(0&ogs%gV8vjc49{IH!PxsD*Hqya*H>X04x;gu*N&5WD zd3eR=kT6JFt;x}KoP5q-n){i*RGO%d2VQ0ne>UbXaf$EX? zDgJ!J&d!v@*Ea*ZEhc@%UtRuvToCx~abYLsDN6@V*kNBwH=%KlNt1D-qu{)(3mf&o znD_s$TE5#4ymXR(tMfyTKOG>uowA0Or@+w_9&GtVRcUjVSnTjxM}VQE@AAq(Rih$s z{a+_t^Jq9yq{A!;V^3Q;39CO|6o%RmF52D$#@lDGo$mFd85oWiJNFhmH|g_D&iN3O z`H^i(HsJ3v{(t6=Bu~xYUwQc4W+14As`H9_6JhtAm2A(*Km2g7f%uA_7Qf_C_V}eq z=)8Fryff6{w{voF0*s2dc%Vq=&(jgh^~(fTE;X;Evt@D99EcC4Fqi$ryQMH>mIE%zX#-hnHn4 z?4v_HuUIo2N50krg>*G8J-TpSiw&CcrI|VO+a)~c5fWoZ@SW!_wZf~;& z)?8C$0d<6n{$7YPcI!Y`2kKPqFhD-@r`ELdITsA6Cp}HP`MI7ehmAndX&J=GbojPY z8^Fr6BlAqA9A>|5SaDeihE-{B+m`v@zbA!#5Btii9cf>>zkpphM*rt}i*VEsHyA}& z`fZiL;2ajf92*p+3FEq;&iNEsM3zmHg1IPM9Mh8-QGWGb>jE&+t{1Js3C}4l$7>6n zq5hgWUsX$fRmx0D+iu9WRmZ`jTn*8PIM9)KOE7>q>0t7#6l;3psybA-Khv0BNXvz%^Y5@8KMc6rog_GSrc``#mb`)fF zk=~N>{Qph)D#|?R2A{bJi?^%6tUP`GjdrEOhj*|Y_Fws|K~DI^Ae;@Sd)D7$DqhJK zp!^K+M9zI+$R1y2XhNLnl}YHf<&2Qpi)Q$v^$;+45o=9RlI+`7;^_s&jXlU4_4~7})IV|K`8(&bQhueGwcF$gk*G@5!niZ$bEQ+I=Nk1OIv@|LbyvKP~u9pEf!$p5RIf$`248sb&RC%bYrUOq4bbjV-h ztsD%s(_9z@pGs$J9B^8_n*d{tn|u~K3C&)F;RFukWv=I-w|kDbHtr;UrZ|GK&N{$9 z+UIw*r^S*AOu9{_a_&}P zS%e0Msa7y+Z3Y{txjsjixYVXT`Di+4 zAcVMR^7|X6LD1|(HvF|IUv(sc^dsLJM-wl}zlGs{w`Res1=L}!*avnW?8ypNNPM%# z1k~|aC)^2C=Vq}k#?Jv!TI6YQ*)E?%fR%qRcw$CG20g4#4~{=<4Bc#0jE^Eeyn6D3ugGg5|Gbno{) zw^;7C8tc`KN32-|Dr1X96XF^oE0$sVLN{n3ETzbAD6ISD&)nxKNycZop+Zxt?0$f4 z)BV*=LS~pHJ4Kv@yX_{q_I??8mr|7~vBw@~_^wYFi~Uk~`fVEfIoFVHIW|{5=a+A= zmfBsGV`~2x2(i`UTS+74U(ui4pe%w@v=4mzlqhJ_DDgkWo8avJwan+cJ}-0J0@=wU zMSapwK2)#7i12B!ZLS8Nr?Uhm*t@ZtJryMv;sn1vU+KPuFw9;HmSgwGO6WSrm=`|s zgEwciS?TA#Qu8@KR6BW7C?KvUXm}}{OR{ISN=;nW#~0V?4-t5ZB{x`B3{OYAWfx^8 z{Qg7Aps1-7rR(IiKfDG@LNwtzX(ksd2f^XfE10+YKi;_58lx+!#Ud-pdr=*Zi)!Lv zE^+tQ)|JBMN>vt^(aarQj6|pQO@dC2D!-GN3`-ZLvO#yO`QN4a&~5)U`S18<|&hHSe{=W?Tvt3BjxGx{yJv}7skf}C(4W1}0HeJomMSkX**PJjRb`Lv1 zy#Kgs;W+b{0cg$E;OAENmTT{;a+oATc3pE<5rsa{WN*m>^^d? zcBihb^xdNg*T?mTfEZOC&^sHB?4HF^`zlMn+!As0iju}-q{X^^E*~Gw+XPRSYVqLN z#2M0V@8YQ@-PHEOLw6j6P6K@TwfSkV^~n4tL&^|%zSbGkj&U*3#a42i)r1RF30Hlj z#ciJEL43d{<}*N58b2@@*IxW5b5S5{Dxm;pFZM;nuDX2P{up_#!tu2<8?BdP!OIo_ z(1DX)>#?Ohoe@-33D}y{0^sv2qNjUx&|pazGDsolwPIYLl+=ogWU2 zGKQ<9k#?^ug%YQ6%w6duKRntW->)i@EkIlPJC(TC${drw>2dpjBjHbmxNOz6s1+$qOm#fLW89qd5d1G!Q{?SphdSvLr4hBJLAk`&MH!mmrn9*%$byj zJll7mTzh|^#fWDt+5vcMmbh2@1m~ki;QJ9BU|NtS@7^;5djFwp(m*xoXX-pW@l01} zq*-CyWi7tmQUrxA`h455P%v=OWjCX(CFh&r_+)jfpj@WLCpcKb@xQ5T0k-gc9mB9! znTt?3M~^R_OT6C253F*CK5wtchR4;lVgcQQ?G*($jlAmDXb>~y%roPMysQ*Tys?jYYh$sZ3cOcPS+`(5~A1Ju=Lv-LYD z%gA>PWd_)bRYRz^=zIaXeu#wF*VH-EV+KranZ$JL6{Q2pl&c-6C{xTJAI;4OY`5M6 zZQc0^bc`YN^{rjs0X*_Y4L{ejlihmiOsc0VL z`2Z6i8gZr6#jtYxOVMs8d0@k+i_Jk7awc@*cMcAg_gnqw+CgevZi?Zl>7v5>BRtzB z2v@yW0qZRExJ|%jc(X{6^^CHSZu(T=mx;>oWwAQE9gC&IJ`kopp&(8_yr!0Ni(;fZF(qxZr+BQk`lJH@G74v-Ajh}6=f=T0A z#P>@mkD{Uqi~G1hYn>+d-@F3QHO1_KQdV(n>gd-+(`v=>rS%HCV|r$^aip9-_B5 zg<8t4JY81~k=>oxR`uijz-})r-7r81x=9?wlr2!c;u&)#?Bdd~MELQpP|UnWnkeH; zWa*l4!%d4%uN(~ulUA_X9oo6}S6h_E)`*uKNdsK#kFLMtAkaaB$JG}@u%OI-Yn|qN z)MyNI+$_Y@sq(<9DX{8nD(n1PpO?=~f!F%oMd$wrWA8(~UAKpT59Qb|JstvMyNqLw zQwg{4=ZKw#c*~B2P(JWAe_R!E9G-UX!c|jt!TsH7ji+`T<7Zrl;gF9epyjL16(*;{ z&=qFvnLTl}j+^nH=V2jsm}-;3`pLq*pw(>EHxs_mA`*=E+!qr`i{dtyI#{0?K+rn+ zzEo|%QkunP{A%G}7l-4A&ue5$J#D248V4y~Q3+2{-jQL)Ojt1So7hUXtxND`eAR<; z1T&)H-VMJGnOS`mYZYdeLXT<5+&T zKfIr+!Ye$pAtYcXJL_w~qnfuu_VdQ$o|9~(U*k68iVK?{^|m_qniBzWNiIyQT~z|& z>`otd5PI+QrA+Azc)NZ%_gA8w?I~e(H%pM9hA$=s?6xxT%g=jZ>+L|M=VUE?rRQ_IpC|lxR+s6(06pllU=guB>fFugu$x%LLlib z)-TD#Ul)p?vR#)4!#HSm(qVD2^!|#E#Fgh-1*b`ByydeMgg;DWiXJUod3zX^Hn|9m zq;H?|x&Z#0{hm1&bmrYBtcOQ?c8fzpZKP!(o3YA*Ft~Q=&MSz9(x7DaqTe5Gt?7mv zW}gvXkrrja=}7FH7z^(Uba@o%8+{x5uz>RixM#x%3_qVLhz%P2%<~O!EH0Zh%BX8Y zwg$>$?ZxUy8)-$@W=t729iIH8e6XBo&{{o(d08k)W}03Y5}+iTbcl3x4LS@KVqQQU6T?XwIsq8>^bG|w$2{tb-5wEw>?v3#{NZlR2oYdxS znE)#W1TjflNt!8I;M>)yGTx_OQ`(M`!msOAY_b>4(w;@IE99uiXbu+}R^!ImF0kyb zCa)a63g&)_WHy95bztOIdP`ompL*QF$_I8TJFrXC&8L4Z0Pi^`3DaI^b46JN^y!e# z^rv*@FD91Ay9+PGk@m@;8i)Brfb~AgefDe1=E7#lWb)<{}#Zl-v;+9|?ZooTDssX>DgIFf%QdW_NyYOBX6<2iOOTXts z?~xB#C*y&9>f}nu$!-=!+LwN$X5oxxO}IE-i{H{215ci=VCQuI@fH4d*y~NT$oo_0 zqbp@h4VnX{cPJY?q*Cssy}0u<59A@}`+2kAxL<`2)<}h}x~WY4u03xc>}bRlL45Fs zcCErJ9Og0)f zHLiHxz;y@s;09MyXbsTd1-YwX>Z@*St0mpDd0S8|@vz|WUbSiN!!RMvehvFELZ44g zr7om^Yhq#|VL@(DXkudsPbkl)*Jm3z5O**E5mWI`5M`P3AWPB+C%8RRS8ei ztc#yW+V~?M#m3>M$baXI!TZYu7Z)wQdvgp#I99Ty*9Y>vb8BF4{~h91+MU!~qcAHN z;0|RVL{;0tl;M8NdffponvcYi%k{#;ORD_A-*vDEXR~$T=G@7%P@Z+ao%X%thAo)$ zZxgguYx3E9qvake?+%@$X-NUt=iswrtbqyL7d2I8Tk%f0esDYOnpjF%AL~o< zvG2Tou<^DoKev7h%#90SgDwv>CVA@}wRp*jN zrXT@_EudL0LJxu*bkLpD; z{G=$#9*Dej;&3$B*CLd7IP)c~+o1Or%?2gXzM8Ns)O-*HLDW~foVtoqM!B#I%}&ya zwxM{-+(YonGj5t&J4BwJpwnY8?;m;vN|JKLBex~KbYlP>-qrz55LaR+tOm~(Pu5-k z6!+ifjJclIWHp4V+meUQOvUQs;&5J&LC)csl{V^$HLFm$!u4jKipFg z@ci{N;uOL_@NqQ$x)clhGIaTZNlwu4r4Q5Yet=sZ9En?wrwa2TCbgZI>A{1%Xv-)J^3sE`8Kj@r+d}y{Hf+=^>Xb35K|7P(!i@8Ve1`*Z z!Cx4=o@mH3rY?cw6P}6Ao2;d|ocg&|=)&YJlp(pq3;rc6W&Z`W^HayW;rG$$;>b&f z`OmJSG3n1T_&}QNYc#tQD?2b;L7fY(HCS?A8Oo@y{M+*sFuA>kCG_sjf6~1_;(3{< zo==~DH4(cFaR1+ zce}HXn-rzt#I1`rSGf0LU-*dSf1O3YcvPL>5+OYlQhOkYlCol{w)C`b$EbY z6}%~QVu$Em6V$N?3KnO}+9&kn>Ir3#bKwnp=w{E$H82Yz$V{0=@3! z-=8)P>hj}RUG85#h&K#Ka)qrb{u7!IJ+RQGS@i~Y6u|I4O ztd&)`*UD6gE>2-*DjfLoyM!};2XQ*_r|Os8 z+ol`Sp6|YRh~&a7xRi`b1cmH(@{n8+5TiE z?K2LAI4&?B!X9b!Z=2#E&vPhCi!$Poe=M*OELJsh7-9*Pcv7WoZBE*FxI$`3UXsP~~{ zjvT8=A-&d&zDfA>@+m>#b{DQ^9RhtLi&))%ZG47e7aXGjbVqCQNw($Gd!E4T$16y0 zN78=#$XL`QPIKao8vO7m7k*x)+?8L+a;#>wtC|!YAAy5QdI%@$b(<8&Op?!b8R_a1 z-TR<_z;>2lPx^#?L1_8U7%V7r&(w%I3o?UQ@cCo>_ckBwbb5=-)z?<)I(i2_X){On zwdComPlgAZUx{XaDaYe|HeQZp!mQ=Q`#c&0`)=m59wWc;3`=W#a3qkeB)xhEF$hzS zdBTh+EuMa=9Olns;_IMB{w{bpmd%}UbNerk5XH@~mS?oJ>q$SnsW1Bzj*zdjFZr2dOLx~zb(j^Srwa9Q*vVPAD8 zZdYsrsx#ABpOQN6vBevUeYy!f-_lLJeJlJade7qbS@2mWOJGS*gE(>+Y3Kfsm+kx@ zxPD2CpA3$Js>)=xsqQxqcm`-yPaR=plsQm23+E1+4N8H!eE3Kg*!Z{)d-<@A-~Q>1 zmF@`wkQQpC3bS!F?Z_kte0yH7s5sx1&@W<&eD zjkKzA2Yy?$TiDr!aIK|@FjnahQ;6=&okCWCli>?-&K~+qhhz*pp$nSbb@(_fA1M8` zgxwL_dEhq-{9kufu++#`-kpdKJ0!zA3oX9rdI6kR(}C%)qukxIJ8(^36-XMO!C%ix zfONu&i;i~Tc9W7IuXd|=w376-!^glQgYWC^z_l_eV*u;V5{h_YyP9fB9l_d10{r~x*3Rp8|BU@c&%7x19 zpwl{D97F&9;l{Q2c3>nd{!V%6m5E?sAY*phdvbG2;;9>o-8Rtf9lo1BKcWiQK~ui& zL?|3yr_a(Ac@M96dw}VnVg}kcH#ry84M>|M;P4j`%3GMvNIo@2`ju{7Si{ z3+TS<`Kp4tDb(1#KlOaGuQv{C%o0lVRk+8&G%$Xi!o0V-@a=!emsjK^Ix5>py(X+f zGQh~mrr`96_nd)Xu-g3urMlkhMX}S3#!URO zQwgHCQ~pxxR!Er}%=VE6Mk6Bw554Ums1w(mFs2v_-uU65p*mbWeI9HpHDqNvAXlj0_7{3}wZ;ZZgFkcLcV)mGr~W6;Mol8OumhH+Oj%>7VTy%UWrl z53R*Mz1G88;v>ASC(8Y^1O3&ctQ*tu?fV|WlI?m;-krmQbDC3_rKSbnba^sVO}Qfq zH1luyhEN%X34~oz<2ubH&~`hBrRX{G;;SOe)6kcBjvU{a5T*FBo6W61hA}iViUf1lE`Y0 zDvv#dJKv3)YIe)y`21^UBVHY_8*c826_wy5uT2QX?y3sVFjSLwx|Ip4PTtJ(EWI!0 zufU%H`of(U8%cT3I`l3eK5Q7}XC_RQ@ADt&p6U}Hiv!XpA&Ov{=B>xi$}6&gU%jZesS#pC=Kh&iqdPj*E2618W}I-WomK5%*}8@ zE0<|brktW5ly7&~Q9QKPMp`Tu;l{Ny;1O|E%H3jNf7B%QmAa%`2ado|XOv{|geOeC zOTVeUd*S@|zI>Qs2#oq_!VcRX;$uBWqo|?}Upy$IV`(AS-LYjkhv=Dcuf^jhcME?$ z+VI6@#n9*LJ=SNu0sl!@{h)tO#4|M0GHIqY|I&p8?$nA}D&HVF}0aff*i&2wQz>xA7V|)_8sDCPpGPU5xdZoi1 zi!!l4@q=y$lX3e~cW@_da0jG3Qj^iFYLt=`uhd&U^Lv{qbHDmR=sB=Mli^-7e$KlV z`g*sB4+?FhKHKUrV9fvsi`3>14N~EDMl`d$Y{!-U&l16?SQMQlf(&>>5;#=4l~Ll z;Z7vYw-HHTztx@fze2Y|Df!}imbhJcNc)U>DxTb01w(F9?hRqxoegx@2qV%KN@KCq zda+)0Z*hiJ{zmD4b8sxWX z$;G5pEjZ;t9$57W5cFX=yYT5RcQbItu(>tjr_qGr>x81rVJ^JusloM6mV>8<3X939 z=T*ymaQDtEVfPJXUR{wcpZT-S{^9$U&&2#Rb*9siItLqb(O=aSVo8rQV#{RcXEL5C zAD}$6#v%B3hmY(laa9Jkp}1*CBh1~rgI}BOjn?j+#Scf;>jmWs<))$85rW^s3>N82`A)LcpcvLJ`j9WLw*MS#ZZ?ERw$v?t zf_e#N&t%P~ckn4Cbf1oxExR9OD~IC_r`pPEU&QR=82ewKE&h{2etxlIVo z*W%BN=7HjbDrOq`mB+ks$H9N6G5xL7Q|2@Wuk}EP52P-|70z-DC-9o0)I4Y_+MG~@ zAGRv|+{N{BPPUS6+i-&ttUaF(pPMxKnz}i#q0?Y?<3Ba2-}Mj-z2_t>avs4?k#0Tf z(vqfsil4dnzW*cXJp8$Qzdv5tdzGX?X(3u@df(@&P|}bR2}LO)iD+lfQnF?5Q7Kx& zeZ9}SXzx8g?Y;NZ?|l9K0gvLo&wX95^LjmBy_nUhe7;Y!TyDR6K?d?!K%gr z*wn?9cbF>65`HDJ<$hg-&9oP2J*N=xWEY0(zkV*al z?FG*8XHqurulgNT9`#{Vk<6{$XyePo8rWnW%lqH%jt@!44)1B%`u!m>E1uV}_BCm6 zd^+uF2SkH;xdA`yrYs9GTh0bf7$7)4*O7)^^y&28#9qg#T`Ku)v5pr)Xj5pg1_Q;FXv_b3W(L z4rcw63-=>cas90MU}KcYJtW^yv4VOcl;?0|U)uAU%xCd#Q(y^k_9h3FgO3guO@1H6 z<)fxE*QR4a|CtK1Nlp=r8(eNKCRYE*jvXvj*B=u0XkpU=?@o{9rzBI^{ocXs`oC4e z9sQnCvu8r5Zj(p6!A1A?z=FL2;#;d@czM8Fh8bO9%Twa*w{C;9jSgI)Kw0J^n=;!7Z-&~J5I+1d76S%c|4Ne~D zz~)}-EesFVLVh?O5)QoM8yEJ+XG)m2dN%Ok!ZFzLIzqFfK)hfa}OUmT-iGs@KG2G$#NQ^4Wfl2X=;(zqa zfBG5AF6v95e5ED^)H%YrSI%51iMp%4nX+$@Px&e9_82%j*^l229*t8W4-zfR#8bCvPvINKssdMl!2oSEPMOi^ zy-`!7zDNgmR`n`M@FWh>|JXLkjyw64H9b-Gy#i{7Qm;LEjGbmoWBrCJfD3iI?=6h# zV>yLLwr@+t1f{96QOl7Y_;+XQo3P`guM5`AbuzIyFcN$9GKVoaQ1>F(?=-xEc zx&l_G59fmy9!AGEQ`!E;QG($DLzETgLz2fsKHy3(977uNg-=!D31Y23G1|!{?$IEh zq$X~6_l6AI%k#uFD8$XvI@%Qlt5ynJRd`R+97kBS-&ZA zP-Ufn8_g5oXk-k(-O&pNQtoo4nyJ`9J~96hJJ~3&3DBykiNlS&!L{6t=S9g8=6M2h zD0GmxuBUv>U3aD((+Wd3^ujxT4#4ku39T^y5H36Kz&@YShm$rcDAGdZf1HFC@+n2F zE@Ji%4hz466{INvOFQTMa-CuL&6s-blz)pg*>HQ8DxDiw!ske99{5~I_BL!D(>*;>2u_%e>y6T& zGH$K3hr%bUNbSw`f6M24YWCrmIkVZM7cT_=v%08qw-^kcx^a&SN-~9uNi5s3tMG6P zD9M&Dp_msk!uNJM0X8sJnJ?zP$H0aug?tuES(AeIKJEYDg+;p3l`obGJ&$|yyIpm0=9t-V=<7*w(M0lWY;$J`$p#=J{j-a#9QIhw=O(m& z%oE%@Xa1>0ws8uK8$p@MTh&mgc1(Pe-i(`5X0V=3#|7s*@-j)&TBhE7 zskt|0e0-MgWPOAE!HjmAO^V*I`r;@)cABzm{(?y?;0F^9mGqQeeLbo3Y`^AUceGwu z4<(K(#1FC)IO*vEw(*WUgxps`m;aJr{6XMqf{JYO+DIm~(-XRHraso~JDK5tLU?{r z8=b>^A@REwUrXMnGwmU4>WE81^b>W&zQjCGO6ErYRpEp`_UzATLm{4KexX8PXO`-# zKXo*Js0XcCXT&h_F8-i=*&FFtI7V~t^Yzu8GhZ0@2M78&Fx@|=#nb}wRuzV_!ic-OIHdDz?_eh{^O8`>bhv`#E7E!IYbcwvdmnV`HwfRTxI(|zJ-F(ccAOcs zg3Z5W3~J<+of}yKcm0O*rKC#_vfj&1udNq4e0reC>8;S?EAn60d!yd_c*xiKD7up_ zJ(YCGOMyCY%tjkeE}RADPOs;R^8aw7&mcBX7B5acy&qS0%wf^J*FY5Y`fVPa-)IcI{q-k9^>jdGqdB!W4yg)FS8y?@AgLG+c(BS zsktA|-aG((mA66ed_(cp4eE@L#WrNjmsZT6yU;=lXH-Px$TRYG838b;F zydBS`52*xegWkBN&>L>9)8lpn$lIW_klic4CCouJ%;;Cy>9^FoaR^Q29a%%tC_&C% z52ISM;O4R$e9!8>sL_-G=Z5bVm3~o&V|+T>{73`F57)$kg2iB{w}l69{)Nx{PIpc=hEb% z_<2hloW1;2>_un$7qMY1f%>o2h`I5K-miD6EBK+{DmX0gg@Y5T)?%VDdzcL3lE^TZHAdZ|} zw-R=4PB#4TRmZ6fp)juRSibb3lI&9ceD=1>C}IAN>9|z76GlH+D|Ng75v^VNvX`m_ z{3@?U@8`2wjpYl$=?L|Z?kj+i_AY!&lCsQEn!;4ZbQ6+q6XVyXgh8w$^KmC8{I#|4 zHlPPTeTX{gD&yI)ZzqMRXEbnVh!e!!+QB~?ea8sVnElXZ+|f-9TS_Y6y3H2e;o2Qf zJS~G6LoHj`JMy@G*~|Rpcf#9O8d#)3KB$+5Ja>t*>^=sv0qp|>Rbu1lJ@V^3=PPA@ z!gG%-*^MDp{0^NN@~js!3vK}O(lpT6z8W@fSinvHJA<#uvz^?xMlw3oT;{W}p53)I zW>;xP5PT;AUS+-(^Hu0?k&(`fill<@L>2$~E(E8~nf!C^S4<-YFY7jkA16JqaOpzk ze|ZWx8DkCvf`_$}9C# zfM2O9`1Z_JC<&d+)o4%MP!q}S_~{Cz} zca@iAMmV!jP>{@eOnUpLFsArm9~@ps+&P>Kt#!&=64i#Qjs>vaLycjV9o;LP3Zb>q zoJ%j!dwOFp)45PDXmqHd7UegOUpvVAzSG96^bIh~?t$q2j@Vq6<5@$24&3OkiC^A2 z!Al{6pLhL-Q}qY4J>RJb$7df-sCH&8Q$pdIzYeO^7Q<|&z;(%E_VU$UCbd)omn01g z+8+l)y%TuPMg!DMjD<33o!eC62m_Fuq%aSVse5=UgXd z;-LU@D2sPuLo9snu;pxzoNSWJkLg52+J@1b4;i1xB77?0=}tX#>^&c{BGvg46WV80 zda++mZwY4~D`N;{pBGIT#>c)tj{kf-n8$7qB7SM%(y|P={p~WZnBNZ--ekd^&^=-b z*P6G!FkdoT7~Jp^R+%4l%B4Ac(G za~n4q`bE02>~ood(H6?_{YnM1F-bgphXD=^NP}yNLq(nb)XAlr$qva)gdZa)FYMw2 z-CobnhMMA?^aL2P?z`wyL4ON}2o|!q z2e?w-hx*tto%`7~=Su9D;=qnS^_Of+GM9BV;4BZQBPTeB6H9Ej_)_Lvk`0d@sAIsRaOkNrj{ip* zc(;uUn9sRUg6RY&jJ%lv-@C4tKDhP~EryYvJ-UF8m{E^kmFBR^x-Wz;H0L*V6hcS6 z3!irXIIgmt&i?ARNb+3GWjeFU*t($UY`_Y7r}Q_$cbPsvMjE4)dLp~;a7w7#t%0AT zX2Ot{J9upFH+(yD0CRc(T;fPReUZVDJCxE@=jcdX!_PLGz{R~9 zsG*k7Ip@#+RhFgeu3|@9OoZIq+EUF?%R6=ZN3?60Q8a>ujjH0O9qCSb%ZoXaSN4@D zt!v>?Vbb=zP%Qg(ev||o}Y0F zC_F+{bfj*#|DEk`xPQgai=)^|tvTE~g1#f&y;-H99jKXfN5hT#L9Y0;crYHZTlReR zR6HZRU8*SC(JPX9-MiYHLwCb1ER%U!1i<$r8mMdG+v%~)PEeK&>E^)V&rcFyt%3CA zfvKHyerZE@yfdT$Y#>nl&)Hn2d0S*Fjx7N%FBMF>xDBQyPUi4YNw#ojRHvSkOwZ4g z;7k@?QwW>%bg^JaKxbcJUIuBc!y}mV*d?Kuyms5H#=+FV$voj@1umvL?9k#~!nXTb zc-^=J-e3B_hy5Fl)7Bg+6{MN|KO|` zLLTpbO6%C6=9Q45PMXQ0DR5$x1;2B&0^MsJm~ZV`!RCe>Za%-(0hfJImM;5#}f+HHlMs>Nb5X)Ggyve*Y7O}KqT4NE7|940S)z~H|qjU3Os zWYuB<>7ujq7PD6G5P12BcIzg!klI~^-!YWodbtH`@XJiWj&`8Jl{EO#HHD{p>EgiS zTfuf+f3cgPnanjJi@ma&2(vY4x8l15hIMn}Q`G2uwS5v>IBJ^2iS(BDw-&Q>I}!A* zlw*+^b^i&vBD;SO73`dtm3>e6l21Jm%Xh*mkN!M#CF!Cs%2?QwBSPkEMd{PRAVK9v zB2OP@Mt7nl813^@oL*-t)9yl9q3j;;CQ1!^oF50(+JRixpaMU7Ik1G9Y|=PYP8*&y9h@eylZ8?)$1 z1^nr&dQ=OU%bqQIDQq^=ME5;Ko#**>YOa6e=ERoWY?hP-nahgqm9roJO=lyCkv=(g z3&eKq$*pCkvaH}F7M^iRI8O|XCBK~E<)<{>c=a24dk|0Quoc2C9t_Thik1f#2>q;GcGVz4BSGj zOTL(SdfCA*d0muu-3JPTPm0<<6=jCG+3fTpP4IRjKb}<{RQYrqO`!eh-qtKuTowRr zW7Scn<_n9RNAkC+q_tjO$3U`L_|&JTwEN^~of^)w!co|C;0F91nJNya{m$1IDf5}L z6dL|$puvrF__)@QfB8-QlC3dpc$1#+k34$|A7!!s-W7tSrXKqCSqbXrbvY|Fm5HC$ zF`r(Sg%_3TIGyrqWmA&*k3;1+^t}UXziuEDDr)2A;!=RrkNnil;kd5P5eVCGQJlA& zd_LF9SyS6MxH+5hw!b4f=lt-We~=HH$<$Y$6*Jn&tN&sHdqnx=EE{7?<)i7=9I#6d` zywz7ucEr||9q6whQKp$()^{UYx?(?!C-1uAoVhSbN1J!-k)h(|KsNbgKUle)?ukE( zz%Is&->3X<>6Tnbjmeg*s2Pj*PBuWs*AM(#jxKi3iH3O>9*b4isjE6EnZ@_gg&AWs z@B}({&iPYj|M1dsb2eyZg6M0y56^XXW#5-jAEc%_j+kEv@)}(^KX3vMc{nq#_Ci7a zm^#+YPozCm0tY`+wEvX_{(tL4;R5xTWF|AUnF2%-za6g3g`oa(dHxuA+4+`{>_|tP zWYbgyoIAc0o*n5beRxR&A7&Rrv(-Vd_1sCkcyA7~%)TK!CGO&;9|=(2;>R-rNrIZkf*Js>#8&OR8wlNWH$k68`k1oJ=!g1?y)JWt*-|-(Q^+w(nCV zO!}vT(^t8}8xJ-9dpylIg(YlK{B2>fmIemzuY-M)NAc%0^EY`dVzUY+30g5)IQT#o zyi~iwhab?zYwoGQBqid}fy6hU9vMg>#Pv)R@cQR$M%EwGEIJ=>j8XrZ94lfJw@;zKwTa~)8XIz6#j{P4ztvf;jeXH zv6TGGt3G72&&3m=qJaD-KbCfSFKaa9W#8+ju(Gw&B!dcx5t_V&I8Gvb-dl!`#*^k4yOtCx&@xu?iJEY`+R zh1u{f?YH=mc0j5r70ljK4Yu4>$L7=xa6neU>oR-b&$2K${Vqj}p>wj^`HjpqZW08g zQ=iD;@h~9Ho)<3Ik2{EUS(AE1SWDh5i_l_tK6?XiGwFd^1^Liia-d}l`MdbW3f5$n z12xYyP&;4~tot&aM=Yfb&VfZtlX5gKoo1qLaW1?Yu}RwP^haFtWB{{ED&SM37xFV&~L;AI+o3h+oub|Cg@7v4+$3P&Me~DC-kvp`y#N< zx+sRw%nuvBgyp;Ug56Rz9Bx<(wrcKt+wYSYp5@DqHdIM^(+*{*{sHDcq(8eRq5cBJ zWSC|4N(>%kCd+)A%}PsAaND4c7o zHvaRdhuWuY;)sokvf^nutbp#Vk5!EDrgL5=-&l!e{s+?>X4z#09C$%`Y^Wd9uNuX_ zkk7Dx>qgd1wpu9cYap%s>eP9*{}N<{kMi$8Vl$pcS6vn}+pup&que_7kY8tY_!J-!SzRUKI1 zt)4<8>F`#c==+fInjbY7gXMNo2pMxrJVzQrN>&9^Ag$+At}5EbMZlexkzBd(FAiKX zi>=lf<9x#mm^ew~U|LobOt80X{OLQ@)tpXB`Wbw?_ z9+)910MGXm#r%58_7+vJIwgOwr7Uf@<@(Od)H_{yS$-EccJHBrsT-_e#eOKUN?==zblmJn&xy?ddys@9M|6$pZj)y&Q#-enXXV=cxP1eR9mm)j0 z8mSz4%N0{t^$cCOMSlJU*Ew*%D4h3H{)cWC&Dl%41aZr%20S&won5PrfVIs!sG(Q^ zpXMs^r+YZQnmUbrU!5aJTU0Q*G7f_MV!6NN2<-1%0E^!>i1BoG-KCYnW|s-@VX!7T zA94Ys;yK)}SzeZXV-)k=8ZSBBPXRyJmO=WJuF~5+>R2+m7?vMu6hq=p(BH*{RcBon zdJ(_EY-u7GKVHi7?h{ARKL#}X)Wo8%q%%8hWiM@l;GL+6)6kWeIhJ%brthr3A6q7i z7RFQWcEk1Eo#*+1w?<;-=hG1Sa+657MAV)$gL(SO!7Jh*jj&7v7Yl*cORRDH)H2v! zx_{yp9Wz;+?^br#q6+?b>0#|5Pw>5|&VN!qC47?~ThMx2_|lJj;8*J4b?``@HT?wb z0ezWWzbV3X@*3^8&4#$Om-#e(eN4T#6V{Ed5EZ_)qn>0mvofd>9!Aq1d@4QfDUp2j zoxd3LRl>ej*NB6|h!=Flk4;rr4O363QjcV9C)2WUW+R>`aAMQsQ-mpd)N$e!-lWn`JY-1>rP;Y`$NP!!rWky!b2h{S8}70?aXKrvgRsE zuPd+a)NKaW=;NA}wP5agPgEuE+3eL@*!k}IFm|vKelr*gJ;yBNi`z?a#x4hz;pQhP zi9~EBHWawzKppup$_;Yh$BAF!Cwfnpf2m|Ea@8PwggQEAZ-l;MD){5bFSz>JH1=L) zDW8Aze_h5~*b;FPxP__U#fcLjb^x&@FE`t!Vi3eEwi`NYYo-3-Z_$MeYNDzYEDeTgk;E!^EO3mx?GVc*xyQpwU! zc)sT#cB^+GmvrpGe+%ca%#+WBThVl{bSsA6h0c7mVk=JXHI@BNJ1E(|(p*+2tzuWV zIWfoU8aQwJ7I-0c=fW-OP_y33_6nzkpI?Zltvwgu=nlRu?HjImKZIq(G9EabvZ9&w zFlTHmm;CC50}j8evkj{BNV!btv zh)JZp`ET)$H+dkB_%WW`3+&gb;W(wb&UyYb_$1aIUBcA1S4n0Rnah^!Imm9N_Ge3& zHXa{}09PdllBXIv#ZiTYAGjTxPMGb7TjKTK|bNB+yjnw|2p-qW(#P|Z2RHDW>)AA1x9pNvfT_#7T$c=emPlJ z6%V%gvVx@JEoCQfM6#BS{os?=2Q7!phjw`_u2|ZLAvKELyXU65d!E%`&a#nuGcSsy*b6)n2s(T(wt^5>b@n|`K=&o-8qqYGj7)bVk5K6ogs z^O^J6#;&2D`(7KP5-Y)3Pm%wj{G;5OIjk(EK)B?sgu^1@ zAUq+OXPwr?TaIyH8E{9r26irB__cLnH5@7Ly3*G}(^)l_+z#wTm0zc^lErLTaO zQ_5koemALwGG+F|$zweFkfiu{Zq7HMZA&fmOYS|k;SV^yQ89Z9UQKl zD{hXK;)L88EV`x}q*hah%a?>s2Ey>!qtVis{te3eCJMwFm44X9W+hj_efpjjE}b%`m-I@cZ4Gf@a{t@MaeAr`n`1Od@J`ai8RK&x!uK+FtTx8; z)MeRk_ceuUT#sH9pLy>udi7*1^jVGA5=!^|Tz{4{XEj8{ zX<_>6{otFd&e!g3z~J&3tp0MckWS~-t1j8FDPSA7A%CpGhOIE|NMG^0BQeUTFU--~ z7OoB^HpLn`FHskvy(8_uDaWbe=_sin4J7o7KXn;%nDCPr%YjXx|2D3*e*Hl_a(6Z} zzTFchf7ix!m-FDg-4OnRybW%?)vV-2lVDULFYTBW(z%D-GtdA%&TfKBxBn9lwwTHy z45L_ptv<{xRK#T&<3J;C2@lLJ!C$8wSnm-_B`qFO{I}SXS&G?I-=cxG#IpOJKJS@k zCW~29&9+`pgRc9@Lsb$3kI&We*{6(gU+;KGyO|}n&>gwwfGBoSXEMnBR>qEN6QQAT z3ZHzm373>CWsSXLg6nYV!P!^}x&a$_wWdC9oKy@60f$<=iikZPQ_aR=4g?8m*tlR* zr{A(DT}5_e%TkscZ7r<27mne_o8i@?Y-x_=CtUt+Fq1Pc112xq! zOr;p|AI;+3UL3_S1rF@eqejW70CQQ*^cwc?nG^dvnclm>vCt>SfZw4E#TdSgU9LMV zj3lmXpRum+=+q8=Yt%P1Z8T;6YZ;$gLHRz&IG{T}s_UGY&KMs6X*d$b&jG1rCZY#Isx5 zacr>_>qQwk=_oZEW3?Qt7G(3Zn6K#DI-ZqJr=1#Qq94@yvyZy=5cFLWU&ttbH?~du zBd;hsVVlQRjL`($x_7`+M~A7V`7--o>WfTLBknr@Wvw5Ef3f;wAz5*#9DR z7Prioxcu!Yy%X;&n@6a>~DeAbJM^$L0vQ>4dj+qH2W*8f`odS4+o}$$%+=*nj@&5V$bSJ(gmZPig@!z9Ay8B;@MUG zu-~#YaJpF{wop$0)l=$#a|H;Ps);)$FMw6KE_|S}yli&u7`9Cu0A9g6flV(*E$0c`qZ%&!EqaA&Z!f#Eob?HaMkhGxyBDTnP5y~DRlEc zAPUFY(1<#|hm=$b!<5L6#Dbyk=18uxoOV5Jli24=HKM^fI@>!0vRM_YVIXNr=0A5s z)Ock+_D=(5RnKDITvLSJmo@NhOAg#Vzm2QE(ndp{9q{p+u~d!N9*wXCOcF6^16fsIX3V5~fW zt1MHNZ8@=&1&kxkVOj(>O%>rqT#j_t?oZg=+>{0FE#&5Lhf!tE64sIWRT%MC4IKhX zVbB3*uJ^qOuRBa-CuTQFJl31bHs7jc1Lnc}f^^%TsbNLz}!DKOCbJ!BUOp6DjnonX4-3{ln zK(@1^7X)OgBHz0k-W9rWnL-_=t*~b*+qX+jl$*!$q_)b*6 zNzeaI8+OvmSD4eAe1`IYV6h{If1mdir=(3}nSn0ch&(NMD=9;?+#Vj$IWQpiK<7Ds z$MkM8L-TAlD1~neQO!gTL!#@aEZi(Yv7;yB&9D>-+x|j;QLOf^~l9Ip6oVvaH9H zL^e9IyKtqQ=D@jpHl1=%vC6u5yh}Kg73=aZ=ZHlX6U_#%xFS3nZ-C=%DHr3J#ebU= z=E!H7diP_t&Rt-FDlEUzV+ zS*&k>f70IgWw1M}jnL$?79b|PUBy11>j#Ej>Uj8eDQvYc<7QIoK>T6P-U}d1${2&H zFAhQSqYr#XojxkgPlikLspG@cO!jWhb~a2$50>g{;NypGq|rw3LnR&fD{>@znUWx? z`^&k8aY%msN4>^ipU( z)gbtFpqvIaSaUVIg`@m-Nl;JJ?{~mEa$zfq1|J zUV{a9oIri4;VYTo6eDcfN?PTxdZ-(g#RLEAfjKtypk_B;oIT_Oz8>MmKG!ON+-X%@ zPRxqQl>+~$Z-tl7(mvLG|HOLI)%TR`V4wd~LC+>#G&$)D(o^a@Z3bnrcdTT`s_zH} zHcB}6Xbtf^hjAxa4NeTVXP>l(3VVs&dh2~Y$PK&Bw~~(zsF!@$kaDqVE@fNxk7351 zRl*2j4+bTLK*WJauB6j}H*D;f`i5F@*)H~5LQ`&^Ni z#aPW`+YiyqCm&#;Nigf4$^li2(4*Xe)fa1uAC|Xa%PBv0_u3#B_D%~INb+IuzQH^t zopNWMbxc-#RJi|HQTq7LI$?NYGQUDxDUXD3X!vqXjJis>;43jqIIIt+Q-}epY7cS~ zgZZ@4ML6+>1B*r<$=(~yxFFAi*&ojUBV|1tmtO>Ws$Kb^W@4qr)v-4#)Zy`Yns1w; zz$3MS|5`H&Pan*Nm={&z;`@}Jy%WPu)lY^4%PTbAHOJ=a&l!v{uA{x3cCZ;jzjd2@xFnPN(Li=b{Y~JPy*CJB6_T#VE z-`0Ye*E8PUrh#X^?T53+V|e<;8f+S9&;0qR){Sk4aQ1S0<~pz+1in!;6` z7wAYG(jz+O{GtQHu!~katQht|oK9^2EoWDTxv9)wHJC*lw1;ivHOiTGu(NY^^3qedbM*?Qz5Tk7a9vKeZ*?pS{&>0BiJqC4 ze+ro7U?7|e)xg9ptH8$8ino& zpN%eGPxsA17{iX_T@f_r6ANqSR2V4R%5xtSqJGF!cC%{_q2UuT1}|22dMu6ddSYI9 z1>9eDP#jBV?^`~*ndz&JVx~_9>)e$cxeUsKZ5!WvOpgf!|tf z)K{MYQDe>c%)&yn8#$E?&<+vKrK+OQ(^9bbx1Dzz*b~PpRY1EZh(G8#{JnKIn@ZWw z#H$+k#wr#JfB5i+q0}p8nrN)sL_*?zNh=+4%KoPUEU~anUc3KVJ>^O^s-QVPaWq-Q^Dtx zKVLh(7jY@K!*p*waawO;^2_aH$1bgewbcFkwA&)E(i_h6>1-b}D1?n%7bASUpo-n| z>f!srOuqI;51gO55Atj0i|_ZgVXluG8~sKRM!!|UA7T=yDox~$8x>?blh(1XwK2By zM$!LKe<#a#tcF3)yCZJ*@660L%p-r!lo0m(#~oqu3svkmQs1fDD@m)d?VdgRwtNWr z5_{m;{^d}${XYL`V2Q~=`yl6^RJ1(Mj?0dYV^N>01P^5m{Lp7LY<{za-?90NZ?fpS zY*H(_kw!XbTL|+c57u3Mnk}E}JAF7)_EqDkGt^&vGe+n(SpnDFPlE|!9B+Es6UV&E zg$yTCv27`3a_x%PPwM0DqNj#}bY&;U*!7sa?4o2gTmE#q#PAfovoAxK)dLP;?+Z}# zj00QqNkeQNeE{nh&SeMp^#u28+NhpX2o)Mbc_ZyiogVLIm;W3U22ECwiv8Ag@^B&q zeO&oH61pkh7jMwr`J-tZlRVak%WE|eI~+md;%e@xYK&*XPJ?UM6I(~iqquar2RkKA z2epOjxTGw%(^tQY&SqI!dziribx6}zL@ZnnGv$i7VMt#bGcW=C7G#JI9-GS2ZR42V zugQ=;Q5#o8&w#V{XK|CS$8hbF2CaT=@c#sGJnz>gnNmVIsrU?+xJ3xOxrq1Dr4Q0tf{?Q*dh7oAmL4OZd& z*>M@>`i8Slce_FVDmC1aUJj=yL)xIwj%k!G>Zst7C)>?_sEy8 zo^6VsPsKv|iPz%rSkjRaLfGOJhA@M;WCd9b(2?)S6}MEQd73>-?vg5LJYg=AS8ieE zZwIg`f60sfBNK`be-(Az%w$W(7O~8w$Akk5s7q1U0ROHO@rXZP@cjT_;d@>9^BhxI zYk3GWer^w?9Xi-!-w_z!cv|$gmEqy%OPKM(3qmY)oVl*gg2=A#j$Wa?O!m4Wws3F| zWJuI8S+)vtACKZ9oi{8D>6!7RnZMXTTGhv0Nb1{%?;NRxKL;KJ_ji6`?23K3=lQJ8 znIEmFhtuB|Lw$z}|Gnfmexba^vY*!^8?Mr9++D=7_ZGvd0{Tv+go9$CHn+S+GkH`T zTP$}~$my<)Vbf;7-Ktc&2Nj@k+*I~e(p~T%AJo^KFf7LKij|AL#u!?d4$ z`C<=S{e1%XFIK}l>M=0%d^A@XG5||8w?gSid9jxCy2Zod**VV;xI(;zJBMe&i}$9y z&Ak9+{im{!+F)VNQWboDxfI%ZZ0E*0`uJoF+6sZa2HQ4#p*{$RXL&yxK)Ig*S_dqEx*Rnw&6lFJ-WoQ|#0Y%2I=bAg zgzQXn{=M5F%w0?OO>c=Xr9}@9)n`FWyNnOb)kU*!q=)}`D$Y|N?X+VjYfYk=|3Q=X zM~fjgZUYZ@=|IW0cL5x_w7uWvt?40?(9;o8`gXJ(NrYm_2j^pFEZY;y0Q1H5> zfCslGLgbq$KE<>T>MNx~t#+~aT%LBy+Ubeq0*mZxUym*kF!>gc{y%i&iOI6A~DaG#HOs zDPOiAfSvRo3=?X!NRKLng>pl>ZI4&t{qRgkDlQ`^C+M0bL{bLTzI_t8o_gcRaD(^R5Y%?k{9Z?xsVFwFWxe z-UaFxeuztsQdeorUN-KPIxGlL$NLen@bFe8FUU8-g)Yf(vnWfv|HM>gRuIpMU<#O8 zXycpxv!K7)Y<^f(h7Dd3EMVJN!G!#%`JR=X8h(1R6?~2kM~yM?w`m-|O3$aATRKZ9SuEHt-hg{8PC&}$T~c$KPk3jIB^&XzkV8cSb`yPB zarOtHOj`r*r&WP0XD)XOYR9%N9_-+9spRJlbJ+{8dS)FxlhqQNA~h@?TpIO>U1=tp zw=kUvKhFqH4pPSaf(N+xZ0C z$d#D<()XgV4{2WqiJqLeKBHT=wb<9@m`2_)8Z)H{VoNGcSzYG;;vM zG1|E4)?tX+eNwECJcZvE2D3}4H-wMmXFG8{p8dLTrP-X$%%9#DGb>`qOsS)@+0+P# zWH!8m&dGCBsP@aqLsVwBHuPN}3^d)*IoasLNxYn#%UjGZXJ~RS0yW z9#72~FsAP|9{VI8uXUTsw6gSsB{dp2$DtZ-mwwMYZ3!Kn#nFUQxoxv^5oO|xfN5eb^ z7F@PcxNu4p6YiBmdC?AjIMskyxYe+zYLZy@j_y-Uds)Zn6;OOu4L8#{M0eC8{xxp^ zM!wz($qs{UKTk1}O@A5BOcpmnH`+h?^mT^uz0uGa-LcsTgffyNR@Pc0Y~5Zqlna=q~Q`UM^fBFH=1tVf!r-Bt<$3*zu_r zJT}Wo)c1Na@uPXsoJ#5`b6{Qf4H6W|_j2B)3My3}@RuKn&Goz- zR)5?tmiv*P*|L$$C)VXyooGi{QG5LemfR-{x}BnP z)U;;!>#WTeMpxo}@~+RUj~4zYDxkJX2E0*-=XXgDfAJ|38utzm145{qV{9oqrX#>v zi7H-y83H#)x$@bi@-oG_b313gYqO~=dqf1A;v|L1rNr(&-vrBcMz>yG-G*xe0-5Tw z!SK*U3&XY)!I4jcd3rw?J{&NWt&f{0xV~1DF7b~Pyxddx@=!gz)GZ2bq}~=cQ}&@s zK9O|<^@QjJnkaFe1$=BMZ<#?ujah4}M>M-cOwJa3cb5?RsqDbQz(7RK$I4P9Q( z2_*nv)3qtuS(t>KU+u>@*?UwGVL^Pj2g?;*C4(n<5w#vtX z(fP4_(sxtYor4){{`19xtJZpK8gdeLJ;{@9uCd0+Q)8jO_)e4yk>QKe>lhy=2VPIr za7I*Br{CW8Lpy$@9kj#&C7f~u_AmCaU(aVUC4b82QkU+O`tCe{?&d}3GT1_wvx4?G zRSdQF1k>)@`L*8P@Go^$`(#bx?>}f^@hkeK?}_J=_K(DN*;QC|b#Cj$`%P$gVV(RgOglXEk(lI$(gv+;mxRZ?;8WX4JaQ$1cHr`bB z=y5nRyJQF^iJEBC`!H-07xAO2l~{7Yo;`}$D!FuySkuEf>qs|Ycb@3t%GKF0uI-Ch zPrjO+!%JCgpX0);?c}Ncwx)CDr>A~Jg>6&V!2cuZti!6>x-PB=DBYn5CZeDsc5(Jx zihzWmB8rWuUUQL^7z2sYtJ?27{77c zgTEvnyP`$_)AM(L|Hz~J-=GFq@}^BJyxfMilh(1bBd-Y?vkfps$b@SLKQu0+d*X#f z1q@%V0Sl=H_Eg^rhvtpqIk#xG`4YuE>^2Kmw2Y*0{>_tX_#Q(wksqj+Ydbf^cGO+4 zp8XBz1}n*@+G}1R6p{~Nn?Wm19OuG}Q*TJxkah$S1uVUPK6Lo%;D!ysV0~AY*U?^e z|Hmk{KkKS6?yUwIR8NDQ590aV=qyyd;K&Z&)D@f_s$rnlK{>mA%?jEXNy|Xz`Z2Mx zfbM9|E7`Z)iEvOs9TQX{LAxW2J8vD1&rSD3*#{l*5b1Sg@1xmqt&Nl~(8iB7Ga=!q zC7_yTVVJ~S%vge28ULD18#t4fJgZ;fp;=)nK@k#)F(>1yRn5p3q%8E8M zE#h7-in2KM6)du_tHj=r_+ut9>|S;aINj30$gZAn+nTxvLo2ZVHg6VlMH}8bbw!o0 z1=LAu&i4e?;d>irb~;`nSkD`QS|*K9;r^DdrYzFZxiL_c|4E&uLn6JVAt{~r+Um%UN722n7|*&pFy(vwg8Gdcqnjwup<`;Z=0KpDMeZMaQ4zG2k!@;_#R)`7p6^wgCtx?C#0BMpCkbs(GQ zwFwqTl&N#M9I9=Uc$0ZCj&pNh-j73tl=odQzUw}?Jv4$kB~7vVGkLVihl!nt1NQu2 zArt1)^2T2UA6?i8L!D=FrK5^6w`@-qS>_^9zerxee}U|1ffU?m&z`;H9Q56t*z)68 zD<0}t#~ynO1S>jM7aYlhlKvKaK&vh;&rJuP=6p#;LKmrOMUcFsYM+T7R=y7f?U(k8HwKp=E8)e!(tts&!1Muur7}&$MTZcddp@& znK+FXeU#y<1wnER|4@JuhSQG8E@M5HeHxDKt?e*h`A+liks`XBn!?PC2E+MA72IPN zE@xnVHlWU$390O#-x9%Wdmx$|Jq1gonbPiSM`2@pg#66+HsGjD_lVy@XE2&X@BWlS zU}i^WPIeoLUl*}ZH<@H$l9gq*?xR|}689fJ>nk=*3sAUyoxEVNy6ZV|56VTO_mJHFct zLOQF`w zbfI3ty=N8*dkReW-x%Tyk3R~gXP1c{u}9GQ)=W0r>b)>%yf%Kmln=R9)A^)(C$T~5 z%AU2{kZ69Q{ibCR>z$SlpB`&t-j@&vP15CUq>b!b8N=E&It2SX4eY+tU9RWe7{eXrLX_=l#s%{!}n|P4A0BDR|u;%>VPKLz5gA=7ths`}z^M zv$hF7cf943qV#cQbRwJ>^h%sd-;sIa(^%kSePF1DuTy;B@%t@&<%ECu#L1S;?1&bp zU8}^yw#!-E;BAmg&&DZs1nM_;<&OHwvWxT5m|4dS!P{9CKOEZw@xLSa#0DLVe;5y@ z-BZPDq`f?zMZ5d4lc0sT*|rat%6<4}4=Ku4JhEfK@1i7j3QG8OeK~2CiqbnlG_O9Z zgi-D-;@!*2vWSi8Z2mYs_*2;x=SdRed)slzl-o6pfhbKCarRhCSyfFM+rN4}#Lzco z?^Ito8|^Bc`KvE&XTPk&g*W6MJG`b5_U*~yL#WgF(bHPk{d~4)NQ@Mnq70VyVmy3R zSI5y8lVOPIWbQDt7mjwzghRt}CaTS_lx3VwV@TZ0%%eIu@9`S>-gZd@`6qh?v7IyS z3N1SS^V=MQKZawtW2YjlSmD6b)%y!J%M9_I#$jNe9`NM&6-XCOL-B|eiQgJlpM7U27%V^sKWm73PF`yYf1ZeTm{)IR| zv}b28>=gErAGLL29(D`*7fM!MfcX>lwD|fpVbOgbHcGn}2piQ=^L!38jOoww zdg_sqv)^e@UtN@LlECr045QWM=T%!DuR z{ki)U(&W#bgL}@8ZKqV$qH*m!HY{ZiY^OQ@h*dFYt?SIMr*V|raAXd@a)ejJ3~|bj z0yCQfyuANVJTW{Az@S+4rssd^rC63cc?!%d(87hev*g-N+*TP5P2It8;d!BLs}klp z6+myJ4Sbyc2%PZZG(6L|+id^VQZ{O64Ksa}2~%5C(8f1Ho~u2hLmA{G%7Hd45#}EZ z#IRFm;Gs^IbgyqeJg@8z0aLGwrw6y7OT`vuKCu%Fy{LwXoeo0*?J@0NwBb#aCCu-e zOmeY`_MyLP*!B}{>_nImNN z?3m2e6?M?Gdkb`PjOMS^3NZof*;=C$Eu){*;-(lEHdDzAT&Q0@$te{yPW0ln#VWG7 z?h#D3)fQ>V=hMIu6w7q5|Cbg}(Kst^y-#A7F8*)Q#tVNw~p9C zGpFz}mOZ<)5$Y&I>iOFP+z$-m&pk7+{<8x+X}5|PMzr6VT?TF0`?&gY16)fPXWe6h zIB%5{f7X#-dW{l1>#B~Pxlw>+-h3s^!vn^wW^?;?lNb>*(~xpZR%2^nsHZN@De{8V zHc^RMSk66mt3H7n{1!3`B{yN-BqOxilLOIv+j-R;Eo8Ie z%8<-(~zO)N?GgP4x(Jbu_;;`iFJ#OcxE2!mrddCmq_M*Rv`ay8JM z{6&eM6nS`I4R)A0v+nLm!lLCGIBons*q{^3jpK}vpG<}+1G2@5q#ZrGl*R^-7uN5k zIx4CyhYho4@;KTj=5Ct8Ug$(itY0bOouUfR9j7Q=Kw4k=^$KWKZ4}iWa$M0gmw9}= zB)lA#sym`89exPPQl>b~xzSI0* z_HtFYaLbJHwi?aQ%P^a7w>HAr4#!~l{dwY5ovyN%KQh>jLE~Yo51q-;sj$4+p8lr2 za7T0&d~(g1s7m+TXHFR`tnCo=3f0Eflh?xUi)wrw#cu&;B zS=SH1$`L6X3+eeEkt1iL&7q(FF{gy3_5g@Zqb$aN?Xc6{i(AvP)Fo^#JNL;&a{M;s zbUZ?s$`Fc(2WnvZlVdP=-_DkdOT@bWw3MBCW(LjVcYTcoa!>vjx>w#Co+&@`e;rnq z+NFgF7VUBTZLkh@e!L6L7T*vnsY_+1O+4FWWefrDG|RW4u$$X8@DK^F&Bmw?*U&iwS)R@{>~on37&5>hD(Idp6cXns7v%~lV`tD$+Y z()W-!n)ab#gW_31&=jyIPX6&iPw+5u<8#arKeX>)7uTK>)C|?Je|af%?A^hSk~W*L ztWwUpA92f4HaM@AHTB7YWBrMf{~;O{6i?tott@341{rMAC?8>BpFmvVa}MgiWlDX# z4KYW32|QTRD*k-M@t#!>o3>N|lE~+?R8j^FqeEbScYKIw9HHU?sDQt79QU z-C29CD!$zmC7<&plyP36o54mbI43BYs^bP_Uyv3h@$BW_aE{G5b}Ml*pEij+74a=F z=V288UD+R_ubzTmJM3GsqUzA*{WO;P#0)zB)x^J6X>g*j7q7HXk*!gRWSV9c!o;uI z(tf_X1QV+z{NxyY^zqpQcGoY6#x#fD`4!9#?lb`z{Z3SL8{pHTh5S@j0UA3vu%NB6 z605hwy8nHgr4;vPb0{0z&pjQI=YJHBQ2xR%qlBs1oD}XaQ^Td_w!!4389ZtEaJ;6s z7rKqh5{J+|v0zdNTfE8<_;Wq9oh^e=2QHAkw7^ zV(Z6p46&NUy#9MDjO?O;!+9Qbc5&rzmNsL%l>;;CaY0h|%Tl(Ndgz`GEPz1zZ({0p zK#0B;ccgpPQpLFP`sSqm8EZBBVOTNLE?XPPwd1?%S#BqlX8x z=u9@P79HY59I)Go^=iE$Xyhwnh+8;ZIvdP;{MEtmKH;$J?)#QN@`s-@+|9lZ_lFua z(r~uTf+L$Oc-Cg`=!7e<= z=I=rkWv$=VF>zZri8^)EPI22!e3)8rdZ>@bHhDu$hzb|FzQMT9SuAhl6wuhGik+?= zhT3{dey&BtJlR}U?LSr6DAPwTyBz5E>?GZTw6Q)ULC!s%Gl9By_l{s^J2 zt$|;eJGg7>U(8WpY`~{zQK#StvY~!#ZFV5M&``l|T@Hbr1@RO5*5ImWSN3XklAx-o ziBZGTz{V<$&$wcQA$}=P|2kV7YGWx|EM&4z&nCgWAT^A=Vow_prcFUrUAVh3j6-B(aMYJ`4sE5PQ; zV;(@gmdAr~;adIy@nNi`Y-g{7Oq!-cMN_0fneULF^Ij=`apm`!EPZF0XhxoP>rb@V z3fl~hmzD6(;3}9~ro=Zc$j88G4s6Am5aC~>A^!PY2J^3{^Xo%QP`05M_H_&u3zJAM z8gP(3+X1kww>tLN8Vra1=knW66lFQi3)t*Su9CT(EoGbfgfim{1e3Q~cz?GD&L&|k zORrSp+WYgF##&==qkCw>9XjXd58$Se$MDseDNH}!Rd|r8BrUEBll$;Toi)VhH_?#% z^nv(WgMMb}Zl=1-7Wmx-a5R#7TvqdlP>mL!X%Y~fOw zHNCIsF!wg5Imb=l`fkczooE18m4*B}WrBvCwP%0k#z?BaS;?YvPqNNk%$YH<3eU8r z!^&MB#M6nCQ|o__EzdeBSoc#!@7voTOOnnv*A2#@XA|LRP^#ELcf;46Ls_o|M{uVd zM6YBK&c&Y==VhNnGrdi0Zcc~b-)xAz>u8TU{!637+5a(w53(<9>tHzfpUYH(js50K4h5u8AHKEikl2ZWV z)=cC7I-fw#pYE*F{p*rM(sSw~4zfkQ1>oqRgT7zGz@SQxucEzqN%C%1u6a$!r1@d7 z$1E6P63?&yChzWE4w*w^B*$!N2Y0IsT)p1&ou72k^!OnN6spBXS{(0QbYTz0tHO*; z%IG~U0)k%z^M`kbVtR8ftbM2@+V&v!X>`Y3a+9rbwc_ePd}#TX=ET`_RpL2z@i;3@xVk=spY z_u~X%c!mLP-{>J1X%9IhPMz<}~nB#~f!Miu{d*joI(HqCF zH}}OgiTU8M!!bIjKk*X1|E#zH^m4ByCe+(=PVyEJ7vu==K}6!pMD5Elx9Jc7 z=J3xP-jvWi&ZG!-$8h4}<)n9|Kum%JDzpUda{w87im3!yFSkhq{1Wztm>*}h@+Afdf*Yt&q@ z?Ci$pH#Fl4*>=`;;FM73tBnJ(25csWaW9=x++uCdPW_$P(z~_^H=du$mg!i*?M(7m zUW#~+t@gnpB_Z-PDu;2Mv{iFn}_zyfi)1$>Fc^SoUP%@ zp4wSMB=zgHH)q0Xhdz8&cNJO6oM@((XCcg9tRo#eK0=6#_2E9$ftBLB4R)=(Brc=9 z{9}54A{2Up9%V81r8a_~v51dcnTH=L9N0XY7)jtOE17~-8}oB9XJft+yWmYWyjc5H ztV^dk=inhG{5dI%C12<*r$DgnpUQt8H^FD$cL947CF-3ZrsA|+Z1Ph_80uz-8R6{^ z-1(~5WY>yC=e980Gvvu9e{#|2e8}+q+!%esQa16$AvS;Vdf0wL4UY`mDet9?Ar0K^ zYXW;ZDL_yuHkQVCtdyVmv7S9KIPoG((Ag<|jXR1i+m^BsBYq2)cB*4)YXKZu?8-wt zhhs%E2lF;N$rcqW*;C`gOz&g?gqvTF6UU6mz)mIC@gLQH1 zyn5J?p2;;H8{)|G74YAgNuv8`P8m#B_GP9L44u#oleb5a?_xf`ySx?WT&Dfb$+NZ} zh}YeBMj|sesRN@AI(VkrV!4LzoLi4ia{bvE;B)w6^n0IBcl6B#$;V+sx>}3Vd&kN?Wbg^+Jv4AQP`KQwc zIO)ee(CeQiKA`i>Uy{wHW z%1Q(#RYRvMjbi*px~HsM$kGch3BO!5G1?&$Zk=7nP4`lNoXQ?J`$bK>NoRh0%zhS4 zzV>q3ztsF(2fM~vb7#_9x^E3*jj9ns;XQg^yb(_P+t0%dXwJWW4&1HRi@SqQ;hgEK z*r#gZF+L(j!HZ1j67R_C0u^N=o`f_BPFK02u!k{vr0Mp~Z?&Q40lafe)3=^Qoj&3{t-&uAm-G1?r0 zS83qUfyMId)mrBUj6LVTetvcla*r!XhYpVvWP9TH=KVUDR~`wS@7@%@&<-@zZx6e7 z&lo~nCjO7vZm8&fh!0Qhh03XWq348jG1tga_GZN%wsNCA6gz0*j+*%pJj9K+ z)>Pp1D=V40X_L_MKm!;5u7Y7gDEI$#2=@fqvy0tkwoK#=Xz1+79##&7@wIALWf2d> zl)soGp&b3D{j7M|QbG6D7Hm(s1PNm^rNT|>sT{r@mUKTSwyrvc2POov&PV?UDic-F zWo5a%yD($&Vf4IV&mQ<3kSIJS=GekUR-HVZ4WaztOS?Fjw^N^cOt6#<-MF7=tUoVQ zm#U-1J<15)P3E0`f5lnt61Js_9Y5twe)t}(5Pv$3!{VPuBaA(~=dr}t|vD(_gSRc=+;8#U?#!;tWef|}( zr1&Hr{}jMdiGSt2Mjx-d$^+Y_9~)iBixst|l;s{<4;odPxb9~d6xomEA1SZ;!($J# zO$iVJ%?zb$@A%1cSZ}E#siDt%+VdofJ`WL%$N96c9ZE1>qJm!?^1x7ODo=78j@DBV z&~S=mp#pWaB$hIzu7xm;=KQBCBEia1pRXbf|Ml!W>_y2nA*Cm=7CpUSo@G4O8JCWe z_PerKbvnYY+iKWBY|r{FA9;C-G1m01k$ZKveK>}<%AJ_fl?y`MFeR*590?lBcJQ+O zqfqI;gRtn8f#^?qo#>s!`fb<*)+05sMQ0&&2^+)@tV+jKUtQVkRjY-8f-zcklLDKZ z&u~JG9HT=(d{mS1J;82P)y@nMn{fER07T=!d!<#W1?t zVXNH$SJnfh9Jcj0+gC0XBKch(USBY7Fw1*>~kgSL*Mbf2F#h9{9P z>r0DR___rx$*XfL=#nt*p%!X5?T0mVhU|>c#&eJiiM=(%NAoOYfeN{l>D~yMk5ut; zueE^wgZVAW9#)dGvl1(2y0M!zUxYX0 zt$J~GKRo>H#GA<$2=DMv0SX9{D{9{1S`tk0#BZ3;qnJE=)$$R#nc?? z4s&GX!-Is_m1-E!y9kn2C-8yGjL{;a1TK^g7GvnlSE?&xE3z0Q8)@ON#0VH*v6x?R z>WeG;#DVvgAlnM^4NkC+U@@Cz5H>a)?JTA-&q6iv#%USt>9(*@eJmiE_G@-;O5kpQ z1s^-49#2|0u)JSR!rK3orCZXYg)sfy{LxZvbZL#0&-vGli6eSBiJda(4n^eky}W*b zT-zzzVUAk8A3(e5N87>Ms_}H8H~Wt|9p@9bKSQk$uD|{+W`7~3Xowg4URWYr7_W&2 z?-QY`V=3=--V`r7?FFCHsbcV0@^HRQVo^`*A^e2~GQWj#f9BGFChYWh2m8%V372oG z-~fjTNUht>4~PeG&H;NC@?(0-Z%GsGsCHqFE>^J5PX)C#<3Q7nJo#faWm9=LQ!o{T zMdvr8^w?#1awbD6x{kvGqmm%>*))QFGMMBY!>g7n6BN;#Z{V zJ2vv;Wd0{h8yDR;4#q(-d{^s!tO{^oT`%#LF&V8GdUge?mRQ466K%AK-48ya4QEbb?)W+Ei|%d7dp#>zRqt{($-59X zlTNi;8Uf!tbooC^%FjMbVm$|67Z&|gMWqW~a;}bFdO8kBcVkUUb%mK>YUB;5l6!SN z4%WqIFUsJ7ceU7OL@Umgddc^;y7N?NW{a2mGsn&Cj_$7$Vep)wWe66pO+0MgtaGqGluX_5zV1;h{!nC)z zF*ct)F?EER6lFBgEd{Fy7X0pJ>e5={!0yf+A$X`7qTPQ*aNhV7PhF&s7TRgBeD)hr zd9kHztZE*c{muY_wh^z4GI579xALhI|DlKfR5t5vjQI3NB|3E7z>IF~fHjXv)2^MF=nXiN*u_i|6hw;9?Hn_OD7FOgnh_~tAoTZV+&O6$H@+eiD zSg{rcbeqnzcPh!=-I&2fJc^Oz%<6(K`_(|Rm7?^`L>;{Py#ahSaxp2t1?PNN%+&W? z5{3}3pml04I7e(EHm?pIT)PiuxM+&!*VCM~C66Vl_=Dpl@_`T70>Mv*@liB~hf^jl zdwqmZ|40{m&uxd5ngx6iaTw|+)IyTFyEuAJC7P_C&LS^-6~6D&!bi0C3~+GblZFs~ z=58drpB`@8J;G9^8=J?DLMh~i>R`=@?O<_9gB#}zl7)_mWL{(M3tm&m3-P@L3Vx5` zX-508K--a74(%lvjp>fv#X9)<{y9H7)fiLG9029_rQ)=5OW9iU3ijVoUD!|ljfk0H za%SchkAHaT>3pW5Tp{kDd`jtxNVeg>EpQjK@Zz%LAX%f$%ZKmBz9Sr2*T36@!-i_; z@w*7dFHGRy>CCTxbpV7vgGH-i>a{VgVBKCZu<5LcYpWvQz?p@-;~{x<-YjGHI=e|e z)19|ycO+{nm%-Nl>DUtC#u6W@iAj~}82_jQ#s&}IF)?-cP|1-c6*>t|_jZ+f&x#cc zKkeq5zi8s-)JSmIb4_#^LOG-HdztO>?$GOxI=c5>B;VB@?3s=R+uhjyUJE4(Wi{x0 zc`0isOoDXs!Tvc_Anzr=GQJhvR?cN@vq}WLP&NGHnE)=12l+K)Q+)qyFMODjD$X2j zDeFIJFOyQ<$GM$yeBO)YdQM|CaWb8DFv|;Vf?Yoyw7A{?b54bG(T3(j>&qZ}b*DM@ z#xWdu(uEOo0z&P&;Xai(IX_MJtfp+;`bg$r4MI-GCbYkF1)Tgcq@}CO@L>Hm>b$xv z^6H})zGoXd5&m14Y@>m9F4oAq3;)C&Kr`}6*?AXBru?FQuHY87(SHW(GnwWP>TPMb z)q`J{O@CkNzq>I0f-tdB9iN2wL*U%KJZJG2ELy}Er6A<__k|HBVbkvzo-nTux`mvB zx)i&Xl1?>vk#ZArCYzB*Pzy)rkk?{dUtW-`BHOtzo{iQYBp9{oNN?H32-ny${%5To zF76Qm-t3|%C4c))-$y4L!V!_fSUR*}n`{-?v z%;fb{_!Ov*X%VMk`oqhjkKzfOQ5eY9H+KlxnIkaa$w>%H(`~Z-NKC4g70kS31B~uL ze4b}v@FR2-k05_w-T=x@uHPy|cQcm0&Rj3obG~;Ui1VDD!r4QyqLJ}&T(V^=t9-5u z*#;WuJNE#b4s_%B7AMhof*0*6Zb=;aSjmo4wl1Nz5b7N@P}(H|q#@ee#+>~5Blfbb z{?~;rcEo~PK40$7nJr64y#?;frc75D^{pFa;VWQX|F=ATmo8?twEM%Q&snYd*iF>llJ7#nN|=0Muo$MrOq zZRO`*|3l4PPHfqnSTUry3O(I6vic9fphC|ccpimuPrGr$sqI+1cMZ$=St#_YQNj)G zd*Mo#aNe)T3LW|!f&8j!(KXXj)-5NG^*Le(&y(nz9deRJY`C|jPc#C4}i)OUB=gm%xz9bB4(!$NuF_E>`pRZQaLH{W!5Yk6e z%-m=xTmCkmz1-*zrj)Jd`Yr&5Nr&+pg|zp~iej-xB7{C#dRS+C8cr7!@S8U^utL2a zW^|e^{+fOSwR5Ml(9|zNZCA<+D&#?^t20lsqmHd!(M;=Yxb3gqsCY!`kVKn0aJ{yw5%Baul2D z69B8zHPQ3iaR@Zg<|p4}QU9zXvyBQA%!&2U{b&(fbluIJKX=FL#KLVfv=(#fEM+~8 z9AP=LCc(Y{x~m3k6DiL)U0s~& zDx&^`O>EcielRDr8_phG2>TxN;eWjAup)FS%ew6(v`kTwezJ&>`*XJT*2R#^v2gjw zZE<@)OWA^~eXLVPchEYcj<1cp2Ve6*mcxF z=zZ(AX!t{h2Q%g{msf?tJZA$mD9(W1D{J|H*=G1?bt)V>l_qW&OdT z;MR^M@Ozyb|M$BFgS-ORf4yabdy6`T<<`PY^-!KrYlGbbufp9f_nNEbHlq(rXQ^KY zL&HE7d~LBC%9F?O>(goWKA+F7WG)jLzWAeoK?j^R%#cnl?1AIQ2f&MxbK>c|qu6sp;}XTrHvkra6Aof(&Bj%X^$O+4UkZ3 z-LfjV3Hwi3Oy8pc(A=BuP-b~>ppj;Ki&mWU)|oy0{#gCb(3zy7ofaSNo+p3HjEF1pp91D0$XMP@a zxcKLQbMZ$prsO34^K)jS{w^2#DX5}W&oKBjGlTc(H3EP6XT$yR`$ZX@`F6LW*z6Hb zU`c0bFCPw#Q(DCp1CHYx|830Bu0zP_HUd+hw!$Gl-KM&&$MKcrRCeA^6`p-krS~XY zuHkFaeQ-(AK6dcRR^ioCL+N2*gYd7TCm*}G9~wnGfQ^PxVs9D8z1_Dk#ixo8o2-r! zy@T?+?eB}Nc$GW`f!*#(oCjFRwE9&tZ^a_Gmr7kKbe}C%*5(zXEM=2Q_p#o0t_vPd zRB+p-`7k#$mfx#L$5xs%&4%g;pWb!Dm;1>F{^KoA7^sKaZ&yO8N3D42V;gp%_t91Q zK#2ROh&T7ez=lcW&+#QcM)@A-VfCvej`TXc>=YJRv>9}dXkdcEQm{-J#Ivf>vG&6Z z_8@GnP)(W5*EgDo!<@y#&Ksddcs)G2H$}{7I)VJsJT}@_6=aj?*)UCz=WRn~5O;LN zPG(c3CUK@YJobDFYoA&V7YC4^JZ3HM4=Q|?>s!?PS;!)Er@}tk4RsEvgU(y6`QH8| z*mjjzg?To@$~*)72M6Hw^i#ZQIkDX`Q^9rp3vmvenbAsxtYL>CG*GT;meyvuo)bK^ zldR_8G`2}4PCWLt5?S#k7NZdY*S08Qb$&T4S<;F3npKS__j)qz-O0k18;Tf_uuneQ zR~^^KhXXR<>f$U>dkuB;=oPYII#Xb}N;kaezYaz$p2n^3D$36E^JI&&Vk8Z<3Mlze zE1&JRQ76=x@r}^yuqaLoKZ5TfX0qj{Wx}ET>iA>le)ua}%iq(U-F$Nj9Q4u<*QHy^ z4n!5Qx7wRv;Uns>7`qMn{}{#-_6?GKc^Az>u0#ms=k#z%(OFn>tB{9H*1(^Y^&rc1 z7oR&-;*`xE?DFPs!oMF{7(O{4`sFzDhr0~$+^{S-6`4A5X)$g;=ilo_#wyTXMW40Onf-ak&P%Z6&m*%W8Q%Jzuo6lScY|cnnKv3IH4G zF`xA41l-Wj=9V8aQL@;P9SPnlOnjq>X5UHb6->{nAP{Ny}ZLK<6i{h+&@>9*1+%0jTou8CYv%w$z)xM`=zb z%MY6dDT~$d)Zjy~?$Q9B*j|U}`<)rqI1A8CN&4C#R(|Gd#!@b_AQ~b|u89@oZyckM z$|~=4hrUnL@oBV=+=nk&l8$$O&0qu47D^fBJ z<;=EXx?o1VlU*Mq62s&GKQYY=r%2Oai9))_==_W}Pi1bm9KeFUm0dmQ{i40?(@WK; zl^Vc&W}$H7wFZ{P9tGPqyLiDbQ(U`LgukawHtT+C$7W-1CV4s*y3zmp38}ZMP~ees zX>aIK$YQ!J7w-4*M>C&m;B`J-T9Dcshn0oG?z%H{%~ljq#cH70@==A$D=)sOlTQ;DI7&TG0Dzau}*NxbyALTk+ZHh3tIdT}iEt zm27);6*He#1Y6tGaLu0xa9gLvSJ2(C+%T2NY;Fj}#Hl{8+6OKd@8+>|=G(9KVA?Ty z!uF9Wm@=~(%zwS(Y@RMgOs#_Z$7;lJ8`|(q%3?Mm?}0G*xiStr9}f>mchwk39TwU# z5IOEm%Pi8^|EQ+1->O^Sq=E)Ej#&mjx(wo}iRrk0mIq6Cv{qQYK?}V?8{wy82G6`| zh;v9!cI+}mba{9R*R1woJE%uswmEsCV2?a|6<2MBv-C4y?{st9-;0P*LpiC z(?dziI!M}}!e8aT#}$`LSm#)0!U1Wb^V?&_)87bs?!T(e&xc8`|-T2gE~XwvfxWomYBJf z&X$xS3foSBC$yu_4&DleK_2|TJSEx29$svbd#ohHQvpX_sFTn6{$@J($Fzlb22#

;Pd13x|@(Pl_v3kmSZoZ}`Ud2M_eZ9LFP1(R@_lwv)C(0=0s$tZgtuTAl zQ2voJ;HC3o*&3}#@>c1hm(y7YkQQ*g0meAdp%pBLd5aH=kKl-Tvsh>SZ-NuC$DilZ zGw|C-a{ALlIL>KsMToo!Z*5)p`ayxb&$oeug^EJsJg9*aANJouX`F z$!g}S;w}j#?Q!DiSk|+M@-43i;>i5h@N;c;%ObBT+-~N}%)`6Gl^?X5P&zE%+cxN( zz^!W*u%ZF;h3|hArMt(+QDfaeJbM-NMH_$WR>IDU3jD^d8gyxJVs*RHgk2?S_|}H{ zViq0ZS8A!dr!g6PUnPkJ^nRU*O=Ho$9btTjI+`>s1M8q^{73I9)YT7QOMYZ1?vHQ@_4TgqJT7O@(?i-Pweb-egA5DE|OhIyS4}UV6?3-zqLq)7q&aIb=DswrIU4} zb|LX{-QIF*53~x2frrCyi~AlDd@v!F#jP`i%hU_mZ}oA|%v!=Z<*8rcc_uM9 zmYEH@#9VVM*d*F#`Pmgh&lg|C1Nu5R_F)?2SRIx`bWnCf5(VK8viPP!!)b3$JiU9_ zV&iXmCW~U(oJ&qnPZ^?v%P+#hrVcS6M}~iMcd!S=9fIYx;pqJJ6!|K3n^wM+VwWFN z*}fhs&>l-np}!Guc*#h9lg{CvyVBU`lYxRsys`BAwXMQ}e`dVCvL8;E^#ty9iWXC7 zHW2qOXA72o6S~nHYjgZCELU~s@ykx&gHsFGnc=r3UBzZxnL35-iXH_~>clw@Cl=XL z4SwI&QZ_y&jXmFUL)hq{f%&n^sZ%3?Z~K>ys;g$Po!|8YO*Iufl~xUzkKb{>P|Cs& zu7SWQb>giKWm&#mIve@j2o5Yz#wlisLc-j^? z*PD7P0#`tAp%wr1Ivvlr&0=qI*9lM05YM@j2nsK<_^x{ca6#2+=;%IIT)XTj2AYu0 z>D3uNTnkf)6opjfI+rj&k zC(lbzlC|COVlxwCC2qYGP3_d`|}0x z@wh*~ldX^EpJhY-YF)7l&GtnBB`o*xCQu?T+_^QrdRTBsMbR7GV`apQNoiZR-TcNmYJh!Es;1@$3k^8J`b3 zGQYJ%(L0sgHJ(l0y%qAw-!i$Z4P=GdJmOM1=9f9L&7-#n#iNKr)x83qolfQ+-3{@~ zTO=YpE)VX?nV;l(pK^CuqJC_{_x z-)BEo)jf&o0d;Wg+-mTYcHz-+)p*3-nJxXBD)^02#TRdqRVvp;t1aJLON0{O4JeM;CJWnW>|>-Fdwa6{gKvROeNf8F$l z*JUTgfL|}M%CCrh^zI84l!Z)wcof!XdGR^51vuJ<{0v|7B|S_A%iexG&JHmT7PDFh zKSgIi_C!-YdxNFy#q<*9CSDYVeAdA$eZ%0x@eE$#HXM6DPKL8n62;!s1^>CD6(ajY z^Bq2VI4zFq>TE`}7;R|823X3DOc(%d*VOUxoIL7Y?8WsTx1iTHM>bLSwPesl9qHwU z-NNpV%lJ=OZ^R9I;KlYQ;$@n>_x+1waLg1QP|xp-@2xN{X&FyXG((*+7hzzdip0io zutv)Y4W*ryl=`&y@BW_Ozdhy#LJd3(JeZJ7x*J_pTkSGCc?+J{IKIG~p2D6Xw09 zgHadTVeJWr@NX*gC}V@S%B2uZ$$Q*#=EKx)-VDc|Mbn=blJRxUa^mf*$&I`w%XZ?` zV()zs>!aKfR4ZmF`2QO$y8S4TnCNOk-)m(|Jevd#p2ullj}rbdj0EkY{msBWf6j{( zqW#(zo-AOz&5rFbe$XUZOOtU$<#N*EyqlZN_?(HOdC<&HrRQIc!%btaKx4{E{^R`` z3?Ji2l*Y2i@T)vBs@N7pgIL$?;aZqqXu{ZN*_gvL-k_Hz+-UZlioBW!bV4g_a8kkS>B;bF ziasP+~(S^i%dKnnTv4Z-I z)-{P=l^5-P1nQuz{H zEVnzvA{%;x_R#(%?49+RX^f1Gte9aWYUs@;md^WN6Vu!M3Y5f zpF|7>OWF3Kj-St8oaxAJt>eF1TUHP{z5++J`b^_vD>uq`nWR? zwJ^ofvcyPK{3)LtzFQ1Np(~VWv$rMY&HFfxJtt}GZZ+fR z30n1PGX7%sWpfv6etJPGI<0XgGtWNbtl!AtnVK*#GFe5{f41TNwbO{+WL?1(b0bky zSTxyW(E>5^N1$s{4muesZbpO%@E%hgrfhH%!Q_m1BK;KTb0KaREIUsEs?+ z6TxxH34UN1^I>jDWgI6P&}SabnSVD!{4fV<`nC*HzwIYUCnz`DR}Meir~&gehiJqn zQ`|V@9!M2GY?3Ig##Xx}Wc~CBkorU!-BglUm-IYp!tR6qd_Fn5Y%_)(4{O&(6YqZ`;n_b`jGBHGUYy%b>!c>&jJ^l( zdZU`4-pg3@sPGmsi=0R%vl-^@n_RK?-m|m?H#$3!6``BChih3k_qgNY*}iR!ITj>k z!|SaXd^pQl#BPZu?)&XvbF4hZ=(NBB<96QGq70w4ZYG~*BWH246(^K#AfdOj8~g7I z@hj&*sw3qD&IJ5 z#`jJOXFIQ=#Z;1U0EQH7B&iOM1^d1*CXxly{g%#xyfF&+t1le952;Z9#x`skH;uR^ z26F0Ein#jkRsj7NYW^%4-)&h*o?O-Bx_8N<`l=deAp`V7xF*gTT?Y$eYWe%y28&v@ zogy!&2JE}a_NT0qjXxDmZAYl!m^0B(K4_qMfaxl4*QJrhwSGXEZoKW_4yf)hqK9rI zqtnKfBwcC`SFu9{(`$K_4^5>Wt8}sAC4xkV1OL>o8cpXolIMN@xY>*~XX%#$Q@gj* zDp!5<6s5z<&hc{(u>GulN*b|Bu7#mQ9s6JVz^4CX>9oE+#`Mc4Ex&Bw5aXykKHLQ1 z{!{6xe_6P(*_u30n9MDAWxY|D59c*o=@phk*?BG%j)%SGhx;3e*ql$^hHJw_=H(lD z?2!1JUnMa})Z(*@{5}@RAL;ml!q25-CS&hUj8a3NQUs4ViuBOJGpISyhCIp(;dDi+ zNGIk)OKcqF=9}Wvi;Zy3qmJJiX(TF_C?M;?t)O+C0?vv(1Ve=`RJ%n=ls0ocQFVzF zY|WFv!T0K5sQVD%!U}aX4!!{K|1R)}-csRdiQ_mUyD@^Dqaa-eH+Ako#94*sTv6;j!dIV{C;JM$+j@h>3r%u3+P z8CBfB^q5$ySHI5st&(HNl66lxH^#a8;d2Ef^ab?VqGT-nx`@o#uFEa`ppC;GH9ZFM3W*;r$ZKJT?&IOd57qO7p*u_Wjc9m5YAgjvAkYu z4B5Q+09^d2fNMkBVbXXNdTehpelWHpO%1->qFB}~`>jl@+tjA(py#o2NU}EN=XSK9 zj`>nTRG)D(f>|FE^HKb7p6^)FhSIyIlkS%z1Ox1x|I!~ro*ZidomI*BbH+*{si({r zy0JW+{C47BH4GA+WwF|)K-^v1ce)5?2eRzOO~S2wEhU^%8_QKRMAM6vN{EF~@cZT+ zK5cg^-pQFp0<)?(A8jQp{^AACi}z9KX=5=_w-3y%Kh5=sD#zuEwu|`*YG;%&$*uwx zhfC1EYpZa%?-F8So6J>4Yv5Kl#)25Aq6g=X!37%Gu&*nfU(EJOp&!%8uSIO0QD$@6 z?Cs*Nlbb!ISm$tn4DIE)6;tJKd-r)*>wAcfT40FMTW-SO^S7H+FQpP>Ia>ZJ`WV#3q9yyY?mp=;D-cl3hw#0Gw&TXa_8H1?nY>3#C)5m;P zM=!;Y(ev~mn(2G9buWX~h%GcQjO}GUJcN-BYJ#imoCnuC12;F z>VDnjtGii8N%?k?v+n}8Sh)yox)+jP^P(FwQbics<49I0DZq3OIh^4U4tqMxsnp>% zR8OByE<34n4;E<&k8Ta%zB!JhNi6r5Rnr9qQTzE<@9MCApD(e^kO0S1j9GNF1hk&A z9nG8~ysuzIo?8k98In8(y|*LPI1?NibTBpAI$HSrGqcN#gCfjST@iW#xSo}e^eu=t(Zc89mv982dzoB z?qu$Mr5a8}eU9oWa=fX+yB6p&b6#d$Mh67D|n_COMtQxPY$;_~hvs5ZsES%c@QB z#fc_Z*>D-m~sAqKH+_!BB6sj4t>oC6bkNXBtSPpk#*xK6+6vW+_bE zITUZ6y9h`1FY?z`w&D~EKVsnakn7Hu!Dgcjkj~mdZRYBtsdfQe>KM*jXR+DoaUtJ2t3S9s1xf`xcEAjnDmBn&mJ%i&y=fR?UY4JI7JL|X#(?uPW+|n^LYB% zMiQeT0dKPuQTFzOE#k6&TesJX-^B-1dqoV;|9Q?I;~mLs~Q`uyvgpgkuc{! zS)3AE1a=3<(&8j>D00=vDU)_H=!j8x&E6*R}VE8TjT!O4xLuLd-)pdQyQo8<&t| z=OiwV@%)P%GN7-flK!YR!9`z6q1>c^pUCdEiR;qI?-X0`VEcN}{+)1hvYjx51jsXtHfqk`tkn;5wk329$k`T zB+|W8NPaKb!bN24L`T;LfMb({k2P5)^i}{^d~4@tJgUT5KEdRl)=zHJ6GdEM+zd}2 zt)?v`6PF&bCb|)sf({d7(RRE@+|ymjZz~o2q>=`9ts|()aU;>)_ChkXzmuylV>9il zKyaKHPxt$cL8b0CdBx7@oYbFofb~I7Xdfw?(p*8S?|xNI09a*Go_w& zL;Sk}vie);{g!dKKjjg0|4t*Kim%0y%wmrO|N;BSh97xQ) zJ2{u91vpOKirAfuYApK1^2LtJiRlhyu$nK2*Y+I;;ea_UVA_Js)^u{U&Yv^%))ppi z59Xer9=*(|GuGKn*s^6G|5CCMO%43XU=K;~Vcy_$t{i6mbfQ}A1&krHkof-P1=G$o zV>@AY2X^MmuaLu(h~uzyv@)Ht%}DfbRXSNP?mj2YzNd|i+rgvQi>XxlppTML`geXe62)nn5Bg>VWK5 z#~AH{V%C zhDZNqfbY+@{OuUV)OuS))JN;UPIliMY<3iC&mN-Q-$$dfc_h?MsBBic#Mql2WkeKR z0g}Cv=ry@g%)l?Yn1NOkY{*fgW1Qw7mWi;*1wHpDYUVux4ObV4yRPQ3JW!!b_h9QgL?@T$zyXuP+Wls5aqs1uCIta1d@8cpemi-w|( zwee)c_%QAo^QW0FzYljV6wpF7Lv*6O;H($O|5Yf%w!dyf^!OXM`aeb1L3tL|G}ux} z=4n|RQcTv}FM&oA*5&FI0zM8(^gi>+>^K-t3XGp|6=AaYFtQc?^i8K`E0gh+{$es? z#z@YA=?|KOLN~mjKFm+}*RKqoTNd%|&zn$Y^kVX*C6}vVx$ODV!r|F-f2t5Y499E5 z!qS1R=Its*BJZ?#a$@*FARAbJjs9gZ_rCUYGA{IAOoGSn=i-K{F+W=^#3&}w!B2H? zYiSjj*_-iuY8eIm(@NrQ|B`b`VLJ|`IQY@Ffrc)T7Nt2JBwKry3ijDBw&ay~(l(_P zdQ+0I;ffn6Q&r(}9INrj*S%!Vvym`)pA6+`-*4!uMBC za#_8xbp32iyx++B84o|@z1S>@=Ci~*+0SeS7W~->X^nfSJ$vSNDz70{fgXbSxmCDG zX)n34C;^ahUu%pi;NPG@)c6g{jgIyrR~8g;Q#Z0%Q6>i#J~~go1#4iuL?VpUj^(2m zr!MPK21)6)74OGq$m|kp^&TCixa(yA323F<(5DKh$TDtfE=OpDeFna~XH9&YZJK2U zHDmJVwWRciDcr4AWuB;X@OHAIk%!rRSx`(mQnzr|=IlUO)rWB5@G0SGUKM2@`oZ5_ zBL32zG8}e4kX(8Dg$tf3hfnhAp|xNcT|GGi!z!)Gifb8y@fOCSVLL97WZh*%mU;dS zJTf3sTaSjZXP!6|lUqw~a>4s$Q0rg-^kl`-l9Vr~XzNT!fE6`2W1I@xE1+q5oQ`AJ z1jnlmq@up5xybzwn*Ena3LkjD`zrQMjLZ}J?Q!r_oIGCyhb7hu9z0hSo?UZ-8~wwR zj(elSGTkw7yy`x`VW^QPCM%u{YSDxBtZQui*lXanXe-@$j^%wK7n6aTAp)Ik#-iUv z_sHHHLsB|k8B^8sp~L($KiK^|hA@B8@>k2bMa;2K~AXIVN}bsCf-|Mk0VT+`7hQAZEvlWEH!MuP&lgp8p=`4PclHk$5E#xDDL18l!}^ZQF1@a)L| zqV6jRPqrxFn?dEUI@FOSo;io#rm)Y~<^_8H)#Jani%4_uH29t*jjz9k!K!ct>d87L zVmdMyZ-kxm-{n#L#}4TE%Q_8zvi;QNwWLByiyPl9gRd&;AmZf!T{VNTzC-F^;gcFZ zytW)SwmTAuogG}r7B$=#kqOUxqNwvQ6?9z}4}si=W()TGyzI&(d7}Lg!I&X4UwOml zokn!UKr)-d*AiX1y&KBb8-V9;FcWyr~ZcRYT5kUX9EKE znY+ypB(EI;<6pOOcO9$i~QY%WFd2ATs%ewC0zHf7+=Ix82PY=P0E6lqLJI!Za% zFxKT!Zr3>ljG1y4WS2(K9t$08w9JPd^)vh|rmNRPmk`@RYuLYE3GZGy27?E!q)S|- zM3!2fWJOS<;C;v-eBjb3-p?-lp^8RXt?*p^06+mOSC+FpzU)!)Ip2ECP}Fq!1d(4C#_eP8zL3#uKYKWn zKL3)0>&Gu4I~98Qao!ius$f5hlr&5#g{>J%C@>Cz z=f4$bz*j?&`uh{4JMkGO|5F8xdOD$YDNwUx$+-IU5;9dZlKb1OjpkDj;+*^FVs8zc z$e4J(eg%97v@?>+YSKKmlye>~gQkVYVQ+T;rGtlI{xima5ASLo%)UoYbxsnA%!6Rc z*lX)|F+baPHTpUu880e2k}lzXZsvOp^qAfR2Un%iC!3hYyQc&sj1BoK<`;23IyDU6Vk#T8VTZge!*EyeBzq~?;@Y^89~es z>5@f;J{|#aY<3EC*$we}dnsY>5m)xiFT3I)Fk@c*x8O%qhBB^t4(kY*Rt;tT60|d* z0~goqB#tACIh_xxxRUv-vay0TW_`o^&H?04?r!$8H4@!gkwu2BUc`D0kE_qrH{u-|K}>S3ZLE^G*o^Le;P_%^xb-FYvV?Oq^7{bL&pZ z;=aiZaE;wbhfPRFt&i3ua8!oiv#qfxW8@X0n6-?^F?Nu(XQud^zrivl(sxV9H+qwE zT_eNxaQGE*$J3@gs}~9jk<)GxMSF`+vNO zum&yuT9bJvmUBk;<#A3xwAgPc{G*4fjwC|y(rA7o^S7*>bdspNvaG4`9SCNIuE9LOxr%13Vn?@%Ev**w? zi)=~=;C^1v62`e65&JEjdQ~yktP6tNeE9o}%ets!RCB? zu+)k?&}kOr6xCt(G&@q9W)3!kRWP(J9)2Iwq#izuNoAWwoL=AOLY~N@_Q>7hPODp! zQ}D$CmSZ4a26S9cmU2kRmS~tejwXzOb<^;!D5Sbq z!5Mk9k)0umCe`3}*n;9nV((Jqx5@h`TCtUizQOvqOv`QYI z4&h-G~!G^jYH^&20+Tp!lt>vOFBhj_^GU9)%6kIA4@m_EU*g7cC5$ui}xgvo` ze0at^C{@PZpiWTJ;^>k+$(X#>iI}PAaj}g$*xY#m?#$??mG9M1Vqqyv)i}qeU2DZl zzN<;jj1umFjQDfRt6oqOV|Ks8TBRJK{=$)UIk0nEt_s|4 zPo$c{Jmd_liObWuTzajvFxW4Vvn+|F6PB>t!3vfO=y}LT`WlHcgl9;)jxM~2Qb6hC zy>P?Zhw9!+M$b*_$AT|3qU9y_>Kp9*GzbSK?)kl0rm4MS^ZIBy$VLLUiz&tQsIErqW z)PP%~7ZY8LH-bABYQilG62)ge3@~l~Oc?YIzsmROG8V!91oCj9KJ>C&`I@IU;MeGF z^hX@aHAgs+Quk1SW|Xl=F#92K4K*Tj7~|qX{W(Z%_{2}HsX_fzTXJt;Irn2e8GP3(bF$ctl`MBJki$^3FO*T2QX7sLLJ@fkhAnEKj~8?9%LeR=Co^W+|MOH z0s1os=>AhG$g^DMV~;A{uc{1vJDo|>&<^gBh7?AwPXG_k!}RexT@2OB7I)YFWbdrH z!fbLP_5du6VA+j>`^DbNQs%w9lj2Uy=lF1O?HZ{0`7(@sm_-$Q6!G(qYQVE|c#D{e z=+d;CWaX>C@J-6tdMg7S1$xn;jE8ePH5G>b9XWS5W|OTm>LFvL8fq^Jf(~6d zs(qmkn=DF*=>|Jkvy=6DKSQyGGrlSfA62r<`*}ky_9)}SgqOhNAFb4O8OwG}&ITjq zOyO9U(2|jik5^L6%^D|%C%+sK_ZT`^3=;XdxRcG-qWI5F|KW@$m1K2PC783_oPPBM zm^(_ImPDlCx)V0!lhYASL4$P!v+U8f<#801hvC|Xg%BN+&F@;qxEace$Wi9^9v-8J zhpj@PY|#p8ohv2E{BIkXZW$#w>ibXVeZNV}$=Sd${&SiT^tdM8yR08K-$^EQucaVt zwlt;(oq@qBTj)JS6I_`g0v$S;FLbzo!`3b$JDw{+-aL7fc0MNNVIF03xJg+edHy1d z+f%?e_U~?jN6i^J;4loslx{)xn9aO1>neKE?n@+0WnuJ01#I1!50xG^bV1ToG^lKc zXLrt9*1R(k?a{3uGX15nk=4;4WiqzUSW1p59ONEWs^h+W&2XV9 zg+58w#yqd{;M-@)hsj<Sg0_U9{Z^hn0{&}CWgt8O&cPg>Me9!%DZaTUC0*$OY! zQ$%li8*D60MwvQyGJ3iyAFSJtckOaWoVg?9tX09A6YJqb&1Cwq<1F?cuqNh)bGaiL zGQt75ByQW%IBFQGiMw8;K-h%m{E<*2k&HR(>hjcOvjO{At@VYqYxhxwN9@cWvVr6* z-z2cMVrTy91LWSrMDR&a#+os8K;I0eyA-PNd)5jP=#|PPPGU39^fPeRzk<%sW6x^e zDX5T(;T>4U%~6m;c4^pwgADUj>+NOT7WPy!u?)XmIZUdCiMWAM1tc>N?yDZ9F9)UJ zR8t!g+q1CQ_eLA8p0SI_!W_8O!tyU6OmAUx{?@Y>a7g_kBAg)29lyE_N7g=ppo&DH znUp4~yB&dqhIZaav#;rN^px?avwLuhOG;(_3(7gB=ky?&UOI$>0XnBjSD&sGW)@Hl{PaY&?IR>4(~z zZix8_8v>JAKG&Jlg!9d#Oh4gy*>tjEv>PnzkwHh_9N+_V>6+IUP*-I&v8?+dDDz}9 z?cC#VV%RnQ5W5?i_aqXPD1A5;ri`(TH=%$0cDj=N|8kR-l1pu&f(dN4KX>U7;qMud zm_!u}5-}#sWY!&gfz9>;JMztQ1()0>hi6~Kh_(7r8hV&ulLX%1qWH`6j6`n#C6dH& z2MB6V$J-yeVaJF&yuMl$>nryo$X(>xG^gN1)!X3Gq|tb*trimwIgq1qL!gS?Wkd=m z;oWiz8piytlg)BS@U}p%m+fTdMD@V^GJn3Qrh&~Bhl%diA>jR55kLN9cg%?{)YI%N zPG*!))zyuHkGE^lKh}YK+iwnrq0DcS77vzt)#(YgGfkhHL&jg|;qtF4pbX~=&Ie;C zXPAQ1!aPXOa&4|6OBz%38{zKm0Xmdu;%G0SxTE&(hB8#wbs-nWb#V18e^FwS2`d#N zsGxo%u3MH1DZ{0B_dLc)SeQ#zPdNxstb`sK{@|f%Ow(0U@V1`^(bwL`*_>v5ou%zC zxB4{oVxOb-vle{oEcw-cf1>;CBw}qi4F)sM@TBMIV4Ss;{&#LD9vgHToLA}1b!Ohb zXKQnbY(za2)UxNtE|_JzWNBgR8=TQnLb?_0U`d=JO0zz!o@jF#S(1vKZ)}LfuZi4V z=B1aOSqi^WTIu=sN|;re2}35m;-|<6aR%6srl4XjfOVqTd}FR+K3-z+}c4T5BG z@k}1h{;1=Zt)}=><^TyFa*uO-B+b~EIqlAABgmqI&Cy{Qsa87Q8GM4}Ag4r!+sCBzGjy&20!i}5w_yEN4tNvu~ zba~jIr-;}43t)-)B6>>790fN!;C@c6rO!*o6HBQif0);_ZxQ3H?hk|h)e2OSbyF%0 zOCt8E&pAW(KGhlD33)^2((Zs{924w9jPL7l0fTjLYF8_?8T3=f?^;+mv=$~MmGWyY zSL5|gJF@p}2IujQW!PshCPwFBn$a~KADt`%O#9uuWfr@8x+IZ^d;YMBF+bY|x}dXN zgMPlk&h`NpGSGRDvxry22fLf0>P0f0c1atjYu15cpc!Anx@ZT5C6Z*l;V`va5jRVp zge5NS^xy}U(O7nvxSw+o1hZYCYC7u_D{TY2Gs$?wiFuWyRC$g1w>X{4CBNJp;mQZr ztEG1y7JV?JK`U~Z36S-zzqa5qH%SRwH=N=MuE$X0E2?ufuVcHO_KIBcs$3W5 zL?~dM?tYLm+DAV=Wx0|H4}xDd3CxcC#uXpS$RDqpkdD%*y{-&~N`2?|AFE`{&lTj^ zt`tthW?FmqbL?5Fqmwujbk;c!V=W7Lk5fjXkosJby2}nIQJ-UwZj_@>G{NzveQnPkAk52AM|;U(`(=yje?(Xj~) zt}Gyf*GO>X8ryJ=>@zU(PZY*^jKJOFBH-EIPTuU@bNtd!K!&e10J-A|=(bk`-D})v z3A-;GVz~)rS2clKkg-T^N+%gTa|PMAhH*-T*|2V(9xXFrniA`T8stzdIJixkv9%Aw z*FCXR@46}W+n+RC%~@kUV#({%M6rDp)c;k$ zZEXcGD%pU}+t`X-VQY!3+IK;FjRsE1j)B>Ew|GfimhqIFLgxKy;P{`)DEZ$lICj{J zCX^?m0+XFcnIhjF%Cm~0xTY4Nt*%~CnqbHEWH}Y&7Q3-+_5K=>#WtM z_Q%w*V#a;IU;FtZz!Fpp)LHcKYL zmB*S?Hq1y=S(rQY_YLY?&Tw z_T~bNEjOpxy(w5=WkWvBoXGiS>tNvUdYGTrN#~qW#(#VksIPp@yY3aDhn_8w|5D67 zjg-S$))TS)%K@tCHyx+DoPqDT?ak*b25`gpO0wlo8YIyPP)zwcEPwl<|3gsRAiG_$F??94N-ow>tX`oa`6`WrmL=Vq1Lj~81 zu=cDOpK+bX%HfR7VxRzy((-tAf2f#gJcZ5eKB39vf)nE~<|*P$i7v*k$fCB)YZ@(o z1-#ANc$4Mj*d^FZ)(8FOlz%Ir=I|o8xN8v|$2e?NjY&j*=JC0k87o!VvYNclEo1yO zc^r5e3T7fXs?X;3vx&(hNU4|0V?M^uHk}YY&yuFH9P|>iWn`k0KIi{V8|PZIgK}g) z^-r6KE?U>%tLFuN&B;o9%zT)+*6CdId=(u0_Y^ouh0)yw%zyhe5-#<(H(Rs2@ZOeW zvSD5TWXLL`5@WMyJlCL;a+p4Ew~Xi+`Ey&}so^U(3R+ny^u*ioxK;WJtT{A~|DG)^ z5=f^I*7OP~jAy&hGy$%sxKocTDN(iQ5h4h25%@8!+kpL^Gb~HB9YbvKa%gVp#z z+jsaqK95YA=M4J4u`afI{>s#sg+6MNSA+$P+-6>v)K#<5c-MCSKCCgV53EK%! zs-VPXk1R--G@rVsXyUQ-)9^IhUf?@qD>e>!4#CQa!tCcG@k@C$jI6oM_aAwVRp$yx z;voZg!2VtFgIi#f%o_UIeLQxW-Ur7w69rbgj74uR+$4p`D@gllHnSCG!EnD3RNax~ zq{gR!;pJ+<+&yYoS{V%m2hwQ9M^kL+O&4dTo+T;ayY06?dU+&Oben+s-}+$GXy@ju zuBDiozLCU+>A~ko@_6IfIWW7WPlstUX1kAw81H6U%5PQNN}?fsXeTeN-i9i|DWt`Y zo$YUw@rvgi2$bAGCGL#H;a;ym+Cp96l4L9z>GF(xs+mMSE2`lF=5dv5|Ha4rYQd~$ z>&Qy)?c7qK9G)|Y2hVw@sX_lFR0_%m``ame=|Uq>$JJz#VY(RpgsURn?uP%d>yL=a zvCMEkkF66W1(EXN*LCQ}aoYq(8L#D&ZXOAo#Pwm>!U2cLek#P0qgD3f5tIi}hvv zXwRf=po+GWdDuUg@Q+S4;7I39-w+hW5KMbdcH$EWc1pyd`X)VVf$7o?V9h?z5@i0yVTcMPbH{Ou=-2 z4ZOCr2EH%7OvC$C@nPLrkpJ1wf4ITpDi5Y_$QN^pA7t>UQ;1lTzi2)kzX@~T{>%2} zn~iVrXio*Xr(6b~8Gl|?y$vjD<>)BpE%6>?OI{xf<~Ccg9>c$-khC|BZn~+3cE^iB zVe}c^{%9*MN^l~>X20QFg5}BS4*BG2i z&Ta1HwAjw~V%$y8J8nsrvUzyR)8%CRMSX56o2%R6FM`$Me)>LnEFNmP1m6uQ|4OqG z<&^A+)5LVH{e&uN6sCaia5$xsD)>7-3Kp+vZ(d-}_Aexr*kb?~x3PJ6Ru|mvQ=_*o zCZo-;6(mtQfV--~`TK#I zjy>oPhWS3U@MSXgDsLu#r)(CSvHOW@23HWXv`!e^$GR!a8z67tVCrzU9;H8QBont~ zajrjyqQku+@i~8clL=a^sfW_RMZ8I+k;uM1pIFVa2QXH|#1DaR;k6@m+V&jJ-unM@ zUdXscI@j7^RA>l2*f13Rx?3S_m#}HxTa^Ee8#)KwZCs#3Z1d`|s!(jQGy> z^{2xc=dnJr{XK?0tYmysUC%EBy9{GMpa#z(H zLPV^${Yo-CKC4Bqr?LD?MLy|y|9~rEbBJx{5f-IANjv7HpiSi#axGhj-BP9T;WZwd zB0o^kVpaT^N#Vf98or(@$J?`4k%V2Bxn3djx5yX3z^z!?Qa=Kpc;&&`aYJ|ymdCfw zJx7{1`U5as!fRtNX!lQ|(ncw`FnbFrF!kfc=4hbat4_FWn@v-h4j+@y0AJlKdB^Q# z7;3YUbb9~ceAX-DDb-wQ5%d(E?krs2?MMk1YPtTFt?9cEU6wqnnA=tWP z2yNZai%Sld5cdz(@b`c!jt#g9XZmK-BWsw?;ou^&F?9mBuZ(fnzBIz@lbzIh8_W1C zJu7D2oLfvWG1H!WxLV8&$&ketlfpo8_W>#~w+$mZr;&H^tN9%t-(uyGDzdJm3@mpl zV6l4}3@385n=zShK3OE5=g0LaVc^>`2;LM&Ax017dd|bbrUL$L@&#YKRk!!HD(2f7A+K=Vq)5-ixhOpdM9=%^P))qVGgZC6+ zhMX0NdTTa!(;E>c^*NFS9~c+RWZj13O#-^S zh~=!0uOwq;jpD8{Uu8jM2e^Fhr!An4SqU|8X?7t$jt&teElVLkTKc$2Q&e$RbSflx zhSMh-CS%&WA}G-Nueq7!{mYxuNX48$@EyjoqK%C8l%htZpRjz>t(9cZ)c~$aP8H4C zC^#=mrlfl;wiaB0$*+JPH$++_aV?e1J*Nu_K^izzCj;6echE^Y^iWqP9kgx*%ss|@ z2wHd2$U>IIn!xxB*WSH^iW_mwWwviI{7gQ%b<7FQvuAkQsYcjoZA>qG&ce>y*5v4{ z*<6B`oUpYygBvc9KofX1+%)qvFXXa4{`3NpcXA}8tYD1vONU^~uYEK|f)yUV z+(L4{Z5I4-{DFp97376OCk&mej=$JGMQN`LOA$X_U$!pSX@D#=nsZzxk@;*s{@>8 zgi_@>YPfYZ!mOc`uQ6m^ZI#5wW*Q6U<}! zcGcuNUgJjZ zvt;Cw@sL@jh>c4cVREZ0O>N0SnN(}C^Hr_jct$nKq12(4 z^%hwd5EY+?+|tMLn9&~yry>P>y88@RYaFKn>7lr>F%x2k{%Njy%X&%t3rL7`04y_P+KcjG z@jM@OAO&BZ-bxNX^WzMYRM0f_3K)G!r~bzj(N3!o9-Oq~PY!Fvb2UCB=b$pgZD6b$ z)uiqNYe#mQP2~1;=rEpAGic1{qPDM;aCKh}v}L^JqZrTMd2KD3 zlR6w$<;tO4Ksa=7^QSK)X5g(&d9cu|qq(N{EhdClk&ebPXkq?j52to;YmuYJ{v=~m zg&oBM5Elc00oZ{c}A6wmWpe&}K8$X@s!d5?cMw+yugZ6_;YFLEji*w1Qr87$G- zN7wHdhI*$eK~OTBUs~RXiS3I>SDGCB8!U@%f5RXwax%>{Ys2!3GsuH#eeTLaCA=Qe z4gGVn>FufNn18Voq(`me1DBTJ(2?88y$ip&U*!t8tgckdEm1Y zd~?l)sD9=^akB#2ZHR=JZ3=XPM;k8sHiH~03gLdUS>@iS`>-aS&{vFip>MjHj4B(& z?L4WCW%DmX+v#`ovJYd@?x=#tj`_TY^d+1`}$1!p~v z1xwqG=9RmQM2)8D#DE3@w^#w?j@*VHChBz9D>m0Dc8JdHe}ftS{1!mHxv{C$?=lPxMF{!d536cy%$Fg^^EGW=+WMha@CZzEv^TLjcq zLi9DUo~Rbz1LsdeFx|EiHVk~_jk_}O*Gp^C8WF)gn_!A1j*qELd#vl zu>Wv0nB?E!A7{Qp%VFn<@UI~Z*H%SS(KQ%*X%p?(os1z~_Qbt2O~6MQi;QmEC71M8 zk>7S~Z{?Q@a?ZMR&xu<6=3+(0=WpUnA4p>P-J_6N98JAl^sr9q1oVX;=9Mm~V$z$3 zpphC&3)sF@{l+S?{gJRaL9-0&E^Z^%_M_k`<9;uTFBS96ql#&$E9=QxQUG#` zlKE3Cr(8ERooKIJ0?q>FSsHvFGOcg&{qCiBVfH~X+_RN?VrGc%)4O2SIpxL~RvoNM zZX3CqsSZ!rE;##73XFX|m#$%Vz{vDM@>&?gZOqXYcHN8Q8Yddi^lnvr^Y0;CtlQ5! z?W)8{Qo-b?_8=G;!uWDn4|@MO(`aNF2jvK1|y`}NF?r{TCj zhwiFljPA-pGOg<&H#<=lkG}V3Jo_kW<&c7{s$Rt8z%Z_Mtu$_ELij(D&O0vW_xt0a zy?2pSB1L4+?)SNjQY6_U5}A?lA&LmmREnmw_fA{g@9REynxa9avdT<0+2eP8`~9u( zxbOG-T<1FH^?JT`zxhZX%+|scI(2aDUj^S

H99xROsDJ=_L%KW%bO7~mmfxN2g| z;&?ds?6J!Aa0-c0g- zQ#qWCS4CCs0?a9uql*omVL){*c_Ll{?h1-1t5y$FbZ5}$xCj)r+7S1&@!a3VTDbUD zIeZ-1NF|wX@h#ie%fvnBJq6Wx`@%XBcB6oMbyXG*p7e!-i{0sky+d)qu|RNA%n(W_ z^r5Cn5ouw)`@<^=*mb-PMrg>>ITs@EZ|1~`jtb;ev`8%Y=T&WwGx+zew?$QKY z9DOXuGC;EjdVAaSbX=isNy@7yn`c-uMqlbGazxq+c9b*D`D;HY{VhjBm^aXSZ48+j z^PG#yRl?uwozkB}=n&>zJO&GFR%cDt|vo zyI;T=4repZf6-uZ*N0ASP{zm7j0dAtD-2{BMd!2_GI-i4cr0Yxj~neEEvG@hzl*>! zwaui|;1qY!gE4}x+=P3Vqo~}*k=Pzt0|#{H@?!?)eN&=gH148T z_DYE(E?pqglhz2_Qkkc(HHMUIV|gtt5%{~$nK&e>^RmbPVoqNPIastEGTBV~Ez6JA zAg1(9K@1uyEFn{N&*B2yr9?f~q6cO;?%morax2RUx9jC|3Qfe1CuWiN6GlSzR0V7c zJOhhPxl-}p2s~uAkNh*D!0`4#yrcg#48NG!JjseVQLJLMenXsn{^^SJ7IqP_Y_&K9AWjz2zdIV|)(Nh3v>^SifLYgm&M$a3G9g8o+$P4YfTWlZZJT4+rB#pu2yAt-y{-3U98$G); z0;Q{Mh@@P!z(0|BrlOhusAMC_t5U{;=TqUR#Yk#Li!ofslJqO>;NaO{ERgg9hwcD6 zDf1gH^4dv^zF5=GoGJ?P9zpPbK~yU>0vprq$&4Uo1wWXFGCN$ztv-FYzfT1h))hkU zY9sn!Ogi2;YC#-x+XU`UR7EMR*SITmFMV-V6DQS&!s3K>9v4*M`N&yBwTR7g*t{j# z{voVb!TbonB5>Q7%_LLFS1|AXM6t48FL4SmC2fUlXJl9e-eJFZPyKZ4KWxD=f|qiw zQ*OuIR(o zKu*8ifZ}aE+;!mtJRE(2&-cF0q|awa*a^m`nj(+SOK%L+{K<|n*pXmKUVSVQ)a%q? z%x7nEG}8h~SpV7C8U<})E&7%92{1d0#KI%aXSf_X%sUNo%8ZAwB@(r|_mk)^Lpk&9 z(%5KL36p|9(Uq69ag|F0JRD2;O-e;*zIg}vv$}=LS*wU$=aa#~!H<3m(Zoj;2?JSF z5(O+@(lDE}-aiR1{;=Lm{oH`A^3uvkJn?Kl!Ch|L$`%!z@x2Lh7sb-?+gVOoE)S|# z%z54EH*nG~XOgo`hV>aT_;7dZK+d?Eiw+jPPX;wf1M@db2cobqoA?!!LoMs^Y+5eB zBunO*`r3mkhIyo9@e=4^=XLY?I}jp2n;QB=AS|#Yo}b5a#cYqWq`3q%W9n#8sWMg` zOM@%W$2WLa;SRs`#BpB%H+7c`UOegxe@`E$OW*5atX&YCtxp%$FZhaf?44?BDg}9G zMNF9301`xje&r)DFV2?SQasBEd>NmivkcCuhS3#2)bU7QHpp5rCeq|G^we2OvX?#J z+F8H-!aWFL2HVq_KcvN_+8*TUv>?H;VZTJhb1Db=e1}$5w13$Gty63GxZ!0uS>hzQ z+;xu&bX36MO8MY=?FhBMtA)3w=fl1X9X{?!1>QShO9l;AfI*>hX!^q+ewvukgSsZ- zg_W^n_c>p#FI65DquSxERvdNys)7Xx&G4ngp0Byjn3nd;m$6a?s`Qxd=s+&y^jJ}c zh^Z)^cNa?cl+FJdCPe*3D~M9SB8XCzMQIm5cory2L)re+;#n+l8T*2}F+~xb{&v8# zLZ+o>bM;8~Ekw^ppL>2t8{_UY49s&Hrm5km!z>$OXa?V+U5A(2_LHU0u5)w_V=%hJ zz_zKrR7OPwL;Qn*+^H2>GoSdpk#WQ!{uD@!V((OU$AGRfQ!Wy#JGKzxFQ+(>hGr2gcwxlnZOOxLkt>MNo<>f!NEzQ$M#I;UyQqbT`K&d3$dSOcg2Bwc z88R)7yo#!YkPi{~rg1-!AE&|JUDu0R&(q1NHFgjZsD%1OBCuaNiFO2E!%m|mMAmaA z*Cin>QaKgF{Wc4xWTXaejE;x!_fL7tYPMJ6v&oxtBVm<{0$PNgg+mdp)XXdr@3UR} zM4i2Y-Ff|J(Q}>bz10Z2J5=$!Srx1>lA+Ow*Km(u3HinOav!!ZM!Iwg$j{HEx1Vd{ z%*tdCtB3O9+a_XB74zTSwgFSd{U|o|8mRd%LSA6{!UFQ5aS%jmE92jncLw}Z#nZI$ zr&|MDXcJdtMfGFLpQ~hl&>qnLu7HOEl3Cxx{8KH}=(l?#Q5i1J$(1@`S^g`S9CBH7 zI#Lhm*bta%b&rpq*@xPXi^*qGV{l+vdd)F+;KK85)P{NG^4ar0I3Zd<@+OLH?7PUe zg`3FT(~68!lrq4;S(#LX%D$E)d6*OTiuH=Yb1#B-Rwz58zv01EyU8BurPQ3=JMKDl zK}3E44P!O`ll2yIQb{blb}R?ap50HLdyEE6He=V{RSc#tjOd8lsd(;~1qt5QD$r(3 z%RIkWZhVb1b^T8R1BQfwp<5e&(!oUhS1OLUpVtS&ST*c)=>cK!5xQ0-5@mX}kn-cc zf-f&7iq#$a$Qj8=M3dcrM;Ed8mq<{>m#H{8%z_*(Vi{x$7$-zC3T}qS(LJBEQ7MG6 zgXa10OOKj}-G{{yBjpwF`+)++xp%<*Cyo4+9u}(m6rw8 zV%5z3WOt!D++mt?tCLsZwUs#?#kg(3#g-&HPJ_F>SXWdp6~r0a8_*$_RB-CN$Kc&@ zj6W!PhD$G|5EX^7AY{A0H7?51!2$6$ikm3fgyt5kqA%iq~%<^>~{NmH+c9?YJW zH;_L#u93}N!frv8{S2z~jPaSrtRV9L8FTSWi=un26t>N*r^;;J)pkD(ln(Uq%dc0X z{^E@!CAg3qC(YPm+xo!ni306b zi^TnoE6DuqXE_I5mY;s53|?f1(z;dJnA?yKnP21in_p`2ipZYyjC;?;4pKnUiaxm{O8 zMY%$_aQGN~dPW^RB646&q$VG_{w6-!wt;lsRE6hEUmYBJ5$ffq(CF#xnHR(pyJlZ5 zD}eEN+&kg1Pdxo@qk>lrT0moiJi_No*`2|{o6f!HHzt!f_u4@`^J&g!Gw?duNtEu7##JVaaThd$bN(PD znh+DqZQC78b$75V$RBZ#kloE2>LJ!>Sdhs91)O5K9RAyL7XAbrp+5zYxb4jWqEfe4 z@U7zqx=b!1U3c$7Jkv8Yd_kDJRFaxpjmCpcOGtF04_B10i2pKD;m5CBdeTb=2Qyw@ zdVeUd>QaeAT$hl5$9>%RUUm+iIu8;#tEkReY4KsZ7P2r^2V`C-;T`oRP_FZ)ai?`q zy`&M0zul}baruNZ^sbULnO$txqks?Gn7)G5{ILJ3a9Z?6;=5apqwBY$!n9tP@;*dl zP^pHmwEaNYw1&?%eT_XUN{HIy@xVyuxHYs1$^)F}`2*~J^lt^Z_%d2BJ7uEyPTvEv zGkX*1?2yN-D&L+=Mrzv>8<`M8xF$QBDvd?~`=Zf<0|*a*%}U>YR*0+1FM(vP1~u=$GxnIgU? zF#fJ8QaTeiQ1czxPK5su3L}5r<15%MKI~LHne$K|{H;}S)yr-$*87jn8WxFHJhzf( z?Y@Gto{8dSxwmBDj!8s1j`_Z8OW>W)Z{D{$1z%7LQp{U%-A*bPD2{=5?n$)NRU22Y zje@JvKKy$2d?vEz)9ug-(5B3+>JHPV1aF&%i_j7P97^C(|?GZ!Ntd6GTc zUv3%GOV2Q2J)!kRI?^B-FV*p6$DG|~X$;9f4cQj{bdPT&s-8JSzJ46W$)1qLI)iGk{PdZsu9n9?SJ-`))%ltz zim=O-Yz|_-Yrww8W63~7KGg54DHs zx6>1j)9@{=0YMU&@AzmU-nlc6l<%wnx`)k+9-Iemqcr{A+Kmaqd{Vo13A|wM&d1A5 zFwS;19m{;s>%3PItv+K;l6j3^9=`#{?CYsuGxP9fX26AOeZ2GP8XTs)g&YtTafXYT zriBk2;NFCOoQb_Bb6{BIEur$kcle>KoXmew01ehmxB0jkELqm-?Wzd;Ub2#m&pFEl zS!9J!H~g9xHKUcESM(Qqf1&Gp5w`U zZ9#%-nLkAHI&ThSQDxStqj$@F@PA&<*M7K;WYRIRzU&UCc!bU2cND|RHEy(em>MQ8 z%YpkRH2CwcN-=B?+xth#!paaCT(=-#fOYnC4%Kl~b<-o}%>a1-b-U>RNog|L;kq31MG@RElmc{jq;eD=*77=3aD`M6;L zyt=P|H941H`+Y?^i=89s1qsZ1@`96$ki+8d_u-R~IkmsfvMj3{iPmld?n|N;eki;H zv+Li`1!*d{*1Qb#q|HL1S<74@%<(un-GOTxs z`Itcb_Me7v%&WC$?*njKph-t6MxwXcHnM+|C#UgI71zwFg-4oKsTbqx09R@FerF`P*XVF=4)yLKn8zyrhNA_xr#; z^ODfTwGTC3W|IfjtKm`tt3QjxEZfVJcFekpkz<#T{GjQaImn2vxF&GkV=mJTjKO~S zO#-O>>fvYfi*RzhCAm~yz&-!|KR)x>0S1ojbk&P}viVDh&Mj~54AU??FHU2*sCjhMNL~DLCmn+Chw-g$l{jp^H95HP z4fjx00W;q-oiMSZvHs6+`P4#kY11I^a8$zgtxW^H{Z2ze94qXBlGm*jJIr}pwEQU9 zP%s1J^;y3$Di!8)3+Wo>W6k=tndGI)bCwy~FvjyWyv7jGLMaWj^$UQKxpn-{tuJs( zQW4o7HV)R0QAW!z&EWghi3-`gT{d|oX0dQYH{3$B@4IuArV3c{CkUj%!)RCLQ0#gh0$!RPe4@WH#??H5tuF%U6Q+aJ4s|3? zhE)ppkIF^USBJ>t4t+>u+IzJlC9px$h-zL>MsHb5Vi|Q;Fvw!GD7p7Kw>j)AJ*TIE z$x|W*SZ6)nEXQF;B5|E!0C(A)cR~Ms5FXl1$Ftem%ioT~Zm6H&eg8ypbl*Fo_-qm> z_G11il`?qV`62maF2u*c-6X-bhgWjP=0ocZeqQY6d8&qQ#v!IGLtPX9iSZ%hqKiR&a)! z6DEUJ(PvPDI|B<~GdfZ?(&v|mV27d1PLN_gt!_yadusoH^zi<&DIJlAX zvfZ3Tg&ba6mI7CjeCV<>8rbfe3|f=^2p?f33R0I6bCDW6ILbHxO5Sin*_3WP6p4wG z{v(~SCphk@7OMI_f^ULUs(L^d-(=i{Gs|sx>GJnD*Xb%*eRMMTwlUtCWip(6w2RJq zJq7o&nqPO2GasQoK`fzootXAiz;4#-E?egf`#PklPE!xY-zp$IVk?MZd;qPcMrgV@ zlj?*qeNO)>qBqlo%gR*6_L%a4EULz}%DDJ%CgiKV;gf^~xU$=dm`qFJrp{vL_(Mez!^MYk~t!svx^@{WpoBir-SxxNa&v8qhsbP(U z5af1*(J^)UcsjTe-rDB!=7%N46I-s3K-ZD*%|QwK7hZ<2wVSEuQE742ku&7W#vsAx z-0vbYkE#JSg7tEBJe=PF`dH69z01dmamUCSzD8Ac4)84pIWuN59XN-%v+MzJQSd~^RG!cKE zokYIaz2wfVU^~r44`H+t&~!G#`MY{M(Wo@w%noRw$G1k!(CW$N>HGL= zaNNL&rXSJ5+D}(uw)7$M1!;^`6`4dH7SzFX8!hY^{dPc;6S$)nQxdaD#E+HmW1SNI zExZZ;7EPuLAqvmzXFlupXga)Lu*?Ut0eA?U1OB|~~EBzJ3OaBJf z@lzfx6feNK(qnYol1QBQ-+$zz!9Ky3Y5iE`Tud(ZH$iu`GF~gFhAtCn8lDt|kKZpL z?|i(uL3)bV7MDKI&woxIhHYv&(3%;^|4bBPH1p!ks_NsWRx07Tav!M7Ttl1NdeC=F zA(>AlAcf6@v)0{(!LdGcd;SWGJ>FKiWtnN!!?t|v_h!{ z56NsLdsG!TvuWF~LHZ3mC=C&Qdx7^~6q9l6cMr1t)WO=jVDoqf z6|fmjG|M4jn?-@ut%>5R=bw<{o%W~!|t1kk3ic$fF3N0!0ofQlkt(2!gUfw_~ZErQk!c8?spZj z=T|Z8#IZE}P!jIawIue3TLf(mhN8HCrCg8M1$wbx3oYEDL2pSHuge%*`bU`G=b!<| zZIVN3#Om<%-PD`S?X%;y6Q9F=0>5t)#eO9p$hei0iG7kP&iGgk+m18$&8j4nXZM8( zF_v6bsyf;#Cqwj;G^+ni1*gmo1GCt(d=%4}dt6Q;6Rqu_QcE7~R&;^R%RBsr_Gc&q z8AM~k5C}@v#!#Ly$@fc?cP;;kr5D1<@j0_$INRSPe~AI>ujW+dTm^a-EFu~gl)1k@ zbVM6MLk8yd_O}&rX#C@WIzMmMOZ;t=MZV1$57XFO@u)-Ru`l>4U?P(d<-5D#G zx;78pPpu(yQzk?CT^00x91pQ2x^&{kYSj9^oMa9<%Y_`0#_3sS7>~i9R<=jts&z-m z>Q+6@F<2Vc&#i?S{a@&rYjT+3ML}a|9zQ5vggchHv)uD;F3(*VgFUlA_sB&W`cMZ$ z`!b;4c`)BqK(R??2}x~H1_d@NK2*-~J>QxzT@c#^k2yjnEjh`lurpdC?=FNqilGy} zvpt=t4o)sx%$sC&{?E_&u2BlY}uK#RWcGozOa0^1`|%1`PpYPR%A*;ExlBtgsZP) z!g}LAzRR=#C#74Ftv3@nMYad;HVB6g+2?8JLNzoU9snl{5`@bC-Xi^1K|G8LA^xo* zYUDSA)N@68nfZTvCD#xy+jE?RygD+<8e__a(VD^PIH4wQU{=34cZgVN#uYN^+6YLF zRmQsJE70TMz-BwrV)r1H*SRoAV7>jjXhCN6z^wis>uvU?w1S^XHGl1OKK}d9jTHIa z;evwX&~SL+K%V%N#YL!{Yco*K?=TLSuR86!oQw2 zWd96vc)|Q82a+OSeT+ISWVJmuFPV%kW(=_{N_cW?547)JNcGt)#o2BLQE?u_ZS~Yd ziJ46U-q@|(su;+0Q2*mt)=j*QR{J&(%e%3h7uz4@ER2U1b02!POAG%ixCZw+?+V+` znTX}yCzFY0o-p|{c=IRH)AO`}=p0hDJ|r$wS5!XYBDl(N%gkS_!$mEGN`* zJiqZ_IWFRM5dE8vxa<*%nD{#ej%PbjRMWySkE6k%{h+ynka4$+QV3^Q4;5=7v2V#y zve;0IKezf7KGw@2IzcPhdC6woa%_ITVG31bn&imzCFFq4G_F8F9ra3*p+)K$KkLm+ ztexHqkRHr>rYr4Qbf`v8=?ENGV2p+K|5WV za!d=cpmYh@nQ?)$)l|fb?=xW5syrGa&_$$K@a|GLzqv(>b&@vZpYt2;8}lHmr29as z^lJL=S2zBog~TgH0z6HXv0k?o9uD`V;m#2lR=9?QT(uOo8fD|>;%(%T!8q`I$$ZnL z83XlP6K-JknpI@w*1=rsE=N?F{ubQaLPUCw+Ssr*1Z>XV;hQSEQT}ovNgrniqc!BPQH+3VpC~?P(?e4BZYGAzTTv{VF))+wud2fPySI`TmhRkd zKRwjTO@z0v(&*YBdgx!ve8i7D`PeoYytlLiUcB?6nd~ln`v=RGGP^1KKKwQA8I?rD z&KqEkKg)kFEQUuhhBVtI5ieR;k`*q^g7^kCk^g~YPWFNebx~lv=!6KUJ#mkZVg11A zpULFOO#@h4EsINUb%KWdZrU(561#nOkZt{bf|*jL;`p#nB=YuTBJo!RJG?946UWeJi=-aFY9(Vxf zlp6V;6Q1HiK?WIqaWJ%GYon1>6$Da=@@L{381{lO0jL}_on_wG!gvT%2I~Gx6R+1q zgH)cQ;Fro!(X7u`IQb=pbfT*QM(R8s$ejAL=Ot>hUF6!V@orC4yUk#hf+|KGN`!W9C>@n|69axNCvD@-aAgHjIBNJ=c$VWw z<GzmMeg6dd??5El<+u_*DG$!4S`ls4 z@4=N9*Qj!f20mZI?v;|({E@IX?Ein2sD3sDy)}y1J2?x2ZoAN(BWlowo#{nG+s#cz z-o(_awq(ni4Y0nDo%^?Z24*#NDc!i{NYMb7zGb957LIKin92Xb2+Va@NAl-S;5JFB zp-(@%gS@##Cx2%e*U~&#RsWv%zIGiuUo9njniDyVAIjLWCmg)CdQo?#5A5@1`HA6i z!sDH9@TNCUbf*=Gjqj4y&OtB=qHi*?XZ;Rbk>598l-7h?SD<;2NZ8kVvB zj?>IAc=>21jWIV7$B#)Ray5S3$rf2`KKKA`8phF-h*4Pc=>z=kKgK&$^kJAs3K>^F z5tgypS_GS={JCgLZ=FlPxW|^{zmq2B)*p(nchm~v`kw$sU1Pb2Zjo^KusU7HIFR?} zrjiZQUU63#(|&eH57>TMK*>FpJ5#=sC}oV{GKXlf9FP_$^?pm6-m}ldR|N06v-p~X zGF)KmM4BF_aKk_okANA9^VaI1TXYT{G=BcP zIowaYLD$KZ_AQIVHGf=5>&g9s#BX2m{QesxD)=t^VvP4gf2#*(HNV;U__@o9>@U8+ zJ+5YaPFe)vdv4Hihjj6?V-5tXM(_^~+(c=&734_EJ8qk^Jl#%ip)N^Y$Rs|Lj zqXY?9RH})(-cP`zA&A~PJPw10_rd*hofSHLS@>GtiQKhfHQ$o)(3WOGPT?ZDLH`Es z?ORQzT^!8a7{>b5LqVYWx0b(qqZ@tNi->fDAsoNY@^Hts!BDH6G}W7FEdN_a?)bzA zKHZxrE|h#m9`O`| zOg!((YcoBA{QMp`_30uFAEJv(J)gtf8w-VtruU)ih!m3XeIvN&vp)6-edyQobit+!Y5_N?!aB`dsa!VWt6H+V16;6lL9NSOm7Kk(p2G8Ty;cg1y=@o^@nAQA^)7+e-#h$Uguun zUawpd*JljY<5h6$%zEInH&Z>m2+Yh{LgaPx1#9wiu%%-yF~Lc2%1|B6Oj9AJUXPCW zg@_Ls_h!~hJyA1IC5vJLPi`YYY=j_KkI+rZU9 z%+EYYv8%>opjU4@{6Cgd9yHGgr0eo^@vB!Z_%#mUJ0=P7LcJAP6srVt<>hgOz-ORW zS7!TM_0Z$w?;8(JzeW+O{aPV^Sq$A}Gz{a|Ia_M7iq|pD!9}lj67gyYQ2C&M*M4OU zaEX0X46!)90#bsfm~UAiX8U(rVw1WKj#?^W_BlV$94$jP-|WVq+F}xW${L>QE8(i~ zZOjichk7!v#Fr22$=vJ-oQenAMrv4D(3<26i=dN^O0e76t3|K$hf@R|Dr2Q{UOWd&JpxSo5cf-@Y#wxB9w~UvUlGF<*H!)h&gr-LBMHW+-M{6~d>E z;k>3-0T#b!Z1yxMh!rYfOMEyCKQfC>urv`nTuCGSvi{ty<+5m{_YlbUSZcCQ6-P5x z(wxs*`O&R?c)vWA>|10CU)ovT%J_2j%&wqA$Hk*lrX{i1X>9(Ypa>O?+7X3d0ob;& z?1noLu;HaDRo`hM{&qc$T+DpM&2&=2wHu$qRG&rEhxvofM(if?iwwC?rgIa)T?kzA zmL5K>irK6gu-xn)M$DFkK#3H7<*5XmG+Q@S!cLY+Ul5lrxEtty+(W4eCD1U%fh&0%)dOE zi@$bmAS2#2aoVa%s2!a!ps}emoPr0=2;twgAoJKZ6S0#)I@$HU9;E+`#-huEiS3bV z!uO+I;I!8{16q31b~TJS(g+5|GwG+;2uy6UCWnlsabtC4MN+Y8+%cO_syUA3i5n`XE@JbsaRuBRp)4kC^@g1OBlI5YZET+%CxW#uf}>Jj(dpj}(rU$K9P<^? z=R^(Ms*t4DheV>;nx*8Lq&JspuZ8KVWnkSr+qd3o1HErPw2pB&pZ;4vz@q<>nT6Izb`ama zzVPsBg^dIQO6>S-G@PkoQzcH26{?XC=FbMl`E2Px@8p+up{1W?rQA z&(et1`Y{khrO^4yeTX^cM8}axoc&`r39RxL)F_yW6OF!-vDs$Co!zf3rN!XhJcx!e zPn?_!^CF2CaZk$F&dVVY?2VIX+uEVX$tOW&k3a9sp2;NkOsZ{L2^!su4f~=8!dKtr zpRbk^N8W5AI%y-}R+2UrPpXCC%LbL#ZOFy3i#Cwcj|aitHWhq*Cm9+d7f>f{5y~;9 z*?UQKZrMd$QKd}yKo9>mNESbMJ%rwr1H7ThTa;Z?NLHdLoSmtL>X+_-qLU-N%4Zzxjf;;v5vXuV-wx$?(lz37?vVK!Xc`{NMP;d?=9`>U< zEDdp)xfD^ZOBIX=mB#Y02Jn0Ol|Ev6=@SzG2K2I6f&dY5RBIAw9;fTpT1N?c7=15dL>qc(*o#I+9Gkx#u zcCc6#OTAe3fpPn7_`St~x7ftv?k^|F1A9e~v{%6QnOQKij`o86%OBh|L`>bn$<=EgIosh6ma^~d*GC)NFP{5V!Pr-;&RlB`^fZ}gVKcHJLL-f{EKP( zlL{c!B!-{4Q7ho)9gGg?A%uiG6vWA zQj=;ta^%>6ma>2`Ie#{>d$HvOs-D6A&chi*g=HdcUnb8OfZZ@!s7VV=Basi-OP;(y6hE-wmXjfuAvyU6fc2d?0lEKPt53OLnt#YqK zIA-o@et+0H7^BI(4vH1c=$f+; zIBeQ7a{9nD&Ud!7C^sr~pl=UgKU3nE2)COa@K)c;5o)Z-)ciayut^R(5`7`X_847s zIuZ|6xs&I52Lv8T{rE|>f&^W-3&47qH$F_WUnfZ$jU#crh7Eb@>dlRsr->_vmO)T; zIW^MI#_%0EfYxEW^n)_o@419H)%9?u>ar;J!W$-^TuwW zzp*bhV0E}VZ6g_CZ6zGKIvba3>?R8j8bL^+Jj#s99;ofDFEh|9%7R$ueGvFw)4-Jd zmw`E|c!Byebg;QW?#(uWrr&I@@sZ8+*6*Q8Y`3!e!$zVS94pxId7}7k@Jmvl?m*O- zhIYG3F1(T%NwbG%;@fr$HhAk{ zW%c}+ZWE+^aim@Bd%UuI8L@S}E+~9a$#!r@$eD&ku=BDi<_$`N`8S5qo-)J_zZu`Y z=`=UiN)qRd^n&1CU)n!>47PMhkr9rmg8YNh7=8B+>@4|48@w2ovXjl+=7{)bqf2oI zJx1E=JGg~Rlkh(s;Bv)4x_`GW*2!LHJ{n0r{@o2+h1Mj~RS_mA%3*7YFQi$U&|G08 zmhL-A?x&pQ?r&$>^@t7#YKx^djHkM+p&9<1Tf#qT$VR6Rdx%_y1kAtBa&=d-d}mhA zSKDXcV=YS(Z%}4#JQeX>f*q-_TnEAIK5G|r5rQVl(vBlNNPd(Ne(^HsVqTB==3QXu zI-kyGn&(?v?MY+7L~a9{lh3RaGUiYXbuwqZ;MD8Tu>T$Z>ta3rcY7as+I@rT`J##X z1@W+e&8c3^P{sG(FM;#I1mVm(uW|GX5y>$u1l?Z>cs8^hWJ;81n0zE&zG_c)wR>^v zm|o7mvl6~Wh0_kU_uRLk09sc?^My@uuut-PQ$2aTLg4&+9CXi!3zWfY8ec+iFIlTb?L z0o?mDjj;}D(MQgi`4hERo;u4bk&R;d%vm&jn~C^rS|+)5)t@_L#dz!mAD}Efix%3d zqUPmCu=E$3z4zwhEN4&Rwq*!BlTyG*7g=Wao8|P=^YQ2ta1UVR_4!i0)u=jn4>54H z17+s5@sNlb*sJP0nTUU9<$I@WZbr_*XrLmtIrf8 zQt5S&-XqEO4iTs_YdLv+)|(r9P!28n887i<4*j@F3x~eV0h^9c{=0h_y4|!Q*F-&B zEb|4+ZU_M5o2%#u)hGCQO)07BmjGktNjdPU9WwX%&?&(Yc#^Xxe{Wg|59np1x6dA; z8e;_cY;O6kDI0dLTtu_7(y>fzLB`<*X%Q&lXiu)T#R@70nTj9m=p~yn8Ka+ZHoB#<|=jBf^R_c-0@ISu6ZW-pyk=jSh!>fe>yY|wh6Lj$Op(NO@`$;ms3YUQou^asM)jaLOw9I6)KNHhhMVG2Q%* z*AvC()=Mpz*0u!XKWn3Q(k)0a8C?G2ViDeRb0Wi)Wq_n8)!c7{%yUT%|YiIMB zDa*+&(*i;B#$3FTWlxs+n}OdTRUDU}20<>v=+%&7r0l#-@H@n{eHenqZ@pl~EnjNI zM`FjAQ{>02k=%*P()ib>32r5Pr$boAqU^{{NFQFwJH_Q-SH(WETfUJ~iC4$%N6KK+ z`pZ;Btc%;96abec$y*@n!A&7 ze9*Iu^eWrInGi+PJ{bruBW3CMqHes9bA$Yuv<&dO5;__^0Er#*sqO0sbp5`0AQLuY z2;(8IpkSk4OURq?>=@53H-h$rk&`Q^OnFWyaP>ERBP)Uw!BfR+BZ42E(M> zc%jtqUQCKW@<65#N@g(LlxGL{tX8I7QzJ3Ybqm?Q;ykCo&fI>@DwtChPHl}Cr%0j@ zp2A7AI<>K(RZ>7Z6lcCHHk*B%Yyh1=*_HlJDh&zqdvc}Z|=c)w_|&aDC8Yui0V z^sDKF@fOuQZ~VzppL zl_KjCqG0^|S#&e2^O@taNol7)C;ZCpu-zYFXH6DOl2yan<=sr9vYj^?^c*$4Qb_%I zV>qJ9GJ>Uq(CTJOBjy_8q?k4cRV|qRWMvJW-t0^ySFeQVSas~Y8wZx*T6BpI%j2-g zCX+N@b4{Eqo~Z2xXGxBhFzxp$RTm=BIhOmRsfES2?}OvN_q6(>HnvW<4b$8Tc^ePL z*ngG`ZZbY}v$q+Nc!VWSe+ku?FZ-rPHu-t@4A@;(W}2KgaBuc7I+SUy!ne4Pr>$qX zc}v+&WLpy~{&|&pWGgbAB!yBvV?KhRM+_ey8ORWk94wC;z9ztO&+XKl&2|4W5mz5|JsgPI6$w-5fe` zygHVKW6!@jcHRN z;aX!8uOj)H&GV5Y1W$yrAOFkFegua@_tM$#4e<4+H^9qG5FC(Yv+F5+#An`CqLZSE z{fA26dDR%|dM*v0{jwk@cdX;`+4thPJZhk}OJ$ni*@M}jF*lG`=}^HTTi*eyT&CH< z+Bo`EFRXpLP}udT7auBRkk!vN0XJF|=e(>0+kX@2m%wW{rposP0p-01kyGb_ch&zT4zTZwmA~5z=hOFToiO#nu?46 z{vus4m1wg4xYOC{f!ZE*`WlLamc;Zn;a<8cVpexDj4w%~ZJj#UbSVW|?fiND7Umm` z$R=a+R>2_VsYz)408?Ba@_+3l#T9|K$+%&|pyZ@BmIgGyT#doy{%N@wUd23m{exk) zqzdkQk_KP07SQ~(YTV73Lb;E1xMGoxD0o)Xz)Z$RRT^`QAHk?)`}swC`*2HFG3kA1 z3WqkRVA!!HFrKuP&A=njEWnoN>@N_6E9T;zf9#GBX9f;Cm9UIu06qAmL&r-LqljsA z&kGK5e;DUb+dmM@Xb6qdjKbfmPm>pABe{>aq%n9`GXz`ypmPma{?7MS$k3!bom+}u z_qdZ2S39|3pV-WE6Jtu(T&CW(j5TyK3+z|_6|ON9qs-^kB!j4f%vgD}-Olvbj4kgr zIts7tK23t-Jh>RwV@!4HfZvTVRB56bjvsk!R7_~&7I-Q%9db07W;@dUR%!7GX8h3uQA4Z4|%Xm$DOz)WW9b~dNAu_9|u>T?GZ)v#UVGiW@|qCpwV6O{1~N)#OU zneNYVvvwL;x!eS1J(I_?GkCBmwxxd?RPn8H8DL=K{I%o7Sf;y+XxrF8&I@(?dMp8= zjkT!}(*VB^<&d>5uQ^8vmKpc62khr?bj7?#w5~ir{#cFUW)0WE+=HFaoce*?KTEM$9633#oOUTv3ft;n98q$m`C=mtF^%|P!aWfHG^Y02bvz+k}8o9(xcn0Kt zE8@|meIWX%OQTsomh$HSQ5gl;4Aurt|nqvk^-_xRPeQ zSDbp13_2fsGQcRIhtK_4 zjki?o$=DGUT>Cp|EVlI<$ouwSyQe54Pcqf^kf6@tBPz95kXXNF7^lYWl`Mx{*e6A! zSpM=YS39!V+=p|?P{(11%9+=yoI2!dV+-^6w6}-z7sgExXIKe|z1&J@Yhe0>RhQt| zt+gye@F{kE5|W6jArPg_*uRwzV70)H^4BBK`nm%-^4(gvaBU9G6}b?XXk+N^k;A;% zdGNPu5#6MjioFjl$XC%DLD_UIk&k3D*FAI*HFwZNPCEjEp5EsBm0x0UqlgUeF#(nL zEK^DA5!j#IL*-dN>H3oO@9lAdW_eSw-Oo4Vc+FOl`dkGUzbt{eC1a?{^i-CmYe_Us z)^evg4K(XafO&=Sbm1ESu(OYy&pxCV{T6-vqJO2CtozMIuJJuzD+0hPu z|2+{pr7b3BKa_D2uNi~UxEubL_ucNvm_lX;Ny52{f6FuoE)Nz zV}>wot!xJ`bK^NKyiq`!4WuEjSqCe78$s4@Ncn|Vd6=fNjWkb^1nt|3SQ(Z&prt9> zQG*k`?a7jIU9O=;3ZJff3`2wV^FPgdah-cHnN>a!>djOz%YsYWg{@)=2@)dl-9PH-r|}vRz@H zCuyBDig^a4(f9IQ=o#{p{%ujmrz7se!xNO>wlW{7)Dco(ewWi6#dc3SZa}|#2vu`X z!wqk;2RH^pzLnsdi_6GY83ov%s)T#kJ|+K)8O^#AiGII53H+31tc1wU^SPuW)?@y2H{^F=!QV5+trPwYf22Sq%?gTJ-ZC{w1)C` zm3laiTSof+4HD`NP52vA5q;wxQo#N!7m3vTHGS zIy^JV&$V#px|)u?>dNMHRMq!msxkKjAxi@v|CYkYitU`~Xyab;-OuW4AV%1g;VHF^ z%(Bh|x}Va)?3yUJ^=k}wKO)E9-KVf@NiX5aJAE_^`3yS2sk||jp6NNyq1|ke*tjbL zV|Mv5ol~9Qn}r4*8AIJAA=9{GnI7I5bQRV;2(#<%OgNdwmBdGN0rPGKXiVC;{{>?n zb!L$KjC&?K`?Fb?DpNy;!HqC&gTMX{? z+C5%0OgxXO+nm^-l4F7$?cK}@h~54E2zO00!mp`u9s10vkP=)vin_EO8-v*t^5*q# z1?jym{1o{Zy%K%c)vf+Q)*NEsPzTD~@<^Vf+82M%qBxJa-M}Go4T&@^E26#CwHJ?wmF6?DKNi2q0*R=M#>}Pu#9o8 zP)Gc<@13YuNXeFel93;~WHx)caip+7NmX_%G_^yYnR}D+ZqrhrtQ&Q|T3N}1NG7nc z=mSmLRIx-k2v#WjazD~1SJ?V7dxy=E&<&q(xgfIQK@XvegEszAxDR35RJjvzxgT1( zcH~$EL(21h&jWrsmv8qs#xH}jI&!S82bJY^*UzvgANxSa4lS&*A+}Gyxx9E;6M2nF zSju}NO1T1R7es3UGDIk4jkvCI3G*vpeKV@V8%Yn^7PJCBYJRbi^`ib8=Nycg; z*-`H};dT#u-hI3w{uvSqi=A$ZgMwRe@vNJyN4gDI+|tBJMO7V{ri+zfI5^Ooje|>) zHQlV`U!S$G$W`8~(7w_#Xh@tM#V>BA4iT>q zNSWd*R?rOd^<^{2vQKc2zTx=5&4)c+ctdJ%@jY$`OJ_@>yA!Z8=`a4VO->`&W;!!QI#TBX4@)f3{*8|2yBJeAEU{vz}SL)3iO4&?)1i1%z7QL8+gtv#;-lN&6s zf3KG?ex7bo(fw9jw=RNZo*Myn5jwc=WfCMFV_Z$M46QydWY=Zpg4Z8YnO~Pk;kagB zekDs8gEi}56s!~dSG+--pT~ASwt}8h^zi293Md@s&6{2lkELxk%l9W2t?B7&YGu!cno(kM*DKC$#*hi)p#_kXIeUQ@0r4P}vjsZ<@0> zxc@thH;QFvWkbP}bOwvbd2oJ$FJHSe9(67{vMsZ7C%pbao#t7ySY7)pu+}xiB~77F zK1`Q)S8G7E2b?JlodMsvYGK#4HK5;P9DkueXM);Nwmo==aQ?Lx-s>iZvA@dr%s>O& zbFdiXeZPwCe~JA&U=y?LbyXNjT3M#{Mfg;Ch_6jCB33!wTNflscZ6BX*B2PtKbESp zsoS-&p7Lcn*Yr4$Pw&0gQYLpjEacG{Xtwqy+?I#&xf1eTMqTajy>FweO_vp}?Bu*k zA;ec3zr{yEeXJKRu(^h}$GNa+JLgEkzPHKt$KUPHXOb3c;gSi@;oZ~g;^rp}cyvJ$ z>-9kuuGG@A>0t>R?6;3^+DEyDF@i@kF(mj`n`4`_{J89AX^G0^H*1#I#1r4;A&N~q^ z;kJ(y0{5S{lb^Jb7jL`Iwhzt&!;O0AWq%3Mh8gi(-%^Zenan(8futP9 z)0TzfjXl2Xn|FWVdKVMSkADsc4WD?@M|FJcA;SK*aiX{;0$Z0mvE^Tag~AG5oRyaf zT?Yp7|J=+lWN=Q9%oCjv%MD^RNY5n z@|(J?owL|jr@OGgvNK-2pvVkXgh_u4X+%kvTz1gG6?T88jQsI($SWJpmz9O#q{VYs z%bSrxev7iK-@#NN_vRTMKs(&=-%~nx1&&*@F=gFJb z=>RJ%-7Hbk`-{h7Z!&}H&%yYkHrDu+cQA+d>xN^uk~ys6Pk<1#K?m!D@Uh0?wK_Vw0<~yzcs0c2m^?9x3YKILhBiKfCj_+v!YbDq%Bks6w#6Hg?ylgVard zyjo7ZNG40!f-WvnyYaN6AHJEzxekJJ(ORfCA{QRoIdR>*ID9df@(zoeB_py7WzHYs zgeE$R%qfp%Wfl(c+wX{r8e1^a<`!F#Zv%$y8ff>s3e3hV@`b&QJK5;O$*E4Y`W%m6HvRLv&OXydjfo9X+g8Q+JeEdoJ z&7v=(4_2~cwza(ap@RL9)Di6HF3P_rUxVbK|HNN?BJiHN6Z82b5fsjm2KX-t%4_0y zuXtOWVtyO?WhaO)oDdy@rm$`gKME_%D7&%vH*~UjC9ePT62<;G?Cm5K@S@#lFY45L z`s85ImduZ6HYAdbO0b2Q3FJdCPKF1G^pm$O#XgT0vDQ`Q!i!c@nd;K04&BBhK^YGR zk;k=Wov2TlO{r22JM?M*#F6H6IQ&tEm!_KL`Mf=InC-h9Ns$#XFx8i^o$rT1o`WU^ zj7$XQ!zR4Pr)+#X&6z1QZ4{14w6W0cG#og1h6j#~z`X$n*kFfV!gy6RTsh}4^eOqp zCC0?4&wK=vph#TyBa8YhcCcG-Dh0`I19ZAu42PW0@K?V~am|@Lc&4o^X6?!)CcF#F z^w)sv@tU~nG;#i;t@#s41pW*@z^rThgqh)_J+7$&=cQ3Rns%?N{hxwMk+Z1Bn=xlV zEL(qu?jSNvG&RV9({DHOxxsO`j^>b>wK)@v=ssfBOgZSXMUe7EpSqkvVcT#WF8VZ} zy`PK)<Q^jEpg)ENf~(mqbr*pTPbKx(Z<0A zQE+UV7r!4u_tszMVUJ$Sgsw4dvf%Q2V186tw*H9*KJu!8p`)&e=hipi5Qk(oS6vNq z-HFrdSq7sE_wzrlhN$g9TJ&6Van$EBOvv(OOSH_O@U=D`$c=`*kBQqbx)`stOlAg= zU4^;^^6)5r1LuG=el?5oDRejdAB%E)`5W{-k;bljTa(vB8y~E=28)<0S1G36_Q_I+ zKN4Z*veQZ~`}2UU+m;9IERmy-U%{90pFY_5g!K5bm5oVvEpb8r|GFa9|aj=M^onDO>t;Vs?SyKAO{=K3H$ zbE!E-7N&xB-)dBlCTJ$?pjA;?un7cuvutK7W$7tr6HNcC*e`PqQ*Alk6#X_=z`mll? zXS4Q!b5ner4C+DONDjYUWo5)tmO4ta<=kLABZ;7#dGV=!KK>${2$$C-*xe4$IE>s zr9IoplvTpiPCW))MPjMNJc7NC)OqYb;=N3o$No(|DirAIV92%th&0dTyN-;-VLe~M zy^*gLU4Y!1>WO{xl;THFLMJh??V)TuW>Dnixg<)^_SL zxvYbdrKO;5punpl$k*3J3MxU_66ZhK=qhweP`;)5-^M6~Q@#R0|D3fTL?DU#kiL^eAx{#K#3F`o?#f-b2$i^N=rn0@Y z8wJnZTKF*iG`#+Gnrr?FN1JMY7J9FjFyxLZ_M@|R^MAj&%|0DWse1%Feq0r;-e=<9 z?>pGh>5qimXF3?OmUNr`C%H#_e|)~^E{wD=5@%NCV36)~_GX6$d?A+0qirFuzHm5q zs;2DcZGSd@*a6`rJ;&L?8icg{V)_pDp2RnhFo|Z zxRL8Tk3qvwN49cI_Jmt`lx6NagJHD`bf?|@v@Yj5n8SZIyhIxfIa^dW0}4qiu(f** z8bikN6TQf{7PNvLix?^>j_Zp(9N$ou?HwPp+YtLC%HZzv?_!kfDn2e;%31@{1P^EG zpnsGAM`<5jF_HfNCqkgtgGQDa`tnz-7twqy5NH8vc7l&)YO4UP!^ z?IG=Y5pn;%MsO$M3G|}YaoFvHBXd)vptSh`<(5If@FY;V50MTRZpqt?rv zB^gujNhaBUzr$m5koA-n#Y1%AVpJ#x9RzJZ=GlM!eHSwH( z9i08;DUL39gSn)!hn85wJ^F6Py)T8-raAmhc4xd#*|&kalwX3(|yVwZZIrPJHR=aMV)U&OXi?AcU?r#tAR#K(5oq zhtM9jaPC9sv^qx|OIr6n>nTiKAy_z@NIV3)47hVHh^MNVkLEa#@VcJ;?fGi1(d-Ls;iC z(wT0WxH$CzeDE5^n<)EG@@77>Fdr?vzMv+XlA9&0*dEGzZKiG}Sy~6L;PQXjsMTW{ zBfz}S*-aHocOQqTeYfzY%5bdHJ;-cBw@7lAe!*J#HTLJwV+eUgJ&c_yI+&9QAB!k{JPnfO*}9V3M|Qo?4A#| zwmb3ZZZWuSy(1g0&?NbWhBDKfM8R&QJzpMXjIE(ja4P4%_;kS=EDbAVJ9}HhF&)Yf zZGQ$f$%}b*8|9v^tYD2XF_J0P*7EGRUs$!}QZ}xF_~AkUM0D-N4fn^OW|Sk#d^1Zh zzpaCh)MB9eV7??v^gYRB z1=)+>*igz1Mcx1|T5%8Rg?!L^3Nz?_L-OyPfhKh z%HHonA#$q@4z6v3iSxGew}~`+tliG8jVJD3Z)>^lsZRE}Yi!xdf5ZZ6DTU~h|HNHq z!*HbT6lPUFK`^6Ey|m*g9l58LL{r=|AQf`Y1c|K$*Dx?>u?pgx3wQ;RyRY?C4(Z{zv=iSWCiQ~NePCJF~ECEvcS8GXH$oW!HzFHp{`-+tb)*T_535tPTc^4uNw4 z=eR2ENnM%`vVWU;3lC3{KA-sv3`&3V{4dm9821#CmlcaGmYG;{btfDBxlK>9$}DlYXn!NbN*)GLFRP!fbcF- z9nTs+hkBnV-dd`U19n%#h&E?&N#Hx&qMFE>=GnmcJDS*5n-A}I`|y?bE}>$TBRjS! zYr?dhh3MllkD0{JhBL>t@OS-Lh>TL_?lWHEi)kfn%#xY#YqAcG$Z3R|5fVPED?Pt# zRxvZJVZ!Q%7C32LQ^z^KuU!u(m5E?&*)EO>zlzUYm$Q)TX@WIs6ey4;P0tHq2XqrAMCE>z{UT57 z|Cp0AJT-CC(ia`<0*Rw8jv0Ro#!mI)LQfN{_)Gcd_O9ZJaT$26bpf;ds7(3@-95L& zcAV{Bx5%)KSo;6#5NSJVj*IJ**x6h8T<51cHutTC{ps%F^3F{-er6_{e_#k~Sf_)w z$~QsPY#zUntB*DoGMGR5yj@yb5%$Pf#f++)hyksKCM)B?c#JVW@>0(I`Ig)uFDkz$R|)z?962I zgN5-e#GyJR!kSMZJiN^er)p7#&bwN=`)(1&Ry(nE-}GQ%x-Krw{t7bl?%X>l96gkF zvhF<&37Vg1#z=SqomwJ!;u_LRyFY+{kl~_|n1+)wRevcTg)e*+51rT- zgT_mt=HQVD%X?VKW0mrm&bfQ!&(p`?+#j&B(c=Jb%rw$0mMOl=QF%J}) z$*;IEwHUrSc0GY1vJ;37C(JckZ(DCmTh|66B_mO@QGqL3_R1^FIbF&= zepZE0%Aq_kse`Z-Vgpj<+Sh3n>)S9*>f+df!Sj>Y&C6>bV5c^Q`WHf%XU^Q=??q(9 z6tzC_TGD-%kt{MdNl-XCk^i|vejBGtU^%2hoHp(ib*PoHJiWp2)kqcB`85l(&FN5CFgW{(;Egbpm6QmtK#p_P>#I4H|Sy~TQ>EN2Tn4EBheVyY4N?PP; ze|59NZ?lJb178O_v*K+xB$!HE@O=;|W8yUB@t@yZhn zm>z0g`342!c5^S%kX>DNva4AqB*H*z`Kdr9`^xvWENrPZUJojRb!Pv>rtmOa7Uj&G z7f1x_Ys4hHodUbcVtH$ZDV_~Y>&QSE_mN`*ag|NRd=|XP&+z=y7noICEe^|hiNTNZ z*^;rUu#(Jp3%@R4-gSqHj5nmCM)=B(dA?jn2OnHahkd^Gyvw%~Eb8LGG*nfDHOA($ zCkZjaYM*}GX)3Yx_Wpq7zx~9kJ}+?3zg+e+kT{>@@hEGmpBwCoJpG>is6rdFY)AO#x>7UvdiSl}u*iB`btYBXy|bJ`}V)&hcYz5oopP5Nmzf zTd2FLiu?9e!F1O@+=?{PPZ`fTIz&d0N9alFPGUP(2rtU07e*+C@_>{4!?A&Q`Yq|1 z5);v22<2r?&0s+bG$5b$2kac@-%MTncIP$pv;^K~Z#dqyS=<~ZbBMRJncya`i}0&0St{M8CNCY+ z%r;Da1mhHX=Q-@ z>+Zvb8J;|4t2xTQ-lnW!tlj3@x#(K4gk@#f!(E!6*AIw;=Fx`y*7U0=sdi*@%l8YJ z=Gr)4GOHn?3}dMh(^?0RLEYW&4o)#DAWDw8MyBm z#e2{kJ6X|#IW~pMsw5xnAI6?K{1R66P{9wU zPIR34_0PibTH7IZ!F-#gj+Z^M|f0*IO(@o$z;%;$czZSgYm&{J|SPKs|wNb^r2yR_*<`cd}V{?cj zdwlMdq(_*ctfwSd=>FZFUp!AaKH_suX}Bdu4tRsk>?Yf(F$4zbs*uM146MT!@jH}{ zFrBuB^-GDBDA1YT+3Gv1*|Lm1C8orpFb-X0eR+G|i`ahOk^R9LLWYkH{<9~4`_L$U zt)eSt>0R#7aQ2sx?>g}l{H!|37rp6%ZUr@n~i}3bP8>Hw9Jb zQ51#;v)tKjr^7`qiD~FGYgI@0cO>^aXOck1Q{G(Bab{S*d z28%22-J}l9wQR?NE)c&*8wbu0gJNGB-b5OaQQ=`$xZ7WNa?OD5%dHUp2xLBM29KFq(F?rwLPCAfh-(!5&M1jiQuuX7B?%}>{|jG;Dy<-R`n`RiLaKHwey z?~W0Q&q|?p&2LfP;X1B9vz>kQyDGT8)xtg0C-wZ?LGsC%px>)YaOq;Q)cm8hyx!T| zK37|V?M~9bu@*0(xlxy&T~GV{0qa=uoB$!AULOrI9>BWQ5&Y*C6NCXbp+Y}Vyq}qm zi!ZETTgSZ=re>+3NyG)1HNl-fjWNT!F>&yK$4~It)G8bHkvc-Xm1Vn(X|KJ%9(K81 z7tQCq!KYKQSg!|~;Aud!%Hn&Fnsk7_8PFe#X4k{|xS`^)F;~#@$s)E|Lk;ZvQa8$q z1o-d!cs`9^#W#x1Y)(NJA!mjWP93Potj}ceo3GW-@njubv~?G`!FwF{DVM$U84e2z z^zh?M%JN@!=L5{m@JsS-IP);ZuC5>*m9ssVZ@_p6@-)PC^HU%<$Bf&y7hsQmN77{(;4qfdk%|qio}&y!_b>J z8#ZdkgtULu+juMsik}7XX-B)D=i40cP<W4c17@rC*smu9{ z+9aGO8o-it=v$)v!-- zG%uw&{CtZiTXk`a(B`Zv>!Xq@M5>2!Ut$(5c##VWm77GrO`YWV*V*A%m^J^}CV5$EE%$EKwcqo!Gy6752ggun;HX2?FYFMGe>yK@zZ(Mu zi*PM$vMPp&jXB)Tj5<43Ujd65C&dY&S1{uB4A%UoMtJyM4~HF&1gABN_|V@kuyW#c zCj3T^X9$d%q=Ki%RYR9h zFP_mkoVqF3vb9~}BqP18<&m9#vRyrvvk}{f`QweybDbq0XBLeUwVYVylj(xuPF?(Q zlUTJ07r6UQQ`{XN3n6~{#EmVQn11nd2kSsz(;QcH`w2&;J43&-6|`~e=bKP-`Jbq=f$~}N5RAlZ z$t;@jW$X|~zp>B;^}I9wEA{t;u!FR`anN0GOKUN14s|HrhcJeP!Pj!>6kzLN0Q+g$d# zAYO1^*`NEgD5Fi+w{W+8lekY_hZ@=i%jC&>7W^ zBMc8y6B}B~u*PvMyF9KlJnXK6O)e48D}-22-69Zg9btClqcF`e!l%Q&!2Qe={w~@a z!+hVvrIh*Nxv9;#raFmDD6)avdh!`QE`-oCKD>Fm0R}hacXWtcwz!Uk#;e!`oyBm_ zgP4a?V&I#OA%8l#85{Q9V=Y(QAbt>e3m?1zL#c$9PY%bUf$Q1TL>oa?-x<%0r~`NV zI<6mSgqh|yptAQLQBk;t!$$02A#DZ1!NJ;?X%Y|PyB^|4<{0Byn)%=VN|J7`P?75@ zyl1EpQD?6z!<@ zA$;O?7CicspvKfN!95yg|8V1fb`+t3WEv})F-;QryG0hDQqi%W?Moiiu_N2)SzIAn zKl_ONz8A8y&HB(v8p5G}_b7XKfFCOFhruUaLUz_rQ5ty##~OIEfiY?jNps^z*F<>w zYCKnHGN68B1-5R@6+T{F6(8u;f?dUY(X8t$46M4sgam82xLz0UeY*$KC%Ex+>PTH) zco%}AW9`mJ(=m4aLbm+dcyMmk!?}-=pwliBZucx7pPZk(dw(99%LDwJP+HWdP zK1JEa4f|N5&mh5wx_b&fG{QQ~&pbX$AG=O^2>og^#i6;B52EZ?{DNb`h<=8cF#IZP zWhc4kO>=Z}$?0H}CCosa^xKtLtDAsFUmc8wA8`IrH||R3{J7|S%w_3eL7?++iu7rR zm!3^A!XK)SVYA{$ajRzmK3KAg^*CEEELpCJhrKc&`qV0ZrSvi}XQ*4pTw7AEUW$@I zZY*%)CP)vbyxvI#7IyTEbRm0a{=HqY?WVOn`m3J(dY3M2 z8SM(^R93@rdriKOc$F6S7qRhEgM_uWw9$4Hhsm{h{9hdHzE$(!n&gal)j1Q#Ys_TZ zE2;%tOg(z87hrXu7e6f4q0Y(c>|(Mq?DMC+cK7#C_JDXJKf}=7e?4nWnIZi^xu<_> z$t>1(73_7?BF}>qb_F`~Lsz4);JG7nU)Ug-rfVeYaWqYsy<`%XY@?lye>4=;+!5`v zU*Up>|9`f}B`V>;p5(nbypX$54lefndbT<{PV#V#wfxDyU+e;3&UTRoxF_HmOk(}H z?VBh(Z|212$fgPQLx{n6BeCObZ&IcXpaXGmddxm?$4pJMxBt?ShwVP1D^}C{f3fQf z>CpT}{2hFS@gbg&MZ3cDk#`~Q;$S|8I6^s&GuZ6!Hzl1e>&q5Q&+pLcy_5`4wO2|9 z_dse`hR>$Cv&M&VA);CrXVU(~8TC#Y z-G&9v{)wi<*4uw#1{?W95VjCs<$PEsOgU>!3 zN1aMxUqJW%Q*nA?BkHb^ve+PXXvrfDr+Fc})ONUN=OXH4e6WuBiius7C9!m~Ov+0~!~p>|+@uJlg{Uv_>AqZKxZDs*PfHLLDm9h7wIi;H)) zbe!kW3o>!w{*BBbZX_(~q>hZvbHl&JTyw-_Jg|o{5#N^xzfNmmsxD=ax1Z$|ha>Qj zPXNn2WFhQOQ^U->IuJD#WSy0?@uD|r_11;r;j(n{-|l6zR38bB0}OCQU+OQT8U8S_ zr?k4}!%I~K@#Od$m^@`2`*gB1L}lw@{GLdN$g|~N*G1r8_W)+S^q?Tm>5A}MfqC`I z<@*XuaNU+B=pl6#J!oFdHoDBVMGXauPZ}tjUj$)QKHPEkKukaJ7~UA!O?c2J5A$2* zF^k?az*I0mT}SF!Hq_%YO_euoY9YKGsEr%OG{M3;3D1hA&N%-K?Anmw!Un6( zm`EA_#)Y-q>8~Lc#*puQ>~GQBp#&p0Z)ci)3It)XHd-decld2Gy-o1l{aBbcIYoN@ zxw8CcOf&my`4IFxbg@^}JLv3a%vawENAuDR?7aC=;p_!HY|DB8ssZ6V@wW+{$i5A> zeJ+bB+H&0dYAdt9&?=ZOr}?}OJtO=Va@Q55c;loSJL>5sk$w9hyB$%{F~d(8Xow%{ zKSNzyg=pjU3Qgu@v(;XjFlMQ=d+B_;>#^K8+y?${Cyg(=)8#O_>G4#_jGVk+GXe#YQ&9(<>P14 zOBIav3&tC@@sR8XNb8*WNAj@!*JD4cZyh9j2{J;{;@9xA<}>$CHb#f&XRvWdo@jnM z3`ZNyV*m5f&;F`|g-*F(voV-&H|mTYCV9~GuvWS`G#}xgGmE;f1J6&AzpmsLyt~<* zzo2{fyjlC1{>#I{7b|VNFrpe}Cq(jN6AaPW@G<0B+ls;Yg&48#Kej;emGEMr4(c7w zf$OFlxMgr6>bp3ytDaht_{3}YVUrtk9kUTy%6eewFda5$*(K?*p0DtAf6fe7Er1s4 z(%q@@7}h@;#?Mh6e^;l)ENInO;m|NOS_(nq2|-`8J7h(^c^9@-rQ0 zySi&%OzL6CI>#wXCRWjYN6Wx|@VzeVmK*gQ&`#>xS`Dr?jk4jy>FX9=_nZ;CIRSQGQiEH#W3KD`BatnLXYQEp1_fQR1?a;&B z%UZ$8<|L0KU;3Us8`;mTGo{Ov-r|FxWcK;?N-%vzKE}*qSgbgOhs0A(jeO|_Gha$Z z-8Yg&m1hV6cP8_Q%+5HqH3=R*e=4#~tr+t55j*s8Bp8~j;m$Sn5cz#6&+bnwS-*|! zflj<6Wv8{=<>Mb_w|WH&tkl7A#&U?6-Iog$k$8Hd6H~eCBAC;k2jyOdwvY?_1$m;T z{Yn69+x_AX+C!BXd<7NxDV}tgIJ5)4Ldd4cQXi{Ev|N?dF}E8(CdP$nIk@Ex;Vgo( z3=d|qSL<#`zDf0Edn*fs7>_Mn@rWUgnwk!GRGy1b>Q?foZc?@;r$4Blpm{*{3%qCU zCO>C59{1eOvi6*koTWRI-3vAQUIC+7{!P-a%h_<%5*(dqx^dYmlfv#7eH>AZ6Fh7r>@p8aRDfJ6yW_RFs#!B@cWFvscmvr0m%C zVlV1EJyKM#J{=X)H!wW|6^J7*pYO(8XbGLnt9vD)&m9MLdwwS&Ho#c+V0>H$>)>LU z63zV0aL{d&7(ePYiuy7Jbwl8%u@0(StbxggmhdmMbDY|1F}t&(Kyr2e6@2q@Gs8)v z!GrEieMaO%lwWuL=2HTOQnvJ$=q(ICM4aK6GjP-8I4_^S zzk%7`=?oVFb#cp5%9a|8NS+PYRoS-3Crw(?E-jQkb-VGe5XQ4=*SeKzvot2|b6Dp`;&W-lr^ue&l*|#1XyVdd6wfeZl zp$yVPe~81>GqFu!37c{uLFm3p6Z;&Chl+N8KKI~IET-OD-&Z%Kz7iFA^5_;OYpj4` zW`Kv2Kf_W(bM8r5jHX#W?Ch?igf!K|WknTmV0#2_>TE{YvHP&XELn6eLmd8c2NOqs z6!sla!@YxJz-5{TuL~^2(G8wV2JVuwi63MKmp$q@=lkSQ7Jl)2NSbv=bWv@@C;r(i zt3?Bh_fX&Tu?O&I*a04K!2*}=sR!de)}n68Rh(YAfpuG{3kr@p_-a;ChgNfnU&pA0 zo~%ovr7-$HAMCNyfStHo%8%Yq#(G`qAW)w#I!t|q>HayaZ^01QdRHIYd@7;n>q5TH z-wYSueE^5n#o3J|U+8aNZ??*P0{HaOq&!qSRB7q+iYs#5M*F5Kivon43hKyv_XpUxNN{HSo%X0w>=2Md0~_z>vCMs3nk6% zDRCRTg80gx`sjvfFn>#hG^tx2)_-(ni#}*W4KWEfSO0?n@}6ArI`Me>Q|@Ej5#c=Q z;m-vx;jiH(?tIx0YptJxYM+tfwb(559lDKm4X+l$+sSJ>I~RPK*7L2l!^zjQlO=CeakV!~ zHXkSW#H-2tTMLD`m%@1uQzIN`D}_6IK8Qo6-N3nen^@W~6y)=i@zTySz{mLVEi}*1 zYdy*w_U)8NI}MTB4=}XfwYV$$y+I4l23AA&dUZa-hj^7kmaqb|U||gTIi2V({J))S z=2hw!o54Z3N4U5rKLeN2`{wblS~#zxOZVanFyy)?S9@2BrNLz^@~1NBkI}%@2VO(7 zb0Bx_8ID8EeVF)TrgYTBCbaWSVX_}9VQyDVJnbsNhwD?gd(?S6KG=z&OTEPFppk6O zoy?9if2N56&P%%lOFG{buipKD3NIe9ljBE1&NcFBEPDypbe8e1cHwwpvJY!J6)#ac zW-Xui@E@x-T*=1Q>tN>Lk`8@-PTqOUaB*T8WmAPqv^x_{Cc}N7XrBD(J9^{>GLNgS z{K0xnd{X%hyzNi(HGhb6C28+qAm|jm#?kS)Og`O*%hr0lT&Y({(# z$+yi0vOnfU!Uw}`yyCJRmJCkq@X}Z5Sjk;3h%8Zk0Bj|H=G?hW8tX8*Y#$(t``ks6*yAM6m6nRZOv9dE~voEb6z(i9lG|hp@&B3DcI4gPi zeUbGeA^2MXb;KM~WUHGS#4gEiu=hDR3+=51xsZtKm|(~lI{jix-i=_aN-QUwmt zjzINWKC!DE`K}-FIQN|c>zu79sAL(-?q$b!_~&o#=!I?xdd#%+w0KFbiMG3|;0*Om zG|+c1vc{X~{4J1_8D--7#LY}=)F?=vrH4Tt1)!SIoyXM9$l`oaCz~n3( zeR+&)Opm~Nc_34b>MKkvQ^h4)8bGg1LFPhCu()Tnusx|*eCC{utF9kp{BxDy7ioxr zYPaFHZzzwyPxqt!#W4SqqUgQ&I)1ypo~;>f4!?Kn;Iso5V4{&N|K2|WyQT%QE^tT? z$&YR9_5~(nCGqSj#+Y!q8I&iuiu0bOW8WiwY;>Fo+`35JKqIa}+N+&>lDj@eWsp8I zwfBTMVhIj=y_VHhdcmrXI=I{<8X5z%`RRlfY?eP}YwvkM#C|RO6Z#HPcMALlX(nrH zH#3h(BZTRT%(3WEJ(x&qc}5|5DHq&^z?FZ*f8Av05lnkJAy3%vu7Q`r;-TAkf1Z4q zn5*dtaDQ%!G(Aa4o~HeQ4c2%FmR}5T_nEKY0G+vQAo1?{`ZA-Yqk@r_0V)MP0dapM zA5^V@%X)BFcKp0J$VZOTFYjja&wUb}_ff;*-=rh;^xz9BN>NwUi(UBRE{QtyUN&+} zWyjgB_S6`YAN+#slBc51od&#cF^9bztO>i7$*Zum9Foir@W%P(c;#RPIE3~V+cRbO z{rXO}uBS2l&Lr;Nz!dn_Y{$QBlH#1FbC`i*PvQHDo_HxskL`{s;mOOC@!7BcKil0c zn(&@M0sG@+1Mf2EcUM~hOQ(47_RW1U(6teg8nf({JS81IZV6Lzod7No#24C-2>DO- zdC?a+9@O+;ugWPWrJ#d0WB)?`PcFR9sVBNno-BJ-mPA`_h^@s<9W%T+Gr}neRnY8_ zE2cjuABbcQv-pqBcAEcnHS%CoKoI|EYl=gCb0HwGTB;bDi~6cAY~melceCWc50QW|h&h>V?@v;dBi z|Gbs5&u+=KTs|rsFaNici6_SixwF({iS9T)Ro=nr;X+IlqvYC!B1}p$AE|A z>GcT~DxQ%?Xs{geTl4tPYsP5$SO(61;bO0;8EAv9?CytZq2ZAZ29UltzuJ>m?`Xo% zQ{~K}yB4gxrjFy5yy;*a1OxRBYxpw7qFK^)+HY~VN*desZxwteZQ6%iSJ10Njd#xBU|9}*A2XS z9(fxE`?6ma2@+2`A&_x7;5zh zwj>VaTj*?`Xf}u4KYLp;x{sl3$2zGn?$&mme~8Y{#c9;B_Dp=TJsa=FPGOJZ==Jp0 zM)QQ|Xudd(a(3mmPCHB|2y~qH&XqZ5=ZN@=0gNyinV*du^W(j&6ZV*}A<~CC}Gn zV9(>e?DV&haQd=7emPJCb_aX%O<{3Z{m6lZ@A49!Y3bqH{EN^_J)EZ%M&R&0L2QFy zDXcM6!%hbq;m6M zuL15HbP>C3Xu``Uh%a}`2L9(Uvv;`;s?EE&uLJFQXB0!)#y%4$42L)Nu4iYzEQVt> zdbm915`-VprM!PDc58XU*56wUY9`bj|K~kquLl18K{#%0@ntKkMhN*dV^8&b0XAyS zdCglL4Ai&|tL@sw{G1YWOW(`-lw1{}=ICKw-!#~*bd=AzZjNnnDbRCZrZo7KvV7h7 zRyLe6IgT2Xk3Qc5&juUwnJwY?x7!wWdTyZb*v}Mi?5cz0?lJs8<^Yt9YKHrpMA3-L zaMIJAtms^;a4=346%t|~ZVl}>4_!x%_Y2v=ST{*~`a4-ldu2y9_S*ns?7HbUG31|$ zD;GB4)wATSnyLv?XuoNpR{?7e9pD!ySYn*Tn+_emr%pTe)x5~w-mwGYzvM?9mqd)3 zu{^YUDQd1+%*rGC3H-GN26+F3$0bSJ{*DHE-Dn24or}e(MK96bD3{&8Y7GtHI;e2F z0&Ir5^Jix)Q2#+AG%n7vJ2yWagA0~+^g|V{Af99)F}wa4aOXSOI5BxD3#{2A=$KLm zgxg<82Nyo$A$iU<{n_KZ!NPIMiSLbg3(vDY^KEp`s<5hnW%JU--8Eqt^KdS!etcZ` zdr1%5&lkZL^%MM9xGC0n=EI+}HPTP|xv11-8tb2;4QGptQAJgadCuz3AJ87Z#}I#Z zV|0LEMf%>JIW^F@<~(0Wd1r6(hACy*iVL1)VcOtbZ1wvZ;r=_yMfRhP@5|9o2Y227pxctlV*ZoIsljcpDVY&MdX z^_X)3QZDG$0XG^u;zeU%N>FoEeHSlYa7XEi%PMw@CyvSA$Cy;M{ zuER{p_E(0oLseNF^L$$m9XwkV4PBgWh}I_W&|pm^b8@zYeH+w}$zGEmdj4ko2Yec<4h#`#y75F*Skq>1VEkc)u?cP5Z{t1bxzPP*8eDuqI=Qu#eAa7Z`40v_ypJ|6`1cpo6L<4* zN)fop)}I}Cb6TSF*jj$$k*58A^RX<6^tUm$pFrdq75@H17^=OS%SN>_;Utp(WLqJe z@0!B%wkpe2v_e?*kOA+$Aq=-OXj}OmIL^Nz!{P zJrvK*RgQ!^ph+ydoDK%UH=kHcQK0UIi3)=E2XlP-NRvfju;{;_8ArsGu|X$CKy#ob z>d`*vq5We1?tk;Z-sS9&ZK0&?Xa>#=+REl19R>Zow9(HkABOeq$^&=DqN}zev)Qyr z_(A%fd)XzJW){wO`b1#=XTi+vo~2OHpo(8!zJ|;MMcHJ~z+*xU7*-aD)nWr~>6O9~ zZ)(9d>I2QZdlx+ahVmm;dRW;~1SwVuqT@qExy^dk*US{Mj~LgJ|-NvwlqmmS5om2Ys(#B_GD=Wy6hcmJZbWuUfWH@BIh zkCS#tiH*~Hg5}=p_^Z^1ZM(Gu7ElKN>k8`PIit(>9afQ-=Y3}WYI`7v_=>Yfw7{cI zz{_dg9)4;Y`@G6lSX^d?uUI4PKulu@QujeZ?Ot{VUpYD5O;P7rgR>SAR6ShTzy;YoCQlhE+>G};7uS#Gd z&neJ(^$Tn@J2J^-?!kY!9jD5V3p+fyzEmt~+p*e|x1;g^1&kdOEFM}`Pj=x!=v`$D z8;d~rG3vml%D*R90NG@G58i9@z^>sM6_r)Ru%%!jGs(B6 z<0bt4$?C z&x|t6>6`ik*fFI{-hD$NEzqBe&0hNO#>#}02er^ew-;O5!uKqlkKlo8$At5VIy|?l ztZm<_bw^4XpI(Bs!C*0ES1h%}d!yR1Qeo-@9l9Nx$h~@=>{#Xv@?p;C=i5#;eMtrl zT)7-if7{HT8UF7M&_Vg8Ao-u@O3L1?#91Np!IOLZhkhx8(jkM{8SeS&*WClZXO9wI zv}h|VZ!*EGXD}PbeOnF}IrGhAgob)WTjldWo4+-Sf_P%14hrdA)_0&blmRXCNIJ>4BcZPYHJ?8IVTTEa;T_fPLis zWbW2~v9)v#i?PQpeYn=bf8LA+sGoY0 zZ8_JCX8%;hq(yJiuJe1Y)unVWnmUC|nh-z{8(dKBZ<$Pf-9*v5&pkmt)R~2Gf7ZB8 zH(=ZA95HEpEya&1#@#yyfqpx_*J%9;yR$d3AkG)s8@V0VOG9PjZrCZ)^3)f;Z2(2wSh|kq6ge)vpg>g*S#%%}c)5`Vk_U$LdfJpP75U zKFbbjn~-8c3mi6cmT$AGqSDkP^t$H?x4ABK`ScQyXZ2^F$^&TD#(DT4El>7&r?J8) zM)DdX;if2zG7el^}Ive-Yu_D9RXzKW zELVkMVC=vcEz5H8{i5 z+EwuEz%@wYZou1+0M_?-5Uu-o3Taa>VIF6=8K0?v5UHACU9c`SX}kq#|5Wi_R6XS^ zi^mKdBRIf}$Z$nI%)NVwbvHL7lYtp9CR0;%QMpI2WJ}xF^8T;6zgzVdjIJHZj5xz2 z>h&q?pzsyGHkpybM1B`@i(`wXw4=@3%Ws!AMr6j-l=>|iy;U9HC-2*ZNjacKW-6+9>pLeAbV&UK{ zKc*3GL5dTxaNj0gzR>wE%`C0K)NhYq%}qlJEc*$!`gLH{ERa?xz3~;E5HwF3@Vk5o zbiNqKdbt~us^1eJ&pTqsuT+{_>y6i5hO1=(indUYQJQx~0Nja1Cs?f}in26W2gIlT5+#MI{Wq_pHZm~4M<^!4H>a`JP>9A8Jc(4X_ndqhHk z8_)aeoIoXmrs97e_6Rd+I+*#n@%!V=*Rb7dh&b0ej%O|H#!FSN z1Us&A9dNpu*hLAdiJ!!@qghmx zu^k_qD}@I?xu12tMaA$%3NHWLBqwAx-@H)(M^rm+wo&D;#MD=Z&r12vSIhBZOGd6M$p+1S% zvtZ5EX-vzTb7=-m#9ircWUph46~ETp6FgnVvlHA`zIf~nxL%wsKKkziH8>Sva??QQ zZpH5-JsY9o+eT)#ERfnC^2YzphsyTE*(t5_)SXIWJ@K0{pL@Gxw`nG`F9lGv>qKny zogioo*Q4$Bk!>8ak3mDIlgU%~8Wk))Sl)@u3=FYu%pLa3*@*5N@ZI{eh8C%I&-@6C0DV!z#sr>?UnEY7wV2+XEv|J&Wb@yg*x`y<+CKePrrDFaX z4dt{g0eHK!IxKKBAoX@?_$GcIo5FcDwst<~RDDk7^M`AJ8ugvFP8!LXEc!G+Rt!E@ z)mVX)>tm-bzys1T!ozij)S2^IwCtZJjE~7M)xyajt<9))5GD{Qa#SGNroiNvCPon zI?qXQ#yHb|vfT2nYZ%LY^!nS;R|?pxHk1$+J*%5F9U(S+;&;qqBWh022_^yI@oSP~k| zX71D_d)K$nV&*LNE&52uwkP8Eg~Q;+6`tk2D;FfOd)ekmM${0afQRR-9W#wHs43M8 zT^d)wmeUe?V|9zOI3z4tqOROA{VNtO_J-*B1~d)7f$aSlW;M45P3x|ShFl(})yt9s ze7?ejn{_PwsyUfHFNUy=>dbx$k)7QE^b(T==LjR(YLf^t)+bpE*K*Ih8Vgf?#L1;o zTFBeE1_LKQf(zWg^TVVCB5rhKMsF&qB$xZ$0v`)|M@i`V%ja#{_&w#FsG8rcEXT!( z?>eSX&nMe)aYKzT;Re^N4v&Dc1kS?UA(FlGA~dj^CA*VYtN3{LMVlY$mZv_wT=WfG zn({^M@(=WOX&Uz7S&C(eT=Qf89D?i*Gp#=D>8ZmDsBh>deoc>}$%9s-_Y*A`w9SA* zX2e3wNEtKlahEz>9gkxkNrh3sJ+L+gILlGa0$*v;>82WZroC9~pH@y&P9eBAnDrl22iH+nv_RPON_-MPmFeHWh&iXZg-{2;e%DpfzhQ5I7da>eDK0o>TXg_K# z2@`%CH6RB|Ib5qh#n#tZQ_QqHh`RYz-eW={8IPWUrPcbJH(^Y>JG4Wu)L!hmaS#cO8)lrJBqK&#Lj7pz>4cgSFEjpzZRod z`rbh5eSHnuRE!oB)3p_9$EdA`FKUreu$)WZa~s57gEGh|ZyTyRDugqA3}|EVO>ojU z%>K>}qA6znSpIIW?A$(1K)5d=~_l__z8kcQ;CVb_yIC)`C zTdr&12y+@C&xX29m&Jv(>Eyg=8?LhZC3NI>lg+cQg2Ucd$Ip@MGuod|qKpXSO^Aw@dR`&Yl3WeK-j_O)r=I zxvx)Krr(4Ywb|mHFU@r1(FY7s0zC25qia_hp>Eqowvyjvg68kS*bZT`V5OaMTfT;q zgU1?FPcoqJs9X>(^kSRrrBo2E;CBI0c5sp&?YJ5R=4l~p;nt3v8kPVikw?Vcb^2s= zTMd7WyTm?UGND83Rq(20g52w5H7);`hS$)IXH0Otkohaf(|2I%F9T>)@Irii|FJBY z&t$G>Duu5*z1gR|T!T~^4;2otM0-+G8Y(VfuM}1A=%Y)n9aJ#)`%d=JAc&IneR2Kx z^Riin_Dax{IE||riPP#0DDKM(NO9I+a?be=&R&S^H;fTN-}2gcK@Ouw-(|7`2DE%> zEOfQ>6~~pUD$5^S#OA7=;POJB;Jg|Rajg*7rqt5)WslHuw*)>Ja9`UGPZaL^rQWLM zzdkk;4Gf0BhtB-$9+?VRN5-+X^~Ch`It^II=D#fxHvk$o>ugKjN4`m z1;gJO^n`om2AD2jQXjsHk6eR?b5mtiLOtb=48uNKwu9?WbrR;qLjN*j=J4YxwJvwY zrIJO$en$x%G`$TDZh>s%)gaofdK%9M+Xx-M@w~s!^_+*JrkJj#M-$&y!J9{E;;riq zWSw*mpSv4_V^1mV@AZW5$}cjNa8r_A%YrlNT4Kk3z<^3$fFB&sQ(Iwd)2aWky3hSSO80!TEv8udK$g*3T6(i6#mnZ zkc&w??Ca~tzTUQ=K<;b%A9MIa=r5Y6tij-Uxp2ftO0L!|pzUwLKDhHbur3u(859T+ ze8)7*q7)kCL98;wf>!fvn!S5tMCZ%NG|S!_yKB`5KAhEAtsV)!xyxA7wg{Tq$rA?6{!FqO zxf;)I?F2FvQ(9}Mi_$y2S;r|sbbshkd}ec8XyzVOv#Cu`6C1`VJ9MN}&YK;u07VW& zAkPuIaof?CLRmBCC_a1uT`bnI-;1x(EY7;r@zav2nxxQ-xCI!rZxuMdwW1gYa}?}C z<@SH;=wkh2+z_||bj^4sYSao%JF=jI zZ=+~pnL(RFcA)A7g>Y~bKiA}8;M3igg>bL;Z;R77LEI-hJKSEmkHkG+@uTAQrTyU+tEJi;_C*!U=(0$J@p}bm~ zid(P1N1DTO*1w~p-0!KI2b-$+`RmIw?;HtcY!YQ-t2m!Q zOoZ5pH`(k+Q;Pl^1>v9ei$}Kc9;Ul`TWz2EpeGF&VT5s;SIE6bRnu+_5xoN3p!Y=y z-QZfIg5ZIy@=*_3yy+v@FIpno9cHM|T}wjln(fTk*pM`n6JTRIK0&^qrd*R5fXRib z5c*JuGOwthm))tB<03^?BLDZuZJi9Soh!d`97~;rjIK1Mipg)mgJ?Ao=(& zMlu{L-05aUCvvi3muDigJ;k}==kLM4X?~*dSe~cm#(f-BmBQ5B`h>mJ@%rHk@$RTv zie8?F&6g#h&TIR`(6!iPdOUT-1HK0j4Q<=87Ife_kKE!t-F5wf(^6%pTb`RwaGj2$Z%EgHU1;rtXFz0C}^=yER5(E^yLd5Pt$ z=tY0JR6xpnb5Sihj%F`ehB}41FtH2wnti(sFEWR)UP*7LUsD0fg>+%&6cZ}E&u4=# zW0>tHZTfWNE&Ta1R-{7&e|C_Dr8G% zcP5EiBdGPSVH=L>Q^$ZuFme{>4}Yp9gQZt+r$&X)X-#{Ip31=DB+peTvY@>N_n_P6 z1bOVFpR~%Z2ANq7++C?d=WH4w>76n2n)89aE)p?(O`(uht49`*FWTnt@BOT4y2eL% zH7Qlx%{@5M`3y-@NC<$jtpx@4gVtHX{3}*d>ck?{QsZD zxu)q{gF0exJM;{n%VK%IG^Xh&reE$acsufWrs5McWHqt*c?J|v^9tT=j1#rZVko-n zKJ>kFTj(t_B^!$z$X{@Q71?r+%+CZ^zOPU|rgsLNJG2_VCwGJ^-X3jcXB|z*aH=jkU2JlkIo)3AUS#3)`&(CR<&4eR^^LIQmNC0F`W@N-iN(q> zMMBF3?%O@^7;1i}GD(9q4P5dDW*oXJHnb9Txws9-pZy_x_0y$|JX`jEb9kTopXkZP zxA^qB5riz`{OZ>4uyU(E)3xnHUDl{z&adZbQw^)>Oy2}7zqbY=I&l`O?NcxrI+tbg z9^T>AR9xx$RyJv&v7&YCgSMG`Io~-x>=^<5O7g`g_V3AJ=W}$w>HyQ{a?Q-vUoZl< zvR=Hmbm+2=?;OKr{}tIOn{&0C>Xd8o<`zElROCaKNxfO>d_#J=RS9l)M46{1=e1tA z57}RCvCF$mX=TS4h%`JP?l~o)4O&{*s2#*c-!!5Y9~B&O*;)R$u8QD#8lPh?13%8~ zd0JKmgQ6XnwsQ~C-1G^i4O=4Hx?waWhP1+tztC zePQn5>+!(#^SGBm$&^X$L5Eq}06fAv`qb#%d!%=oRNWYL?9xuJM_nbj9tqI={GEFvYz*gH<1T3o|)S zZ=U5xNO+;9aC2!--8_Fo>6m;mdT0$@mL_7Sfl^q)d)oYtPvNosB{uj|PYQ2e0lf{) z#pB-bbp7LU{C8Ln+_-1<_u@P7@5K;ilJ%LoZmhtJeb0o7_%l7trSJxq}$K<}=8Y-d3SZY@Xzs|E3LQ{CV6%d{Tb zc|C&r$J^0>e_tTM*qB`~uAy)v1>UhL5^|Or(`?l$2p({a^{X+Z7gjHz{j~`3^WG>r zvtTWjMU)DoYWN(9=Xxg&@?^JE!sv$8cvM+DO4cQ~TCv~x6>PYup_s^7Pud2}(EZXA zG1{q;YA&VW#8y4f&eWqNrcHqgufC=+CQ+KORb8A6!aWhUV}slN{&fy1!xqQCb;n(Dd}lM9$|hkNsn*xUvS z`9bC=<$B$Tx@a2S=(v5My>fn2M<>}HOPn5HL@`N?P~u?B`j=EvVxKtNE7 z=T|_;>Br1}w;4T{ng^p zd){x1_z69O{Mm)`7BrFPq$I2=Nqgp0O>?d$;-gb*q2D7zLRlfCPMFJz19=A4ndw+3 zt&qjMGFCV)NEHsucVQh&jp)m^NI1HtK-}`>9of4(&Vfnf&y8_}k5f1>NO2wh_}Y=-4D-(`_l0`zAxrid*cr zp((Yh#}R>3`3?`F9}++Ooqs`=_Rmh~scqymZQE!(IgV%hc6kN9`RZ&__dq)RVJT``jT34^ z4e9T^bf~%<&9Zskif}3g{CrP{>E~i-^!@30BeX);>1smPee`g+ou?OVf{$eaUk}IWtNy$((%3X$z9Tg82 z+!s{(+Oe0Z#&o$s7l$YMiPh;1baQPX%4s-QmTHs2yAp=PFJ%|_-D+9oMm)GoE^8lF zM|#^=+3S?;6H3ItIW&eY)K_*hx1*&e-9ejY>ZDLGuU2dO=_CJ zS-2yd#Hg%F8ln-8QPP1>U?id5xdm-C-_FXE;K(B|yV~1vX{Lh0U>xHhyeHV`acxg?Vq49h#^0BQ(EG6AU4s0YyqO{k8*p3TBe<=p zOT+K|fS}!`>__T*>V95<|FwT6Sa2O({QN5T+T$v#IAB7SpI^ZCN8#e;j+YD!OUp@N3`2h36pNMAj-;<-S z0>90Wz{UUr`jPntLbv#^?p(Xuda49+uXhoT@EK0invK|{Z#%H#{ZGf*`!J-v6U*Iv zhgNOmTEP|r;WmFJ7ah>YlNTSb9lb3naI*wwZa5;Q`!$o{%>q2);sox-dUPzm6b{W> z$Ucez)b7_Z^gnFtc+M@FPFZh4RW|??4HK>dOas-qomth+JG|d>#`xXqh4lk@U$IjM zCz;G+r}#UyR_i#Xy&oX_=DVRmZ$87cw~cJaGu~sIDTA*4<3w+lcxsw>7_*Lt3%jaK zsMp;`P?vmx9oW%@Yw~kp$G|$dhcuJc&s>iIrk&yOS0mciQx89Uvte1sKhUGu`FMU_ z0q<{l?&17z;5{*vIi8eKhjmqu{c@+r-bcdz+JC z^=mIjkGOa`+<7iGC|zOHJ{$TNYl+{oV&o6be59vWim+g~2c(wh6K!pP8+}Hx-?zE< zN4^A`A$)@|9gKVq zxvL+tetgdSh>xX4!WmI7UP&<%ci}4kW?|+p?lrCpgMdy;S^ubPvYX9t{>~plfDX@P zD{qFPfBvlSn=zTC`~Vfja1um&vd@C9PJ;B6D|&t z(%UncFe*NV4V!F613odhnEs!*^h^xZy3RzkF1*jr=HFMN9_BTF6t~Rd-h`3@9IqyY zjbphlzQ<;~vid}7IQKOaJKV+InL{8jMvwFsDquzKcxHAvn0D&9;K{!~Wnwoz6^~99 z_O9lhufOf7bFCCtclH-Gfi;d&ki_v|AW z&f^Ta^v~elgGh(zLPT7jDQt?hO!XfT>8zK@FucEA*i-Hi9W`dI5nNQCTmjT zl?sU7G)BzfdbXd#6Hs&4K$u^wPtkh|U?tB^vRKfbln0)|=EQ!E-6txkcbDCmban+C z{>tyXns?jg_Cf7_(3Jdo{OZ3RmhnFPc-(ie4gvO}B9N|?9mJg7!-YGCEy%UF5gxyN z&+-RxZcmq|ZMw>4%^K3Va}5h~-U`bj`Eyly51vZ>Sf5dyNTpLMEE|#}4?X^a+AnLs zQ9EXmEzxSQ40;7N{?8R;q&eAD`tRWHN+OM^g zsdEGGtu+NNg>hLrQ1EFU)Yo)OvEzi6A=OHW4g`Qa9v*G>n{nix<7C4ok%}(}%?4dhh7KBLz0(IKXhZF4v2`f{3*X znMN+x#l@^ZRh2%DV_l+YQ0`__rULY`L)PSd!TSNfa{GreT7|?O)Pr=_a@8BLA!grc&|K`qK6#D#v5TmC(f)W zK9~dT-Oe#n&K&s7vp(KLHpok?GwIu;jo7fGGhA`y`_|KXcJPrf^LA%v0v_^eJHOLvRwj*xZLw8gnca`UG!x z9Q7%cw*6dzL+^XS*))6l{m=$Gw%(U}zHA`DyBJes9uQomO_$Q&!^^HiSnpGTq%zwJ zulfmsQy(owok3Px&A&QIhwi(H5RzXhy0-g58+Hccil7Feg`Y33&QUPzgfC0xelF*J zdYHYw(Q*EMd*zdHU7RegSmAron7&&!!!pi!c79PoMPK9bLdG+p^K26ezEBFPU3g!V zr9;Y|tc_7Q-zlEr8{F}m`8(lMm@cJk3xyNai`bvQObUw<`5gY6(92Gjs*Hbu|0#dw z*S0Xo1+g&NYM*#` zrV-8d)k6*b?lceTL1+J&V09li`BTp-%5+lTudOR!1)pD49eV}2TkV;bRUno2cf(&P z1+v|S!%1sVD;!^XRbl_0?+aF^fX&!9VzO&C4Qbho!(U|!1HS9gqorD?m3V-ej4+{x zu^I?9hO$jF?3J6BnmGNdbHs{o`gCzgIjGxfvI(;SY5Z5Js;qL9g2U*BFZ}|+UunX^}+V68)w}g zyv4b)v;Gs`fB8&7_yV&%MuYXbcI0*ULmS`bNoXLA+UJD^M@3nqb2X`-y^CAiw!x_3 z5-OOQ0V#c~Sj(ayO8Vi9`SLl!1n#5HEsp@7-a*U@ zClxq2A7LW@`v<-I4X5^xWxL$0C@w%78`mjhtDG#zx2zFjLf^BLp$24m_-PyWpy^9I zm4P>|*byaceXUPpcO|vyEmx=YrtjI0phurfxsk?Ca~BhA{WbBWh82r$ zeMcVx37_|VCfwSmOK*0(g35vbmg>OuJnNoALRhFcW9I`p6m|gJx7G^__SN{R`r3K=n%4*Jk$iQbz3M0$--LvQ| z$oKiM%gc?ZV%$q`>fTkXzgSN;8DLk^0!va3k#EAi}xK~Ox1XSUkCfjP=WZ1Sf7n(*IBObzVg zm>UsIE4pt*o$Cl5@qG66GZ|_Zw`WqxEsBVD#vqNgf(Fk(nL1DheNFh@a7GZ7N>5^< zm4om~&b>CSoHx6?k$G6?()2a2;lKOQ;(uqWsMsI^-}}83_I@)Xoq(sHrr=PN7z$pO!xj6V5oH;R?_^QOi~N*u=P`+avJwFa5m;^jWG6x zXGYA^tAIZX28mDjSv*^E7sIbhAz{7&W%*}-dCpe$yvdLb)TYAR>}`%quf$X9x&^2o zyae2O*;Col-fcC%d+JB3$#{;fC99$15AG+L^QldTOuo;)XOvoA~HK1Acd3m9E^P}X@p_eo9f z>f~(L4fk<9=fx+#U~z~ki+cK&;yn{^!K!CM)e|XMta|}{LCH4Vv7w+@br9Y$PBcr9 zlkxQ(c+t5@kloa!-pVjoJa;j>U6w(aQy8j*eG~4;b!dyu@3xwMinH~0Y5WGito*bu zE#SXE2o)!rGcyEIc)UB)jI|-S?HU=8h(cj@k---<`-Ak`lVLJ_@pa zJ{D*2J6HNXh8mkXLkQnhMgIN^3yQZgqpUz0{^<~^?YJvD*v?)#uTs}Zd5dR_bKP(8 z@)BSp`m%S=0;oQC4)z`~MHn|)LUDH=fMnE7_T$E2dRFlYG&+Td5_c22b4Y?k?$_Ct zo+f1VpC;xFoh zdQ+#zdu2GZKuWi}ah~U39X4_T=SA?$Ebr3sf?g!Q*R08c!BNrd0Oy#!J)?xbcK+hq zKT(vNJqtT)RtSUUo6-1{(zcraE|dGs$3H`dGg4S{mh-(2Hvyf{ORe}`O^$P-@bC1Y zu&>I1GG=7L)9Q)Le_Q{tV}8VVZy z4D)6VgW#d}RC9fGBwkD31|uT)d#aiV{Xbc9A6y{i z{&mJB*JcZyoAoI%;4b9X2eLCd!SvX^VpWR70 zSEgzoOPXs<7x%sg$>dRvbytWsS?t60g)6`-n}^vByaNgQb(m=h(VCTM=(T<{)K1eQ z3HRnt$r#6WORRY|w;oQuoi5wk$%5=-zJtxl5A0()=XLv)K-Rv$V%Phzw0)U3uGfte zdV3lXREzLz)_?5JMRO9}l0o%woczQl6Vf=Rg&i%e*mB+XB<-4xM`jlZC!2I=*XAm1jDPcE{I}zK)Xl(GM?v3ZtZId16CQ4 zw!Z;x*R*Adzg2X}tpHcGJ`qfJ8k5GrKcMm^oV{tZrhrU!++sCDteIU;_q)g8c@s0Z z<6}U7owGm@yN%@>?@Ist3ZOOgsN-4Ae%#?QA4B>r2LF$C6gJlu!&fBBo4?f4v(V=l zTId0j@9C4x)UU8Md^FRK52O^M9r!#4ga;3`6w}}43YybGSYMt&cI)3`82!Cb%ub0V z=k2ReQzb??!gb)@VhlX};LB?61ySL(i?~8KB%8L^UMb&W>2&dWH(b8lgjTT@h+$@| zb--Ji;gHx?=k;8q^n1`tDAZH3ru1H%w^Ik&!Lj1X-F0+xXb^TzFoz63p6fC2E_`=f z!q%O9NZxKD?!Vk9Oqb}=jHNB`aV}?mo;RlarGKEn;7OXsp-MixPQtCuo}juzLe)D; zApXc)miHil?n&n1BBm34gh%0L${Ap zgiHH4cYQ-DXjI>1zu*Ri89L*jwFaz;d*U<%LsSdB&OS3UdSBiS2ko6MfBC(V)?QZP zhJ|jh_zb_}^eBUogYB6SXFF_4bjRGkPi23&4xxp(t8P zyUO&@q{)Y63@{<7pB9eImCAIM+bf6pnmILg5m0%@nBI%^aD9#*Q(ebdSU=pc*C}UV zNP+?NIFS0?Z_y}#D?~^(guas5_1A_R>_MRcGeDGD=onK2c6S-gb zt`U@UwWfZZ)$!D2v(zmy)zo2SG!~!ZEShkB)`X|S+addwCjdcA)<~CR6aU z+s`x_W5c&Y=uQK&7?uT>c%D}WzJr_o(gj^SW($Ak@myN&Wk@|8$S$Y{)6mP8aD8iE z!TE*;O+M2EyY{Lp4)Oj_y!HvUYbwMODph1U^*&DRXUMr!oWI)q5}LgN8HaX}bq3Fx z>1ZJ8wnWposUG<0gf2WN)}t94xKDG}SkhQ+CD)GRI1 zIZzEbX5+;Yu0KiXnu@0@hr-}$eXfNohNadASgwOL<+Of)`hZc6G2iZ!0==;I-#k#R zH6X98(eUlCA^TFSp!=z5*tNrG=vl|JV4PdQt7IJe^r|~ebkoOKt?9B8Q##U{Wxrs9 zN-g{8Ye2Jxmq2#YA2ISuEESsX!d^=wg&(DcG<1pxrrl04VVOCpo_hdIH{;~RqrQ=W z1j@(bKYymL7`3sNZje zM=26|#AjonAI`A6DpPtnCj% zg6d=8N;_j(J+!5*&JX9kcWF>19B(&BT(412Y6IeN^f)tE&7bq#=2>7a+saI)asOl4 z1Pr>WCNtlcOzkXJVoa?&Ofcj84Htc!FgQS7WzCr+8(&~yrU#7WGd)M14d-v~$eQ_# zdViTWeqMk=|6baPPoMLIOZ~2}=qX0D*D4?O)O{86@)&g+vJbZ{7KJP;32Dn?+O(IG ziSxZvE@55DA=!@;_R2ZoR!;8+b;p|9#v~oj=OJEZtS9$4tnGRaz5JgEM|20%tb^@v zPgW!I%rl~~MftEJD@fFqrqEWNdmEkfSy*7BORa?w5PN7bE95y}x7ss&c(YNMc}kbI z7`DRAnP*txRb%>Z)L%F#f09;u)>%T*LJ=r0k7&gOpmiey%h8DWyg22 zpJgVB!ru=CN3F?BqZ{AVZb^XWiG|{&)(on*RN^bIE^x+`=S|=L2OXolScf9+A1pb7 zcBdj`l~(pj=?{G;+pe3i&v_|r9Q_Iw@3CXu^>}7hrv-Sycd9UdmjS6APK8IEZnCT{ zcBCmO0llG@L>qT0eLib|`VLoFYN9DEc-szpCrp$3{;i;2y&j^v)D7x*7K7#2GH5ih zXNk^%G-AVQ9C@)&cGPkx{jpQ!zV$1LNy~V4r-~9HL#sr|!%QlDxD8u;vjxU?D6aFg zv2yeQ_L|rHIlHxSI2y_FJnfaOm(86XrUi_)*p%W}dF0Kxqk1T5JUK zx^$=+%>~YmcI_;W>f86$gDWBio zx5|dC`c}-sR!T#S7|i{bElXRgPdBbb!JprO%<@kNy{!tun*IF+vBGwWkDLGgqJ164J|3o?WX8 zCWG41+SOsOCx0Nz2oQNzV+v**y(`?b??Bs4^l|*O2kc*gCZ%<*2DiiG#5)=_r1>lr z8|MszD?K^mv|R}d*?xd+c;AzL&8-K?bD5(`y`0V@?Z&WPOCheAv(dO0BWb7!`>(Hp zOgz)@d(bGzHPfRxnkqQMaXdS-I*89{eQN4B4jOF)CzfbX z_>1STS7R?TuNpvU=GwUN6N)SQ)X? zeD5FIR|^+f%o0z|{YZ=P9**qU9s+lB9pKeRU~pD<2w$y z=mlpy4Qc-+1Dt3YC=W=ir4iR&;K)uM(1GjjK0RuN=S{#~zTvExnq6qr(MiY~t)(b! z_qc6t)57QBDY4Jt`G-H^f-{VU6z#{Lv!Y<^%^AXeap2E^?G7YlD64x+UabkNzLiDgEbkh>n|*V%@M z-F`;Wp%!-xTvRSB)!_M(fA6;OD!nWfWEvyKGp(P6P<=k9;u)hpYtOU3&c-xs-9Nbb z_DPy`V-*d1`2YvCUk5jB4Cog3W$%rg!|ERgkj^shTZw%qtD0o2FkSjkxHM}bi;b61 za$y`Sy!J%gbSabcjMFiGM^{+iN1x0ZRPphx9c)@XpJ~7HK`Xl`S@S4+1QFG=m4>J|cCQRi8oDWBnpw?3=-UvEEe4Xz7u5q|u%pkF$#VN#8pUHs9WJip{Z za|{21pQh8fG23vtg$lItd~bdq zNi2TeGz{j+I2XOOfNKwDvgLjOv^jAS`c-|GtsBvWc8u(VaOR?zy}6q1A1%Q({JoCt z#`DFvwxns8CyQwaB=O%atWhUf>!FV{)$Jax3f~8|oCELl`4NOn;`y-dJnQoy&+~H6 zmJRUMqpZ9rC>a~bCS=~HsbiDy*YqhueW(TrdOx9~tA?W5$&g;n_zmF&S>n0tm9+52 z1AM43gahNbFXr(JxHf?bD_&3E@!XGmwQZ z5h zp0~Jb+#)%PY8^?ZGsOGchy`J0Oq z$s!j$dRRt`$~V&BLC6$Rzf6E@nq=UR(=0kii7|`9&cgY<)3~@eW1M)mhwN$nLeH>1 zb47j$c^cWx-=Fgwb^bfbG#k&j9qjpxHIxvYu1hp{c`$aR&4x2VJ6@&xCqA9}13W@s z6I*BI-{AxR4~Ed_yapucx$vp1gd5LTG%Kezk|fuAH0CK|xQ!?$I`2dI_=G5&GwcY+ z?W$%u0;;&gE`@A=u!%kk3dS{q9bm-o2_kdD8VSv=?$g+xNY=o)a};2_Z!y1SRy}6C z&IXloEfQTPk4JBp5X<*owCAb?<_?j8@dIu6T?Gy3UKI*OWHQNfSHodX*j&tRvTOGS zql%pa{FkZ9C0ZJyxq|`NI7n&D6FodE6~NUIUVO@k&nUf~1Ep3rBvDHN-_(|nn-vS` z)$ai~!f`v;?HXmb-u)YXY6*v=Z>LFAG@DbRrDVdt{`B3sV4S?%0Rm2M;%;&R9I#&% zS`RFwy1RmKhJ_zIzA}NEW5(E1hdPMirFQyckpSn9swL}la4TBPLW$Xz2FmX6sn3pJa2^TWI-e1za&YpJVuwCCVC0H{dPZZ^& zEO9!W&;9fWrq9@I?nq`a`Iz~KAD!2PR~+v`s#z2Fj`{9qtcxLrpU%+DX6b0Akp{8K zA)H<|HUi)NPA;w+;yxDi#t1>7HpW?NNZ|A=;)oTrB! zc17gki+jB0=47-r^?+s3EnJ(EI!>SXoG5==OGB?xbUehvSF<*5U$i<_xyVDz>Fab_ zhdGLuX~PM>uj#SBeqxwK4vgD-jJSC+KEojPZ=LiX&8THN`GKpT%dK7%GE7HuCHw`a za%V1`*1*`0De+`qQ2{UeCIdG|NMUsL0P=(}yQYW8!2fjhK8=BB{^~5)$3%(_&9{=a zm%y=)M*^qo|GZ{UXF@FS&#BARL`hu|+Y&*Au zdTF7k(QE=ve1>meEirqO>B> z5N8a1ORP5V5x7vh=m0#j&k=^j{}OdK_D46l{&1x520v+QJ^Gs! zfwP(o*|(YLCwF&|s9n2hmDmK!M#@9SCkN47rau{NFNQ1RG%;kE6b7Z5%z^*kcqslda7P9wI#Nk4+P+OT_Q`n4|YlA@`XG`*!_I^}W0$FQe zM-`@~t{?p$%ETR8!~w_^ZP56 zl65iO)H)^rJ3p-guY%`x)_2ADb*wjdj$TWi1`E)uGm5Oep+QT!)A2`sI@nH~N>qgc z9P2F$pHIx9vltJ#m6Wp2wY+i8qDKK<*<2Mj&LG#G5>si@Y?2joX%>5gO2RrZWa zP1Hh8l0iQH@TJ4{-@~hH=X`y=Eq`Nb2c9+T0K$A+0iSj8-%A0kiylHp+J3_2PFY~( zQpoAIX`-tP%kG&ULVd?+BK|BVu?eAkTSyd+dE*5Y71f+E(@rekliJtAC%fOn+ru3| zUu}Y@TlbS>`V7WQWlRW4TDdGb|8}Pf`Yj~8cLq4pRN8YxSJih2f7la4k z(4#v*3&Qx3_detJQBS}^Y(uhB)o|HrF|m3;Xq4z4a^oGqS5cMQVYUr}~$X$=tWm!vd(6S_w1_v>I*XdgF_{3N~ zSf&-P3`_xiStDZNu8Grp-V(bEPwKlV0A0^J!Oq+AqD+GrTqalxx_Yi;Zj}WZ$Xmj; z#c|?d#-iEt$jtulf=Kd{`2rO7_Kb*}k9#Y=OYZ>7 zk#Q>_NlX6lgTtCoxcDA;oowPV7cwSiZY+tlJxjSq7VMd^fc8n6qTDnq>Bccb?U%Nh z!Pd2m%>g@L z!{Hik>1g&0FO4B*tk=7t$Hc&$tuT8@29_r2VX z*Ux0b{SYtWzCsH-?y#)zrz`0cc7GX~x*9IYe-@pctS#C7_C?=LK9KSHG7l#cSKSYM z8+nE2cf5l3Ic8*ZjVfyU$wJR?ce+9~2=C>cgJH{}M6s;SpX;Y(KfrAt9GEM_px+{f^dO{Kl~E~iTr%6q%#|g>@VK~*wL$vJ{!Li z6$f>i{(${Gdv-#`_c`47@_rb8`y=UhP)sw18=`u}YjUsVDt};#6t$Dxp{k*WbJ7*! zzp+9%cjg;^^cl<8$}ff~ty%0$Ob=6T(IFUxv^;vRc{GI#Z$-N zoUv4Nu(B1`=cIt#%oBvlXyfyZPGvp>uzm6ZFuAgXn;ofzKU9*)kY~Zv!!i*s zIx)`4&iULWwg(^?oh138g2eb8(<-=hl8UjJ{PHEWxaxZvoEK}6Hl{Cn#`?@hHMi-c zEXJKUx*D1%U*_N2w4l@W`*2Q2L_Vki8Zbe zTSRwYX>A8&Xuc)Vak@yI1wa*s(B_C{^klX1spumooTiVz#lMKffhTkYuZDFVC8VnP zAz$YljqW2EuA)6f(ZFXWQ)KM8g|hpHt(Q)~M8HXnKna8R`- zI1X;$N3HmRn)>;$_op5iHB%E+n!Xad!RP6#tbw>^)Gsn{l@))T<;$e?4+F&-8>Ukf zpy!=*a;Zi{|0&-^nF$V%HB*Jt8pir1R@)7KC(#@~LmatX2(#9n;CD#B;*`nnV6UGY zsXfSep|*`Ati_coSuowg50-axZM0p~zE;#Ki-PO%XNh365T_r{AUb;e>F}v{@z;I_ zxIA(L*C1fMsD&o`?v~Mg%xCR5>nhy+JdsmVP{Y$7fA!s4dsZ3az_T(?8j{5?cvyo4 zZ=b`f{uP{0x)8IQ3y5grb?Wu=7Rq=nfZ#Ek_z+Hl(~aF>{~%+su8C>;;K7rY}3U2j3rk@Xy1QnctZxhZIA+Ik6s3Z(J&b35hOFEwz<0SF zq;!)lrQ-(UpGivaPxpN4eA~k^G1XVnHSG7bYPTyG zMSd2YZ`6^r+{)%mZ_THF-wE;1>Ld~z@{V^`eT4__zXrwUW@HDu_4qZ*!MK8hwB~mp zo=Wh6b#J3Y3mvSaW&O47yR`Phy;*9Q?o>*SHw^1z3w-c*g_#eXx%Vs^#hzvGbqOQs zD0U0Tx*t!Lgn9B2QpP2&(u9+H@6pIh+E|*R3cg<*#k0PB!SGx8aIbL}QQM@BqhB?V za+e9z=>V&ByLLmJ&IggMjHV=feI92w_ArfOe6VRwOjna##(yl5V)14VaGjmSCA<)z zf4LeM#GIs&9ojfypa8HzTlD;?mGppqe|ya(_Ap3W2YsgfAhxJZ_Xo3VvY6fQ*>f(J zoYfC6nN*QK#bR1^tRJ>c&L`7+uJdDm#p3hf8=%(X3#U*dMB#5Oa1U>WBNQ(2~00B<5D3hv0cb?>;ZT$+Zpyx=oG2%Qb&=G z2CS<($3MCyFHKkNg8C(k$Y-`sc=fM`7`5)DJzaqqJ>DC{DN<1xZA1NnG)V4ulKeWX zg>|xpMDLP0tu6|{K{3v-NN*|kvsVkPJ|>gd>qF>UaXgy#B*Ih0`P>h&Ja!!TL+sNO zB)OM#aqJy=(1^_AZ^hT6yO{)L{?H-c*=O!w1``+ggL`(qs{ zo}f@a%ZA)2QO7SIE69d7CumPW07m||7EV>h*p**T!sXpZ;Dp`^Qa?=vAtZ_jGt}sX z+B6JiECSR0Q^`|y``Cjj@KE2G>MUnzT(;xBC>Uc$vkZLy+)SOz)v#?tIZ1Ku z=64-q*_yXb!09bf+^%Cfc+fJ3Jm2I`je@jr-HsFz6a7rAY@?0+tOSsjV@mHvR-t#w z%RbFyl&UTg(Jykh{4tHp72=P_pU9cxPkEDz(HPd|4e4WRIq_mOY;a?JZ^Aa}y~7j_ z1O<~IsZy&ol0w-Kr$cLx=BJHU@VKz7=O$j8|#Waig?82wHz|tR^ zcqjJ!1jej`%R@Ct`dBs8o~Z%T#+cJR?zybCNFd)Oo%4ThfIoh8lXr2``Re5jcs(Zp z#(&Wxp1;&lc|G$}Z}y-InhenYb{+}%e$sBo^cZXryTROfYl(uVF-Bw!=wsR(QkRz^ z?E+ngQ{>-cmfJr37g^RmjmFdr!Phrb;PCrAQILU>#5Uy}H$o6huRhkm`)>KfF1LlB zG=Z^yw}e2<$S+*QaSgP3l|XuA&e4z@bM&wu1}0vbB5fC0Y5KljaBezd(p^)*A9g>< zC>ITSY1C(&C5L_W+-QU`8qI1aB=Q|~T*dVB3yaCSMR)m#m?W%<_X77lt(@{I_S;_^ zPyQTPPx)`@_?6Z3+&QgW|0V&(tX6;>y4PvlO2!v0*9GUwZ|RE_YjNXh9)`T%N&MwB z@N3{lV#S!2vK52s`+$zKUN=1Q;6d6LSAh=`yKU&LGFMd zDZHYFzTFDYmFr10YnTpmi9BdISc;B}VLC}I9ecOO%mK1o4JY)J5xWD!=?mRJygOkX z>>J_288MyVKJ_&>E)N|xFQ0H*_n@g z)Ir2Cz8(iMpyK$M)?3s?HjbCr{^Kx1t30$jJ~sK^JEv|0d7gs;0%~)M8F*=?%fjRcOI5Z@;=|A0+n=BiKnng z_CHReUJf_k`a>4GC`jJ3TSnr{-ag;!lzVkp$ue|=(K>8rr-g#pT4JewhZ-|J>h|0+ z@{6kSS2I~&N%uamHPawg-Wq5bpGfKyr_nVssW?1N48f`4%+tquR}UqK7#Bsk^dXor zRR`v8Il!NJUx$W85?GjHLoTrAFe|B&__2Aak-dZF%dLlF%VX`1-)GsQ1NVSGI+2aW zO4wi%$z~;{jg(DCn>-4lsnf{fzd~HntO^ANE;Pn12;E*@fQ)e>&OV&^zAwmvlEzn> z+bqEUj+YZNm%qFc>)X?go`jjXQC#+E=ACSLNg(G6UH4`HV`b!$jge{MDAx|$yYmm2 z6z7q*x3y7nRt*Ma45lKRY7D-c)2EZnvtfFo`AWmb(wJp zyzA4+!mg6y_Lxy+#Q*+de(Sy|4 zE$RLD*J6mC1g`(tMb2DRN9PljeL|mY>(dNI|1$pS-T*jr0{)m+VNNCb8d+ zRw{YDt&m^$CFb=MT&#DrlYp_`Sob%w6}yN3tB z$VLq}t*jusq{Hd>S%Ii!;RcCaE}TlI4*rdOMVyNxX#GQdT%3kv+V0c5MjLw`1X@t` z=pHQ!2}0Mk*CA+Xh1iDWzAddUf|rvH5F-h@yQO|3Q$I|k*2kFd>E}M+=NE|T(p8IguSCJN*8j$^71%z_usyKyYm`#T>h$?xNpwlz0B(H+EYm% zb2ufNaTuPJlPxYc=~+K*G)XBY;{ufVAbaMEIm(-0-?X9k-hO^heI2fGMDUiGOqAxayX504VjFdmKA9MZ z=QZ5md~>W_b$`Zo>lfeWX??OR4J+7r%s@PqB;*Tmgp2?p6kX`W+#uYt{vzZTi#WYd zBRq|=U^MCI>Xm6msL8wDHpR4zlwI)5$RJ=ZoD{ zWM6wIe{bG5Bp;&Th>9`kWS%cq=81dsWCxwFZV*iT;1rC)VX zxlI%1C)V+KhZ^zKn|IJ@p-)WYnWqoG5ZMW5sWh2+X1$wKmCtsBywIm zfI-b#uK0`qbNw{o#jPcbfe?iB+zs&iYQtS>R$-c=&c0qvCDvIYn{jP2Se&{tRM-JgZ0QMH+39&jn(r=59)l! z9IuiF<}dTJd+|D&u^%_Wi2bgl=j{OWT|XF(HiwJ1+hyS|UkVGp%_fpC4IJez1HO;! z>H9r{@wcOD-z}BXRg!F?A2@MCFg<&M<$=-yvbkRi-?BOe4I&PK!|zyb9P8zp_NNj5 z#PifWJR4)ryaoN(NRiL0UOY1DH}p>ULAGcc;ADLjXoLZ@{Ve-CPs)H3`#*9QM;Kv~ z)lbsk@s0*nXrq`fC87{5X*l>#WdAWLqJ z5TN@>MaY5LB^NW_I>r}F*E}ftE#WItC|O*?7a<;6xS#c zY3NAm+Fteb?U8JLzcyS<7Uz86bs|y_3@C7O4axZ%0({$~2n7kAG<$ z1x#DGZ;77$r%mp#lX3E^7Jcli?Gvn-z9@17lx|$eUH&P=!}2*qIW>&t{9&1fE2YH7 z;xu1;Mjg|Fwcsp&k9IE{jVF&-g6i`_;`{A?P<*8p%-?#G#LZ0eaITHGOtztV7XvXr z`v465T_ieLr6Jj!Tgdq|9--DvMy7t znjnmOdIPN2-w_G38QcHZAo~i(8F1N454)~*lQk=}Xlqy?ZtXk(ODD|dNqxlL`~NLF!@6--)WeMTlVwNsMpO&*6QN4 z=YRTY`&`B`Sm~4ki$+f)VeB>_0d=`j6Ogy3eaV zMeH|(`Ga%^l8S@sc#Zxeoga2nyWv6DGvE}=h<+hj>R*SttZzB2>q!Q&T;_wrOUS43 zmUKMRxm|hqUmv4vKYNdKO=nq7rNQ*tvRwQ=t^l4@ZsPX!m%}?Z8K-oMf<*L66*blW zlBd}j{8XlUfA<67+esaQ>H?fS;3G+!c$2=U)xy^WVCf zq9&OvwVg)4t?VOdw3;_PNV`if`tLLv3~Wg^OCcc_?nqU)$hqXM%3m(u}Z z6XuYTI3Y&dRD&MFh1BF+5T<;*1Z%HxTs-61I+x3_qVbh}|D%f@*5AmuKqczdk9j$F zhl6-{4X4B2N1v>-$;k7*^l_plp5fBS^IH+(fAtdVdH51e`9C5FdMwjiRvqq`52l_D zj7KyoAAByCa!y6sc-*s#h}Q}6dVCJK$GqqFHZcw1$#ha_enez! zq>h)zX*0ie63u3;Z}EJl(LLnJSEaPzWtlQ~>I=lsk!AKRYaHz2NyK?VJRB_%%O&IO6ggz+T?=o)gpELwo4o4EgnY0K1%RUL>lx=O5oPo8sYaAHE@ne zq#3!&c;{YYU*EpjxsGL9Cqb{Z9+9#>!NlV|+1z%R`dl@~VP6}GQIelsjd={#RBnOP z$aQ3G%W%veI0p9BrHBt8;=}XlFh+X@3HD}uPA3^?3I|%D|F(xoab6-GJz*4Js0Sm2aHF$lEU?kAtImhUcCCd z6IL7kBzsGA@vWRPRO~XQc>!#<7WM*ujIQLuRv2Qp(hsuSFP~aD2=VcOV$wYMHb2pd zaZ?o@ft9`yiCv+Fi^e38yp8K=bxAThUZW83_$$}CLluvtC<6SsMs=3zqs>|su&yjg z{~i7bkIhARb9xu4X;8s0h2`Xo%_8b#9EhW*Y=Y%nlgJ}ZN7CW?mdl*uL@zYy;7b!E zp2nqo9ov7NozBCY!3Jcvt{Mg|RtD>RN9d9$9lYMI2$>IuiKhE8o#$zN`&-Kng3De3 zKAujW%c<52oEr zf0D{P6ejxf#c2Bt&paxD8w(DQql1K4G_r$u|C>U)pE9m>`a#&3UMxz|)08-de&7bQ zdC{2Tx(sfUM{IJN_|otetggHRfAu>!r_Cyik*m>nS1lNL8#lDw1b2(OBD42a(&A7P z`;~uZfMOWqMSSljTe^fap82-Memw~1TIX}E<;+`MSW4on6X@SIb5z;eM5c^?$UoJO zLEoG$5IE=yH_FkFF=hwAtEgVSX@V4cy3&D6>*7wd=`fDj-@ZD3bYvs0- zjX~sowHlgv^pbzKc2kc@LAcl8H0)WDDbkIrL(@A+@Z^gpnGnWw_=+W@#My#A6fkeX zyrn?gmvhV4vRoCR=wEoJX=YW5GyZ4|uj5Bt*msFh3;?>tO z2IG&HAhV0jZo>pPt*Vmzk29}QXpD_bO)Q&Un-AOFh-MCt`t&o~-31uXlt^^!CsX_H zIrz}!9V~ZEVWTbSNl#F@_1 z!~LGUM0MsTAEPwM5+*KK4r`g(yzY`Kbj`tyyQ^)p< zEOH{lh~8knOZ$P8KvtpXrK&3PeF)+4hyUov;voEyatnOsPT{=As9?~MKcxF}8#Rs) zqILOiG9WmOuQI5{(s2pU6j8xN`3li_Zz;KJev|G<>xaJ%l=Lymj^B!A%$6;n@2W`_ zI16yc3N2_mZ9#W>Q#=rw27@ofb8ENtM}@DNaHS@NX1q~CQ@=*Ctal7QhUvY>x-hQt zYCYn;S{;3FzbF3RJ?Z1OW;ocgkz74{#ZKQM3gy`bo8(wOz%1kt%BLy%Vh*L{bug0w*d1F zB#}`*>u5OZ`FCxWfVAo>=f$+#{+e3wsQ4aDs?xyD~InvmN-7AY9#Y8UDz{ipDb!SJ)K;`xebZP&rH$&*d{;QrIy1WqBa}nzaSy zrZ3_Kxicob^DAsSl?0S4QD(!{OjR+e5t8qYHO# ztB25!-sIXvO*C)rAbM}7P_^64>$KGaKHHawZY|W1z{#Zidmv3e`~RHSuzxT@FaiQgg9P_c_H;J>0!2aU1_!)H0@S!b=z1r$8Rxl z-y1?_ge0T(a|xV{Uc|lcki{J_|A>F3f+T=_zh}9BL^wT@pLpXl9{-#LlXmKp#0&v` z-%?GUUb#h|))-?+;1}|Gt2Un(+K7uQ9>Kz8wqzq?&cFPUNNsJtD$Kg=NS`a* zMsHtV==njoBZCd`$Z9zlx$O(JKF2&$X-y=vS)L|m)nc{xGl;!e%c-$j#{JE2$O>j) z*?L7E&lzWtl%?@v-sCUtQIogdKDwAxv;O(=X?0koHkkT4R-@0%w@`4sh*M=Zck>JK z@NPsDb%<8Orut80;jK{q=h0?-wJa9ow2etnKJyWDXOr4xduik|bH?>5C*5_tUH*x3 zNpbAwzI{$$s6Gyj(1m7c6Ti)f)$_I@P+Va^evVPccg%O(d-*)=8m5n*+S^Iv9ZUY` z)o-XZEdgvLg#5En#rI7aeYaQlNdX8J^T4xFkqcv-5R0Swa8)mzo=w!pvef^t`O_CQ zLcm+GQ1(0w}b(SUil5B1@ zqBd=scs!FQx8}SP$&Y28+$FlOnq^EMb4x~1djdS&vYJz{Q9;+a-Q+^bclv`dySip| zF-~$CZ?^gqM*Adzt8XQjbx)J=|4WIb-wo={nEziGd+m&*QG8-pG|Fae1wWRvcKMV5 z_g~Y7?lqS5h&7K_!_#2i*EsI<|MZ^+SgxN@EbVMk#P?4diRY>@JdUr$AId54YrY=o z2~@|>Q$@sI`3T+YX@Re!zL9%VuG$?5k3_TV%@8nS4Qc2ZiW@hNhJJYo;&;ruF{d;Q z_+LQwF|CoMr7Y8E0n6JB!q@-KfL6wAuE|tUGP9_J8)6bd&$HXT-ntLuP<0ERr}7-N z|2qOF+hV!X?9OPjK}=@0`%ro?8Qm%o4sE|L`l4qoosu!ie(LC9u%<{CZ#1fa%l7_s z>*q$Cy)YNj(`&fcB?Ivi^E*VVmQf31cF&z%Og=;e@&)~4anihFV5HE@ePaEd;`3Cp z)o}ye_c#$(cTiBe(99(~8H^WCnSk~5XzIac#)ylmOn*|Ep8BH>=hbDwgZ=x-h}DX? zb#f_r|HX-Fu$mAd*$Nv&zld6{=}7L*D&UOF7SQwvwr4iTBr9yo`TI{2@b(uT>0b5n>>qYya&G`yZ$|)-W5jZv-}O|*>Rq~c%J2q#OXrz@eq2S&7p}iH9=vxvsmX` zCrT_ogW4-^a^sRF``&+(Wv)}H-HSkcwEr*+G%giAKy}FwNm1WEXWaq=M5aO7y0evU z_GZtI?KY4VCU7qzg{UiQ2*uMcP(3R#UVoMfAG;)?HC-nY-GJ*kItRNs>s*;je3s$>jjvqta54z7-9;Kc)a zkh`yqU#}%W<1=E|KdO_n+o*#JS>C<(eLPZ%z6ymHOWyC|tl8(_1M2`zAAo}VGZXe^)7qLR| z?Bsna)=9$44hTV`7jehm$>0*VUh?RGf@HvH*5~KSGH+=%zyCx%zL=8@#8aP~nl3;? zu7-?GxkWdP7>m1dl%Y##$v@6&z*Z6p-dk+R)ev=D$aH<(^0rh{{|nBT@*7NZ%Q)-7 zW^5Nd7|P$hp&`-cC_mO1l8e3gleWz)8}SXOW^?3=zaqYVR7Mn59j3#S1MzIwHaOQ3 zZ&&{Q8_GNlho}`-h-(ky-}*?&q&EgMW?2?$`WC<~vpK|8tcJ071fa0hiB?Ai;Z+$w zxD*21n=+QQS}6zF5lwWij}G2wZzZYQl<4I@jBPtC2K+xZaAxON_6^fZI{N!j+goXmH1_M9_;+Di2L?I4-YBH!PDk&nrfkfgO#huy@?O` z)~{c2I@5mKrTxi(UyMmOHlOUyJ47>o-NI6}`S9nxwdmO3a*0iI19`zTt4FKV(Xd+$ z_7+s|!G9akeO4(LY%?UTEJHb|wu3BRaDh&UH^kg>#xU#{!B6_sfU2WdKJNot68BFT zmjq=H%h4Pi=MaEa+4EtQgAylgVf$wr1ISpDPQxwqv2=nSSg$$BYcA+SSN{eW?J$pw ztYDhegTKgwwoP=b{{U3qE(2*l;%)2d<)!AaxzIE87Kvy3#yjs`lO>GRP&YeiF_wON3_?t2i}w3t*eDK5e`&V|A*A{AJAYbY9!423t<0 zfVxaIcl{~LFId2MXafT1f87SCHlma$J!=#vu1UmEB6oP{t4GYAtKh_NEf|_*P6ut^ zaj&%)(#7%IUM)kk{G<+~EP>{oP{izjroKAA>IvhVG^F(P_9Gd$R$yIB8p01#le_@- ze6ECgUnP;GE*3ZX@9E2sTBVzkeFo{v)L4od7!yvfh3Y&{`)p zC-$BN>-`Q~WPe4;sTF11*UKTaCS47;@kQj$f>z#oK{SrB@B(3IEcfHJHa2LzAfr_; z(+4*b@Tj!}mL3fj#aUTPqjaq7hn5e6i|pPi%~XZ?`Tc2*?HAPj`WiaY>bPoqBYe5_ zFWX(br)!wcBKu4kF`j*!AF}2-)<+zL364$NX*PG?aY`crm2ULPpak6VoWj9fU$`5$ z4Ke4j0obwpj{BAR*pb0>gOc*};jRrhV_PnWvJMjMX^JT4%l@B^3ux{%c7Hjt9oiQ( zi>fB-O1jbtImgS+G-iY@PHxB~alK{yNKC+!t0aBB{aRlEiX&BFgV9mywKoW>l>MM^ zPMqk)GsgJJ?`MCIdVqqKCN>M2$bZq+bin>Ve4W1?;$;5gT39BOkHH)AG$)Mq7L3HT znhj)GVIaS3gfc#5Ik3GgLG?G=Es*mEMMI=yqjdxd0#meD_LHzVL*W0L$Lx$+XL)ymE5Q^H{czAZGlXLx{ zjThJS_SN}U4;t_yyN6y3wk5MVSr+H0GNSv@h0bM}vm-25fwQDrH2;ISWTtEtmsi2Y z=)d~dm^KK+@2>N0zr^@cnhtx%4uNa4yNGnw457D12cnb9DsZ2@lFQpIM6+56c{%AmEuEZ*rs)XxyB2cRYi01} zP#O4Nolie*fW1BH@c2#%zv|wf zHR9b_VW9HTj{Ii&ma}PT#CX(HT3wflCo;3(^WtbO?yL~2oQ1$8Cs5bTCMfHs53kh^ z@bS&x*iO3uT>b3HyhM52KeUwe+&DzXjt|5?!8^buIKgi2p>Jpw76E6DT_LfLg!s@} zN>U~Iw0Kw+J}i6(`7v`y`yK(VpCf?H6CCN|qi^oPKi_T21?jBD{p2HYpsQw7w) z62{I#S!H^^e;taaJco;c^<2+5mUDMGpQzsPr_me7p_~18ve>&sJWfG~{Tem*o5J9E$aha^gs9UC%wCyF?lWHL0#(4`V39ns`ZwfG(12f z+|2Q$gfWB*s9mE=ndDhiV_%&YEz!WgJ2W6;K_y@Mo7MT8GC26zkc4Ndqo;Z&@#(xk zJ+j!H$f%3l-!y`M01epr=l|=x4%?IK7H0PK^J%UDIO%{Ba8XKJ*+(nPTQe18zcM_AVM%NVGZgHzjnEocBTvz{fV=UT+@Q9ypkdN zyAS#Affky`eP?JWa$^Gc|Vl@Mz~KKA8_NOncz@iE6>M`$B=r$d0#XQ%ho_Qxvm z7*b8axvq&z)e<6aDFmf4cc^b1)59bPAaHhRddSOqT(UP8%-_3{?QzW8XvZ{WIt%D# z$3T2JZzt^4_$rcltSwojT*y5sb7KBeJ=}XEhhXzZ{!@7zeqrwpe|vpG;{_;uC4fh8 zjHcWQ!e>_ga8W&8v^v>JD${CY?{&=+rnzh2VCGTE-eXPGnKnlE)=p@8@E>=H`PW{R zzabexVf6M`BfRdHM}~Wz=atNrQBhS3#(3SP&;5qs+lXP{tLZMDcW`y2y(wQ>p2jK*mQp26Y?DL@N(z$k+Z(F^yiMD_Uc8m;mTN5R8 zNflboeWIqmS_u0K$c9^2_@-e==sUs#w737{yl)wzm)~G$`y)<#(>Trcs%C_7Asy znFSj9>Og_lpfqXyXMC8>!yrFfa19}yl`E##)J zkin*1GVnitD-6`fYpUw7?_&|aabY7yN4*BCRzq@aupVAa`$?WzJ){;phvD`Waxiq0 z2|sLB17=)$0)-E4Nfp~6^A+O0U5)dA6nr%&6GoOra@MRij_ogmOVbnR*1Udbc2Wpy zt+(;+GGFo8*F2ao3djUGc?{lLLb^N;Qj1-Ic<9(p_$ElStH0QSXA7ROXUvayEEeL_ z@yti>qfgtu#N*on3H)`QOxF2nqVp3?#^zc?O~>8FNa_zGSSGvAHEqlV8IV@iQpbO6 zhAL|(x{H*l&)_;tyTbO{FY7s9Bc^{_S3xF6GoHi20L;4T1h0oo;g{w~@aVBOa98aK zv0=9Z8`f|9Z$JNaL>n%>^a)&L8@XfUI+(_M^#9w>m)!1;1{Y<(YjhfqdZVRJe=6FW z%-cZJ^q6jcK^`es>`q6go8x`oYVyZPVi)>csMHxVI#BU>F^IcsTm3Y#@901@JuqO8AiZDOT>jO??wB(68GPOl&AMp{dAPfWxT!&K?l*9G>K+*2BM~sH|WeN7dc*2muwnY&J_k9rRL^(czaq2 zX?yXF_x#<2yJCakqW%x=T!#vJ{$tF>nP=#LDXBQ~aT*L``9b%LtfhMc%{ zb@64M931$iO>;6#@Z%Q+SlL-D+HsDt{{9sAY2)h}b@6F!F;SdlA zyhXH(-6;y+yTY-P|3uq9jFcE$`@+4?aiH@j>7sA%K)5{O8sGWt6{6Q0=qVpYR!JFC zbd&ZNY+PNYOWoJ zHwPosb5FUo-5ThbDTJ}A33O7XAs)BYf>EFUkEHYPtNDHZczd7rUQ#I~vOh-7`@SL} zDx_D7^QF6T4C-9o7AWpYO&37k-W`_h)>7UD?EM zlpfvxhxOWrl)^6Q86^4;>jCl9fE^P(r~&g;4jFtA(qblaZtjd_mnH?vEgI-&)}7im z@hkajs7Q+{>T&AJ1W>%##7!{~pn~CRa(ZkiO|lt;m1*@PZsiM+oVfts|5fkz*l6hF zO1_Zt1Z}a@hRj78j++z0alGHB4tx{ zP^Do^GwGWP7Z;8Yo?KiZ9#_`Z&x*erqJdd=wZLa-1Mhv|1wQ>jA#erIz^9}g65iC>SkOaqVCz4^?8JD1=nA{xcMko0&|Ls+G5G+*Wy0?tP z)zt)^?C+w7jE&KIxhd3{hwz~VxtQu9g7M3&NiFMryM9X=-f3^42U-nrqq!7BO-^(= ztiXB=PNcy}$#F7|We3FjN=f*33u@}XSmGzMN$;Q%A z@nJXPaFbauIC&;>KbTj!j6Cn(&yNmF#!qn)DEfOt=r>slFM6{5Im4J9Tv3C43Ate6 zP{j>@YK)t2N`vNy3hK{#0}l^*NA`XR<4b+w5Ls5vFt3d>HBiPWXR=6H-AY>fH5ap# z${}Hl3^{yFfIf*DFeEXO9zJ7*mn9}(KcXi~X=O8dSG&g^MJ^Br-Op&PBrlVR13bBg=dy&g)0f@N?lf&1Nfjv@GNl*!Rv} zv#4KtktrC6TS97xQNww@^Qjt^>ly-KY)Mlg%jKQC4uAPZ(Z0gZs4=}6?sV=ammewP zFzN68^W3R19G84P2p0>ggwrpmiA(ru?)01k^qP%2+RMBlmogjq7c1K_d)O^-G5X4d zPE|yeG1}lc@Ca?RO2<>xnP7XE3jf+VN{+v_ab6{y4lQ2n2K`tTHh5}NGe0Y=_^1T= zXWk1(7%Ss{Gt2uKl2Xg{@vZ)Q5^ZsX_s&X1!>9Y;k=J(){xXKZDP!0y_`x4PmyWqJ zvcS&f3m1HL5DGeVSjN*l)8RxD*34tsjgwBql)cS&J**{vU_LdPWsP?(ekMinA;JY4 zhlop`b@b2kKS#~*DX|AZgd~S$+|h7dOkG((s>eK}8mp60IX}B! zW3P7X6K5a%-#nL=H^nz&^q?H;`D;DxxU#4if}4y*HynvbY?trQ0Bn@p~*7vO5GPsCXL7&Vz4j;=LZA#rT#q-9E77%11U2iNmCCC{;q1(AkakR@7|Rq>PY z@BVq7%(9jZ<66nMR#QH(v<(B_rGdUHAysT=M#EBaX@eU*%6geMkMn@8Ohry>lqq)i z*n!!aV!DmxwGZ(E7~H#)7q0q@ed}8wee^W)TwfiRupVUZVn3?0Mh9O!{z<;ied4t2 zdJA?Nr@|8JW8^hsINWS5BWqt;(725nD2UEwna48WD8`;z+o=a%OTFmO(MqUtiDlTI ze4_*81W4lkl8&>Pyvy=t9P1&0N6(wN1F~8e6rrdjnnpdgL`8RPSaEDIKRT`% z1FuS;jyEK8GSsl^U=106{{Rj65{5f=tb((uN7Jb z)y`!6qJ?5`9y^)LwP0Ro2d3AJccZ=W5g2KG3X=WYIK5@^;)1?9t}6954V|cu79pKv zgpv$Bayt$UY{;k$v1Mc`GzIhwoE$MaZzDx8wMyw|*0T>@?k!G67EaXn*^wQ4}| z-b2jm6@g0R66~#cD)guwCVAq%B+PF|6ZtPWd)CdeD=bHe3fi zK2{R1zBsyQsv)lKEGE&{PVhUY32;=J5!fufOCycVaM@l9_>{L+^j`ZJ>%`0g!>BoA z%K;^fI{l3lj~YYWq#{`Fb1+n$uNGdi5r|D4YPpTF2dN>;N__qKmdqdB&PPcSkzCsi zzr!-PyOxSrp~(2COiQmbPsjZRBH*pW!iU2hB{RR;I)CVx4)e=ZF#Ops@^^*`HC{Uq z4-ZlT;if9#8m7rOv{#Vn!EvN7c2IRiL&0 zpK$LHFY#X`L-P6EL0UK26eq~r!-M75c$Wzo_DX-6alo{fyuad~QPTZdy3b&JO#Z3?!UOO4sUO<$oJ$Er$eR#XALbz(*G=w?xlX61 z+u*TRvM@(;0N)te#Cn1r!PrMmWIW>wxd-NwTc?1^EKb5Bmf5h;opA|N1vph(lU1)K z(=o0F7^|oS+GZR0(@a-6e*P`&61b3vTdF8I-$5|&2z?O{j^2;ALDvPA<#+#x&pyXO z&)-n8ll=}Jo&JpMzN<$&Op@{P_iU&=F`k5+SH-?ibub?9PObbR@$J7$Q0eT#Wo8=S zo*#mNcqie=maxBPFmn`-9cwNwO==`+rmY3YYpUsd_|+cZwi04J995rfI8 z{AtEa6P-(eOCd%is8WDQa>b-rb0^)nm30~0dB8BMk-{#AauTIxL5rh z>9Cngy8>Be^W}VatD(f1P8*433n#-&_0Lr1oeKUgW-L~j-TcGwY}9z01uoAm$qwcr zjGxg*1}3hj8$7g8;rdT<>q4|s9@F-nf*4nJ=5dl5#dNKNQlexvfKE}+K+mw}wv>k>0X|&*CMCA-$%1_AcdD1hdZPyXC7b**_@9y{d^kKC zcD!rmo)>Ci>WEg7zBZDQGGm<3(M)3Qd=}lUiNW7@w!sH?4Pxi1fY(Ooz=J=7Xy5(} zY$~D9F*unsf2)g!<29grU_@Ly*9Tn6Tf1Os_g3xEI8j zKjApgV>O&OrX=hwPsDGR_QGj9U-CQE2z53M?w|8}?q}ffzZBX>IFkYFZIXRN6|V1` zNjHZ^psw_3$Zv4t7X6eH7kvECKj#lUQo+YX)xVvW(Yi1X4wY7MRv|`czgY&n_f*ga`T~5z*lsfRQGC5c6Gl}( z28#eAvO87{XL;lh-9}$(yYDG3sLTaT_bzTKd*jS{sM)`(2VaXo(Ui+jy<@G&ZF>t2 zeeebr#|4n!&x)wt+e{XRv7Xj5;h1oI2W*n<5`H|XE&g@pUH`8B?z%EkftWZ?e9hl2 zPC$#d60mroM|?_|#;$J!TJulRu6GfrdhjyHh*E?~t-~a?{^riJy7xg%E!)+%eFT5jB6Dtg^>!0l{Jpxou zE+IvsP5i3e@pymoF1UO@jT1apK>yP^P<-eJ{r4~p13rtuWwBWJYn-Db*Urv))twoD zzjV+}MFE_vbf}5>K-O=i)bEE8MY1j)t12@0SUlCJ(ZQVK)g*bvB|g==4UNlhgZoG` zvhB11`l#8!+eTSxP@RrThf;8I`o@KyWqnV36v5tEGjmmDBWBH&z}N3iJ5?8~FaZ=o66Hl?Tp+0#qXg`(zZHx-9?Lh5G6#r^_2Kv6B@Iuy<FS9Pe>%fp!^fn+$lW!v6kpFOs#-(C`qXH!=$Zc-r9UJnV(D_??^zc z)!A_I`Xla*uNtnk)B^dB$<&eUKVzsC)RwI075?kM%cgHZY4K!okm<(iX`MtOIYRfb zT|IZ{PEdAAo3z54pmih)<4<+}^lH=ErNCdk78-&T6PQU|}E{6h{(sn8hl2b`Fe3@4c;Ag8U4i&e{r z+|2Xz`Mkk+Y3xTLNh=iP4e^k;#`ro9beRBm&a?lo6MAs^tqnc1HxD=6lt73$hdVmV z1Rr<_;N;1t)LzdN4=iTAU@Lk4_NpcfN=SueQ;djbm;fL8mJ+Mno%BM5HO}#CA+iBD zNhJGLY-7#-TY+-ob<09qaQNmH~P{ITFM=bWDf5B~JU@sQjid)StBw&{K)~TWx~Vdxt>HnG$;WxFJsN zW4j0IaIHF`p&eW=+jpIMkdu=@}xvGPr(|?G@#TcjM4J;GAG!61U93^2* zns_^=lKe2SqzcHF?32FDLR$G8y;!G&C7B?=+?qrQdLC-xmt2H@)A9HObh*Pyd(cTZ4mj#wBe;G zEZ1WIq!+cYu*3qUzZgwVXQpG~Dlyb)Cv&XD5zDPLpzK95HM~0z-)__C-{IG=+}xTP z2?$aQ2x0!uhJlTwdtET~6)>Ldr!{b_LP1@rz?Q}0erw>2URC(DdM2IoC<425&%np%nVi{PRZK~$WxH+2B9^+pFb znawV{*U!np?WbsuK{ETU<$`a{E#ZkQZ;69=opUL-6lQH=-BrGft+(8Sn&viQLtGKS z6#IlU&9!K_j3Ao_|=1waW(TE zbnp7aX)ykPPNY`<%``JG0>zG3V1&v#(RS7ykT$;<^g{y3mvR9*ru2}Ii!11egUlB< zY8NPmcL^nDn8t2j&Aly}M_o^<;G*XevfttjUu_zXCi5iV%XmIZRg_Ws3uC)I3Zk7Y z5!fAe1>SE+6)s@jk`YM*oOk}-&%CM{C_967=K74LK`)rE@6j%h{=JBsmdSFgo#o^; zKB2Qw4@*uJllFhd`O5=Y&b`DGa<1K{i(Wy;2v+2%RY)75F7Hp47amE8Y#J=pFzfN;6RW2~Z zp<#nTK_ilXa*O#A$MA4`j4}B&Mh$PwQG!XHyQz6}1YXu>{b;*h3Kf^I&aWN{^5KDG z3hQ61ykAZ353`~Q8yI6@?^@P>w4B4ex;U2>5gpe@w8$(GwKqS5J0It9ztet;k9?Pb z|K~zS22 z(4qBZ2`B;9Lu56cJYzRv*L-!jd2J3I_&EYsY`h9z_D|)u4QH%ND|xuItc8w<*2QAc zKXP`MDqU<}k1H0Z0Qk0WjqJNDwZD?s-@Ql;LX1&)FY{0lUNqU;U6SnX>nvU~p7p%2 zUg;=Zc)$&!n~KFa`%o6VsTXk{|1-wE-2#aIn@sQ8>!HOWDY(Bsg|EtQ#N8oj(8##u zzf%~;^=2vA->`$uZnMU>6WhomMaiUDUS;AG?aqGwOlGD4+urKHhSUbW@(ZH*2NAeS zOOvx^x_DVb2{!j$qP8y;F+#eXJQ!xmCx30hflD%>aUmge3)3D?v%ZFRZuH)PFf{D* zggYW7?rD_~_I~cQz!XbJ_CCdTyCG&eiQwzkfh0>$jdepvfkWB``bnUJ zOVXxYTGZorcmh&FmQUIbItb-?;tzgWf|7gjr7kG>1;{>B}IDVQA zwhh;WhMiC8M>joOG)Nho&ravFhqvN=jXba(U_usdQAGXxcVxZQZn~d&iB~*W2YOD* z!j08GurMSJmPX$qze^o(q$&Y>E=Tmo%3CSHZPWSJ4}Ybq0oB$$0jJd;8B3Ghi2YxY?&z~LZoqK7 zkTef0-56W4M@QI@#LR1F^7Yo^*Q zs;DhhPtK%8@}ZyF(FGI0aD+MOo}-C_*A`}!a26_04%9h$GxM!lQNId)Z`Z996IcQfy)W^zPWlH;P#XU)Zw!o?wLFSc6#j-DHZZKz90jJsk@P_WddA0Lk4ae2&p5R^KY_` zz=!A>;f`Ob;%8>{{rh~^c*gJ?UrwftYvF57$Km&Td*F0f8t40k`L#04pjL94T24#D z%j3kLuo#6l>l`K4X+xa-C(ML}wYnINO3;&}Md$*AflUFZw$f@;iqP zoX>88@5@Mi=viK7Y8#r2z6VXsW<;se0OuDCh6h48WM1Q4h`@R$1{$;u;r%|H)fT)xP6)~*?(gx=qz$AzaP-ewoYN}?_m6=j z=nM18erzUdRP1Rb^CrD!nXSMl+;INC=R z7PiZYEm%Hl*DD>^$~;kdk`~lzE(NPi#$-d7E?!iUf{j=1Qy&uxr0&vCrDV)6zuAPh zMKMr6Qb_i*e@9u57i7UYpaotDSfc$5Mz4I#MJWjIkC6^&UQD5Py7kfKnGV$b^yBNy zKjQqB3Rv7eh0JB1js598#I^hwy>>ku9}eCFn$y!K{d^%K+28&Q#J6vfO^;R4v-laY zE!Ls33CZ{&HxJz1oJjC1)}tZPfQiL(>GeO?kc*Ch7w2YhwJ}=ws8}9Y*9w(px$HE% zzvSE3$BE^4R-et%R!b};dK-hErP8+4Mz#|uT1*gl!7WC)4fgXzp! zV%$183n~tZxF^bk&?3?RREv;a+^>aOQhSNmD3Sl**MP_486#!4Au(dzI(xR1k)p7j zRO;Fwthmt5Oe~T~md8uQe~SJ$=fCx-p^~v~|1H(wB+DPsN;CN427&|4D zs-087_s81E--#xC_~I5^H!2G@tt4cenL3WVUO}uo-RR{g*2|N<7=j&@Id7pMHhS5E zIVqxBEA{ctc60c5_c)*MkH-l!v!L*j1#yTF;J3dr@JwMdjbdI<$M`;ybSuW`m249l z&&q&@7RLy;MHB7qs!7gvOWMqK_^lm_Vd$kboP(hjc6eFBA5A~{c5N!k+!Mo5PaiJ9 zUI{ZNDS+?ypLF6xRXk821^=(ZOB7l$f58iock1A-jbePNfO^7TyG(B=8#1qW3z<5& zOJwu56}8Oo!`j6_s+Dzd#)Cm{Qgu8n&PYckgKW_CdCJ+(wn4+MRwqV17JZ zc=2TspYirH?yr0U)733W>v|28%x@!8{yR)Hhlk^TLF-{mg0k@0*zdUPQ5@{W5+o;zMd{zzZmi2g{sJNKk5xr+vN8znyVBHLmSY+k3XayZIV1Mg`rg*WZN7Ym zDzM+*QN7*7?yfX_(%p<(rQ_kj_-?L{`2-vz^2v7D({xv#BW~}S0=07o2$w1^ljsfg zbv`l73vRF*YsMH2i1IX}H-g*npiBj*y=ddo*?YubvKkEe(L`6VJ?%nCE!h(q&ab@i z3(t+_q2|C~60M|;CeisMvUVfgyHSGg&Q`+EIB7CJfqh@{bb#A^jRxfo!JCWhpk}_b z=x^)~*0t9JUp5|RtR*#!iTy$zKk%kLY!2&x-3vc#KMPIsw8XQ=)b#K3v48Z?P3|oj zd%S_4GA<6IwQ^wJTs@M(K4ajj2a=GZ^jnjN-4`;!e|5d^s=cG+G|L1H#~|3hUmdHa z{pjE4wQ?9k*dYMc3|+#_e!=)KFX~C;^CWr>b@8Dy%lu{^=MPP0orWU@fQ^_4PgU-p^Mbh%_@MbHY@9ovJ8Nu&sfNGEA8;*P(?;9lnw>(B(~jl$CqKn!)jU)u z8xi^6nrQn;9W3x5y-^r}rei|k)z<={d~z)|nM%N8)jksSSsj(nx01la_Eat?97BJs zhYq(D+=v)^Q zarmAJSgT@68XoE3Oy)n)_P$TU7we&w`B$R4RFl8%-ip?Z2{3Ld5S5+E7^C})oOm^n z4oQqhyTn}BTKkv_EL6j)o4W8}Qz|w6V2ZYWCeV_wi&q@of%5m?LDU2n;>-Ft_Vj)w zX7T$-~A2 zJlAWZj{&i&(CC#wm(9|^$40$m_R4tP=o8}=JW7Ysc0-cst;V`L%ll`3ywf1GbLb@P zE3+pZ9a$m{?dv4IQ{}`~jL&u;Qx~KzHt_Aw#aO?J!ZA~6GQ(OGbFNE6Th(d$Dn}j< z<+qXi7smXv2Td3}I15G{;mFu50ltf@?4S9zVPQCJu^0FrR_1c&8RCKaL*VGpH?(Pj z1+Ly_2TP;Q@q12)vB8?cM1M=-ku1PgX*qcCb2E(&7>v^<=)l45=T1cH1CCvr2Bss9 zFrU3L&MGY-&#s!##`-W!&GCX$Yu9p*-fQ9@&I;_W`_Y?P%wv2-3@4AS;;!vvUOx6c zU9_~9<`%PCjJX^fi>CYvaUC|U&4GY3job~MWi(paNK$n;711!vII;mocWmJcKDS^} z^8J3@=FwtZ^l-3+EV~J`$1?-3nLLBZ4^y~{Sq6-`qz_q6Sv0I?0A7*OgTo6J^VU+| z*dG2CZa%RlX#<&7=G;O|f`aL8OP232^@CBeD#9qWFZeMo7EaB(K?ZyrglB(EfVMi3 z$eSeNmq$E&n=T~(ePG$u8Wl*mF^$ftj=&9*&#~QUHn%iZMy#}^k(>7J79I6U8@11L z6QgP=TE6@{ezp*SVxScHXwPo_AM?qRGpFdTlf$q)ZVLRlZZ1>^@sb3L^>u!~e+fvM zHIP)RL+(0LdaJ1oZ5t~=+||xC2`upJd-lCs(@1yvC}GdOT5|4582`sZO5&#Q44Oql zNg88cKtKWUE!jksEfL-CRKkq;(!`zR=~9`8Vb$j_TDZ&(t*i&b&-Q;=RwL9TW5Z>f z_rD4!)6c46X3H0n^L;rT8Xu1BWr47@>$7n5A{}w)xO$Gew}6Jl8{j6jcjRMSGp}is ziSBQUL0;2>DCa8S!zY^X>CZtrMI{SmV>6)oOPx@_Zkn2-teh)nAB4UDwo6a>L5d!X zqRVTU2is~N-2bwK>)WV?!^6wTm4QsFch|zfjYY)Z+Y!ELEbE(dwgBZP59w&;x2d-t z0_sZJM5D*?*j}CmcS_wz=y7d~I;aFe4_)Z||03{k_A&4uTPO6XRuikeY35#>4W=(x z{xqnuf~;<6=9fyvV|5?PJ@ut?;j9zEW~2q&(LPHPVxQt>=6RD=5DNz$bd(rP9OnE= zJPYQI*F$?*RhXk_K)vI>0`YED0vdqtLp^D5>I?tDlNW@<4 zgRpID50~PukMmdC!POc$`mO5)PKYRjs-cP`f@PC4(v(4Nt7axPc3^;2A^1&lA@YH$ zD0jAzaTPqM|IToXkMx7c7-`On&J~|k(r54AJ=Bryz-{{WkoYr#pRnjD{(8e0M?Z{+ zA>-{2o}vQ#C+wk4?Tno}_Z;M9zY^L=Gu@lzK!blCArS_Qc~aI&oPXO<3&w5h%kqO^ zKUQ!}ll9S2s)Fc+KcQliG@R^L1j$#IaxK??imeRf`tPvw|Ck_#n!ugaE&L&NkLX$b z4iw8x$y|{RPEV9(oW1+hcBBD@H2);p=d}660LGr3odjz-fhc&he(LqPWZGaSI^{0K zAM%xuq@KZNu!a!2BYBOU?_Dz$}hMsVB*40ayveR9;_dNk;et#);@RA zfL0mFWhs`w`+SStyj9WuXCBcSqf4i`B;uPdFJN!pM3OW?fD0Y;VfgSxwAnlrb;T)g zS8)?pI7=VBPz_YyeWqO-l(0Lti}-$!qDxfkv1&N;kxpsj5)(A=7~^R)9J|E4rh_nj zQWse_`;}<)u33_GZ+)Hj>5YRRLsiWCsskSyENN4#2!pSRAmn=%r@c%UZ~ReVnbSDx zdYtui9O@;1zsK?VN%g3}-l20wu{$912+dgjj%?Q1Lk9eu6J**@i0yo-|6ow8K%fR)UGFMLr$u!dEp#0|2rk8KqW4cG3Fr{8B`Rea8r&jrc;0hNIy!XrQ!j|zt@9f&lmF*(_3-G#sVmbG$oan zWHG{~k~rIKqZ8S!XQ1vTXgr}Jblu;BOPSs{-0KE$T5p3JE1jTyI2Elwm5f{FiW!TQ zBk?Sc|JqUo7S>Fq%VZ*P%ZBr?w_py})hH+SYiZ+#8Qr5%j6qi&(@n}(N>R5-jrcYo z9t;vbana)iI4`(>EMvFw8qN`|K1>CZrUAlBWs4;pO1{oPk&9thwgwJM*8nUqrBbh3 zS!UrKoQZ7bE~pH^W#3idpV~vtFe0vs5 zHLj+h^vM)BKcY(LIL%R_Vhz%vHgj2dERe}R8Be9lfQ%17+3H+nZD*Y6>%n5ZY;&R)SV`oMYZ9FTgfo-+BtIXIn%UfzakdH z4XECgIP7(P-mlf4ex;7-riM^iu!L&+rJ%y{6u9iMkvr6(kKUIA@L1&w&El0XIJTR7 zpDs-geFGK^eO7I zJjHQYA8x3Z61KT0!`hF(sRrYsIL%Rmd8+yRM3q`x9{mh(Oe3fMfc49)|3+47-=wJ@ zY%!6_fSIX0|EIGV)%_oW+c+Qr3$@W&XbTQTpML?)&7aG`MH%sj ztu6f?8yy!dT(bQ$2_jN-!q7%Ed71!!UAj2EUUjrOUqo8e&(g1%j`;ZPG${IIAspeg zNMf$*>%6FY5lm@he4Z*z2-t5%^IBSPqiz-K-rdgK>@~+xO=|GXxshfBvhMh?($Fo4 z;}0!p!=>p@!RWO)Il_7g@%3x6WR*W1Iwu7^mlVMpy0Jp6V&kB*`FlKZzbhY8P|P(5bRv>MOeaXi^pGVH5;3*2wB>b>945~xGN(B1aTjPqhG3t z-^jFc!NNn-nRz^FlHQS?v}Qh4E1t2w4}z;qCO5i+bu^5y1bqgLHXh)JpDHH8fjtw1 zjvpBN<+U<6Uel$!gIPD(rw}-Bav@h^tcMOIKgh&T361*AxZL4Yq=OIT6D{MhYxhC0 zs_N#(Cm6GijNx#xSecp)7NKfOKKy6(kGpjt0__woz#iGK%v`Y9#*JeF3VbzZTZ7_=of7*TX}f^W@=UmJ{68O>Sxoqwmw1cV(MD zNVc!ymM&+0?3mYt^SVnXD^dJ6uL=@U*K(C3e~8aG%J#7!BNcwU}HjaG|4b z^61+24nCh|y4gg=>Yro??P?iRL!ySpYt?~^@#e?he2(HnBKV?aM?S1q!`-I6dya&_L~Wlc0X-JCEFA*Nk2#CungUu*@fgwygoe`5{uPG^We|i@x+;De)2ed z5FPQPH}jHl$JZ24eBj4*moqQK1I7NE?0;@bm{`?A9*0U(*`Lj5`BMywGP}6&*J_w> zgn=LyUZ8es*c?0V4U76F@lW^9kW{AoI^U@s3p&y4hJH{N#G5SXjl)^!Qo#e)l*J`$ z>f?3h;XERfM6)Qnjc)HFbLJ=T+paN2#99&jKSO@?Y36MfzbEUW_tKW*VVM2e8=5o6 z2+{bBc;DmhexLjmXZ9V5HUi<>R{qNEEc`T)<-`~M;}YhpU}KmpbZlgq_uUpKVi}+L zz7zQ~-OQ6<_MRmB&!nr_4u8>S1!zA~;YvN(j4H7L_czaI#(qOgO|yoN4yX7J+L@So zUj*_81`wHZ0_=`ffJVcubfwiW9LF@YsTYf!Bm-*kH=oh3)#P`mV)>COvQBpZz0t-x zWs+9F;!(a_E6Z>#7;6PP)~~0IHOW}yoehUVeYno;O8DOb6)^AnLv3SC(3agD+yhJb zeJ5+N;LvkW^>5-r*zK6#{E1Z6M9@u}2O|!U1N}C6eh$k+J@kD9U)KZCJj(9oUG{J* z%8B|{Ct~$zgnG9G?wFYEEy)@%ocU^=O2X{_iM^5}(+|j?o*FgTLM}Qp#=?tNZ?u5LidIehSCiWe0)Z z^i{~s)e+a4wQxYh*r@ z?nK|?CGbyX8oB$6X>0Sl$orE^=#GowX!>~zXug%3cjTWK(^TLbX( zYAo;Moru?C#LzUzh+H*S$M-s#kohZ!ZqSd!S0^q)yHb(R-|R0owS0iRr_Yg6T{RrJ zubt>C+tEuB=5d<1732o^aFL9Wu7B`NKcgUCmPe(eD&W_z<-Q;NE?$iCP*5x<{!*lY z|8{D_y@+yt=BPY8Hjl#9dPR~jL>1%C{vvYX>$Kj)0N*j@aHK?szdEK7AHGWhy-tq& zd#R2&WyQqEz=h82dWwfPGlp<>BKOSG6z8Ydfpb9t-OZM-kghytP|>d z_+WCjl;u8d{2_%SPtZ(L6a2kf2EGmzPI5D9!KEWp;FZ}q;%+9uWt)mf+YtlWG$0Na z+{}mMgb75WP8r3idN6700=hJtef~$L!aiF+?ue@%dP&q_b65}6V;b^`U((=Zr9zuB zn^A3$1nv*-=5ifa*RyjS39-9G>wUto(QYMt*em2Ca}>~cjW$$74xqA^GSOoK1%sPe z-20KNk3&}x!uuXlt2@lMFE0f*_ym5+-WF72eq*@;GcwgwfI}YD5YeT*wEQN!jfSrT zKliah_eDiw*#EiTV{_uS05i84L*V2#{=lwuY*`?J&t1Q{{p@=o`&|yAmY=25*BW55 zjuLb&AHhFiKI&tZ2n;VnV%8{Qr)ed5T;WQ`v)iaZa}|73Qsvg04Z;^IIT*CMnYwH= z!82NR5bkr9w`W}IS zUnUov|TDh8Q2vWjxi&f!y z?_X+3jZv4=g$r#Z{Km%jxYPeRY}nDrX-`qdA7x!6-!hUu$+5-FXXL;@EYGh_Y(jbI z$KX5^$bb}Wlo8m&2Ca#7$;%WhE6;_B4^O#7_V2EysR`s{0?pC3!Xe{L;rG!Me96Lg zTydiqChQqNemk-bi*K#OYbxvc-4~9jC$>RyxvJ1Q=@Y(r91pSD*NL3Na7-LI6KX39 zM2Zs<(EEiLrggBsS_{TJG}HpKtl2bNDiUArzXWfq-8t=Ha^i-FPHq{!NB<1d#^f#E z`)9kdqydL~NrJ_Ly17ah0j@BALniB=p>6CpYtw|uusXyOggGFipCZhSB@7V3$;#aEOPar1YDuv!>Z0c*{H_5eYxYJ)04< z`GEzx`YA%JON(%`j0)?VddKo&kEob=Usb=dId2%kTe7{n^nf*ZC`Qu{i?VP?eF41q zr_Rf+%0SPlJoKEJL3CQwaTUudx_L~d-~Ac)rtl;L&ug>?8_edm2&17zOIvA-}|j3x1@Ir4A*e_~bo0 zq%{+>3o1cp*lO-|_c!shod50Z#Z3RqpP>);daHRWQZ% zrwuj4TP}<-@=cc?%eUZYBi6;BH<=W(->mdIC8Uq_5Pix|LajALu%R}d`*FksH#peA z)(@|!IE(rBVl-fT%nJTyU=HR?$bxyMw#4!f>wdlXhwPC(K`%yX<1^bIWO&=CN$(h= zJ~=!Uc%}2?;vNlL>|IKR4>6{1{)0^aiT<;@oEI+6Q!yd%Z*IHUQ(MJX@H6-)Vfz2r6 zDuIHrW+X3=F?DS|5P6$@G`1>?c?MR&ySTB!kq2Lkwf^hrpY6{FYvRNXGuXj*@`m@) za85DP_S1iJvdjbauv-aSjV@5NXcM$)R)ZBiWBIx_4R~=4Lhv&}Y^E^Ip?Wp>@_0H8 zmxQ6tb04VKtjawb&U%hY2u$#Ap@aUKqTa6|u+jS*Z&`u3!u2_LZnGga;VP*0R33ic z+C)dmFj8QiF{GLmIz2aN#EzQ??VpYln^!6*)mBY@#F$esVqV;7t3f(`J-021`4%qP zz>xfnRAXoo4s^|dV>Uiq=4B<6+n@$PYX4|%nh|Qv)P*homGDP(-ea#(9_TM<#5FY%iFdwc6sUEH%v1M>W5@zYOr;G&UbaN?x}xw1tW&n#*qr`v<*E#_hPAlw1# z#;6I~2C@#66A9p9a-ArROu~yZa~S)V5L%>yDo@qn`kfi{56f1JzH%9U-JQqfn#hTV z+jMa@!|v1CRoW=abV$>cGW32-J*KZphNID4+)G`ile{Y-Wb#?68Eu0$XPjZ%abw}9 zhaQsj>UGYh4;I3hU7DzPSQoHx09{_kx)Q_^7&N$$o1tKa+bq;!@1+KMTw6TgY%3@Cd?9Ts zVqIn%E6L!s?P#|MzJ)QH_UN`X7Y%ng3AZKRf5C zQHNmR9ToQG?Im>uBk5%3Z&WBe1OaRbAgGot3v>1eZ-hdFYsrtXt$f#Z^SXo2P-wox@9dE#< zTaV!9GgA^;&bl=x*~9ZAvQ%nv4xZ_I3+A=*WSS@fSGrz?^5pQ$2G@@$cwYu5A50_m zE7dVH^E0{CzJ$(U9a24KcEE^RvfPEnIb!WTV^TUffUcfvii*3(!ltY{ym@B=-fxwF z>L(*&zC;D}C#plk&j5ODSR|$V{neb8=$-KCX2mDq_S_S&_ z!?9#kuzd*zA~$m7tsIWK&oWWjuHM7?)6-8XLvTqO{Zpic%e~oqKU;;4tYcXU4n=Sv zr=9C!e2qlIClc^Gir&1ZhgK^a$WKiab^TAv{XiGwR$J1@wKlLhGL^;*9_LNvmHHpIH4F#~d$!Cmx36O1=X6YkVTXbUT&4bpbOv0>EvGvoP`W z3-P`3p96TyYStA+ei%d6;WplJZx$wWv5o*iA9sdnY_>0v1M=$>eXBPFr3b6Q&}bKa zOB(AXxl_ROw?Oot$Yc4359E57FFjR#0fXaKLVAND_dVMJYZ74qS2uUlN6(=)1N*tg z{Tv*{^uX$aOo(f+BEHxu3&)!`QVkay)U`2ygYQaQXS96A!&LUwyZ6CD=WWJu}VBo@)gy$Z$;4Q`h{l0XGl$)91(O4lQtMj6u56RfAUkD+6 zLZbAJ?EpyvIN9P$i%c)Fp6hd96wGwdAEd-Tm$!2#R^FhSS{PsE+(%Y(QnXaCwXE;&VbMEcJtl(QZq3CkS_RrN4}|GsW)w&_tajfeIS1a}P{-QWIzV5UQRkhk z1E@70+PoffvcC+_+gboRg>|%LlN4s~%p;J0mcQNc1&2<}1`nYziRosz6YEyqF1wj_ zFbuh)?*)WJ{@_kH3s}UxA2J!Jv0V7IW~>maat z8c4-mtTQhDAh_J<7Dist5NF+J;esyCr*X{dQ8%%Ste*RUpLHPxs~^3Bs%r*Bs!s!J zgywALjG&c)5(SIfrQKz}8FIg(9SRDfY}`-VAB4xxlrVF)1pE(I5C1m=S2OJ8bxNZU z2J7OVqz+O#K9BaSSI23sRRizv&3m-$=2#q)J_%lVg^OOU$i_)^JT$y! z*vmB)Ja$}hKqq4p9E+!lPl8EFy|B1fN!+gdgDdGeNWGaxx}dh298zlHuTJ@l;c0ik z>U#(0T&;{6PliIbFp3tnI%3lbFL<>HgpYGsHt%U=_!O*7OLJpURX!YwPR-}GOd5vM zWmMpA%?IjmOcAs0RTIz3NWTB{XH0Co1Mk>AmQ=vJ$!~|jdQVB3usR)ismE|p@QZuG zIx910or9w;v3WmFwBY)NWs|a%#S}&#*c33)XC0Dpe8Mn@ON2)$2(z!2~{(ty;@Oim{ zQ(o60zW7dNKo9vKOn@dfnsB4NoFBip0DJRAaBkLMBIwh@A+cLfAsTVXPR}UY3 z8Um|}Lio^sVho&@59;xjM0|;L0X+CeLMI-h3#~Np>Z3ozO=^tW2{zOE=V!qen@Dn< zVPB=pDuwJBo zJ$3^QrIudVIHZVmcY5b>sq!OHrrr)L29?oYrxfvR(LZwkWD?)`;xl?YD+Gf(hGdqG zEQ&KLNmSz|`i||-R;jC?pw3ws*IFV@$zqx`raN`pYk-aq>_FQ=lK!~Eas_9IpkVE9 zZf&zXo~)LEZ;Fb zI5$~|6U12J{y!eD_S0ATZk0YZhS-9;Y9#-=D-(CzMvYc)fHOD31=J zmoXLJAAAJ=%?#j{pJ2H9WC6_bmk>8+eZf)1Z$Ku$jZ=5i#=@zR(CBrY9%wc}%lDE{ zI8Tz_@Vx=;uRMU2*&fW7r-olA*g@Gx7h1L~1vUN@!I6EbTq5)78^o!@!n#zdX=;K6 z7Yvy{ZV7*7UK8$MJNfLGA*94v2@4kgARDJ1q%Te~KlrN<&=DvL|LgmPYKpIIE7nGnscdlKjF#U^Nl(!x>c2D@r9`h_N6Sy{=R^T68*B^{^b={$+Dn+GlnC-K zwu&D2BaY4zLD{SMWMPv6%Y5i3M@v>v8@X7FI(-Q4hx`(5QD(ipA1X0q5$ zTo8W<#y?uhWu$82lt16e?u0CAJ&*NhlXt`-=KwFkbg)4c!=SbA9(^)xI0|+UxTF;( z+V(mNN1tMT=XzhVrhwrvR}{cJ-Gk1Ljm6*(;ozD1Md-CxS)3Qy!EJech-R_AhD%3k z$>CCfYS|1=Ohbcxk0G?RK)BMK`R@dRff*k6nDvN_%z5?;W0!u0RNqLVW~_=9nmwea!-2l7j=`2Wp`h}7B^TPIgoo`*$%A)^bob31 zw8*I%z*t=DI>hlZvIE>`hb+T6r8I#HE$7ud3vqfE52k}<$iEr-_$O8w*3_lYD|?uq zx1*VeAItE8Q<~5rI1g%Uy$HrDqsoXf!dWwnWn3CwGI|G_x21AN4(j2qT{h5stb}@| z8KaiJC0vr-$N$-nXyYb=GvkL6$@>Bpw#5t|0rl8rH^>7KESPaM-gBtB5lcBXG! zAF2|A&8)_Y|w}9o)UI zNH#2BdDI@Vu;dxjXq61X#M>Gmd)AHrcf1|Fm}aSL?i7;8xY`GgtBFzQM0!t_*9pG!;U&`DI>lP$oW=q#)`xB2H5k@q>drIKgI`<7|!J z78$~@&n2#Vn4elk{SmAWI7TkcRziVcJ+Ub=rLC?pIBHWMe9d0RZC%bfBJVhW>4^~9 z&%7ax(J#QaYCShEO%5*wvuq+sNiox>V6>AmNDX?-7Zx<(IL&f+dG9B;B9~>DH?y37 zHh)4(wXpYO2XTn}AzJpno@sO+z}!%Gaw$Rs*VH&b;8>0tEKR`!i&^IXh%|1yNC`hO zESJWm(Vj{bY`LurVYw6dQ0E3*o%;?(T{kAGW~`&I^(Q$Le~`wXV>zXbcB{Hlj_=U z6?nW-kFHrvarw4l`6ne71lv^b^)=yqk@yf(%?RG z9lfj*nO(#V~fvEaxhNrkSMl46U!9Dpqt}M zT9{tN+gkxb_q)?P=DS?{BLcRZYY;}&DTx=lbaG+W53#6Gbrc7*lC(b^yy=)GB-P1K zwY!(o(iWiBLTm6(JWWjn>G*zeF^J8Igu7R%;hGUD5I#hQKKm4l5(bfQ*JL5LW}hYY zY*iVU+q)mKT%f4hf!%wvRXu)qavx@IFea-nDWmY2)xhrUGN}-g*SrTAkqkNc+6E7d zwSp3V+q{KKl(AE-i>#WskRE;)gRP1?;bOHk=dr_293yMYa_)E0A#a$+C)yE4yuZx* zo=is3=7%7)N1s#&sNlz4+Ta*`kd7!4;fh+;6|!EEi&p8v(#>^n#X5q_5U|{y{$FIY zg9Fu-XI}f|J7G=oD$aVU0Ixr(AmWM}RBmA=-dOk^e%@KmojdYFJmJ3Vz`h;G@aoRR znn0eH@v$=yuX7acZ5m7zy0!4wC`EYm=ssP0Sr)VGTL$*+d!CKxR+Ett(r;btT-U*S<(xSvr%Wdz!c3uFGr%Uk(vYCLkf`Oq-lf;@>* z#*x9y>uPwC$}`PCPT)UMxnYc(cxD6MH_Zp7#3j#iAr`roYHAFqW*Ohf+bhbrB5y#_~$3qdre zm75Z+h~YZ*#AvL z@evJR8UQqwg3VV``5_sNc=UHMJo7Ulzq}PtUAc}F{RyGdo?gHRgSD`=VXV-)@0r-^ zL+5}N{rXKUTyxS2axeAr`hLY2!M_80Cq)uBO$VO{v|;l5OH`fB>fTgMP<9mZ>Fi#+ zyz2$*VtmkKIeDy}&AjdU6R8`U)uNYcVUC3|XBcjQlaF|T(d=gWdVx7E=yir$Cob@z zav7*Loq}ho5$SAFVu5Cgu%Tuf^>f!iA6eEpC{A--(N%|IjUK_o>Z1gm1o-G>6PdKq zf==>{L0zYHFfM34cV?0rz7MpAcPhcOqf3O#ew2d#@on6Dwr__`QH7A%l49%Ax_Env z&VY`kF61X3kFSLbm;Q3u%x_pzDG491vfLr&+e&}gMXnb76n$}PK%48y;BDtgqz1EY z4lR4A%W|a_x03OE*CX(^P2+x*Dxp-FChS<5P8Vsho~AFXH)P%f{tLtK$8hgJHN}YR zZcxN1w@y-7a*)QHj=|EvUC>;kEOgk=hM}#Q@T@zY)La>Y>G2#iZ4!yDi<9tE`$MSz z&5@&v4)dKa%kND0(;iFUmUTx-aT%6K)#sSJ3Vs=w82SHV|idyfsJ-;IAHy zEa&kyh~VSVhg?mUE^eMJfQbidXzfw~E{g0SM-s2`6J~zK2O7C751hSQrzvAwX$ATI zVl%agNXLz$3UDv%<#uip;E7EpP#Jxl{ugD6^3(LX!nkX z?k7Iv)-PquC{}`JbG_*OyjaZYi-eSbMxpx~C9y+g7q{&1AzE=j1Gh8HfTQ^@UgLcy zCcn=EjkVI`JJS!$*<=HYhDOsLuT#-)WihBk6bd8zl`-O#5`56nq!DGYn5%h;@w5v$ zmpc~tBA;<{^Q)*zw<1n4{X%N@M)CFET2TLC2BdYex#X;aU&EYWN}K{U??N_*-$UqJ z8S*FB8vjnWg04E7yzg`WVCTzbaFChLo?j)b=wr%g1qB+yK=pt_)_P2+78mEfuSqDe{it}{J_aV6SlNOsrLVji454?8u9T@e<4}YL*L>=7B{L9rn zbwHJ4`rtpTkeY4R#u@Bp)amXJ{pZ+(;*DuwywsbF3uO9%bN@f*?`2YK+EfXLoC>+F z+e&yQRSWDY(rM=!mZj;e3^P-_`QA>J-x5~}Hw+nGBvi(zSv@3ZXBe&fVvDYs%8=s` z?ac;E47w_KZkt10I=9UuLlWzU`SX zb=z+4XQZ^)fZf*0LAR;bC^ioV^^(aE67>F!YTUUj8y1y(=XSB5*~hV(tlfW_K3ZXd z=NbT>73&C%4W|~g6$QGNYtM#+QyQ3|U32rZ9_AkJ?tS(d4S@9xOJ;P&;j$ukxgT{;5QM!mwcL{0HG%`T>ETTD+JR>JTR z>}H%+#h0vRb7p55^eP#Xv9+4`t;!1SRYuWJjS)C$g$rm*ULahwz@cEGk%PPWi$ieT zPXi4V6d+0t=(d@$IP}gD7-YMGJ91eKLv`DU%90Ek@me2wpYOzVaTGtZTp4wC*+RyM zBx)Wq6#taCLgVcHqJRw<=&psJvCEevx+}775k+7wN$Qgwi%a`X!9SBG;VUO4@y`R@ z0~m|je07{Y`3EVl@8Wl!>%d`dEZ;**n#^PzbXk!t?EVx@=hpD}dQSx$KlNJZJ4Fp2 z=&M1enlAlOAB*EHqd20@*PCIP$~>~OPZ9kMyGcgK z0{TIU^<}j0fqTyebBaf&iCZj9iRS#h^uu}`oT=sv=Nhl@2R0-lHFyF)VhxC1U@(yb3)ebRAXi$ zJ?Y%h<929}>H%f^SE|0%81)jYAWOKPH?S0;%jbM}Z)-t1-^=6U;jEX0=~$k648U2d(F-N%Xtq`iM_Y0@{jn-ImhmQIm6B-33LV5Mh9|5N z^GTb&;o6=TV7S+uY>QXKV5bJM)MFQ&z%YtsrR(9c{CJ^<=Tq@ypYDNq?rFfZ9DX+N z`avJx8ZN?b7SG_gK$|U5M zy_w9NKAkGs#IUT$4WJ<>;PMO2aDlxywg{GZ4E_yDeNB5pZ{I0gAHr@h{Wh_(fI7oSk9%eel!oFRH%-S>Ii%+p(>X$(c|nZ zXk*&5LzMM%m1#pmLI!)ZmjPi2S^xQdQcxr zeI>y6bfnvZ<4u?*kpUr9apXz9F>3e#l>8Qn2-CP`%RGSw#HY8w zy!5~4I)4{8=c=@L-1J_~MdJ<~!L&(DUVn(RlO!E~y&AtI<*=U9cJ6tn60Y7*MJ)Xz z>DGiHIAM`H$Y$yYcW#|rka{@K-NktpoSmhO_YF)z?UyzEcq<I~~mUnux_Ua8^;0=rV3@ zmWnwbcayG{XP=*QPvQKjGoq2Ytk-pz2;$A=5XxpE79EBxSy~2VG zI%4zfeVoDa6?D3oX&nu#h`q-L{@>PQG_EXz=ubvuNU$bWL|H?>)M*-Z)gDE|Tp(xq ze4$>c0LML%fuzSSw0Bi3-cCLWKD{eAEYU;lRsYBiBQfo+P{G8uYVtYg2(OsSI#5p8 zf#_)x%~TnQPuwO#qS0|t()A3CxLW}8c1$GGQv^8jKNT<&`OsPAOmkv%8VohQ3YYIw z5}z*W;cWJY(M?CyaQK}cOw-ZDPh|c_r2{FT*8hv!&$K;WqlSaey)#tRU9#ZSH4XQW zodWKo1mnowX+XKZKIP>vV!`CoFd=L)_bbvIuRm9XH)E@4*eN#84Qq*}D4ef!Z$`hl znXvkgIni0FkM`XzFfUC&v-f7=#Vw4dc-7C{^s~XGUbcXD?ea7aKEWO*5qO*#PA0pm zqR#SvB>(wxI_9`JhCY!6y?68)wFAyO+#}<)Y5FiGSDq|2&s?s)DW0^#}64>>lQ0bSe)M z?n;qvX>Hu)B!JbCNz}5&40YbC!Z9;*ennJ0e!aniSF9(=XFTAK3Gd1Ld`~(op848B zt6|vo94_8xC`Nx2g88#Lsv4k$<35`}qen15uRITZ-ijbc%7WCtXT0Pi$$?#ctqkiL z8!QQbO~<$;={4Z#e-yCbG?_6*9uGYzBSE3s^ln-o`U>>j@7_I5=8h9!sGm8M>ig5} z*V6IcMb`D;wUzr3poZi6)ZygopEQ}h-#gwi{lA?G{lk621J549-o6%&GVVz+vy)`I z#!=bN7x3l8jX>-?_=^GRXl`W%t)-4s=|Mi;oBIrcXBTp*%zNt;sRCgaAJFA;ny9`* z2?QYG<8HEkK-U+LSzt=!K@QKH_)NC%+D?;MFWcMo8)0SSc;R%eSlm|JO|+Ivi|-k- z-|^c}FmLJN{qpniU(z!$?2{sUjw@sTY!!Gv<}AHnsEapGsKVRQG5n#)tvEXJEiBZS zLNdq7=FN%T z1ome(aI@KLiCFFcnNzmWWmCnd>GTo04)5eB!_2LYYJg(Ihx-cyzlRo{#ysozdFlv?$-)7Q*gX9~bnOc)hmjAh+y@%-H zAqvX2s4J%eA6CV?od{+<;M+6cc6c0_aLWj9&IVYpM;&0A_`3uSvSSO(JKeFC<5PdeP7N7g&!+)QCa*3&17evt?C2y}%bl_wUItzF|@eQE|AWEm`P;ui8?z{QD};Ae(VIIHi>zfv{Yc`PH$??=J_`B zXjoD4Rk);BNh~GT$JLEEOji{!?YiMFVw~}tm$0tKmg-cvTHM3kv=QK?IrgA6?kv^F zVxH4SWngmcg-~Ie8VV;fuj>>&>aD_j1oNWd_k<v8mn-N#k!?2UC(2*~owxKDgZ1Eh{KJDQWTJ>;VtpQw!Gt665{0KD~ z@K`SJs}dc;H(96jFv z690VU7s%$JngxMRyE7ZD*ZO-RRaH`wcJueF%=3=g8VEESp+fMaIw7qoF2!C@Rr+FaCL) z=pA7*_BPA+Yg|D+1JZGHMj>QWZRMsgy_4xUbqL9Cr$Ot~al|LZ0gd9=*Y!9{qXe8N z?fK;s;fJVKcqmD!JS-0}VbXT=!&8S`S267ihk_|lbYUQ_)y+xLE z*|8Wj-MIzAS8e3pPh@$^V;l!KP~A8YPPkD8(o&(E`7Js8dq@*1{iVc)(F&M4O&Qv< z3VGd@r?}j{00e5~T*3+F@nJdGzuYd;`_oLYSyC2K45avBk3Zw14{7jpq$e3UN&^p; zIDtvIJ9Ti*z;7+DA%x~~atuo;-lqr3*R$wLDHW_OSA$_%llWB4B3#crkN+2_nmsEa#Iq#>m%JR<$gh%)fuqkOMn{gmf*kh7A;zkkD=+$q0REF$aP6BK3C?U^4@Gxy=9|!lne}us%`r;?gB*}lcn*OR$K-pPUWaZ)a{5iX1Jbtbc;(r^HR<;pA1?8(W-QS1!@`k0!SY$5- z%@}WT<(3jY+@u1HzTWh3RVR=pi#5AJcPw?jx8nDnX6BK5dky8zNI7Cwj>U&fe5S@(6u04lW zi9Ou&cY1iGnmwCpMtN^1J;Y(p^WjRHEvXi&VCqE)2)ePHS|~9ORPKH-{3pZdubd`6 z5n(}gneC%@0yXj1WM>$Wo4{LS<>7zZDq(fRFk+RZfCZ=xS&^(qK$wF*P5H1UN`kAg zX4p$|6NIdcB+*XtcyU=b5nr*Pjdro% zE$(R%r-J+duHN5mfZz66gUpW~yzoF4&N9z~&v7hQ>Z^dI)ylz$ewLpsVT^+r=5Y9% zF&`*bkNt9Du>R&r?kTap43>@Xzg_+6_C8GWHE>T~B|$1a4#mq;05Xc}>53prJXbsl zUP*;d9^rlY3b?-eFlRT4SV8n(r4Adcb7IbVO+qc?`s)=<;qsEj$o#liM#!P;yeSqe^V1|S3Tzcu4LKr^WMUnzZS$SS000U z8i}gRPWpFZ494ngfwxy(gsVy)i?z=549xbmdFt3?ZwqZnz5Ib4saQ3u5R4D@aoHuT zJLv-J{Qd7Nz3O3(4`v#HcZ3)3I-(UXZ!Lq5o>R%ghsvnEtDR7*S#%`BjyBxh3OVCc zI7x=NDC$^NsG-`$50u=Mz$U=;@4k&itQdu_qeN^>;EN>+jsvS*wwSP z=-{L+641Q4M`Yhnhc3bCaIx2esflP}f2g7RgTFlgbJ)G%FtrZpf1+eWqKp`bR+e2#x+v4SzlFCae69y15SjhLH++ zu;XVu5gZ!HA{Q3HxzXjKSKCssSLP)QK`-)FQvvr4(E*1=)9B(EIe5>HhiC8ib9O_e z#A^!vaAj4u>9SZ29I$98v_~?|ZqA^A&O9t&e1BYXrUeyc-4k^xSvG zwhDWqClu_FSnEC^cLqcskjIVxX~SZn5jAyV87YLF6OKjP`T0henxF$xFPI+5m}RLs zv0l#AxA|)<4}VTu0YtntC3DhQ?(vpNqGuLFXXrTNA+bMb*6ruK7$4-hVkk%$-=>vr z!|`^k8%#`>7dfirV2T0{y5DD!e0H-3DX?6%59_FC8T((KIRTf0{t8#e>5C;zrAWGM zAl*Aj0hjhxk;6{!`FjD*m}e3Ie@5Tn9VtD=uP@1!nYkjJP`C9$t7Ut9VF-mw=wwlD~h4I2B z){hxB0**~irO)4+W3CkkGneca#Vtt2`-2b~UU`#Yc?vi;gkb_+p46|I^;k_f3oj3U z6E4bC6j$B(!*xm@riKbEBWNwt2zCDEYa8qE?Dq75y*+(B>l?Kh3Ga%}QG4xd98p*X zKbMyXuX<}>mYWU~%`&8_OphuXdKPLbmU2(j&9QTn2IR+ope{kuC{AGAb`MVQHQO68 zTRR(8E-@eI+GyzFV8cFD+Rc0}{mi4(vG+G;@JJ7Te>H+rr;YNy9!0eLFBd|`S`+Sr zBAPY*A+3WJ(*V<0e2{$rK8MJ1Tb!ne-=4Q5zn1Q!Kbd~@jIlF(HA>(Iv1fB>`3u<8 zU`$+`HSy;dGYIKEPUHS#{M}w2Vn<7IS^Dj`a%m&XQHvnWW7Kf&Bq?Yf=0p!Tu`aFR z1E3?Zj#C?|gZtOFlZPhhRK0c#ZVU;4-R4a~sRiG}lRn9V{$gqItzOm{QDy;GHJkZU z>6sW7$oSA=2@rz*p_vW?dQ+`mx~%Kc4 zu-xkujV@-Mmmvl)Vb?sj;U!IYVZkHteteb)8OJwR{WCGvHKNKnV{pR80LX5B#=Vyj zVE4hHpnPa0HDYu4tEhVE|~Cx3Cv z7qITdjZFjE#pJ<^yL4$A*xTn@YO{yr#_dP z!!&jGeAO8K@POVH=%JFQCLFu`khhL%!usWJA+^bz=u69^+KsORbKb;+c>!v-!JE0R zLW4n%#f#m356t<>Yys;y9tP!4I{9Dcig4Wp#`VZ3lF>y>t9eKbM)jPfKj&zpOPLzj z?;FEU>TboBa}|(&%8zKyWI63~eh^*lS=4oO431nF3>V{7xEw=cTszns!g?BLK$`(7 zSvZ5E*;)SH+!W08FNB0Xrj1cmK>J()P`O~b^bF&?I?lq$EyOME)>m}6_YO)v0Hd?ax$V&lOo%G_z2Nj{^ z2_6FXE0CqXS!ZHNKiNO$Fdh0f2Di;U2(M#Qg;SbZ&^TQL2H{r-d83E-uM=n>d7{qr zWK25#5|$)+k@Y_E4FA-Dk(Uh6X^s!3d#=j88$aIM97p({ylUI+Mn; z7J!>=shw92E<8-3w7ihBh&IB`_qs6R%QvbZRK&i}zvPJAHGa(4daU_S0RPNQNg(@s zF1Yi7lqYUvJKGrCX%ztdMf@I$IWf&}JyiGUGF2ZrsDxfPNPIPr)4n|+1&?GsB z{947h62_hVPwN=Ci{+(UJPCgm^$XSR8HmX@X_lS1j>e5wz{I5=$-4*d`KPX9aG7fW zjHtNIEev6~Lo??h=r&Y!SLgEGy_XTjTyk^FBP^qlzuoO7M0Uq0wh! z(L3!VOw?G#^^Vp-Hv>t?)Sxs$$aG?>J`#sB2YDGshRfO_FFBmkD zPti!m!hVDq<9$ePoC3B@RDmOpJn0{XrKqes2cP%12%F0l#kx`b9DnpM)lt>JH)egL zB(0ZUHnk4h$7Br5`R^N8?!gL2n6&;pHIvH0nn{)L#`&dCvs?}L6l#NTjsXpWi)eU} z`N$qG;}nk@U~!Z(TvUBaXKs_n*-S@qBp`}!o6>;cYqLS4&x|y>>0#YB4vMr@sm~naaEsDpjF8Lw{6bRZ{+VBcyVB0ZAv+MU&;c(FIVcf|?IF9$&0H5bl+3`4a*FQ|Ia zNH@qEqF$jL43;~5Yv2i`^;-3I~NY2zjr%fTvz}^20i2cQ&hzmO&b`QA4q433(@Um1!%ttS_MPX{_->3}f9;)=z#RiO)cngZZd$@+hvN$xLX~09;y;TdJUu`GHK8r;= zgPc(LNC3N4?MQx&8oE!l8^CJTeM-TT>JQ=5_gqeg46QG@Cwi~9YL&m!T z{tY%_smVKNsxl|5cFJRbUJH@Gyo+i$#^7M_b{Ny;DwJ@3B<_&y9nh;Av&_0ty~AMK z=}ulVBMlS$A4A))f85=hN;r1CI&=q|qwifAF7Ztf?u6R&HRoHfxT*qB){oRDD5Lu6 z4)SsMY|2e$8T+0g5NxE%cws2l!n9@mTZtfi z!b{H8hTXRQO3>+YpFY~EkH20@!`;e$QB+7R9xY>B=L-+w*rtLrBb>mZmr%MR1$l$TsFqxLo7ih(VxFrP>9P}4$uGQ{7N?W@?Q@Eo3+Pil}H_( z7yluO3y-^n?EH$SC+EZ8Tk)jLel!mE^#>on52A(RQqlh<%hqGv-~QPu_%nD2Y~Qzl z*41TWVTc$Swjbb*Zk84wUnV&)=YtQ(p#*z3rH1tJ;;D@|yWtTS`~TsZWm&iTr&?0I z<`j)nc0$z^0dW7hgRtq7SHTgbweBmzr$gHt=IxTQfFM5`s{1$_OBaZtL$-*Mm}Z1= zEW@pKN(+r;KHup#S$^HiYy1brdR(Vl1UCCj$&1%AxMq7LnQgI-y16^yw!{F|wXvTo zKF>5xcdX#$<~uawQ8sR1UsKC)&VZIUb)o`PYHy%E+hegeIvloH{1Ya;HWI65$dbU7 z8)+Zg%}lP;5@dZk#cu!q%og9i&YhdhI*%4w!L-r{`etJ~zIJ>9i(b|XtrM3NEPuG# z{lNHppvJJ5a5)7SUh7K3(wR=aBplBDUB%`1u>8#9QcPopbWgB6PRRa9N*xdKer0IG%44Xh3Pjd>uo-?4<#wEBTKZPu zs*eidDX01ecKAWdRB&)K>u<8`;=5Vij(c(zOw#G&Aoo$C0hXe`JkCGc}jBqPssW$i3m z@56b9T{v2??yyLz7@dtbEX3dyD#?}lJi_>7_U?0BPhg2A(@Dz0Ik)k2)3#VV_UaIL z(e>QBW;u+n_&^q_B+|Yuqft8EpXGNo2+bxni;GYF|7_3Rq=zqrHn1VDoln`BiBq~o zz!E-)^>kHy`dbO~=G~F@#18*%B3#|(G!CEsEcvEHth1X=pfQaLA7 zSQG$CUM`&0E-O^?^?{(0uT&vt7@pP{4;R`_@bhvr@zhuzWd50ws#tmSTKE66y*Dbo0-)LG87Iwr78^g?fz7%g zYHOW~H&4ERO9gwmQ6H6Y3(L-(f3TfeR;uEay)3_-oAn2L(XRZaWfb%sLjO?cu_cF?2y>AujH%fQ`u|T)a2C zH`O#?`jTYY->ii}Thzg6VFCYS%2#YFFNJD>B_S;5)>8H->He^fu06`~e6EME{sA}P zI**6qUGcsDzr*iW#+E26xR%+;E4u%{^G{^lzqZ?w&;%u>FVcYeujgpG74v$(RRXi$ z_Iye0FFaFH4^|iF6Gy^$hr~{Dkj$oaB6jmi42F$MVudw!hWKEe_kixv=Zqe%=oka0 z`e*nUm25nJs{}?1Eg60*izSR7&pxYx*Da^;|o!1B%SIu-*X;9PZ}=VR!b?r01Eqs-TkjYPWKa^JG!&whrjBJz?Ka zb*y&MgICL6^Q|8!cIM^7VXYTj7{fyn8vDtsdvP?3^(DnPO2A2pF46WKwRp@j3%)P* zBz9{w@QIHLgdX&!MPpNO!PIxK?shJ>@rN!x_{{pD8jER&s~Hxl+rYx4Kz{h`LR=6k zh7U~&#Me%M-^WYAzZu8qvvOzLFnS0GKHPU(viUn&?k!-twM0@oVibnl_6HTU52B4H zQ&469TTtECIvMqd*> zcUiK`Nn1KghV^w0DuhuQkGN?PMp(N^ABJ3Sp;l6gs5OoC*Ra`sQ}Zhht|*3ur!2`d zG8nr0`L z0bn`uI=7DXC-^b&Hm3ffhtFs@FH3sLtIw>Vl2%zRT~fc4Bj_(bI{?^Kh7?FU|iOZX6?mZ6PS z0am~_N3cHDEZoHQdB07P9L{=(orVP`QJ8iw0Jxju zx%EocxNZ4FNFyy24w&QK3(jzD#xXuhn1P4d{*R=y@Qdne!Z<12-QBGMg0lAvAc%#c zVkZk?cVml*sF;A=q96#8?mat{fr?05U{In02BN6E=g0dG?1#OaojYgddA<)1MQIk~ zSDYsPeXS0~E05D3F4`EnQUMY#`S~5R>%rb1wcurVfxH^8h?!My$#@?_I(Nt*RQVzV z%Uh4Qve~R>8|?-uTb9v)ow=Av%Hhb+E!<4TJ??4Nf~V^{=(sxOj~l861CFcHPByn` zTv`nooxixp19h0TToQC%U!WO#^>EylpJd$aVv&{ZAe>Vx1nmH4BHF2mgZH?BVU#!h z(RUjY3rk@9qI^!kcvJDSw87|gI-R~x6=(G+!~QRM{OjZo_;O$s3{JHqiY$w5z{qdp z=c#Q}f%V(t)@}q-dx2ol*x9#`H6?{=eHDh|5Yv zY_ZjZG}Ghsc!~;|Pf`Yb>cSte{()m(zlWbqlgY2|N_fKLJ9*SOfqI8n;=&>s$X=Q# zn84WGU%LNa^PBJLVZD?WENe^P(;ubdm(Qi}KHQ8Ld{xKg(grYFVFx`>V25C53m(6p z54$hHcI9(h;f-c8^JcQ|wZ4b==s3`7J`v*%ZUT4hRUCJR^(47Np@Ds`s_bn1JNPA- zwyokO{TqPkO?t3ql#Eznhz1TDV*nb@p7D)+BK+ui4^}>W%ssNx!-b5Erl@g?E>o7n zwu9|tnp>mj)5<0cxmy60kt4`%D-FDq?*lm#1F7@v477J<{I14)?rR6roaj13-R(!T zx`pLme{=+GjfMQ*n~1LU6khcx5QAuCytzXPZmRC3Ny{`bX<;8Z)w17Dbh86hHH+bT zsa>{A4;+jP= zL?h-lt(l;KXLaP@NbUeCz3eScN-Bnd>wj`%YE&6FxQ)12AEU>I4nzfQA%rEl3c?iw z3h(_};D0%I99(4jvEv5zFmjy>-J+3?Ws8d;wZ4=aeAyVUGCt48kDus}Axh{OEeU6i zU*?BzXvSlG58#}qHF;dCieIza$m)X|sa@1S+%ZxJJ4&~4^=_*8;wsx{I5?QCKFJNJMIi*i$Iq&xhf5C!x;8LvV4W1Scsp7gseZktZdq>0T#I z++*KC-g&k0O7jLH87_p%ZI`*Z?7q2ujw5W%JVbM@x#8}s!{O5AIf9(j>4hCF^ZjSI z-GsqRhkRnPA|!PWrM*RLF7)yc7#)q~b~3hrOPVCao)*#XJ_S!Khz4ZAs=R0H&>`+v>%8qKoOw4_12=scg_ z)_^T8Ik5Jr88KumtbM@&@GDA#isxtGx|%BZTley zEPTs;N88x*eYDFI<7Ko#FU*op3}`{gGml`X-Y9bSmpn$>y(L#011UM{fj5^6A?mvi zx53N~hinT0jRPO)zeYzqN~L7lj*(PPLn2i=3!}VA@P|eG`QLW_dOQETFFP;)X$6$bIJv*HZ7(#n{#m1 zp>o*!d^4A-$N1za+Mv+hLA%+x3a(WF{Zv(YAh8L@?5}|@qkeN6G!(H`|0|K;PS6Nv z9h8{+gM4!?6g~UJ{(kjH@a}dZBUqiUDRqZGjzg%J)r8-g4`8#*JU^L;Ra}(3Na{e%2rcMxGD|I*u2KpXvSS zpWC=Gef!z1-mqqo41MQ@xVr5HtSeR|Ys7NsH%=Ya7ADYX(^c@kqzZWSxbROOen&;i zCQu$Zg=~;w`Kld1SQf!Vx>v&z$L^Jd%PEP1l3XJcWRHO6xE415)J26+Ud&IFz^`XI z-rZ$S;gz`!*;k^80y$$i?XZiwRyyF}`3@j4t!CI#gC1Nnv=!7MlSo333jUq*i<}(b zKtnQ_20myrtj$`*d4AHsPujyEYRfiyFEJY*Uw8%j4_9+K+XtZ6LVc#&lo7WJjBtg5 z4LnwD!PXxUJdr^B#`Z-2)%lBT zClUq{@Of}7byG^h=8=0~-4RWJzW!ItU3VW&_gp2vK3SvN(TT8l=3`OUOy)&8Y1QA) zD=oZ>S}(#ksRE4tAWzHhHK1r)F?^cd%{9GYS-?x% z$+yH~G|0~beOC&hHQH5h|2hFT)a)<{y?hwM{xNV#* z(}R6dbA~H3Zc)!{dtBzi!T!7QqTGvF=prYE$O{vQafv*xSSk-Qqob+8HP%lS9fqJ^ z65RL>3$cZdD!Kk{9o?O-iIRC;WI)bG{)C+e4i6UsHN4EF{b5;$hn(PC@L@Xe=N;@R zdjx;ZH3<|$rWMXsiT3C7Qvjlruw6x|UsrSeaT5A8ABI`;7H}nfR_L#w4hxGaXz|Md zsP6lQe5u&Z?|!L@do6~*#kDy!-qakwt^=@E+%9_Bn2L7tB`~u(n1s!hN7Bo*!D|9( zkV*~)C9909_Yl$?;_( zG@thnK3pv+XdEKK9`QYR5@b(S-esEPD>4ue8$my=NJ8@~d*I0fmT`8oT6{w}odhS! zicLlsp@Pi_xP0LjPfXJ>?Qs?CGqE6VI~a?j#Gd)=;^|q3EL_3%IM3ty1oylt9_D$7 zvW+6OzZLMIoh0mj?@E_59Ys*~9=ImGjMFaCzygm>^29Ek4q`kjBR3&*>NN>u_qT|1 z87K4GNf|L&uYqp0*5LQ4nIFC;3t!hznCmA=zS*duUzsZW$h}GDCz|0rp$^!dvEq|Y ze8Iv46)=&GClja0qjPE_v3CljDFZyP)=3CC$9*`dDCUa{7zw7n?Q}z{Ee^5tgDXvO zyx*EkOe^I<^OZSqa#O=)RZLlaD}gaRY;j<>5s0k9{fd0M@bv3SNb@~IblC2OFkjDi zOEaq0LQo(NIeOziU8Oz5~IV({Z5MTBpn^6i+7oiQp>1Vv}T}0H zmkOR^x*GrD9aQp0A|CeK3=0D|!Hldz@gT-J`;Q6seWMO)w0MI22Ps;Zn1Nq!J_28D z3Gz8l9&gRkgh?}x(R${?UB!A}JKmWOu>FpgteT;H=@c^b2h&I}kAF?>1RAAeiR$YH zz%Jb+fq14FZfY6}_Y}X-*M+)hu+|&WeUI|NMI!tYR|m@@oJrJQIjldX0pp*qp)2DY zFnpXNY!=rHQ}gM@UwW*eVw=NOcowsoTe?ymHTDbz&;48J zaJQcr9Hr~OdEQk{`im?|*68>5^TXT?F<9LOQf4&pw+`IHoslA_zx0@Ml-EVO#VQco zdXwtbTd{m?b?~W{=ch7eZ(g+sM*SE;&izxv+)iKcJrGD|nPlSc?s^#fTg0slvBS1z z0T`}ppkp(2a2(6lyd^)4-|HmCLkb8@FBM4n5ypfs_+v- zi14EIJTd0o(1YzUmGOmWUgAG=Z!`1{TzG^?d}pi@ODpIuok6n>XQA{MX1N->oqO9P zD?YYu0D0b*PR*Khap^EsIP+MUMoxT(?XE1hxAzx!qnvU6C$hX$)swX8gB!+86GHqO z7eT@-uJBT0v_I&Lg**GTFnN|eOh|R6Ei9+6AsC@+ULohn_{QZ63}KJiM|xYt?#qLf zVf4Rr-bK`mqjes`%V--SIYkPK$JdeAuaR`7nmeW)5yFgN+qkPbs%Y5a41CrtDqU=Y z+Z_GC<>dg;0xOmwQo_6>*Tcw1_Pw-|)F8ZM6+My0bazjWK+hsc&Og&!oMoxnKf}rW z!!no8b&?r3TKU7D-SBaw5K^)(af%9z?^Npyt(}Ld!(ob_lU{&9akn7z)s(_{OiNkH zrNE05N@y`e8D_fqQQDP+2`UM2XVyY4TG}1|q#8l<^S88kuPhEf^P1#*+{UXFvibic z9|(8MrRx=y3s)|5^gnlN9v^lo4VRC+4wiysB_O$ zmBnGQG6XyJ()EmQAC>->7m{L zOYm&VsKQ4>qW$AmZUgsM+9*524Bl+EVEfR!xbhs!0sIilg}%^4i6x4#efJ~!!^D93 z4dr0zvderC_YqgkErco?d(y4Km=g1c!yR``n$w<(*>Z2;QrmSv;J-8fn$J{y@%7LAq_s}D8AJH8{p z)$bNBuK9x!wFdr%BcjQoL~T59)B%i7#nVYwGEsqf^W%#91XRdl9@A?*`4LH81!|&s zqXH;N`ci{)EdQ%;FG#d5`s+}WY?Cg(p=SvsdJ~x>4t4H}!5qB`Em4aEj zIdS`tw87(u%!bv8>&FD{WM8nyEb#>FRYH5Q{4bJlrCW# zg{BAG$0|jfSnmK{Dp54dCl`NDu7t>C+c<+U%2@PA7aX*{(u2b_FqZ9+6ZUG-b!G3- z>P0Ph{`|$M4^hOtvL8fq@=3bxrU8y)Gvwj!4@Etp=ts9$72wjF&|%jWh+w!y%uYq;C{Sq7r658T|piN2iFjo#mN z{bORUa($t)sLW>d^Sxxm6|dEBvAz)u^{C)u3h&{yP9D5ZJ>kqg>0*Mv8ob|{O3x3p z!p<2QEIUk|7t6iJeFY-e!m?>zUR6Wg`k??lfpq5EY#eIU2#+5ZaFng14@^Xhz8$jLZ|m44Da}ES1eh zCNSNv-D>*sViGDmOn|I%Np3}{rTEw%b)u28k#1slWW)US{;ZA3J6y4Apb%WmFL6oL zD)_a^rQi2tkX^t&vlc2#z6$QlnOx}N9__D{djpX1S7DD*A@kK|FkGHaaM69QX1V?_&gren*CN1z=u znv6fDh$A9(z{fm<8jQ%p--`-BHb9*V)Kn5vDH-x}(O%jssf<=kODWL$#wUip!%G$- z$k+SJeJN4JA9s9VUTZR4GRO??nFRFr^UGF_EX=qb?e98z8)&ees?^#7j7u!(*7z)p zzMKtND`Gi0BQ4auqy&2pl+pTa1~?~Q9!|`-!oO{3#=l)+@b$DMvnS}G)VtxJXQxS5 z1^1w}jlREQ@?hdFDZ;y0220aQ3lbYdsHP!?kxGsvXNMYY^^u3rj`>u$m1Ucr*#~oP zD>Cn7rFg7WMt^OGXNGuc#Yi}qn#wEb{=wNB4gIGcizY=ZNBcpu1C%X|r{zv}@o8ug zgshh2CbM~FPq6~nxcJbGj1ND*Y9G9=Ue0y;YvA;W@L8it zT<}Y|-vhPGM+4K7>|j`DE5Am!g!z)H;prY#@@xg$v!trQ;$b(b1k>tJM|HS4*O=Fr z|AM9;t03oV7+JMW4x=L8_s`@XKX<{h*+Q^gHiY}O(FWCV6zp|sr(Um|QG6sA0yZ4w zZNwRPXsfuto_~pE-uVnQi1JFH16C&CvEfIdZP)|9ArHTxW=eH`JwL3<^x-c*FdmFif){5vemidyhPSWt(1{kd+$#_Z+MKAWcV(f-U7~JMaj$YTq zp?3#^RhloYKA4FoR+PhU59IcLRz~l9eYl>NNw+&NHtBvf=*`UMO@zg`B&qC)01o6Y=_x z?Qo@0lPd@}#gm)Hfzi1y)XCBs7wj1cn=f48-#pL90-HL}P;nv)Q8!>){zL_AsvGoJk-zO(G8>}*TyI?eX))soz@<7{`l$QN#9 z$I!vQf8dNlJ^u|qu5w{@GAOuX0H0an*3H?v80ujKmzTff!(t2Y-&YqR4@|Ki)p#{Sd49wDY<)X=TW2G**~rujSWv;4$5 z2>5)6Tku_0JbS)8abp^9zL_yDm_GcntOE7Xd4pheAG{xQbHA9rv}$uF(+3@=@+)2N zEIa@Hz0QKC6@G=oeHQwUwj2wt=~^t;&k-&TcBSS!SoTMGAy{M-auZe{;eL_>7!<{e~L0O+_jficUN?_;bssB3JbA4`((-G`$vHC&2YsBbRr zJ*Y-X#;>DM5gI6W^*ecb@gqNKg$rJtC4{c(i`*p0*y2N_vj#@|x{mOj1 z;e|1yqy4jjZ@}#kWejR*9 z59ZHP=Zu&i?NY4-tR4KDcgbwUo(DzXzDbIZ2$lg?HVl6IpP?c4X1FIJ5OfZB3se^A zV2zz6EFEb@`&i~e<Z{5ea-erDF168=W;3@qwOdCx;$v~sSd46R@69&#e*wku6 z{!Y}#*9jxQrdW$^IogBIXBhZjI^;>*BV16;X&B6J_bPbkosZMciNJD_9eHG^jMp1w zVXI99jozPx9}@OMilq`4^hI$v?;H_F{I^iL2(6V2V4 zcrMlfUS}Pos@Jk`gGw9i$I*xdu0G}=oq1|_r@M|7B+uK)g zKJ5OOaqAmt+>uTXhPj}Vmk zu^QRcri_Z4)gbRl3N7ieN4K>W@baT8AGf;`@87D0K;b0v^Oh3YE3}iQ^pP}npbP#} z62e#6A>6YyX6R8A2%)X-=vrSV#`y^Xd;bLf)W-}Q!| z)-iZ)^w950oK)c~vyadvx=FS$zWqYgFC-w{jINpEf}2JNp`-FX7u}+YVjNFhAQN4D>+1vK1ROmwBon_*WqBX}#N6$06|{{o zfUJ30^x`5F+$X6HF)juCuxZ6;e7*oSUsfRn-P)L&APXzn_S1p6EE{6db};-y1Tq4# zIN;~M{$Bk`lOfwb5-6FWKtDIJvu*MeF6v7XDRmX>b1;PR2T62)w=zCBpbn4Q-S}je z5*)$!`4e`z6RYJ+|5n*cIu?f0Ut3w;qQ(w5;H$-zHJV^S#CYf#&_QpAv@kW<8^)R@ z@TGN(*{)O#KXvWN(GiTpDX$B=J2%n`BMmXh%M`jcmJHLE#T63k_=)#%8UvL zc;D$nzrALR$~ilrwrnl;=mYa2z4nCxS7K=3!tWT^sOR5%<|?;hrwpn`8TRWZ^H>Io z?JhHjD6i(FC+B0V7R!I1^_cSxVwve;W%xpFP`x-){OhO&Q!dD|9L#qZ$YSrq7mXm9 zt!nu4l>p`%1XE$1Egp>Whg19BQr{`sIKzy2MK@04_bkjoY3+Mp)-6Nkswv~2k^$iO zV;@atOxoW*2Y}nDEy(n0LD9z|I63YDS^V7rb)x6Oh9xzkHQv9`W|NVBPQhWa>XItj z53~j6PqS#J6nigw*Fan6K~AG|fLLLWBAFF^~9;a#n&bVZq5SE>C7C3niL5)r!3}o-AgE<yeVL+o-i1=YyUwD7hLPGPfaz9EwrFaL}OqHEybLnor%tAJ6}ZKP+<8p=;~#+}F6 z%y82du9>jxjEC;9)Z{kJWZC84X0a^ez9doY@N|^AB8E+;#}l(@TG*+t2bC?G>8(#m zctz_tbT>3k+?l=sYDElr3!_ zdyjA9@5M7;-pDZ6JF%Qf>@dV*G6Y;sMdy^Dh@H`SiE7)B! zyod+cml|AXlCt>bC^^#md_Rq2eDbJ-f26>to8PG3f>R$A!Pu{oM2ppVJR$%bf0pX4 z^TrvHLin+HqQHdlvV^ZKp>3lTy?!+hZ_nc4qr-mg^aeW|Yi9vner=3XWQ1pyD8ssg z*Ln9vowzxt3^Fxc$&Y2a7!?}~Gn3ftWs*1ZQ%8W#=G~mXmJ3GO`hj7Hcfp!OmIF1O zhefmPh?5Na?PoCN4BMsJFy_2e@&V{Luf#R1eJ*}F=?)odDl3Mm%sa0Y1S3^%@E>n_ zqhx>(mcCEn8UxiaR^J}d_2Q^YN+!#sD2A02CAp1{D6UBQWWYIu%WYmiOUj2Ak z5?;H10MlX)-h&Q!%j929G29| zpWb%|i=~P|)liCT-K31sch$k4<&SG>xZ+TMdoc3wKAZzn;~uuPpC=+bj#B!t{YM zt?H1lB7u6GNJ8UH$Kg})L%+DeQiY9UKe3FnTO{?98Y-FoAVon|v?JaL-;@fWH2gki zV8lF+W8LBPv&A%AE)NeB)WMMhJGgXd=Knpf2iwX!sUG7`)_Lkd*d86)mr;V-hf?^f z^OEE8mGEKe-+s2()Canlwn731Tih3Ivv9_YbCIyz%#mF5(Z%7#Lt)}OLNANcG2XZw z<`z&clI=PxrWrxbRmQnuoctrFwIQRI@|l~9@Q9-bTpCr#yss?pueXmhyY8Y2n;HA7 zYzOq@g1~SI6;Hm`*Was$GVU4u=L2M_4E?~}!4QWE7<)#F%-o@Zu_7Z7ze%R^o8(b> zh6>cJapHScAQr7GfbE4YB$~}$)L-EkP*Jcl$dCL%mIV=w)t#sILs}3~JZ-HMS zCrL>iV`86|fh&{UX-|71o}aoC2A^HWU2xRGsN_I6acCD+k?~?|w+Q&__e&7+K^o5$ z8TR|0zC~%^qygsr^?XTqE~-xD;de8eS+R3ylcowe-%{vf2_1CbDhKy}_KFgG-(fLh zIL}lHA+=96u=J5XtWOz9=LdVCC!39zT@B; zIQJ?sjS%FNs-vj&7|^=+5I<21)kR_(6=dVcsZsD zGw0>O`tx27IRAukx{hSvuq8#Xx_bf<8z`Vbf(lI3W7#OJj5%X;0&Y%} z=2p9!i&x*!Ad6)-&^~Q#EH3y%GNU^A#fnb2a+?s;wJvh$HmaER$ph9NI7&~>&%s*H zT8LKd6ol@XSoo@Wfq(0a8}R0rA~tMSgB>y)wbM$*HGwDKe(Dm=v(5 zdJ<)E*ExA|KJ5Svf31L#_kQ_UMlwY;kPT3u;Wo2Jn~w_{d=f~IeR3b!X%$I z9dyK}OgA`b^*cezo44YxGOGPPrg%xl@IPh`@`GA=;!%vRTI=B0E;XXCh}G5W8gQ|S zX&8#s@LZ=7q}l26ebc_+3K8S43MLW#WL5mP{W}RcI*v;FIpV>SLdO2}=H6~J!4*b9 z5O?n#n`yh_;qp+>@;JrUGw$4UyCO(CZb3e+XV0OCvDTj@(D9{7=$3r~24_C0L3_V@-VKBBka!iq{wcErc!LO8=TW4`fhe;qjp=8s-ZPe$jVe(no+KXoT( zxIzJ|)b#r~GfP1opNn*$y=O9}OK`pDT^Y=^!g5x-sB3E|u* z{=jWVG@B6#CNU1gLs1V$TMOXVeSbP3Gy_NZRY1BqavIE>7L;TRCVR7~D|?@6KGlJp z4PyQPUxbb#9k$~0BGU5nHJ(Qm< z09Rc(`oQfr)-sR0akB)ey29S?e~rQL{As$1&GttzrpKz<$0t?b zxZ(|3=Vp$YY=7b3Ajh6n3tn@$4}FKmlH>{M_-lwi1jmKY%o(2Of0=m=Vgos!2sgYC z5X$nnJLsr0b~vEK2UZoW=ee2LIPC(f)poLEij)=t%T`c*c!cH)lF)!0gwMNl1P__d z==8%<@Sk##v}|&~2U@q=YFk9Yl5GQJVhT0gvuw zXP!C<8V-6Qc_#!laWFZftA%0DT_E$K8_n2JgkNvh0k^e=^Dt-mp>K4+WN`yM{X++b zP1J;{#drC4^IP#?WfgdOJCOH`C$Rq7S8^aHh87NR#4AsQux9>dZU*xNHO?Lc4(aK% zr`H^P1On(dD=TUZNk_+dMZj?r$gK={{A#5Nmjz4cFy&;NFzO_PG)Z#`x6H&dhiLZK z@K;f)Xi@Z?xHYu!Lz^A2@uCn8&@P0W&!&O8Ykhn8{)B0cQ>t_ax$B~-do9!qAmlkqmY`4>^f_;Gz0 z#4LGA&EK;8k$+6azIKb~o@o|NdRYbk6ep4`wi-C0!5orbO`_UM^Keat7=AC+?)d2-^EX(rp6CPIGv?WvLDzW?c zf9xG0jk(RZ%GVA;?@48@Z!D|lZ!`O6EdEazZ(J|}8l+SBuup^WxULZ7%WrVo*Ro9W zeGYJKbsSwXA`6$7--k1$Qk?1JJUq^JB6I5^h|)w2oK>y@!lt40Qcn_2`*;x2yjOFQ zP6p_GQ5uqG-J^?j9B~did$R_;6V#`^6>ni=!~Zle`#-7T=4N}i7}d&eb& zpp$UOugp)QQlfBPS3BI%y-DKOy)u}+J5bV+<~KN?S&|Tb?knXCPHN+!2}41iZlnPd zb1|!`9**bk;DQb-;Jvl_aL2Wap3_#xVb67du?y+3v0@ZoEdV{)8m@6R>uHz$C0=_H z>DQHvZ}8X{s_MH$ac+*dPc{;+*f5eX5FOrBd)}`EI&OUlW%Y_mamdd4A=GMB?3> zB;Y?y`}rtsoVsinSWS_odb*6caijw54WvjH%T-s{WD0N3oT2`6E%Ac9Blx@;&ClP$ zV}M%$K(I4WKca*xcO}3gbqYQ6JQ06b#DeM@ZSJ6+FC)SH;L$T!7GyyU6bxNAV(FXLgYasE5TrKt2metD@Dh%*6tF`l@-0PUcfP zM8U1<5x0Zs-#lzBU}zSlW3-ZRq;5Q8i0$O9Sq68Ka|tBe8b$p6s-d-e0OL`Qq-tLV zp(pE^r&kAXmnvPcRbw24`ghR$1uobe2e8;}JOBH@T|95dL%E_XnNX>Ll_S+4)QIKN z?R3CHVaAYBciFG(bTjsyyx(8jrJgWN;Bz6%bEy^0G#rfU(uH7PQps6lGi|@GGkpIk zq*p)XVd2hlXdSed`{pMnetAZP-50az^)7YPUZUDx+bu&|FgvswD(t1m^ZRTE@uQ0* zM;@a?lI`(pyb#8PISFhh490{WAtVL`ljJ~ST;J;hU9*N#|7YnKJEa8dMTJ~t7wdu3 zbU+yOhK9^z+0!Wou&hqRXJ;@j@rfD;>v142zpLQMydUJ!+b#6mJ9`v$2;ta=8169B zIyyZc3?b(-=*_WA+y9$`q7?%~aV=@6>Rkk3^TWt7mOBu&#Rz;RZKqCG&Y)3i5^Oj; zfRk=A5r0nBAQKhV(f9yWd=A}Y%am5WBh4Of-C+9RsTa60^(wg6WH8LzcZ@1~=ipV9 z7qFqMOHlSLtnkyyMgA8S+<;dJ3XJEk4n^w(RJ!~O`e-CWdh9CBw3B6)Es=-fNTi1u zL-NeHUXpk%p0}D~fhjl*?)FtvX-!*{Y6t_1_I;uOuQKp+Y9(lqFp?jog%@^N!&}*D zH1=Z-79JNvQn3c-nI(_QEdP+VI$ivZ1x=_FUkblmq)5bUb#%WQ0EJ-}=D0fPfu=;R7EXLuzEE_z9P_{A2S zvGDuhZgLAd5a3W+1=kl8Gen_;ak>qGj6~K2>UdXNVc1v}zg#CBm9~|@s_m9!o}Dt*Zq$O~2ai(! z9F{XOB_D>@_xQDC{lhNBPw-AHg^V*~UbcZhN!U$Gn%HWGBiKH7bVCWZu16D3o*xP$ zyEahE$UIbLdYcW)c5xFU6!5#PAqZo?Qm4l%_{(1hWXv_`9FE7NPX(|*qMECXx5ANZ z4zplOHof)L68-P1fPziEXw58pTzWJTj+EGw@S8g5Xw5-=zCS(tEgj__SHks1D7?qjFYK}eWeDl=Vmc~`g9Ra9*K~;SdBE=s^K`40jIb`PS9~Z{L#@qlw z&Aof#?pG2l`&UMMz(gO{AMl4GBNeFY+zgy@x(YfIrOA#3%%iPo4$m{s()Y8hFnYK% z7`_?HCtVcb&MO5_ujfqK>e!v}i4^$Go=)$wT=LZ#yWw-F4kyWWD=pe1AXMoc&1f^g zpS6LY^f`$yd!2?(i4|~oi50oUW=d@v9l+to0s6Z;7jG)Ed()uheh)`?;LJy#`up~L zMNO1CF9)t61L=8fHm@7K8^X*saxbh$2K^KSFx}m&p~n3) z^GVrysJPn^YBJyQR<6v)WGDvHf=Apq7hSYX(gr`Kt+o7}h`av9!_$>J`Q+&>`0Cn2 zz;&VI;&8@RG7N$DXF}=h{R46EWTs_u58(C{xL| z&QYj~lqI5b^4RSz$Fh_5(%kQiRXbk+qNX19dw<`haP@jU{~HT`kTFhnXd1+P&22TJ zA#Kd>^Ne{suRiDeLR8Rssski$nnOpY=VIZBa;UA`!#(kl6Ekl=85)#BHFeZ6C_xpt z3kq~#R5P0VtOg4WDI&o8oW~BP@f)rSA^YCY(MMGAu%-&kznRK^w`swFH)=pX!huxT zs$#{HpX8myHoEqv9h&`Mch$fcE{65ncTAZ#A^HyOIbwz<0yvm?P*yakIgRBm6+`Bb z31s(Fbu9GKhum2)bWAt%Hp*v1O~rHFU>M zAR@+yxYl6}iA_`K1C?xS?4hvvxjOgOOG#{t3Zx|b0A10ofldeIAi+$M9@c(~mTtxH z*GPf{O;pEvo#F6a@ghBKIS{u!kATG9@q(H^+NieH4o3X7p z4d={QZ2)58QxM;hg=Y(Sn7P}A92u#I<7(w0TuDfmyiUTzibJq5MTK*HRW8nQzDqh( zWyO1sXyO&?5&iRX!p^obJKGD?Z*Y6$)zS8{GgP?8Q?I~GjNkGQ0#v0r>+>v=B9_A4 zk8_AM^Md(!C_?m8PugpcjMWN%Bc*ElI-@M5gMD4RLAbPYKQDpuIRgpGy=BCnlGVFitsM6o7Py6>B z=f!`3FQGGu+He&-ANiA5Z68M`T(HH^yX-Dd=gFNZF+}gKAh4-?OO<9>;Jvv_J8FE8 z*IRfSJ*`S%{ccO5JY1gf{MBLZzeBWUxDzIhb%Ze&=J}0V_zxd0`3&n9rI5pnRT#Fs zhvZaS(#a*Z==(`d~GD^iLMfyq`_m>l4vl zc@I2zqQg1u(#H5vqv3*gGwreWz*%f&vei73ANVv4@5)rdPgQF&zETS-7!RsQypJya znT?epg|I4Ssh`sK671qipyJbJ(jKFOZyzhcY+Y}fXO)CqqxZnw-i_RX7%jZlI14qps+>~f)YOM}VDg`H=j(sQya~_kTU&?msfeL9-dp zJX?WJ(dt4x&GHuOrjSv6%rkOq6ck<>PveGq;OMceuRib3t^VtT*UyGR^|a6Q@DvAZ zxXr<;(OdX4qAX+$8JI4WC4cOUu`SUE($}7*fjZi_H%1Xsx(@s0KX)nAKBn()?b}UO zwcDWiFd@rfuMth3<$>0lSZyz<;8K}ib--2!FqE4^L&P~~_^%wE-Q2_JZIl-)eNrcf zuI16uii}OPm-RnJ3UtHE512Zj1~kq}67SWDxLExg;olvlCf2s7xu4BpmN^P6$~@3t zE|PISf{1RiCTjn72MF+>I$>fQmr)NFVyZc*MU2@yR1ZqL8|Y5v@wwfi2)CnB__KTy z8oaE5!L9a0`=|;w?C&8#bSv$cY>U$>gdn$J6Bo-^UU9MB;4vzbemH1?yF3K2VUdjJ z&4Sx#!1~x5sS}BCyABqhDSUI@Nevz_@0dk4SR0yfPrsRn!*jGqZ^3%n&N6gP&g~|d z$<4gm5L-;UA_SRT=Q(99RWz0HhGj-4Xv;=(ypso@lrTxKC`n}o^BiiKPvU(!_cDor4SU4Tr^>6=JF1>+w32T{1T*oJf}DB{#O##&_kIcZM9Wv>ncwO8eu#+QrTdhhnn&pCEC zf7(3)0>|Ir??rf^<_^a1%D>KuDwuYCzB4o)KS+1H5~JkU7w|Vug)3l;>!nM@ASswj z*5|N1f+0$vu*-{HRAhUKe}}>D?pkhRh$covOMu$JyL6DVEqWXm!cC_}!Oz=o#C=Ox zjt`r+*wvU}#a9AGC#30GrV*`ud>_s}mm<5iD5J5v4sV(zOxB}?YW2e zvG(bBBl13YMOzW=21We2Rtwr%5@^gEI~@GL7V@%Y`iV{dVa?UgustG$jA!hH#S?y! zi$kpFz=5{7obBIDE&-7UN$p<_j30 zN=A4npf8)5Cob4Qi&ks0_nib>8(iS0+L14Qw(I{j{KhMNTpb<+=3YwFbv%0}Giu;a zyEF;UW&FByrr#KQo?Z^nMmS&!HI{yS%o2(Vb;Q7baV4Iz>iGGB9K=1COD(>zygbdl zaBi|LckU%)9Zv~{D$Pb(eBBL8KSn_6f;+sF;ccAyt_q^%ZHO_^#yS7&;p(0JRN;IP zUL92o&CfQG8kUi_e~=XX$9wd%Nx~NYy`WmWiOcEM#LZVnf#0D$)UnbHA6f`O!?jyb zJW&!WhMB;*{W9XT6!sjHZDIeC7d%zV!GGc+@b!JdHQKA;+N(?pq0eB7tcP?8(uHng z1^(uIHs`re311|pkbB3quztsAc%U9eC+fK4g>~$`pE9(#Z5{WqvHq>_H(GnCH1@8xI|MOb{Hwrh2kg37b9d zz&@cp3E9Z@Qy+TCXPxa-+0zE$ixBL(H*yP;RIzP<4>Sj5QIEZ5xaB**`m4-ml$wSk zOj#D>`HAGLp$b~RXU}=hdOGRpU3|VI8zz?YB#E( zZ@d*G@Zt1FVGm{kJ&$8k%izO@!`$#HL)4$a=1wNB z=q0A_dS|J`baa<^{k?zi;LrweboV7|Ew%B*@G%g$OPjuLb;BM%Hj9hh#brFOLCM}> zurp^+L3BVS`ejg)TG1;5G)Jw)qY6-A4aUC~A-Uj!*(*U)VPw4tx*0@z867FR;2zsu(5}&D1>(?bt z?bF7Ge>}lg`6pkbmVstPkKl}+3`yxwLW3|}c)mD|K4;mcb2C-?Yk11JZ|t7l46kBm z65j_(Sm)nE1|AQk$s?@sZlw^qWj(oMdkeha5Y}JA9Zf9JL^}wk_Qdnal_G3n%=uTr z9%R8iIW&2t0dd<7)9F37%vWL$2{E($+{gXF(g$Cl+$@ExkZ1l-nV%%)yg7aRKa$Qn zpvL!qO9Z8K}x9*85KGapM+%3Y*JaFY$7x5d7k^cE1^P?q_Sy{EmF$w z{`LLOKMr!9_jBLZ`?_A&Av2ok;6rOw4Wn7Fh($*yK>hPIBx%`ibRVnf{Y0dI*|N=L{i?=n!dB4n6A#OxJ(Ph<%gCtI-m0_RATv=BWu5P_NFd(d~j; zZ_Mz<6Fz*uX~~|Mr;PIpy|T>el%r^D=MVEHp5&Hw58`7F9q-J9 zWo*F;`fk#HrHf>aD>Ea~Gl3qUL->ewOoAX3a^}zv8o```%*vNc+tcYjz zoM8U)MWnZ=6uo4dY2JJ<)2S&XG&`Wen(QnmiEEY6agaVot7J*d&3fEvgK)yDo2itP z!ERw6yK~kNvaH(_Eg#Y|?Hy}g-7H63Y|V!&0e)=h78QIu-xcyMx)3q(VqEyM5zbt# zXJj|1VgFl0s9F7iRMNZQ1c5vlU%$>B*wTl`o4R56hC7==b;7*Wf7zWcwh{$LGZZ-U zq3iT|=2wjZ%4CcOm#IZ$c==7740mC-6ZI!7qUSDWO$hf`OT;qEuzgO`)SB=R-#T3O_a@Hr}8YKFqDs`oDlp66`3auvO*;v zdA65-fIOy}o69xIH9aUwe1tFXYhW$lhkwl4A|+H99RQV2E|Roc4ww=|efZ@eJQa5h z3`wwq#t3WjT~UB8$Lc{iH=XH^G{G~NugnHLYMsh>S)RUmyGzSbPmU1849dPWf7% zRSC{bttYFNnqra%9~y#R@{V6@7Y?{8jm-1--)fY1Jr+C^`nk(dx6pl2J)F}OV>i<8 zhT0oVP`j2(#>~?}xm$X0@w6E?-ntfL?o~qgT{pJ(aQq>M|6a+5$d~4s0sryFOg33gzhs$$=zGl$Ei8 zou8t-W~`8|3jRCV`#@hAD@D0R7Ki?^hWpIPSu<0N8O4XCqiUEf)DO9_(*x4}t|DD; z`_MZ=)BC}td?q+t8vAK3CMx6?$xzn7gNgKR)vrfpG*{rbIu4G)6DF@f9(QX>La@tO zQv6*XA4kYTwB{2*g3uJ7e&fUXS(Yq!jOIz_Gb6slweHeY_kUY?hxlo;m$zHuz(RmL zzvm=?&ZWx(rrv-IB z8v&+opc;jS13TN9GU^*7!7etM9Mj6g81sEFWrZeF`&Jp}*#v=L^?PD5MGqB(LD1%U zmivD67AoC-27VouY~LK}Z<%W|vIFI3IH1lnFL-0p=?NXTao6;Fu$S4&P7hYW3uUtK zt>2AE`()yZz-0aL~kH zEFm$vofDr-&ofIYM=`mM*|c09SJQsaJG>mS=!rd6idul{JPj^lXD_PCG{d}#a5gti z1#>%tz+rh9NnLJ_zd~Z*r7AG1tIW}D=@cl>?;-)Q^v_-64+_=Wxv3#^k2Z;RzRVY6 z`6!1|JQP7`cPiOjkcr0JVftOt;yspfs0tF-^R9o~&;GZ;1lzXIJyd_Q;Pz#jm!b1K z-L;X)3s=I8A}%oBJC4MUE5*qJ&0v$Wm-(5Ob>Q_Dod=8*>HHt=WJL zJylS=p@)gKmBEh_ohuJFPhaD#cizDg%9*z`S7SSEC>K|6h;_=} zN=T;(-qYYi`|EYgif0O_BIgNVyka8Kr;F>Svk+D-CMXr$#A>lRIKCvD?U*f#V+}N6 zeGuj6$Cu+^o&efE8#C(m2ErmmO_ra&fsBn;z@*53to7Jl&he26uBJQOq`haDsD%o6 zY54@u*mj&O)-c3+Cto31qk9SE4;wRoC zCbai$PLvd=+&#wW&ep?^ujW8sOf%VSZ;FBk;qWnQpWvwIFgBdk^NyQ!f_2zNImun- zkeob=$kM#tsG=%p9Z+Jn49W^WCn&HN)l-S%O*OO_mIuyPoJ^AVh&lO9z*{ECHoaBC zrB#7&^I1088)1(*^sN3?HH26GP7R-$*um}nRz$+M7FV{lz<=$>n9Pfm1-hAXo;$k9 z(Js343Y3H1MHjf?C7*zd064B!CR6^i$2oMitG8}v9zVCCEMh-M zD;ZyLaYH`tPC-zvF=w4S6|i)XGL-#ZMtsGxaH8xH*mINi;MCq1u3cBk*3S_aZqHT3 zR;7TEv-@8eTO?~yQVr#mcRADro@bEU~BQ~3<0#L zy0iaiMr_L7LH693P;z{$2^v#|d8(@$b1cOW-%5tT(}McCFB^f6 zo-WzDtpda9IrydegwYM8U5eLeZ)wgYlCaqr-R~&DS=lzhXv$}Pw22S(pDoyM>Zb}+ zrJXP9Skk&!vTFB`g|}{uCcC%A0`WBq2U0tT^+a`i{?ZucyESmBi%T(qW)+u=k!A~( zWpP#`&7CFhByBtu+GQ*X3vX6>ZTBw~UfDMq44#Pz%g$(`lKfhar{PnEUz-IWrfbV4(C7VAl_bpB6-5?PFN&$= zez1M3$=o`mj?=rRf#1?za^|%bzAp)YuK!MPeZT+UFHc?XMcK>Ph19$I{+uOznL+o4 zI`-%x?FB`0?>+N33viNc6~yjd%`O&E!EJGJu-?_3yql7VT+n_Pw{SC~dRYy3XNJLh zv;9PbW?Syk|7-0_KY6ca{}YBB{oibFqu#um4=iCj*Tx;ESw&C%YS?|WjtQXoqrQ1c z;Ov}3GW4kzD@_*s-wq1CRDH(a)TeN9Wdz&Yt%AWOA@IR@I!O(*!@eZS8@a_Yo@Wg3 znwTF%-F!i|&ZC)^oBq(fZ98`rZ{xq8Pr<}ZjUA>su-gMgm~c9kgl1<_z4r)YFVN<3 zqa3OxY3X|p9{j^zI7>D5&Ur9)>I1>eP&-tk{_uAP9x`#%qvf#ef3rQerVN`Wx5Ap} z{fymPY2oL?8tm9598uV=ihC?HVdEl2GVaZ7d>YKb6w|lNe7cuOUGs;XvGgd>*kg4~OE$5yv>1M|;x<%~4dl+pmtAw72)-*H2{8 zWf}aYq5v81uW>(2Yf&MU1Fci4Y{_p~oKyaHWFMMXVT|D>d{_~(j`{Lh0qc^yD4(r_ zG^Oj}^Kk$VMZ^U!wDWP_+=rkLKZo73QW|@;G$6Tk6)}q|M`kpEwOdS>RcrNy7ArK_ zpOZEaE!u5yYvRC&etzYoF_!+KI)>>P=I>zzOi=KGwzw1IikbnY%%XX~QQLjm8R4b3@~o1=0m2Nb<4i9l+AknMPW5$TL}(M_U6Ei#C=2eoYY<#Gd5Nsx+2O$$ z>Vqwu%KN=|94?ik@7bJH?6jk5xNF!BPQJ1tfBb8)YELWZq#kGTpBm$pC+4teUpHaq zYhc0|B^dqWGB@hyC*1tF1#W6Mvw9O$@pVQBJg-wHUiAC3c@t&0Wo>89>E@&O)+&&f zvtXlF$z$d>CCWdHC!cMy&}IBl5CkbP2fj53XG@fg_+I3zC}WuofT6-1&Oh7^?RUh0 z*|$qf`9B4eKIIIP-P1|)mQu`o*aCk~NHg6l^KtsiDsZ%(&nm^q;(})ipinrD*xF`c zJpKIbuIrf~OJi(X!iO(0FL?H!o(X$wXh%q;){o+w#Ve(;x-`W!-@y)i-?Lq7Eq zxH6AaRWV%57dEH16JOfz!$$gnIndeunev5pH$jtz4cn_MkJlgSz_0hm$ehJG_-e=i zrvIGkB|TfTYU7(BxY3i(=834`W!k~fo@qy{TaB>LoDZJX)yy4KqkFxHuxof5`TKVa zx^1HxyRHQDA4uZ?I?u!H`pI8^HT1q`0wDo`@P35_o06)GSB<^l#942m|7i>c(!IuK{b1%{hXs~I`+%MM z3lct$_I=Yc_EEiu+`POJ^q(Yv?`hI(C-qwIKO#$6zWd3lSF~TFa6eREp2YhYSt4xc z_}^^znWBw7!YNSeqCgDJjKS@zV&Kx~{Y-wH0_rWZgsuP16IP7sW3?ubRKRdP6{R@; z6bEO<+p^PpCX`xEAT+3{=H`*uL48e5hkr)#onNrymFW<+%R(` zOJ`(aT1X0HGFuocTV?#=G8GKd_7E*mTYMK60|sw?@Y-#Lg}Vm~MsyezTOG=pa|4U7 zAGngqHMqUwDa~2GWQ_08+3u?h>#pUHRTtFJmh!vGf=6?i_Fr-5+%^baHir$S%~43h0+ixrn*VBIX1kx8(?NVgEGU3?(Ntn4vLIuO(@@8Hh-D!^Oax8eQ*N!D$; z90oTiLAHJxc~X~&pSzF3200zx!M9>nRp-A!uq$Cz4Rp~ub{>R;-xnMRu*DhF*YS4Z zL&mL90Y6=Kf!FsJ6QO(={u*qBwTt&NJKjkN)%R<#QZ)k7P^E%16Eva6QIYh`sK#77 z0R;5FVw7pd;Xv*Xdur}6V!WJs#fM`cKF5mJd&w4yefcoqu@5Wxi_Z4r6Tq7FAiKxs zq2|Mf@VNXgGec1wxAvOCKGn};f|U%OOa0$$w^&hw-*_Axd#b|5o}}H`H~z8J|F)7} zCyekDy?3YGU(4(rqlj7l45%+ICBx-(7nu%l{kfPR%(DRZSvSGAvU#jyuN3Y${J+_L zp;}Ma_(+pY{U+VqG4xtXl*&dd{1@4fFT>$?$%2pChOo) zKRNLHn8`JL*2B$1QLrNDDcN<>2H#WPc)Z^sLAC1`9P@c0D0Mw&TBfR@dY3&2GUk&_ zr8PJsycHZ3jhNmhSz*saB{tw&Dyh6cb8v$SU@~5u9QNwLCi!MK%}TNtq-j^0=u}v8 z?J`l8u*K)`^seVTl~<=d7W?J-kTa0T`n;z-8cXaU@~#yLi>}62x_7?$E`uo~#<;T6 zVk9@ZWrqgp-&P*Ujk@-Iz~oa;;C`GVD>9@`^T^?_Y>qZT6I*mRLU)BB+nJhT6LhTO z!9s7>3af!zIDDoGRL+{Sb3RGqYnmxmo4T0XvB<&!$bcQSN(|~X2xlEC8`+uO_@aRe zmd%71?*i_cvn}f6#K63)OH4og9=^$Ofu2k0#J9WzyW*dMNQN|%b~6tb#8$%+`T49q z^%|{BR|LVoabyE83%|_DfOj?UpY_2E2X{Dk_t+ZEydS#^#xKul;flQOtqri68}*0rOOaI!s!|KswJ_EM|ZPX{Ts6AX8La=e-!(i zdbj5B;rF{L<{b5S$S#-!O>>jUW7^;Jdk*#SUKM99(hirf0b`Ka{)fDIq={X3EaCSF zBT_L`f=YKeFf(|}JeWlHm~(0NO8hd>JFku(im2DLx?TX%Mi`yXhkrlK*?C5)=$PRL zuTS_9k=yQQMR&E=uLd#X8TG0?4g*P@FXVB6Hs-FOyqyn^IqA2>_?GTupTA&O6It;dLn}OpGGZu9;|Jd;p&P(qj0h zRq?#jbl9Kuk-R&ifmu5PzUEuV>bf&?&_bZk!PlTI^Q9g^U%kM+Q-5T>(QZ1!`VfOl(V~AA<931YU zvy}Q0FZ)62?X6r$V?JK$yA9_>CE0VX)XQ{E8A8^lk+Pml+#_)ePF&UDm6nQC6@B{- zReK5BHD3q!_WW2*vQbhQq;k*z57VD>POl|TZoLhr zOyWaLgb%woT@!D=r|(lyPm=O258LFM;Qlnql-8qNjjHDGNb(EuSfGS6{-}efPa&tX z3-QI(O2{)(W}o$`p!hZk*f(J}iCS)m6CC)EX}^{Uh*m_dnT6=(Wn`6x4z8maod2Km z?BPN*vVH<35Y5g}QpU{VMv!2iOj;Dn(0sfQwj`M_kI?c$hdCquVP{J>jHsIDVm)!nPfU_O$z>Z!Oriyw3ZQdzRUXB=9 zy`YEwou5EIC&_wsC}D<22*~;5koEtpvEV%Ql)eb&?YQBNJL&H4j%Ffz_k>XI2QXRa; zkA&jy288BCaC9#1jg{NZbhH?u*mEx!_13vUrhxJd%4)!}$AX-@=&ov&V-uM-b@VeHLEh(XWm+$o8;q(*a;J5GithE;wSY2YZ zs=+o}JW#UZMXKCEqWCEwp z4v?|SG%#(i1t?86B*WCxe&MhX+IyQBPfKOwlI3Cat89|KooX6S|2Nw|<{9G36h8D( zJuT^q5+*Y@P>U0P+C-su&N%a5ypAE$4KjD%ZiZT3^ z03ugQvzJn-XI@7FUPtdFr88CWM4JTMe?`28FBb{_?)l$r|Er;nKL#g*H`dS>{v0r7~){fN*ng-Mp@kTRSH&WL=ksC z%1v@ig`2yyna~}IxUyyHh^H}lygJ^urTngjEUsX#8xGy4EQMt^8P7Wkm@BY`pRIey z{oFAqeLWDkO+P)&yDIS4{u=nCx`qv=-m~X23J@LTPCjqV#J<>67?-}4N&ZH6H2E{3 zbK?QhwbcrBCdYu)j_UPsSk9t@MV zO%K!eO@xAjFGyRJ9o8)fg567Ya!#0whrU(A^l{>B#8OGrzC^WIjs1k9Obp5XV<4)g z%e(wrqUu3iKb%-p&9?uikCk+BGHOMW;9t8H?x=}@;xP}HStpe6V!~Lc;Nr=1mwdeb z>@nc9-As;-v~X3M7VEHukjN|Yc+Or8qMT)k;E53JLj;h1@FkNoS{mP^{$-CJI!Z3n zyK2}Us`<29^8QY-#$)sxGV`N1J87#1#`N-_amNJ0TaribFHQ8WSH}d>3}Zxw#fbKP zrBM<6mubKgw?fXY2~otK1IcH~Y_EtsUg#SIe{7OT>QV#DSjvalEo&I{1&T;mZ}<>a zPO^Ko(ZtsWUQQJkG%PQ`>}gMce>;k`p*f&K9ma6IE}6)F_=TM&qr4?jBACzddcwnp zwAqQq8;N5*-M!X~g2u#N?$vk$)S!3dy@scmTFNlrLU&9N?N(zrmhzmO`%Am#KgmPp z(JZdaLKh2jqv6<(7Q(+^g)P)8($sxW;3sfJfoKfeyVt>Fl+oVm8`eHZdwY?fr-(DVFBnJ{=9dWF2c zV}(9fC>v)^Ffa6=8w!;8AbMjZTk_r*lh(3O%#J4~E>vTgUK{v%9cP}JDPn55I=p}N zkW65Wa5U|jzm;9ct#af+4OiTg0+y{L^7;Chv4IcPFFSbBs!xU13sgp!jl+(b zXqd;s)N>-_-4E(7HE4w`Au{Zg_i}iyK_8^A6_C4enz&8d5N6Cb zmgCZt2{}CCfs~(1_vUJR@Hyea#4ItO-H0>6^xhZpI$H;4+W7(Zdq2mAT=ZV}2paP# z>r71^rIZXH`|=55Kl2NIFz5xtOBdNVs%zGuL+4NC5d1`+6l4@*&k%uQGLM-L^!F|i zQ-MiZS4p=V-62+_f~fH{&hni;?v{v!*D>a7++0PxJ=bT%yB_)11$83n^BXdSNw#%F zql8chHtr=m0@d;7d`pNGY2>cx7UT5;1masM37&SBl*%eYes~(0T}8PKz6MZp<)v5m zt3u(DpQ0n4nKo7(FWw4-T?^!hT$T&Ib&mnt%Ds$`e&5;_*usNF*~G}m1_MVi(D5RY zo4BtU1N-lTtJ_#Mbg48xZj*$|d*_lrQ>o_ckp{bzbQl?$_b;-Z0Yxbv$)0&s|0k2+ z;NBBlcfSiZ(w&ZM#|_4%NfCFr*n#$c`^bSAju_SE3)KfddR}rb!Jt7QEUR0=PP-+K z3svPPAIya$tjk1)=roA=xs?fYRmap@5%4Q9m87k=r2L8)uy*>+(~}+)wnZC(#ZfWg zpT|ZRl*Ymat$wZ|k>+Q0YvF=i5gxZQ$|~b8+n7 z8hDs2&gPoSVfYzUFk6>S){e16v#I9bqm|=zF-E+~_w;Z0N07C+s)tADT{~%0lVD7? zCHmFHz`nx!%>OfIYJ$eY_lD&p@Np437CeLSoPErj&CFr7E{@%ijuE${Yp^g#Rp^oRCTS6S|1$cWx1O3k%z+kL^JHe~QBjN~+|EaPUR#7j_ zywUJbEtx0;>SM$fKCGR#hOsQs!S80%;Kryra@vq~d0+B@o$lg-zT_elnf453Pg%&O z_-J5mp%sw#yGcbsF|JxE1if@)=FBlYA@fj&mGRj`MxUWwU^_;G;iq1%SVtcpj^l$^ z!zo6C?hRALd_e!gNwOfu1!cZ2gqDgV-kEgos=*(Ny^}AWhu<_qQS{sh+6RM3UQ0FB z`9A=UeJ2@->!v9F&=~3*o|Du5${5!w0V2MKx$TQpFz3_^XnRplPRd$hcK&MPCap|Xl=_yiRHIJYOMv^lcJ8lcIiV+=4O)H zS%PH`ia=+kJ+n8vPRM9fj&vt&uhvCn--TdaUBOw@(jKDUG&h=_%_s;IkefdSD%Kn# zKWYZCrBuWFLK~0C^UTH7Tn!vcj%F_o$l|{hs_@y^llas9X27E&XquG4%zCbdezr2u zlpr8k#d^50h7T^MJ9wH#Eke16DkHnsTlv};5bOut5u(JdCm)x&K84b0(rlBWJno{i z-8X|OS&ft<+Gq;TZ&`8jX##9uE1`L{(+Eqgv!AjG&1aKN7d@P-One6rCvpyKAbvN*W7J#2M1wKZU=7VR?#v+lSxulPc{BQ)U#UF>Xa@n#2A=m(Il9`x4?Py*Ly7PGjk|= zpn} z%=Z*E+}vjg(O-#w%iSw=dig zo+A0O&e;EKAsGBw#T%f}vS{@~O$;qGx|+;iFtSko|K&#%CpwYA_nD}(v3hjyUw z)FCvWo*b1{L!``#>-#gf#aEQk+$elx=KrfV$8@UCi#|>lY@X|kKOhE5X|TjeP9B%4 z*?_plY$9M0mv3!@{nrf{cj_57ZV9mAsv3 zfyu`x7l;?cyX5DBV$1k&w{itLx`g^SdYoXu)rM?nN8~%U!#J7a%;shj{6e3##4&U~ zGG7+Wt7O34{WNE>z6;xCx55SqNA{JHHtrlfA3UxYlAw4C3~PviiF(P*;=}rwKAHzT zYn&>6F1&>~33tHfyd~R`r+{8_H6gb-k?c?}!Tr9);ACshWIebi+;ygMM7O!Km};}L zLLqejb?(Pb3v~NT{lEs<%v8#FdHQ86Tn;%*D!&`yF{;Js%Ovq$1Qg);k~-j@jAd7h zr&%7V!;CiYASI?Hm>X6MlWa4X>KSVI>!J*uu>zvoq>CPke3*{yJQbxD;RQ2QIQT+L z*tJ9(V^;V9@yd~H|> z`;DB~x`oQfdnXA?2IrFaJG!`&o^4hSIy19WR58ve0K!FHk=-p$xc}%v7#=*!tsTxq zlX1=9FwL4h@mn5$Y&U`#aarW4PBDJ9MyS^K#Pc4izvV&eN zQ=;&&5~C*G1ud_3=7&%bU+O8s&4FxEB|~?|8R~F;LWiK-UJtvE^1&d>j7?voiU%tK zV5!Dr5=p;@b@Y4qGbNBorM|ejkD>6Q?IU>@M7vp+nuB*k11Bn4hzGxM@TNnGwO>QC zFpm|0q@<8kVj~P0Enk|e{T>Jd&t!?~RwoRtr+eg?dzp`_ zis)Ho54Po($ebJpGcb%!-qky1Id4n_ekw_1(0pt!3HxS- zf9cN4rRghA>P5eBV2bgGKA%iIT~iIcVf@v8uCZT8St#wmetOBcs!3wuWa?$Azeqah zzVEIK?P{s{D;Okw*cjXeXG~*QuO&(-@qPvz{uNGksF`EMX{r&u^I}lN1dnQlfqP~T zY3nn>r|W#6Pq=}r{BjeQINgEOb`osCSxLP6k}{LqQb^Nr3$zfkgvN_GUM~A2t1K-3 zfu&U~dv2)?RuogM?9?N{_$lW2=3@*zzth0kMY%( z5$@&bvoGzci3jBmpXk*RrG`q9hOqo> zCAZVJns(w;!~V5uto~maw0$%h9;a<1xnFc>29xTpCaamn2}bzYF%qtCeoRuV&GDL6 zIGh|%5)6V!6<4L}E!lsLHCnBX*Bq!VGhH71BGe5#z6-FI=}qpA~($g&eWg z#P~@H5NBieT?gt1|(c!@8Wsu;02?;Ta= zK=Hj2?jAIQ@SmY%>JULCwfk@^Gn3i4Q4337Xu-d&4@u+(71|Xp4R;fdat5a~aZhSA zjGFR4nCu39yp?JNi;BC*(Lma#oGl00_s?+u1--|D$4^1~hdn#{ zt~S1}q1ixBW75Q$qee#zC_LK6DE1HFffz0CRzvwpnS~sx-fgAK7I*gA8tN_4(*)1+ zD~Xw9F>X3p43FO0G3Dm>gh!?cM&|sBNjg}yjpkL~Rd6dJ%+YZ;1{%4GjQ=3*ZkXi( zM<}07f1MG|e&Y?L5lK9Uv-w!RupTB|jb+EYqK#lu0qqhR_Txarz?r?cR}rgABw;XO4hbI8Mn!+xE4s;< z`IoDT?=ynHwEhhlzr_Hfwgf|J>_N^|atKx8biCiXB(b&^<heeqmr=>Ap!V11={3FsW)Yq}y7HqPO$=BzV`2BtzWC}VM<8=!7;)o(#O3o&J zTMY4Gj|MCv9fFK2Iw+qM3thX-*pOlsY@0s?>>f-e9np@cL3O!f9|IVveoOph5d=xW z?@6ba3KCaKxcK}&XPlCcbLt3`U6Eo1ft1%x`Gi9M6q0AGg2E6Ps1HCdyWe@jh`Rrs z=g&*4;v~}`2n~@VzE+OdnI8j_KkQ-7)AM|tvm<5FUM53h9B{B^5?uNj%PrI{#h;S3 zps>_|ZKK@arp+`jRu)IzBxYhH{}4!(>oV4}lyO$)tdZ`dJi4Fq)d>Id*7xjB@peCaxQML9^T+ZABS!9hWm_b)VB(gT)}e9GQe!-DjAu)rdc zn144#^KyEx-|EFIq<+_i_Ap3$+(SGf%`ik}G7M>K(f2s5Y1Wqv*2Z(G{e5j)bHU8?BQ3`r?iF#*W^7&7E#8_Mwakq z(r4mYs)_4dO(E;MkV_1q{akvKNq$R_9ZZzP+xB9xIzE}K+N6U)DY3AHwQCx9AL+fo)=*FWyEY5>YrB*959H(7okB2^HDX3b z=m}d|^x4C^wvdL6DpXIF0X60iw`YeAc4WlDsZ*yIF)Jl>F_;V(a+Zug?tsm|7J~7e zM4oRBud2&A&imNXb8vN{68^W`9P;0Vk`KNDyg;)>N`H?tA}VHh>%2MalYd1POrW2i zDFf$j9p%)fP)}MwG_2jRs)9ZqH%G7}>yH-=M&)dOPW;rMqn)6oj^dnH(-QYGB=dnSY>UMEXFo8mV*+vkK# z;q_dn&uKIt>gF$JLsgW~ceyjvmRpm-WtG^iLOndck1!Xb4X~5uMBXmzA){u=A-O3( z(sQl<@g2Gkw8HcW4(z3uI{3t35!88@lA=*&*g>;wb*r~A0U7-`T|&!y`+T{|fMrGK zElcyx4fbqTsVoWuHQ?Lc3kFyg@;n|myB;LFL z6E4vl!S3H)#qmO%F}50_u8OX%G;Nfz?69Z1z|9W1`Q2=2;NF&k~Duh=Ja9_rp_itwAs zCKap9an>b$2*vk;58XO=@bF?V&M{|a(VUCjmmqr23Lvb$1G>?9K52dcv#s9(c`-ro z?BhFff37N;ezAs0#~ZoXPx9zmMhGtFq*xEiZ5X$Yb{@UiPinj}@vrD%n3X?;C*FBW z_+waXgeS9d4duJa27>Kgnsb+Ddmz_|L1@ z@szzF{v{HYiA0gi0u$t2r(UMNo=nS1BUBfg1|88oO(5jS1rAK+plzBWYkiFN)O(7 z%P-OXod9Fz^>1C_*ffKYv%1Ps6;wxAkm>uwO{4FNKY@$kPTXncVUQ9E8v{Vw_Z(57 zyiIK-+7;`W$Xi15(FaVZ-bHnohSFl>eZCE%>=EXqw=-^aa|83<@8nU8Cbn-?0^dzp z+<{x_7_K%SF4fZV}$z z_nTP}3`28yKWTrl!x$;DDzz2|cTj%F{*O%MHOlJT69L}>Z;;6^P4Hq5%}@^o^2%m9 z;IGMi+KrgNI@v4Z>=qaJa>RyYKM~-@aqSRwBZFBw#sE*xw*^U+4 zaMI76EsT`K#r+y^pk+Dvs#S+ctL{U9Juv1ycZBaAawB`yze{wG@3a_BNpjqneiOV- z=lPXi7nl!vinw{KC)DgYN~|OeaZ9HUyz)rmc|_)+)Z+$t_&S!IoG*#RLnnv z3b$*Zdf{1SkX6Dlx1=HIUl}=4uY(tGF-TWF=MC>}5*B?|9bwC;G-@I54?UkB7b7`( z;#I|eOudgyoXQSSUqqXN8Aykg5=U`OG(KhuXUKy5FM7zKeq`>&U zIh2K^gN|e|Og!t#be++_ulduUwYHmV$kxUW$^j5tcYyO2450CH9dDcPRczuZdhf_H z14)t7WX==^40+%QwmK`klq@;CHx+57U*3*Fj2-;RtAUVY+%nB5#iT9+5;|b2O-JEWGJ`*izZaT?bIfQ zH&q@dRf|JMf7ydWT7v0OmZoy%= zl^Vp0&dU{!*AjN&is2-fa=l9`%`$5M|#-b+2^&_89=a-9b)hrbaS zLO)-hKATHVa6q5^uk_ycFYX%ipk4t3Y@9(NhH^X-t#P-qADm#jJs(CCVrXRz%-Ft? zeV-^39c0-_69$wMSsh-0jS$liFxpu^4i9WRQf@#<;a52F9=Y!ee6lgbVhY zjOp2D^b9MBrnA3S(@b>ZuyHr}HOX zi}?sqXZft{J8fKT6$jO~7L&DE#u(H@_4bRN%ym0Mw0Ir{Cda#pF3pd(YK?;%>PtDv zJ2&Y&y&n8;&|cD=a@a6g8x|ZtOu8u#d~lCGj7>P@<<~A!HLK`19QNbbS_vI|H#ZI% z7BmY+l^A2-AL`2rs%I9os-dleAN4_PAnK=nAR20VPrWUmXE{0HS}>dJH^Tpe@ME7paQ9 zZs@(^>_s-;jy^k2tYGigouodb06ns*M|P~=y>x~CpA1IM>W>(8Jg`a;N-qB6jvmv& zfN@Jean2d$^>!ufI6Vcjrkp3vzIG^1Jpiw`mAqg1<8Znq^_!KQV)=>GyVYy~59WuF zOOnOtcCdD2&R=wNLSCdBG*10a{?cr6XSp17yvpF7WU6ELl?4#l@PtH$>EW{QdGKPw ze!=B!cDRD>ZWdHNVi0(BgQIFA{+Z5IR3B>%09~2|zAiErgCwZOU~L-X_C+37)R@EfnUsk~ z_kcmaO<;$)Id^nI8UFo`=GWFavZo%(25dXKNn>jb0iqN zJ>HOSMYMa)I}oOfO67k39)m&jJaF$&0dp>qvIv%0z{^*siM63U`WJh_(!u3ktgQe8 z_EiDC*}+zQRzby=^6)y&iF~0tiTaVHG)q^*lzmdbi1@$}KfHLaEiR|;@hEdqX5Uq5 zsvFos>)27kvwXT&^0kA2k4FDT(sjq>*nfW`Y43U8?Y;Lvb$_mttn9r)QJIM%$tq-p zkQpMGku+4K>vNxmC?n({dzV$Rx8M2p`}g^y=Xu@Fb)D;+_v9NVRO5Tu9VpUnVd4rk zY+bJfAKMP|N{Kt7r6ctze6Fy!lwv{n95}z%UTC_igT1>AhqF%yaot+k zHAFV#<7xTAW!*qppdgnLF4tZ<0CK)7@yD6u*JzG}p+D9#l|h=g=bsmdcTVu=HPk0~ zvp=jiixvl5DL^kqS@+|dgukzpajU5Yq;#6fvv+0Uj_o^O{Y+D)Mw*Q$o1);R{ZHPr zCwXQMjRnm?IpT~(&X`X6)it&!+0C&ASbHS^ROf8x*H76a9~J_G&b|sfJF^gV-c`|m z|2*N0C++QVn(*|B7wUo|9h?P5vv%=;Yb~&ZZjGR?t+Han&+=7Q ztU5A&r_i@mQKuIyE_^G_>{Eg==^rR;GStPE#BeBGH-&FMXo1x#Q7~?5ATxVtiYqckbmSHIgqmU3^L;>eV~P0u z^l1!9y#h9tN`fZ&s`N7@@N~v@Zr=V0S1G-NnA63=R}BfSlFSChl-m_Ml8CEnjD)d8 zbxfyR7eh4rz_HUwJn4iVRytD`(o+o;U9f~$=1F2A02<( zOgicd1IM!HKa>YJ(;iM`yyMq)OYl~;BRsfqQ5>Lm4)2zW&~#Qq_}Ggh;)zrTvN z5GD{Yeh!TESi|vH)EPk>;(taJtsDK&Sc!DnNpIL6%D^A9(*Z0d zrShW1#rVYiBK-BTW|lQ3^1kVoLfgU=zT%!PMre{>L+h`&HjBCuzs&B)5SzGA3)6oO zhQv-eysw%wb*4nZ55qXwgjN3dCLjtB9>D?%YzN22bRQ@M+*%c4-IUFh|0` z{m*GWIKu*OeO?g2>Ev2{P(C*+;oI8lTU49x}j2B zw$=&k7B=$KPL(6jAPZl7L&q0g^_nw5)yhRWDwqX9@y&gD7B>hSp82AHnZo7p_MDBltz7h2YL zlaDwq!Ho)YKyQ#-+<)o+y=K{?a+sH;CK|qz!T08!ymXBpj_wpm`u|O`_|5s)HSH?= z851pprYhpQGF@2ov(S;Nh#w&Kd` zWq5N0hk{~vVaPW%?5Us(;(!VK<9rE@`#c9mRr#`#Zn~7wF#@9eUhzIIPI%0oFzR1f z;Z+O>*MQhogo|@?B1#wLE|dS&KM}O+x7|LN0R1B;jD0y zNzl|QrX#a`D`hHbl2@qH>N*xg7~|ms)N$E=8Q1sl#XQn<{T`>m^!KaDuUxSea(EqI zpGv*7Po3alj0yLtJ%`oxa>!13$PRp>n`^ZLOt^#m-)0FKpNawK>MWb0N#DD+DA3r< zgr*3}zv>hW6W8_PfqQ)Mdm?$wR*YdbA#{(wcL2jKtvvX-5#G~r1nYZ(ZR)mlvVp- zEFZoQNo#Q%=2v8~{12{Jv(g8k%Gkn4`w0NEo>>RCcJz38S_|!FGeW!p_}B`0N*hwtc?5 zS*;Ai6`H{IUIx=&tb;en3%SzaK5u+sgwsx%fr(HchUX#%6kUKPlk^4i-CDR}{A9Si zSIU3JnWL&^6ts^^W{LI2_+uG#%=Sl#1y~e(1LDy|FkYgBO05QPb@g1{_Te1rev`wo z1K#Yw-5R;dMR^B*+VzbDHG9kji=!yoW|^b<;3ydRoId3*aEYw;P@uCB$uQmktXdt%TQR*vIF zRKgzn)xwGmnmFMBWg1Id`S2-HjC(g1q^B-2w;!5#^41V=vR=(E>N(*v!tsVBcVRc< zsn6QO4UA8Ak>5UIh^wx9!Jip+ywt23J3YG#RV^({{+}A2chG?e`bYUa4boXnQ-%3g zFI7~vO0oOpSQwe^C|smWzY#-5!}7#oyup~hO`9X3`apk{d(0GN#g4swqn8oB z=^F-0O?o_Kq9ZQrNt%jRdp$K@E(5|w zt%Lz|OOEl5;8#v$;t%;Q@Jcshu_=1!U=|Gn4*lSPc3Rjudl;Da+Aq$OI%35$dQT&A z+0z3W`24&Nj8xssf6^SbTS$F&+v5eNPHK2D+?drWUig%cf$a@6>Ta;VlgPgo zYYHy2&+xUBPk21u8T!uG6Sw@Vz?0L@L)KewA-TmE2Q8Zm=V#5~O~GckU7fO$k^M(x6A>O_~ zf^Wyf!sVOJvP-AUu#PbHsSjns5i8p5>-&KJnIOJ-z7Gn=$oHo+hMgr$BXGPE>>J$1 zPkttSa=jb0&8in|{+8hWKn@2iG=y*cmGO3wBAng4lKatYch{H)Prff>^%=(K(swd^ zS>C|YCs?5OypnI zTMNq0D|vkeWu{SPtj4ZCV!WOd^@q%Z?a_x=7-1cYrVj_l=EJ<(F$eVNLtP1<=E)R~ zP)Ah@bj# zO2bT9>qHH#snLULi@Wh@{SY$`lTSRXh5e-2`%*I;cDy*l*ZZ2`Fyc)n>xatXN*r-} zaTFwE#R!pjorxx(G+f zdv$KL6^!kgOj&0&a@!p2(6?_Q-BkGPSeTYtDHg6V!`fK7DNY<>%HuV$UpM+Y>AU&n zpWe8TaEt`kO|rz)E|uf|N`g=4o)XHslh-oZg7p9WxP{hRv^e$!I%m|dwZ3*J(YJ+B^b1sLtv?!kglVG+pU#g@zAk+`vwVm-kS&0Uiq^l*K}~< z$8F3RTL!#!|wLLWFDlNc1^ zaUOTzMVV{xn(jBvN*&5IE|PTvJFqM0R9rt#r&U6}sxC^sW6Z~K3S z5I?4=qMY{jsw?y1aUUmPf23%>SR~TWs}F zVas?pa#)8OxH{nAh$!%JU(1p|6CR%G2j=A`d9AM{K71&^`)(7(Bc0D+pM)BCl{fh-y9#;#^HF1K#m2py6ZLodg#Xt5Jaj@P6 zcuBMr_PW!rB<{)b{6euwvWqJ7wXSbXR($B^mJR#Ly2!n42%P- zycMi)E%`6R(UAA2mLH#KkMc2*P=3v@qGr1nUhGV_@X{7`GJ*Puy1T*X*mc~4@b)e) zmmyl$hQ-TFRW@d($-@Nqu4S>!N0OWGL2k?{Wd5k70D zJzmL(gt&wAWGnT&@zG)GgUi_~B$#Sqv%fRwhL7eC7gv%WZ-^LseyFbv!UPiOv%k_KQGK)0E3#o5(T4#!Eas0vZ9UZa;0l#!hhp;@yq?y@#F=)4xP+lE5F#Y7%%R>17BJ_g!mhJxbKS{9MoIIJrU~6odWC^yC|F{*G;KL7b(0%C( z*|-l^RG&JZYGtjI_H^~8t~kr1o7nfXt2$MVV%@Zw$zcRp{A-Ib|B z!6rzYpLiB8yylRa;3f=sq>Oi-E5YOoWBC@^XG${Spz&%CR{usDmwz7(KFTe;<)UKEsohv!k{<#AotuNWcN;TZ}RS)V4kMS3K9q~n~19Y15p~5^!ir4?f zLrJW&uqRIk7qPLBO<8KMDMM1_Wh59b=*MOnNO6IEKlnE29v^ep61SZXhW{C5Zqs}aG@CCf(SPrw*R>kNm@FDUP9iyL#tIacPbn&iEV&r#GBnw+l6J z_)34!nUl^p$jvai9|I@LM}b@aE5L$xm%y}@p;B|GyS9^G*E@^L zzH=}>5hxpP{{dr^+F)>4vEUymK~Xs#GK=q382^ysD8iE+^e;1wy#{FTehA!WEBV=@ zp6E@p=yswyTal(A2f4G5a6t_xs)Ml$<&N*lWxkAXLLYWd1(c9^m+ z5)?BHEAl3I;v8Lir`|QQYQk6)Lfty_?E&B9XryotVtRYBl-nlqmfm)P;`~)Sn`UO? z0X5j=^i_OqCB^r?3&3W;Vb&*03%%1uQ7^zzKCq`9Ce!cSa6MM$Q$n7>^`tSd*(;14 zP1(hvw5MfKKK~8G&p+=$?uUbHT$~05cQx$T;eU~?Y`Lc$TvE&zy-uhIE{f(m_%zJ=rSg1W_ zHAR86ux+QPy{I=gOClrNQ<4P60={cu~qF!*l%i95^fQDbco=*|rizr8QUq1QPmI=czxS}N!=TN%;^ zkK=k?QoJ^J0lfX&lVzOOMitjFaK*5Nui31FtziSe#w1N#Gs+WJsYb%jSp}?Vq$Zvy zaDmsAhj>bjC(dr_5A`RP1oawQh6XWJ&~M8sLG`mb#)Yaw%^w%O?SK@Wel7s%@H)06 zP!oezjewk$sXVp69nM)qx{kQctRY+le}D3Xzu^krtkBGg--J!m) zmuzMr<@KG^gUVjV_}~=6+s`_7^kNq_P(E9~g`n5lMNr+Tg(fRTL6hSUzHOEr`qJ(( z!@3`9_$@(&Vf{dT;yrG$mv+uo0Dk_j#qh*@yv8nqsh)~}X-e3LT2SY(f!}Mi!?o&m zFx>oEkn6`2@?BRHp>m0We9u-1UU(Ww`fy`De5oz|ri`GAgV(UsYZ_?%vj=Q7&f`v6 z7Wg+H7zPfWC}uq=M(?Xvp||KEJf*zB1*Qg&E6(CMzI110mq6c3f$ZpC$|5^C1s44K z!1L*Mo99CvDVQHX*E4ky@z!y34{ss{*NxA1=o=6Ly=0L}9s2VPb#ME`Ad z;H9xp=uxgjUh@Cn?R)hv!N*19k9)nJl_Y6VKTZ^EmTlvTatSW6i-JL8-pRyat@7%3 zHXR&mpuRB{4Co8POTURz-10GYdn4Gi-efV$DA(w>1s=&d5f9Y~7Q!^Y2Nh|x zgg<-I`?c*7+gePzFUo^${koFdg?OOzaLP03q|OFx)s*k_cN4CzzsYy*q3<&3e*|yj!e?rYYpJ z-rSp?%J#sa#2@{R8O8E8s^ghzXDD%MHNf2^GVQwO9lr>BNE;#D~4&%ME?yV_zUVcL;B4J+RGc;LJs%GO9|X8Yc1 zqURAeD6v?_!_^Q69lZ~)RJ_<%LsR+Dv-X08-D*C%GwFHA6B?}iQ`~MW#eb>^@X-DU zvw5vW-2E8v!ee}=fi1eOh=jug=Y8Rk*0TO|<{4kJ`^-VE1Iot0CRdtPRBJ6m6>bGs+e> z-X=cx^na{bLmSV(2ms5_SvsDPJNt5YF`rvW-(M$sJ}>o`Jtv>FTsInO9p(sYwyNO=T|XEz z&WX3=72^WoKJ3iOU=FV4*u%sZ{(Nue+8WdqrD+CLey7DbA1g5}stV>N8VM<+owgGf zg2h}XUR6bNz$FSy#w};sZ{6|I!)bu^gUb(=x5W>$L0urEP;zhBzlN5v3M1f6OHd~&giG6qWC0Zks|Dfj}d7b=o9qD{1E8fRP7qyQJf|N)FZol0fKNI)*l6q$E9rwYRPGL~` zw4HKbobmnH-jH!LSX}K^jCIs&^LmM!&{w8`iOz&A7>9HFYZ5$lBLUX-3SggNbulk; zB4pfr$Dh-lKczJkWc$*@4=3C)c5fu)X%(=nU`?EJ)C~-8cP3*A9jsT3fd|u z#Zi;1Ve-;d!iz3y`1QLQr0jF%H{7H+ZuKIFKU&ZF|I^251E#=2)lEF$pbcgz(R}dh z%zpG!#?8^f=b+F&N zYtj8aYZ+y2wHfg@2{vd>duEv78rJ8622OP71@g)~{zc0g(|YuSf5XGYS+7d)(~27) zkMb5$z148tDFgWad=@`E;4JohQvy>K1hS|FYWR3zI4l|0&bK$JVYu=L(yZz2N4RE!??(0j}4ohy5QG2&b=iNB&tG8pe9@NOl&VJ}v>%4g1;o z1T9p16b*TuGWfN-#%K~xx)HN?vY9>J%kziZcFg(IEF&DJ)(=9JzKbtcsH3``6{tlP z@kXwXF>MwQw@O+3dJ$2!x(cr7_YyLClJ8?t0%SPF@hDFT27QZyA#uG}V=DDsW(@|l z`bYeiwL6Nl$&+Z1F79bNgL9nj!siHe;W~Nl)I{pFkKE1uYl`rN7uj-Yho5kdqi+U6 zw9Zzco@RSb?M0v!@vveO&6Z=#im zI&O+kvQtq$k^aBG-RA_4YmK?)ybd<>d&vr(s1rt~3BBsFIXseJ_VPt=LFys1 z7%ag(7SZsRjCHsET0PmE9!{WLIuG+TxnxgP2fH+_Dqsj@iOF;+y{M@`HtuPP{F*2yZ0chwjrdSV)l>-mLY7R>zM#)zb*?r(46?vLbPK z_bX`s;41h@ErfZGCAcP;o}Yov{KsJl?$3#a*U>B3v-NIReP|j?&>CF+eN30iE$#EAsdrpaC;cdlIIZx(#L=V`&)QVaVT+QRPoQ0{QJ z6z@;0fz8MEF?gndJDs#((eMgxN%zA2hlwyJtwr|zz-4)hpr3G*G9;)XwVQt?A6)IY`lb=3;26yuucQ8sm(& zgloOr!t<6{Q$IVUnSJcUa^@%__wj)T`rYI&7i(eS0#7(G%ZksBI*aX38sP542h8IP z<%<6`grLL|{4nvkk-JR6bm^mt)`?Q=+_;!@?{0$ASv~Z!oB{>JuzF zGJ^W9nqDZCr0id!!m01lbO59m;SOQytn@Mx{zue$QsoiiuiWW5e zbLZy7Ng1A+0rML(_=-*vjGQwa`s{u$3%UDN-jZPpzeg*`ExQeKY<2 zP;0p7Ud+AdpTF8=3qzIF#f6W~;g_Zh5O3}+tXxSxyQV~F`w`DWgCxjnr+09ywxplw zC!GWbeztNI6E`e4M_Q?un?)Np>KY^8_y6YkNE^zUzHSBHZM*rgfo`}pI}n;OOM@2n z;Mh*x-)hpW!jw|N;oTO)m&=bTHj~F$_IElY8`rTt$y(UsRcHqe|ESd!CoHGEG+d44 zRrt!U9hf2vpQ0$=P_2uZ3!EUt#hAB`D8sHxYhiEk6V^)ptgTZt;p~!Z?nJtX_~gZ~ z#m-aqd9(x@-c9eo;a^VH#omPZ{BNGOySkw-&GQlCM>6{xs@S6J0S_6;&&kBDM zHvTr*prX#!4Od*G*?#2}d$7wK$4v==C4Rg45kHP$+a7>PxhFGJ&XVUSofMwG=_a2^ zT15YBoepi}z_C*F^GJfm9>>^(RxSLmZai#Tc7i|RR-`+nt}C~>vdW%rSpI}M2kkNi zk7t^AU&RxetS9i=@8zg>`!2Y(?q`S69q~bmKPZ}hAd{&I*8fw3KR>sLyG#twvU)ze zRD8k@1kmqaGaY8BrB^5_S>q1EXyRkW^h`n#+Mmh#ZM6pVE^hTn@l?Y&J8o+LwX6%s*|Akz8SFlaj0xO z^|D31j{?j4vxJM&X@^u`w1au_@qa%d{Wk@#>3W&{%QQn(`UWZd{mADmGeRFFTTqr4 zi-$XxV?$>Vj)v$8iFBv8?OzNz5iYzZ-2$u9XMob8WL7uV6%8q4_Gsat^3XBA&^=oc zyrm^c$fbSt$8ZPOO#JxS<|4dMR0-(?o-Ew7QqFtTbnNP{Xr5&ICqYWdC2g-Z zf@EM0TOrrPrFRFw^wNFYD&G|kI7Pyxv1zibkWQ7|8cl<*4$c$q+v#G7=m>qD4&~d2 z)ne$`JFqG@muW_;<8$)GtnYe(8|TyCuSfz|BoyB*kbfn8O*K>6pt7c;o(~dHN)J5Um-epW4|8c zrcLLk6Q%e&DhZ@Bf|#MLE-o{h1f#yb=K&YA@N>_B9a+JSF|PQTvY?MQ4PO4^H#(LDdBgf>6Cq310H`Lk#(v^?zzFH@}e%#+1fIHLig3-7aT zX6iWhoDpQ%=JK&bh}<%<0j1^56&~b$P+hSEMlW+0b_VOC-=J{tF&W3bnyqlz1@e}P zeb@#K3oPnA0s_~+;JykvSe)w(S;hZ}-HRwo^~kSW2eykaUdosIGiVz881{*K zHBr8V%1n4oax0zps zGcOhjP9wYH;Ptu`mF~?WQqSSqXVh~s_Yj-EL<_C<&w~5swsW+WpvRJ#5NOdRyZQEw zT;JcW1Bd@}%m^KHL*ZELPjLYIiJi@)!Ot^|gd4@`^o-fSESt0ZXAfiCs%8(}uc(U~ zEzjZjrKEq;^A_@>>1HoWg08TT>xWBl8~KJ-@uS&HSov2b zEN>?rLfcTP!w%s?NTYkSJrb0kj$mDzRWWp)E3BN?#!nB@!l4EBpuL5Q4u8+!!>@Aa zl&L1X2vx%~yEGxC&pJLPNs5YzOCjL$DyC7Oj}yhIl!bePPnuzg1E!Onv?j;etGnOkF ze>%yfMN%9scZ4&O9`c1rDmaR?Mz{Sl#33;TI5}hi{BC^8cMX!D>baRPs5!l&i`){2 zKBw$WtJ~~F7dK4T_BC~y^qM93QvYUSnLr$$ z7fI|4jwRZf{kle@!2%z z!>y~~e6$x^?2q!Vl{FoFYXo6;$wQZdR@-GUmUdJ%#o5pje3%)%)I{q817T?XeqOcS z1@}irf{{_0tb2|>S{$DS=0QJLZW#6X8aTnZ!$bKn*NYgXc^9H5=d!3bYS`XO3rch@ z@Q2n?w3aS|KTF@rbdJ`_HD4Kabbq+mYT#v+P%x?J%xxY!qi#whXb#!P?xlF*gHDrx z5?lC~X>Ry)^+5Qyv%gq2mhx3d9~ghiO{mzVi;oHo;itlE?oHpm`cF%tG)Kk?hwI?F z^2xBdvXwhcrmT#rDRAJ*Zqee5GhQLheFIeLRrm9EzzEAd8t{Va%iwo*I zfb?k>F2Pc>RN;H88Xj!cf-Sp9V?)n*J7ypAf!q=W`QHF7%q#W=qfOR4d;cpCCQ}m{{fW=2k-+hUt^DRWBh0ckg%c?^gU;F>m8Ug#huL!# z@-l47zE3#xADUXQq)xqhO6$60@Y?0;Fhh|!NV+3xT@A2=l9S9zbW2) z?Xxt@R|2PCfs-}&&d4$IY0HIA%?FFg@h?T z#SM!7_-#Jz$+qE4xq|X8ZrQ@2XJ`2^8)H1A>i|`O8lo)u95z{SC|C0lEHfqe`t4F! z(wx9+|F;__&Zg%ri1|G>!4I3JKy>T}y3L*Od?xifXm1v`Kk`EZf%Gbh+nL({b-Xyx z7W$3J295rvU0@ICNL;!&~1uQ;&HR z+}=2XCF-eR<{dZae&GY3GD8b%KRUpVIJr3HFdfB?HL$v;rm%339@<_p0?Q3s_~l~a zpwBOd=7QDi$N4!2<43U+wQO znCO0zAC9-cx1{+TVizMjdCeK!J4M0V*?WYiPc?D-PH#A*6voHWtv%p(BYgGBWFAI@ zC-GF+V&*Mtc z%1#e^#paKu-q^|*xOumXf1x{TPS_ln>@`^SeTyZomqo*#ZnK0Ql&PCCyD#)8^yjAA z{m}OLG?;eIki7~r#iL*SVcNrwyfKwI@={)``P(mc?Dhd^QXHGG96klri&=sc%^uGIch4j2A7P<89}k8UjRSnZL1zr3 zJr=&xjdRBjJNXk&>i&aGNYla6IA?G^JB%9|R$+nZe;^rooY}_sW6qyI@I3N`hxL`B z-JBJ`P2S7&uV0ieS!@Jj-YCd}q=u-NFb*V#Rru;Vy#A3Cgnk&hYsH%A{|44`f% zuP?mnxH)yMMMA`Xd&QY)!rv_L_g-E4s4VuPUYl{445dj{2Xh#N|2VoEY~-0)lqGb~Q=l*7h&(Zd{$%zjic zDV}@;os*$*lc(^e)EI*`=D^U;5!~>rIo3r}HeG873mR{VW!*=@?PJgR`R_W|cS{f0 ze&wE+977r18*amXYaQW}8gZZpCD7^a7XEHS8MgJ|AdFlg+qU?K{O)3<4xRjYV=cUT zU=n2~>hM1|%y9jX@#I%vlZR`A!GFxUXDCNrKN_&VkO}`Jxkbo%Eha8p4ss z7)#Z_?sFKN3CiHEZ;WwZI>5N!4+1wfb*qf7G7YZ#TQ2Myt%#G>=ymk^ZH*znp5!LP zuPS8s50Z{+%Ul?}b0SW57xAqwLi67I~e!eMc_Maw7xG-8}&QBc0x!7GKP+ zB3$?C6n2ev``_K{;oiX#9&}reJa;w_Rj(o*T~vls6FB+ey#-tH501LB9Matqd2E~n z6W7PU;d&VxzCaIW`j3YH&cEOxdirP|&>tRoB#N5#zPKbS623KNu$QFaQ9ok`7wz`) zrm>!QlJ;7YjhFoGjc{S@hi-C{5vCXy(-SV4P&dueYFr{~0*kR9+4;$8 zIJJO!)21KdcSx`D;^hh$z0yafNP69tQ*&T>HxPOfrdL@$3ToT?@onVYt1%-j_lMzZ zV3I1%o9<58G9P$oCrvEa=m4ovTzot|9|yM~oSUg8EL@<3(rk6;lbp)itE6~iQ8IMj zn98Qyp{^bP=4baETlL6G%yoG-*DMPQ) zCaAjY%9IxDlehgmCG@aVl$TyKz-h}(;F+r;_uo&q$=GC&$K|r+^`y5cm<;Adr}#r( zb9Bii|MjLhGM{)S?9&zrg`al|gDIb3u&Ez7Bu(bAHf5Ns(geMa>|>vI6Cd~92|h1< z$e)k3!H^6maQc}qURz{?L$+XtjCn{|NS?oD2>1&+X_dR)6r#0-~f~dJ zAni?c(s$N5jk-tEoZ+L(FzPs?ev`d-;brLw_Sa1dPaf3=m0QSNsjGd?!DLu{s8x1j z8~JUEjNnPwy12<8yfZI1ud^AMz`CwaQo9Lp?hCdRN1TrXTn{1519$( zK1hbXMmL!z>FyjAV<1hooi~S@yPY6R+h#5Vr<-zi-VA%@MZsm-*`|_y-eD%d z9=k$bO**Sdcl$v5p^0MT@&fYP-h^9cJ%tJS`sn!A7M31b&KFvp!}MeX`|rJ}6Il(b zrp^Rc*>_(1(ime`&IPN#`J&-kGxVAk1uLolS9OI3POlR>e6KH-*x{zf#K{_b2)yXi ztx_~I3tsuKTo|xU3qQTHfb3 zG68NSgK@-*isd(m7if!xO@`N*!ZIy9pfeoqk4fQ$2K3BVlb%XTm2E2al24y7wFAR( z&LdxBfG^~}vfxA4S7BR86ZlC!vMtlpu&rDN1}Wrl=Rs0DW0V3JqOa`hM`L`rb8bgI ze8O8@EK?o>=K1~kmdTE&Wk))SIm1~G;^l|dxp(O2-Exhwbh;l%Q?H5oXYz6C{wfG? zR~Kds>W)ums)Opi)qLDJ(gVb&fX;w5Eaa6wdJmfcZ^Lf$EzV|G^@z9tC;f^DPe)*RW`MUJ?$UlfGa?G`?2XyNNcejpn- zneX$U-scy$;nABt>>73O{f~ciy?T?Y+8E-^@22o2=8#x^)Bx`5VBc)YtaiW+y9h(G+#riG_Q6Oqx;=Bhv7_54Q)r)a2cA>nS&5T++=ZJ@kFzVi zDMzS6ALfN3FD6{w^?nKrmVS`6*H_EOdmDqvSJI-;3^`pe4vei;_%Cok`y=Fm9h}Be z3aK||bU!#S_6~QNYl%DO2@v=7pI79D|xlkb19%-?6g7<;j%O+rv=uEaf6<(dWi%eT6g6 zb#X`SN|3Es$~9=thx^6B)vp3`IIf1Xt^|R}u;*OW&k9k9fVhw>$+~gmS1l(!s@6u9 z)Q!9bmBdvk?&RmI?D6{-UuY{i?PJ}i7KLf45L2>`Kc;;w#3&Vp-E`VvnQ~$yT7@E?aEQTHZ?n{mql;Y>+vrv0LQSjTYhEJI;{9KU3 z#ZUB5YeOm|*`zb`cbeECKO4f9HS;x}^-;Gv9E@r->c%TsVH5cyWILX*YCR3|UU@^& z4Dz*6Pu!^Xd*Hs;j;Vxhmn!rw?wa$u7>;q}6n`)?SRFSzz4Z*`?R+;9!$D#CG0y-c|Q0R?Q{G|G99 z8wgKsJ>;E~vp1?l3)aVNmn3Z0!dXL;L2tw>zPpCr>FeU)P}s)0SyK!!dQ=2VO}@!e zKWL%c?vbE~OSxNv6E^jrtjis{L~~}$mk!yxK^Vg1q=!l<(_YpF3d_|gzpDY;$TxA8 z|6%F$`K#0Cucvs453$xmPtSPJe>hq++|Us3&xwSb)M#O#E_Jz{8xC`)c<{h?PS|rG z^)ejRV%E)ic+ATa7MHj2`d|Gpd7=&6FFYanl39)JavWfzs=!FgeR*OkOf+)hhJ>-t z859rihOJ_u8J1Yg=rf8gsG)((UrJ6G`^Z)#A(_ZsBcd$LWZ zB+^;M7lonQ#u9nfnmF~39pO@z&sfX)1X{fq=U&n5x5Kibh6zcXh^Ha8E zSRZm86h-#JZVLsJG0}jx^Jnt$l=3CSdCx_V`%awN ztvJyA7QvO~>*M}O5pbFQUunNJaE;Xnh}zi7UoTX}sd=8TF#MjR_s~+zIn)H_-zy1E z45+VA)d<=OY0i(T#s$rk^OKh%vaH!FeIDAUs|RFTPhIL>j0dmXM%-$NKJMg{*i(ocng%XCO+5&rb zk{|3%{>Sy+@IKc-vbo0vRK4E>#@&2{q>pqXTuucapA=qtS{HL-7r=5KG2wiCV~Txd&e9-C~YL|l(8oPDs9kG(Yzhr0Vhx2Rg5=5h4Z zTY4Ub_~i;~y!CLOQW_iye^nPjTH?>Q7l35l4TilmDQkKPxSn3apH*1kXVS6wPnTzV z;~k{NMKil_n|V1psC;t}?6xxH+ty2Q+r$<)=<%7gPV9?!_o;*1&%L}YoA|r&Y2a@< zNMuU;{5$)2*x}|YI6AB1RfixL``wQl_aoif=m^M9AI-3zJQmMz?CSXYF-j9HgEubAd`kr9m7-X}SEgLcTD z$xsmgiYHg&nS1=a9m^l+G&If$Dsq@Vve43f09*h%tnxJ9|b8@khz71VLnUvv05 zqe7BgO4_zK4tr*+3MDk>C(lfSzyZ#Dld~S~uwDqu6;=~ZYJodQclxYtcmrNLo!$t<%;0q~WfKJ+!96NVmS^ zmA1fSdQVktTE`sqO!0dv@k%S7@WY&X8IFm&d{WH=tI%|2BXlG=)7nil*_Jwe2*Zgd zzu44@G^nZZWy61{;<`N%F!X#IFMOedcGt#qWe!`9v%nnsOo|eU*^X9aG`lzmQf?pS zeRmoYW(6?yMvPDKz)I?vYkehj(^6YjOLzSLVf{*w{B zy$ z;VgAFwa7}%Y{|0|vk=@58uO3=dKgLXtik1J%+yF3RUZz4<DP3Z>X4637-@ab`{v9HW8*nE01tDT{Mqd&%i%+|mB?>t>JySorx zEv=Nq%IM);nls5Y2UtRr5-Kko0?#LJ;V-Kl@YSAhxS-eF$IwBx9=wdj{isDxbG#aU znqUDN2Kw=7-%jF7>S|G>?)Xi8={bCu2z|52tFno-%4!MF>(Ecp#evVI`IJpmyjxbv zP1Vqixc>iVAOyX1z??_n@MT3XyI$aiX;UcwT>OduG_=6FW^afcZy*_Z>KvB+YJ!1@ zgM}ZOlqvl?4Ssbl;~sUSMIW00>SG48NXlUM{V)Npg+J$S9;o4F%HAJno+PQdBg_Rl|Z@KO>8fH$1km&48sanbJsQI_^6roSQUA8^`O0U;oz{YnIBTEi}~qZa8%Wt zyHixr&XXA1R>g>)x#FF>z4`o6|mh#U{q>Jto0duNm zi{!{#wD?*CNISO*1C-RUS}X#Yj}bg?brsg!Xr=w6fZcK?pZ+BixHt7Wx4Nf^HP4M; z^tHVbgYz2r#4QEpI=$lU^m~?NB!FPExh{lmw`Y_~P&~GYeRl1KzZJ$n+QDVqHPitm z4wRAdaHnX`>$%ceha6#ghphAlarA%Y+rx-O{rHyB)A*h4eVGgIS#_i)x({0hwR_L- zr#^bP(J&E;hm8|Gq?s8qp88EjMbW=kLoN3J2&?trzwI4xZ(A6IR%o&x?OM39yE`;# ze&mh=)NqTn1=Pt^NXki9A5+O8!bDXtQ#8iWE^A?Uum|V9dYE9H2>EwbvndYb7n@Fg zrDelwBeNZ_aV~X}ov&ufw<$k%k{$d=T*Vj1N%3rbD>RN6%u=K4q`uk>U098Y4EY^4 zu7~&g?n}1U>tV;|#Q*otvV$VhfZr%-6XNJ(UaDb*UW=OYj8uDIa-pc7OcrypFPAJ4BZ^qV&%o-7c(V zEM>7SBOc_%Hx;gY+6WiyrA5ck~$(?*uaa39q#NYeIjf2UP=s6agR%S`g6`J8g;)bT`6|;EK+uRHD zgw8cb`1^B)_+U20_+6gu6Gr(Pckf&VVeD$5RHHYpd#wsC;|K7#UpjbfO#*2D*vjRG zQC8;~$`YK}A$nacgOhdKyJq-aV+B+iMtqQiDgQK}1oPk)cvrPDWj93(3hfWy6H56( z!iA=v8UT}KeW)9#ql-gtCcu-LXbzb5Te-dq>6vLtm>?l%%V7q#-OVLEtb`%vnq zej|CEUxt;#?trm}st`hXxvS?>@BG_MeD1IlIN;D(h%s6z(!IP#8u$6XUHwWhd2se7 zLNxa0x>~x}=V%0|El6Xt1}I}$CX2;-@nIo7L~DsW*z|K%q=9YntMUs*%B9vil=n z``#Q2zWRX8IRi<)avjQ;Q3p`Im*70Z5LZ7)2jjn~e9r@2d=k3|c#bbyu}d8%^qK~C zzHfNdMOBRL696Mq7fUV#+vDc7lv&!C%fe|^Z?d<8yVrK}skbF~B9Z**p`%2n`xD;Y zc>xB_%@saN%+b+48`^vPt~+n8hn7zl!4Az^Yz}#stQL=h*ljDh!dx@#_!kZi*ZZ)* z8awHivM{0fmYg(&Fvc^q>jouQ@PRk$&}vi*+&l4+oe%Ge0p~R#M6{o0NlYlK^S@bL zaE~%Gn-ZXKn4h2~qlGi_Lm{tp6t~!FhJ~IH@G5c?bJ3E=9c|8VrnZf%S&(N|!wp=n zHcEz7lwexNf3sTYUN1CiSA|QICzj}>g%jH6!L_7TZu3(I-zP^vo~=gRhnZ&h;tO@& z2~U~971{|ay&+Y716K@h$4pOcvFxsSOd%^@8o#fk3wt>;Sqa33VqA`}v{qJ{8lZuel&d_`P>uVA)S#!%dEg$e z*-0BeH2!xO>R0!WCPnJun&FEfqjfUpgzs&-+3c>%mDiNt*xN);1GM6#%gH=9n; z-B_tKbER&VW=5BIx6i4OP_aRk*DNr_YU1DBzGX1?_13uKZ!nzj`oOFA^~ZLRA1KE$ ziJ0(erDK<%d%A;g`FUTQ@J|aO2#emkp&cLjPZV3eF%l{YNuxM1x=S;2C|LnjQpZC6 zv@D5!m?;|9hQs&0$JnJ9Wz=l-g662B{E~VVF1Nh~zvrwGz8;dpOJh`E!AonNVWo@C zl0|U$Up_ZYB2QUX6qxq>Ct9W_gWq?!Lsp8cRQqIKR8@C}2MMP9*l0yG-b*=e0cBkK zq7LrXwSZB%&+48L_m}mFe5tOpIgs}CaQ`Tnv1c%g-(!GL)HnBa|68tqK?iknhQlC( zcansVGW@;nF0>z16?Xj}OGz{VA!;+fu5E`O^}XSh#}A)Fu6v}B>*ZmQlAP3FGI6iz zi{a0H!t-bAqRi{4F3j8~SQ%~2htq9-oade&h!1tcq4ZvoWYT$6Y*4nMEa()zYH1ZZ z4L<`LwuqSt>8oGVetBO7Uh+pcCSS-rTvYL?$x_(2xquHjNm^EuB=~mt zx5%sbiF8e(br)uG{;LXFgakn6H`<^5?eG@8TaCP?v40{<%-lN?gl-S`1-b#d8wn8H z&q&ffsS=x%>bp4564E^?%v%K-&CB>?+WFPDCqdl3A*`){y7nAGK}GdFUrInRxP?d; z3l8{z+8=X1x}X}zPrm_yfiGC_etP!})P~m+iujHS>g-#(2+|ye3f-&KG5A(6T*?{A zvu2p$8Jfdep9Zqeos`3G>I(8@-*~-P9ov*$VWU=qWW~*dIOiWaSNf&!!T(c^i zyu5~g9rPQsXHF6qJA?=iXeO_1iG%p6dt8<%j_B8Gh^RAAD6aSzL29TNse3 zf@;!eFi9=vNquxtZbB4{{T3q%ePD_yuOpyn#8x5oygJ@*2e@rBi@QzuiGRuCrd@l7 z#Xd2?85g}E`1wcPmT8Cv*|xAQt5|Z@TMc90CqroG3;yM|E@osVLCfbYb^FOvaA18j z%vpGg@NgBZpAY~nA(7wsJ`kTxB0kY%r)cx?Ia06iT){g?PTH@VCSJT?3zMVNxmLh= zbwN-3QB^)%SNAi{78+~Hs92i~(p6|v0{GVfMME_heqn0r!~prR@~I&OsZ2J5I_ z+lx^R1G}fK|uuNSa#oFs5w@WrQAMfk~=(E@=wb{5!xej55Wh z{t=*6yH+%5svTMr$NkRsJA0*0Ue0&+AiXt)4A9cEGR6_k}Rn+!JP4= zvvN7cew?K2m&4vr-2E8u{`&`xxJ}(Rd)-BKhQsTF9!7}|jn;x$)^eDnsRGdn)_idm z-3}qMVfbOv?$Y}@;y`qlUeTwy2NveKcV)$#OHji*On~|fTYm7Qv0Oz)`*RYys?GTs#O^tbQ}1(oP9sUF(gmx+FM?2_v4knh4h zOs9~4ZRrv?oNLNAjH35Q>MZc@wVGMXqpso8{_yA93BG^p05o)_{dPo>ByhkVytPVC zJnZWVVbgC_R8Fym$^Of^@xn^nm2n1+xry1m-IT{`p8##wyGheG>*DD9OJHNgamfRF z>I57+3y#e{$TWK^<2M_BIMa~Ncaj&TZ%H_8(Cg;&FhdRJnA*VD2gCTq+zRZ-tA}@6 z3fbL>xM_JQ!p zhN;XV#SlXV`+{#!6OSx5!v-e?hg%FJfp4l%WPA={9=Zsp4r}91t<~^&({ldUjWo1R zmx8@FWo%}tWBjmC2;TLM-{~a3jDbHKvrLrS={*n|E>h>6T`s%+M+w`N9ijW$LOwat z3SCzZhOnd>pYiigqPcPd-1w6#WCc6mEa^5_Ti8?LH$@Ng^^)P&nPz5kOb0z^ZftAK z;_^l&7(;pz%|U&bp6@`ZMZbtHtm9Jx`7xh6fwHkapWe3$$CExkk3DBY#wp!i>%OY>;;LyS(xUh7XFrP5hTJ;b(I%XsfV5Pl%qI$xol!Dy7U>A-hUW zI)>h-%AXD3@ibY!_sVb7J}^c6-e`kx|ELODou3Uek5urPcGTrMdKR?A%oTMOnqb^4Z_kKPwGtmWJ4AbRz`kuqTRn3sA{+lgvHbUv8bufPLE$$abx@935 z{+Uh`Z6BqL*Oo@Y$Ce0ThnYI=|2+ztk9hNz>H(-UH5^RNYA`&ffyQ3MS?v43+tdwF zoZ${St@RQ=pK>HAGVHpnBJ8+qglyD$XrJ%Rl}TIjA|e_7OjygB$LOO~+cfBt0<|Zv z4#2NV!@(n@iskHA#;=bZVaLDKylp`pUionk_G}fi#l32!7aIPX)pdkR9J!MT(*hny z`pM{H=D-wCC+zpzQdM-aoCdR=7V!^H`lI}H(qcKU6%8LS5D)&Oe!#+SY>GemaP>W5 z&@}3}e_M%~�Mv4A`mgIjO8Xc`k(6P~oG_eFxLu zh_I}t1sQBhks(^vkA;}Nk9pN!3vA`1;7{^U$r_ysyj^<@vg%v}ZG%2otEmNZYG-iG z@*lWn*d+1IZpK2%C`ByY6bb+Qzw(QuZT@6A8@yH(NVJUmqbGgegFhZ+e!9x&Hb4Zc zb{ylc&g&r%mZCCsmQRV>(E4d{(PI5~n(*RTPyAS^4#K$syzqt!7DSK^JUEy4CC%_P zQA}4Rfb)y)Sh#x-Y{`+8E~}#4>0X1oGQI?zcC=N|6F0;d3QrRhahicSTzp;5lj}%7 z5NQQjJ}>G%%_Jr7Cv{!Ih>k)7aFf*iq@RpDYZNz-<1P!GnMxCn_?Ps13O`RXU+SuE{z|@b z_vO4vp%P~-J`0;xiP_r&3h3vt2#WV~mtNmNeu_uQaP{m7iRv(2bYn5lZQdcaK~5PH z4h4X)ZW}*WYl~*2SykWi&%3vZJ3b#n9QSuw;o4F)JU!GFvUd#UTkn>mwFPPRGO2%I zs4Bjlwj822@8U~ZbkWZ@1)iSl5NQNHlA17^u6=v4rZO7v0660GL*j7P7CRnL7O3S^ z_HUITW>yb@Tf=YiL2UzZc0>SW{8~!Z^r)bIw= z;I!{B_H~yk=E#SD$GJDWr$isMoI)XBQ@SMggDo!l9S-L2bC??44n16*V2j~i9(czR z>jhs(FR1Zx=sbx>wJyV*-+6*$l@$tlo8a5r?vf4j^pJZj0}H*o%;2#Oc>!j_yT)w3 z^sOyn*HgCelOpbr=)oZi zVsu{gsNbLwNi)`n-K^HZ!BONW`@-BB1%*V|Hq^GWLBWf*~6>aJ#G25A`n$e!njl z9e%V$dTUl$7e`qmXkqV1W>8Ywhuhk;t0Km3{lOVr3INvdjm5?Eb_LUf030 z3s!LS;9*H&L_bteUJXNfe&I)Li7#kK0i%}uxTOL!cm!~SGTnU8Mm?WM( z-?pnKeNaGwsBzS6=_bRxE-gyPP(6&zafO5jx_sQ>v$&@54!l_Rn?2Gs#Npr8L3iz2 z+?ufKV@1nge$6D&F5`YEJ3kVPhDHdm< zkeMI&Y{ESr9dw0pL#2}6cgk>+LVXuD5|eI#h|xD0HC47Tx}A$q&c z1iKwWYOhw>Vn#7#p7*U{wu6sx@#O!I&Dd~l4mj&4xIqAbN zL(1P<4@SdVB{!|~u|9e^tSu;EHxH>|p-u<{wjbox_sP$t9046NYegoi1Ms$W1oU$H z#)5MQix}wwzgvR%{Et;=yWu8WK2ykEBZJDy z^t!a=)`WLmFrEYD8X7#zmhuA!M!+8D43=s}e#xEVNbB{Omw6eZ>xE&k5(LS#36&^1 z+ywXP+=TKIy>VidR@YA6LEQIDyAW}_yqVCNp@8YeQLtt5SKdke*R7g!z%+iRWYT*h z%zYCMJyslLc|DZz={!a~fW^Gt!3z7{91Ed}DL(t8L+XEpMvIH*YJyX=Dqf#p46WZh z`OCkQ*`5&#$su`sT(&Oi%gzPS?(VFAM0eae%%jUUn(|x&$IKiGuXj1{%|UK>fNt<% zpQ71;&6MLo-Fzz>D|oTLHimRqg2}gMbt6M)9;z*aFNv|dAd#@vA9LW7-B4!WL0!EV z1VIa*@RMh?QMYIW9J&2o;{M4MUCG0B);*u;PgcYPHw$>ObSs~>!wD_5NOPY0&&TIs zfi$X9zRNeHx`uxKsbx@DXwH2Xk_TthTsXaP4XY&Y^Ze{USikZVUwm2v4`d7lkCsW2 zCm&qVHzOQ$Vo$SI^mkvr#uj8|t>EgPs7HI(SvaX6W(|kvvmKlS(eryqyOrq@HnoiM zKWij|$!kB)b1oPzI?SFAQpTT&Bf)*mcHW(Qm&3Fo;qD;9Pj0!Q%q+?(+$Ss493?;0 zi2<;s+@G%!pT*jTccJJ<1@kCS#S5}4A^pQ{E++lP#1+e-Ip&{8IsBot^{x$^u9B4+ zZc@YTL&w7R#T}9`%I(o6|Ng<_Q&^;d0Y(N7>Dtfb^9JI)@Db3f&Qh|w8|mN1H9}>m zhcLBO7e~5gK!QgaFZZL&!=K9`Vf%3Qojhntr1NaB{=yx{8=-SvIHavyCvmQ(>|z=6 zi{<99+;%1O+U^XRpZ4Pnqzd8lMpjCsASK71%g)qwvJd4wZtpckSn!R_fub z0V`m9d<%2?po4KM=D@cd8@Tf&>a`)Mo;_R3D@ZiB=KB~`Oj2ROuUU^KHoh;Eo&xt8;C*NP_>`6D&tq|Ct zHj?+(Cf_dc7cX%ndq}gr&m0f1TKS8QnyQL+`EFgf%F=5UsFl+Mu|XQb#;uBIkf;yE zJ{x$D>R((tDO5b>SD0{TxfZ_Zw-_#ee8kf!KVgsKT(GX|SLgncZv3zaP)U5urm8CA z%a05~|83xw*Ie-^;j#L)<)VQTwn%66E*B=`$Vva{>7ccPHH1A^;BPhmV0}`ESW_ui z*hxFQ>X%sPty0Z<5U>4s=v;U;Wxi-if-%ZDMuJ`F79no9CZ6>h26ip6eDFqBoZl}T zR>m8%KVJQD^8+84JL41Q8QPeYZ3RD`ACkDs7~!qwnXu$|Cs${B=CXDdk0|Ql@GWjoTPBrM7M0>-?RxmJT}604lHM0P zGT;UE*#5bphb6HqV5;>xW;mIAdE2OC!gXlvvwJf(;Y+((DRcH@FGf1NN{TM<~DIwGG_t zXy&?ce=)2$RQ&x^BfIzMv~=F7|7QE9N7N6sH3W2*_T`BSsDFx+fB)uMcH#)>F$Ru> zqJ0nfBC!cRz8L_~f5noq)#SC0Yl4PpZo<&Vy|I_juZyF!>fNXQ`R#b|KznClJaKv7 z8>2z~Ya5q6s*CFT=Yst7UE~Kh!tfj6aA)LEwrYkl&YL2@+RkGBmb3x4D#k!@%2J<3 z^&$0*YSCgPT}@a|yJhx+{%|1Mn^)1CKV3Nwg1c|z^GGLrv?>;^FYdv71G}Tz3J<8d zL>M?I<7YbocJ;U6->;o{0bNa(L1X&Xkp27i`= zmeqV7;X*jTqF5-HGK@W*tdCnL2j*77doI_5_C4Q`uzv0b$*c*k_^%-hezk063!W?D zMJ-EkcFgDDQU|mcJs937bohLbEs*+7?+X_iDJwWZ7e|d*0WPa8_{UmZ>O!I{yUcX< z*V+*4NrUSB`U>akOmO$Xsc^nuti(IP1&`5QEmK>|zK&PMqCeJfv_6HaR+OVx-8tB} zPRtT$wr>nv3Z{aLbPj2B)iPE-RaP+e5W9ee6w z@ud~;DybU_b9x~C>SfzC+Xs%+#GRKWLU~RKAj#A@foG+SAaCa(m}pW?zH}}4uTABefqEDvw-R)(`7_UC4NQ3+0rNh8 z=3&bWQKA+>eY@)Eh*WUg-K?&n%wx8(K~Vx2w-Murg~f2;$~@7y zG|IG5Sq|sc2MDuN2(L?zh1)%+^4G0~xF|mYvK&XU#S!v2t0(mpcK^)_cj;rgl^>{7 zw@RA*%TZI@1Vtt4!kw9lxHiau^uQbV<;|pjb6x`Hr#|66`x>vbr{!d0E5aK8Gc1PZ(e-&2U4vPJY8x4@F;Afa#&_bv}A}*kDGw`iK@5xSo8z z)lXGOI-!qe|E-5Ff;azmO%DU& zRzkwJb!;}_GbW2Eud=|ec8sqz>Pkr0ZC%M;k{&yS^lT<~Gs*i|gLbc4;qgbtI!2t7 zo^`$|gkO-8PAoLQ((9Qp`pZ2@^DKQd`LYrc-<7d%4^?s4-5H?Q`v@218sb0NpHI(8 z7qL~=xI%+E#GAje!-5JvO{I6)kcm7jup9&YnxOCP-RyXG!iNXjz|_>+e7Z}m^!Zr* zE`9hcKhl6H%!lRoHTmc}29(cCT7`{k*+FeH+?Ackz{<{B?1@?R;1tzgyB< zLYX;s5wPUZ5q7l~^=AzggZ$4DKG@j;UriVXYlbBIOdt=)O%*c;)D`ilMio5MBOZju z8@bOOUDBw`hhQxkW~b8)%j`V6_V7dFDLXN1IHc@ySL!<;e3kNCTotxU*J#4A^=p!G{W*RpoN<0eC(^H+z@iMs95{h@t9J404# zOgast)hnUulqLVLi~8Tai?nz-PA6ak;_Z!`SM4gdr^JxXtSxtAVg{<^KH$Aj%TnSSXY9$_fX%B}u zFwQ;7K1P$5_U34i1{CnMmR9)t6?M~G@9^%HeLR@gj+G;Fg5K#Ik1-c9}t z9>{HlbKW$oAE{x^@KvBXaUVZ0L=SJvroxlh?kxS|J?V=a+pa!Sce+FKW=25W=01EA z^;MlC-CA<#WESN^*jJV>d>?(C8&2Zy`508Defz2>c#@mr@ zppmnm&v5ULnOOqNU0dnnbH5rNUT%bR;>MI05SMg38%F;6S*Kq|cXV_r^csDio$l1Z zVDWtD>7C0H$a__>J_4Q_^=4bQ*+@OSqr37L4SOl!{SFuKchl!1;!80%lX7hIp0YUw ziukA85Q0u0;rb~8P6;iB^&ay?Ki5z{RQ3w^DjgvVcGAWAJo3XvPviY)S3G!(GQH1@ zV3slRIBl*sXnXzP_emFh#%u`8>$odfPWyT^w~m3^p@zd8w{5PVfnb)_rB7=+B#^ zhn|&pahm693Cpswg@pZz+)P~+8^6axThIxfwp|yaT;o8&dx7Ygydee>mSR}2Sy+~$ zfo`Uhka}|-f6~htL(M7cb-NLpt!j+%cB~6ax#`&t7baQ5Lg^uimM8Vk7G%M4nSZ=u z4(UA2Qz7{Lj=I9ZgqQln16*lkiL`HD`7#Dvr!VDtuPkwBPB^%Tc8FR&M@nTaHg?VG z1^WH)(oz?=v00m!_d1R_9gUD!@Rq4$8DVAB2C!Fd<#De`FO-!EqHEJcs-#8ypdSs_ zXG92hYSeI4Q4sW}azfs0i9MDORyk6gmCjek_0PPZxcC$AM{|2?p(9vLJ0;0wrPvvE z77QX)g-iGK(0OJighY9BP0|C;-<1kw@7J>i>gwu7`?eMHtIe0OLZuUwX;4zZepYLc z*21T2-=3*igYzET1Cg7+=4`5w_HFrZR{ypkZ)`#~1ZX^zyou3ApFgRTTUgG1Ur|M+ zrC}iV0a|<&JwjK+qn}gy%HF1HLQ(Q@)8myG~j@>T;U@ zQ--xQbxN0P^aS%_S?Q6jeQ}f;qdpN!{{E;F&L{n(Ltqp;#T7Bu#RkTUs`&xxGaB*D z3qBtDTeq6#Ug{`%HZ&ISTH0NEJ&lJRm;70zh8p(l3<7hF$K2;Q&2zCoxcI)7+%j~+ zl7MiyBDJBq~=N@sk_fmAg){MH;G@n`Q?W z$z#|syat1QUxPmr16bjE1>Ep`Ib5WBvx4r^y!)x}e8*`?WQi^wbzA@m8;-HniTHeYC#~vx8vC2RQ8#|oeSYL*leJ;SVCwp0i zmO4J)xEeBc?&qoV^>8Kmp6&(pU{CT}rQ7e=g2iT8>D|j3*g0|vMDOXrx3`mT>lb1B z-6pd^qv^JtJQSu^HF4Yd{qZsNn@9gLkldeHhSQWUKw5*dz!h}xY{xoivs}eD73rbb z^fcI8G?Fcg*T8k*v*2f18#f!Oj|qMe@bP1YWQ?38a?;z^E!x0ph-0JFQxAK=&8 z2(Q=ykkwJ?lbc(O1+Oo6>ADs67~&7b9B{tTUbp+U9=4>X!4t^?wnrcyWOY0Q`sMLC zQTlizfjpJG7rRkpEgiK#x@+HVKdFgwbgylmZO#`4mSX&)CfNDtDOGNFFPkSS*+92L!Ah{{9w@{xU9?M!hs9;Vd|r+|c9cgz_mLx5W2`*Bz2yV8 z34i$#1=@QDc!J!t%aYaRrRZAn-wgjr`c;JxqpsYoOjRxXIW7g{JfCr^ZMrx_WdWEi z(5;J_u8*r@s3Z09Lw4b(68=>1h0Wh``N>C)_>{0~bGI^4O426j%lwKi{KR}I`Gam+ zQ?`Htzp%AW{kqplV!O^lVd)4}tny0$oyr>ik)C-^@d8+i3q_B}vl%%c5=IT(EQFHY z#wyDn46Ekx;D3&|d{H=9ha0hs)%2`BWpMv0Wp}(%!_-UWke9n(a+3T(cgwQiz~N5b zJCXJZ_cT~}s-Uhn>9OCdE`(1%?y(u3%IMX9ECl~s!cBKt;L{}9uP$vDEmn?{jy77vjBif^-?B_r_KA8c$n$0UVMuK&O(S z19gUqz%?X`-*5SYPD%a5%loWi_UBJXuSQ(!!p2QL>!HuiEVvkSUowa0-V3W$(CSdh zKKxY02g@Qr)Z-XGW=mWu?I+vo)`%LdE%7Yjdn54+8wKjv-rWa!p9to^ZK^P_<}PeH zw~t+Sv%>IZAGn|Qo`0U_gModH!Gw!?%%t(8)a%B7^Sqt#&naaK;Ki|ieCP|xA~;UB zc2hcQ&NW6YhiPE6;1w_Na3nk}49uD)N_IC_V&~Yq;B>=7xJ6kF!{?fI?cs?sz3SaP z62u3eI}1aGDB`E2SQruXi$5_UPx12w@HM_r@|*q^qe+*DJ&rITk!H>*U+~;q#=W0g zpqJYOuy0)EW4J&aXGRg`+*{z?qvY$~Ori?B0ZLj9xMiywc#0#!9 z{i#bkq=)Bcq`~v{g?!}_nvL-b!L8c}=47shPogKlvFOKKUqua<1`LCW=Px7~xsI6r zHVoF5ZedaVlyLYv8?YL)ou6>A#~G)Fz=ca4K1~+eq^o@ty7Vd!UJ*9lmAF=DVNnS?UFxa^q(SmRpfwfGsq*rPO-;xRdDhzJ4jfx zl3!bO0weOSLq|XWOHfw8a$yDGHgeJ;+Q~;eP6NY|I*C|HdKHHR$lF@X8Yth!E^j>C zp16xQH=E;I>ecOa>aTZ=og-dWi2$8E8KGakGEVzG5Efn-&i#ux_PX8z-B*>fT$fyz@Jbde+zA)#E&2@fHJ|J2D5PXWQ%cThg8^S_m^b^7udE;1WY3pgy!0TW)0~ z{pTMon4XlAW+YPY(rPhO|F+5Fap1Gfu&-yJ zC^kR`N6$%x9uEVB9#eJEJZB-iRt@Dd=-s#O40&E22e4^r@)$9ZfoW3*|CpwN4!1oa zcgAR!e?`2r(HN#WRE8 zvw0D)Cio#6RjY)awnHFob{;p#bwK$cl#N_fDmu`zQ98uR{|sy}>)n8!;`Ip9UwY2|(y zvf5LII6i=~XNl7^QKMX)7;DHqbWk!sh5lYMvcYclKkBD5!)n5NBkvW}eIX7aE-Vp5 zIS<$ky02BqSDy4`Dfd}oj@`CWF2~~SqJy>JQiXdPySzEOs`apTuQ$BTGUPuRCHUeF zWgWEsWMmA&sb_M)ys4Fkk-kXtQwEFTo3QV=)GY5>R~GKA zJbf$<-2k%=Jd|9PsN$J-#66WC)=&UuO@}3qbH<`L@e7~@8%HE&dhk;&7 zC@&RNVaL=~*u8c?+e%trl$b)t+(z#F%o~@yEQZ7F`fTsJ6VlxQ23cmI>w#R{lM|nSqV4u#Cmf*+$n0xg&5BB%KVU^?H z@oYtj?*T(RekUE;rzUewnQ7}g5@B)RNOroX27WT028FX<@PY4D(ebQ5j6e2D5>Z7x zN`!Zv9m6n#mU`?D0iIIPB3p#h&a}!p-t_U3}%9 zfv54~^gH0;KZYp|?~9c?R=|@$IqCH+CO9>2JNWP&547y{OkSju|2-+Nxc}3GJ?`qCFId|aIH?l?ZY_H}du5vC6wbGjmig*16MC zN{X&74dL%NEnM+>FdRBz$^9ji`|i{Rv@MWU>7x=+I+!Q{jyA@r&$dc5-Q!m&4!H)KUJWooTAWIFc@@Y^;4 z8pnL%hg8h5?7cU*hMkh^?@oQ4E7w6{=TCl|d`}{aY-sIwxb7#->inULVeI*bOhWp- zg?YiSx;l+tn{9?+S7<-?+%77<8zx;bc~ciQQZ!T-d-!<6u(Jky^a=@X>eC8Q3BTA) zBP~3)a~(AIzrjsO&yzT09q7-E7RlLYpzEeNaEC<;ZS;-Xb&}*gWjM*I0aE-mgxMl(Je!vZeKvXV>=A#^c+Eud zjfD}yae6jx(6f>7WJv8z(!u_Zq_YgGYU`q~A~p@ujf4_PnQ-==2UG;a#BNGy3`#&s zrAt8(6~z`oK(Uas_B?i@V0SAf7O0@#{LcO7bARxlcki|58gq={hGW>vMEXrn5Q zDshF)+Bs~--(Q%Jsx2O3o6cqYtrz4bG|6_6mZUYE`A`U@w$CN)zdAAK=S=aPRYm-F z@|oLgTS8}P6*Id*T=(^XF!je;(fg)>m^g<#_LW~a-h*=e2_gV)K3nmTy1z3X!1%UZ z+|3*d;-iWnOy>jJ8t8&OZdJqj38P+Kn>?b#Fl-~e%TxaUJV_na*Oc^u(m*(^ zo52NtHoyX$3$NC_W&@M#@Ub&_hq}*@{K@GdEwncg8-!=_&NYgt{lFA%)kUz`PJN}N zLX!Aw+ekiYuL5eXT?SQlf7sQ%|Lfm#7{GbhpQVmGR+?3)qEHW zJ0|wxT3-DYrZkV1v8|ko)zLcA2bLK)u}cT-&~Yox?Slh2FXAi-F?O(K*l{K|b|~5l zp5Ug?TOtJ=yf!)={Owk3`?;h)+h?G%O2@v+db6 zCE~Y)#KFvxZ0=*O4vwD@2*;JKvh)Wk)TQMG!Ctc@SrL@+p}R~~&Iv9dSrO%K+QQo_ ztJ$x%2Hc%@7gSm%bNeUu!=ESqo28faHpXq;f!r_2oFNoPo^`{R<=Z3wE7CV+Z9_;;v@WkW|o_7-2(w2qIGvvmT23U~C<%f}{Ldga8KHAH+vkrW9 zUR%84c8TV2MdI>k2{e+OiKf>bHe(=-*PApQL`H z21d7tL2rQtyRxYhy9Vls2dA3z{TC?WwwI>hXI90AIl1Cqtr|FB86~>TQ{E>kotW*D z`Ag(q{k1z5F10LTCYMQnc3c9hY44z4)DLS&3wmVTO*l@hc*i&6;pyWClGchEZ1{Z_ zwzz2WGp7*0_m(LX%qe0z#XY21A6JO)S;p|MiSOhWkqUQ;-!d^}#+O>g0q%jG9ro1!wh#CeeakhDQ{JGvv#p5<({NIsxQ*xGVfmYoc|O1&QQ9pG=XDw{p4 zkM!e}MDfi{JNbpLRB^v`0{mpB*aP~$e=&&zP9aVdkgkJW9)U1-@&^75c}IV3^n!(! z5zKHLJ%=gu?pPUe^M@PYVIz>8;UnjoV||7QK880)DnDyrJe{%QCGE`M>Oc$#{qGEa zPjm8t*m!6j`;;3OtwH{Q`Lu^hXNRVk;m)W2u;N{*Xtt%Fp!a@*%quwhvkI>4>j36W z8tl}iBe-Ky6MU=vz**4@@bf?x$lq>aS3FJ88**T~Plzb+mpVS`6%NWnm-5GRG%)bi ze3&(LEMr5=utX)omy#BrfB1XnT(M2{2L2&=zo+*M zhFbS(HsgyfehOX!Gf%A(E!|><--r*X)bk7XWTqMt)C>+!T)^(1`HdTT>Wb@cyyk-I z%`yJ72r{p}XEzRy#6`Cb!rUEt+>P9$!r#*dGJU(RhaSE=9|twjx~%>zF$4xLfx!0} zoYxQoTr+kq&5EyB=tWyJe&h!?SnF!!NSqKU zaV9<8m}ygA=@_?U@%F!$_?$*ny!m<+{MxjMS9-yu-+_c&X+%my_MkA(}IyyTeYFzJPT`^DZf z{Gn?%aVIXM!(QEJ7EQWVP*Xf4|D4F3+(&!xfAb;W!W%YpII&oDXg=XyOAZ;^Vdg~I zoe9O6y7x&;w(C2gS_n7czZqE zx^Wfctj^(Duj-&r>=NMPuCW{B#T~ZV8+Oc|EwS+=koY6oW!s+M6hCR<;`Y%X|2~r) zThoB4rT5^Q;}q_KXJ5Q|KN;52F5Y0JA%0ZIg7}4JCFj(?J@fdfwthhbBvvK-QfpVZuhM%x2ig&Xlb z=(}@4c|ZH{tVHT@V|BbI7&l0Ct z4dU0`Q^ldnLSfN{@61$*Sa$c8!1YU6k}&czeI;+nGxa>KoHVrdSXZ#9-p3M+I`CP7 zj`*o&uE_Td@vGHKAazi8$-GtMmyV2w!$L9ZOMB7FJVdsOe0f|0 zJA>UJ)x(mFulbEO>U!ef_JO<``8w7s52U{QiCT?Sa4R89G<~Zsp505ixj}x+ z<`KQ)YQZpktPl67t{}lz9M@9_raqu%T`M@zvo9M#`S+A=t6^G# zgoRlU%XjT6Fntv-nl_z!Pk7=ueP7Spg%D@Jn|OfvkxWtE7WX7muHlpcx8krqCO!t3 zTJV{jdqg_$8(VmmcR&(yNEx5qUkgIf7bbsi2qrm}(*3Buap*NY{8O9&>DA9T2ipI7 z;1Xy%naNHYnBtHp{%~V$sc1>iVxc&tSjLjIk0S4rItM;tBbHTv7}GPFpnTK^uE%XF z%J^&pslz9hwapT}`xL>)log`4SJd%zS%j<`sG+wyT8y3#&C|xPpNiydqiolmgQ{H2 zP9@Y@>;n2G)L)jah7aAHK|ZNLvb&`Q!|kuarX2(Lsx8`BJ31dU!$qvS${##&a<4LBZze_>}|m=^t3U%SbG{Rt=RO z^trp0M}$|S4Q1NMJi6a)8<+qu=IgN%Ct}5n3Wl#`ncPf~KHBY`2icQeGq1^%*W2e0 z=f+Q$OrP}|Uli+!*S${TFErCx`gagqIULIlgvv=rxJQehQJ2?czyk(ezD{xbJk zUCgpdfcq}HCHj*o+n5jxrvndiwNc9GQQ!qx=nbn#h*d>tnxS+S>%phl} zf?cKf$JPMw=%6F}|zByOdkik7?P$@CMC`NaJrmizcK? zT%?DdPZPmAHkX^dOozCO)J>*&o!w6+J~??Z?`Vce#^~9g(+}c|ojJ~F22t;46m@&G zq_Bly4S2uz18Dd*h5K}@4;lxhfN4NaVXBmvgPGhRr0UyBJc5nTeY0SMe5^A zA^k_FU@u=8<80EV#{Bu^;yup>`%MS{@N-E-FfJpI}aoUZm_J4cz|bK09{?wQW{ zOfHJDy}4W3;Y&QC1VB0pO`7@MtQ*VidYx6Y3j zKj|js}|b>!SUN+EoxE*`=Be2*N3Mx& z=uW;_w?r`3N)WZq)k0V5JFdLAp3kCAmai&4;QA<%Ip4CTzGHt#UTnZ!`J;zx=82&$ z`7^^7V(#e;gDt9c5~Dv#m@#b~MEv@~O09>YQp09g(Q&lV?4}-uZAyZrUC+7kgJ_p} zF&N%$$zq?L7~_*`#M96#6;-M(5-jSAW%KrlS{-yvqiz&iBW7J&i@|%ZL*TkrZf?01 zt}QKx+L+I*lJ3z#W>JtkB80CzuZDry3uHRUtbfLsM`x@@lqz?pSrNxnxxoD=A6TrT z3ULD*VfVBXlK6u)csBYPB=Rmi{-@i~PZ;m)^-V)xE@)z%>hk%3o z_y)0!2}X<#fZ*^NZYtdc)?MdiJ4Xv$>SD8^47=7Dk(>0ea6!2f987Bs^jE%cW_+p$1c;eI+A8f z$&W$YwZj8(dK~Qw#(rSxbXL#wtbrcw1{{?;2#a(6JFBPAH(fnE2{f1KGoa^rM0_YT zY{}v-j~amI#`wYlwMR@KkK%IMao}w;N)lN;3`=Use?A?#y*E^Fx%^=8`5VJ7-Wh@2 z{vLwU39C8pY+XFGJrsoXRb19=%KClthOd70?9sVlX#C0_ik2z!!3)*U@~t(r^>AaO zf5}U`Pe~Lnj66@AI#rw&nhe_-H?wIYiGOam8m3?E!)=(?E<`PJ1<6BsAv!@7QGF6r zJ2^3*LDpzb`-0Ooe%!Wfdz=|MA37huWj54pTBYC(2Wxvt8r+?waO$8~dt4Cs-`7R= zR~c}}CxJD2>f!cjt063M3U|PQcyz(@L9O-`OC;W!-SOn zEXXgh@<}kv-FuzYPSnS`UkhN=pD@Ys4}8p!iXN_WiV(0dguDT z6gr-W9*|dLESb`)7ISAb!RV$D{Ne{XDEFuc61B3}`m;*XZFdsH_8D&ccXK72rWp*& z_1c)3Gx^x}hJtBuj^x;IW86{{0PAaVx$oi1_`->Y-@^~Et38L|tw{Q2H8r^|S*?!~ z78k=wt!@&7r;gH`vE^cuee#gEO&9N#CxLv~Mz)W%g#}Z>U_xv^Ze#jDq0g!R&g6y5 z2cZ5K4``|!#Eb_H!<9)b9`*vfCM#`&B`kX{adohAy^zOMBPKCCsXA;rVE(UDpAUY0%6eddYQ*B>nNoul&~Y&s!Gron{2mu ztq*0}J)GgmsT#>nnr;3lWx$^1Hs*HF7PBstLV03+qqCAe?oLVuqn$6gkYT#$us;+k z1GCvpi4iWQcRc0NCefye3xy8P64_kcuB3uR)VCFNZvcC=w+8**UI$&nR?hC0CE7Y| zhg+XMvrNS<%vW0|-hXEl7m=urW5~yq8WPHDk5$9e(_L9V`tfg2?y4`lSEH$mV(C-xGp) z*WGjuObvs`WY2~Z2FB#i41h3;8g7q?8ZNu(1~HEL?8O^r^dg^_(Sg&Vg<*$<5bI`{ zC&c2gDL$D{Mx9@uB-5fOSCtk4jl*i05^1)g7h#b0D^qlWp5d+Z43EhB#93ykV@CZL z&>iQ`dN61FtK|<$@q@SlY6EeXHpph_Ukit$O8-OP!1OtO!eJrhj3Ep)r~aMYlw-0= zhMEKeRz~{mwpU@`<(tj*)fj+DTYTZg=tu1L{=qoCj{Kj6zLHe~h{>5wyVq{WW%{Y1 z&v+X+*>4pK&g&+97rIjH+TVdM-mHj*=i;GEuDhT?InDb$k|BTMUdc-n(pS~OAv3+2 z>!+xKin`L^#E7rt8q)nAPU_hT7s+Sn6VUHSmpxG7w}FTL>Cn-uE4=_$P4qmN1V zvfQv#NK(Um@h_ zYLDdPV~A06&=LZ4Ygq0{C+yu-1!vcUit2)#q^e3g#C%u+1d*@6EGrp8l7rZ7bv+Dj zih!_}lew$=`=Pgu2h3@a6Zp^6QRU|esyg>2KW;eTBJwI1CvD+oOjpFqYb?S1!UiTe z@ehX#jTWnJj^;ft8sW{|dEhXslkO&ZIFGu7#N$jFQ^+s6e?+Nft{*`*-LQ>$$l~-KM6kS}jI~)r59M)K4 zh^q%smLz+VXmHK~q2Or=Z?dtcU{AXVd2eUg8J;w*2A#e%L1b|&ck?UFLdUmL7ws4J zqs|>alpX>Xvm((&Wp$jOy#l)Hgz+ z0F`qMu-sxCIE=X>Q94fk=iQ|BxoY!=9JH}uO%W_<0LGKo@q#!4I%>QcxNC-}O`RYs zN)B(;_w14C|nY^@;gVI(`lTj{>seP#;0@Hb>T zt920rBBAft9Ik?NlIXaFa5e7@Q`0h~9)UT~8saVKqwR!W>S-qN5IC1O>T;#7ho82| zY-CUuHUzH}4^On`%llEk)!0M`dDLCF*Nx`n*(oq@#XgDA9%AW4Mnc&7L)_nNW$ZR_ z62!z3e@SA6^Jq>k3SZ-@XyAl1Z;+p`Oo_iROch7`vH^89Hzwxfr4vn)#pb;)@-6|Y z__Z_@+SwL%jJPz}XH%fFq#x&z`dtVz7r_ugUU+M)f#u|vTjo2G9VxQHfmi(D$-Kqf zmF2qFINlv@EV#mIt4(n2J|1S??`*tmse^a6XTr$?3Cwb-9_CSQ<+Fk>cbWDwlKzWf zw%=PeIeh@mFr5W26TVA|wpiiMPySFkegmh-E8{PNVX)xwb{4Y17_*jgFkb$PYubb& zAyG+5rh$BEp#E{29PspXVB<3=d!?HSO&SGU)O}5CQ4fJ0udlJwclEK{kbJhoqa>Qa zR;b>MyczS4aqc%XFg3;%^j2ju4W;9F>Bs}nIyISV?C6Qp2c*KWc|C>yzneMzbHPCU zg2Zis9{y@ify{~Z+zcaC+-klU4qn*J`f3qlZSQ^EqCF-qd~bW#K-qjLz_d;(R#uy^3A2z9H0*w@{XI&!joCDH8U_DYBcydpTVh z09=?ax4n-!jtyD}b^KelD8vkFlqP}UYIDiG)LQxmHN%RBqxk$E18{y>AvgtRuw(hX zrT%?ah!=N`=AVkmKR+!Lh6Q|O|LA>uwj&Z=n&e5;DTif7-6*D@7~pN7gbkW~Q+X!}Ma>qxdI5TQMUslIy=z5eHtSF3U4D>{6*C&hx8= z;GLnOZ}Xg_^0O+$+>b=i>Pvg@Ln$y@V<{`?qlYUtMuFC^DV+DEez@g`m(q;vRHy5*i&;H`bgcz~?iWok%yAi%L%m=U9 zPBwWGd4}Joz-1rP#)};^_a;R_=k(Xy;z(s&w`~%bd2V8hO|5XlHtPDka8UHAHDAab zb&UVl*;DwetBFJG9O2>wZ4&H8)5vK0RhoFxw%s7xThFvM(QM>tx7W@9FK^ofN$dq{UFe2N z4-bK#YLQ6ugc|OQA>ZStF#Z^wEnogdf`igDRu*G`yL$#e`cf5c#vVnCDWjYh&G7f^ z^odbF7KR60mQ;|h^7zXe@QK&r*TiU{vD$iw)e|$GzV!}{QIP!1yJ7Q11AI+0i7@jJ zSNc#LuPKfP!M%vB&U3^Oq_3vjlZtxps11{!*>8Atg5_^B!Tq~}-rWt;u z?gQcR2X>?Dkg!y2B7|E$>r>%*p%Ig-pk6AQWl;Jzhs$?RL-|Ty`2Oqx3;IPF z;Y7+c+?yuZeZc|8&`vh@6ypvX5I3fm9egNT#a3}`3R&6-Wsux<~a;ZOz{gdu$a?Jr}T_$dc zlM?^xtO|A8B<6H8Zbp>R>pOQp&X#;g_ zbfkh;=5%fVXyCi$OW=3pCpO`-1{&4R0*##Sl1%}Ys7Y+7tMAuyy#tl;_qO5C3wJOt z`c9qJ)fOw-NJQP{7Ygs^Dao{vOSG5oo1X)R!yTA;1!*rM)8JyyLQd?XiL?5ILe1Fg z?EL_J{C>hv!nC# z{mSKVMq82do?t3GZVr=WWJ)#r z9I)w5HMF#Zimvyg{@IhMaA{>Q3m!r{+}h>v!FL)Ld$J#1^6&!1QSw5mgF2d*kB54z zyAqSh4!C2#KXt;EaVv;1vSY+xkn=8Ko5TMiZx<&vI1K6G=%I&Y z8bGR9W9wI4{61wlC>OrrPWUV11;Z)uNWPT4{cC}X8tMKOeoz#`@`OH$$7EhUR<4QB z8qV-GT$L^J?k-&?P865N?BG);8RLMYLU`qRhXowa!(u)S_U5FB20m6ps2~pNx*{Gt z$tT%98HTGYXT94ka3kHL|K8H$#>~>i#UIB&=rHnE7;ED&(iZ-&hZGU>b96;ExZe56 zI3Hp{R_4Q?!hMamDC;!sY#Idrd&^BE9W`(JGMMu{mwlxU**JRdRyS@GMVy!`938w- zmXY~ptBJ=qP?w^QAzPGr80&7|fzH-1-0?&7eRr>bQ}u0ZgtZ&qHmW85PmyTr5;c7P zG8#f|g!7pNG&de!26wc5ncWzDbnc?=?EWg;{&$M_dyyC}t!-oaBUEwrh*1#nvr%#( z=MXmbZw79c7QbsY<><{f!INbk>=kKQ1Nh~zVvtWmS-L)2(yXG=T+OxVs-c##2b7H{ zWQiU2_;a{FyzL_NQhSZi#ad)MZO0dOIB;AgJXh?&eZR^CL4G_6M)@ ziWa{&e87Eub4W``;T)LGQ6Jce->JvH#^SO>6T$;@+E&LrRWvnce9V)HSs_ayRb{U8mwWiJaVq4VSjX?h>pUCzw0 zz>;iw4zG0M4cn;?omSu}m9v;-M;+d;xeFOTD!D9ob$l9M2$sESn9~IpEEEnx8>Mx} zv|baYJsbj)TjYhRL|v3mSOJs&DzWHv%9wAa?!sBqI1Anw)ePss@R}E_aQ#qRu1ep9 zFeeH2ti>ST+i<&eG_Pk)eIipfz>DZCcJ!|T%2h_dsjJ^v#s*y+x_t%gxtA}wvx1mH zX#sG|JBNEn{)hVPG4R5wiUn!eV?zUFhp%39y`0QT8`PJI@4q#M{l_)Y{pAMuo7&a* z?360LJQ*X)Fc#6wnIc*VFPjv(lvooX%RgLpK8uHIU{|U)Y)`Ugbv^8HYz6tsMnrIt zWr}FK!Wvej)Uh}9_E?d7i2Q_MqCeKdqpt^1J%n}&q4Wk5cb+Lbf| z`*Jr<_rnX1y@6oCf{6AkqKr1syMGa5H>gz@vmr>Tg%M>bEiZ$l!GrxAQOST4Rd@COkBK9@Dj?=|{(JP?;(L8q6Ne`O_ z2EfUrjUvX8g<*TV$jv|LWE z=3ci^FW9#K|9$gWTjNl)^B^|V8Wd$ss1fEy-;(+C0zTC*(O?mlE7Gl^_u_T{#w}rewhzS|6Y{R?wdCsP{=QS{ z21VCDFrzh2IAi)@m?Adft{YVg`y7pB`o@eLGgLmA4H}Ar*+QD}il;?Gw+nfk;VpH% zH+2r|*!h&be{PB=TNc5#fJu^sprKgTNR$@<&z2YJX}|AlmIaL$>LgBYbqPfp4aS%1xGg%=cl_8FDtkAu1Y2{=&?1ga za=PoeSwm5obb~ADiu|1}RqVdo9-=mnWvM%yrTt5fh}~Kh;L9^rjGeX?_Iht;Pj-J1 z-ml?cWV5_*^B1u%M$Cqi#!*be$Q(^{=pON9A@?+n&PktfAi8yxSOO>CMwr?v6+i5y6cNM;`E$?r$Lg3v#o+4LPccxwpVW%T|@E(|coYs4_W zJbpbF8K;al7LS7c6LvCtVpwI25W~3eHrK`3`NG$}%Chc*id{N5`D`xOjCW+KXl6)A ziGakw8*K4e9W0_*=#yonWHX_F1_zT%0ZE=Ki0oTjB z2UgtrZ%*!4Nc^SjeA28gNj6PUMW53_u{o@1!9!&p zywjuw?Vl12y98y{Gn{y^#{*#EkEvW_IcdcSbKz*rb9Typ2=*a8O{K+Al9~Dkzs%GT z-&bDCUm*YOs-+vCn-87CEeiN|Vier`{exA}oP2P5G_0#HkX(!;FVHFSnds$kNgtGO z!hx~yf=WPI9}dA&ln7)12j~-@!4^4R)gu+xGS-ZtM318rHURH>e-S#(fufHh*IwUtOuQ?+`4I z6o?+QsiLELJn(NK`CkpX*nBn`mLHzMg4a@C>O~_ciHB7dGQ1)4}kupT*ZpV=pag@#W zCx+O~7!VE26YcROkD^Kt^ns7uK6f=-ILQn2&IB=wz#%wtC}klzOYUF33I35A1M0gz zvXI&Kc&ecm)bb5DQTHmrG3CE=`0Ga#^jb;h@S;J??mHy6@o zJY!M&&Csuyx(Sv{k(ewPf|jEKz+{(%liRC}+sRMp(R(ecy4;T85wT*gAP0W@Y(;Fe zryk+7o`N~~SgIaof!UnHk~3Z8@mm)Q3NH?GixPA&doA^Y@E4eM_koyYPPbTgn(uY#5L`z+|6ByS-x zKz^)H$EJ;Q!G4+x^Sy0`6KVd88@G`AOnjBPH`HrZ@TW2F>M*Ha#4&MI=Q6lSUatts z{ueM=`2lrx+eIZC~9mJ30_1tvgGCd9%0cnfU+2esf@J)uMSXC*Hi;I-QO2ahSJdC9ILuWoj)zb5} zT@}|V5qn(y06XPP|J^+Z+9ODpFdB&5O=9f(bmOl!t6=N}SIXr2va|6=u|w}E9B!%M zboJG-fPDC=-gPY9XcWfVRl&EuR$OuV6~VY-sBHK5k!J5@iLsD-ScSb9MgI0dLDXe1 zjcboGK*!j*z(0S+rYhKBPj!E2iE)&4-uO+O*Sg}d?rV7~C2bseZxcKmn#VFT`$)%X zCW)!5m%m6E0sqwH;CZZ_?Y~TZmBU^|e31@Nlm7z9NnvZU^}@kFfKfhoaiUTHy9Xh@PF%LA;s{ zQ71#$J9@tcNaMg`=uGb2?!Kr#(Fe{`hxi^}6`Zf{3F?Y>B-(-fG=uK?T*?!VrN!jARNm=~2o&#{g{w!GV<11@)b;6wo%HY~FzEOER_0JZ^LBh}X zT=YcZrC**7=~K$s0m@TsJK_&p^(saG`sWIK%W>I`ubR3e=e}}*@+HLQF&HMjrgBU? z!SO90L5x$aw^?v>+7-(9nW6{O8)Do&2(DczNsd@;H=PL=f@FKW+{cu?B`(na zwTSiSb+96BJaoLhEV*#H7Pn8n50Pv1_{lmtc;dGk*6J6kq@D0y&(E>ty(au`R}|t$Ju()Jlk~Qq0=;9bZY|5z-O1h%4MIpFE7=wy>s0{DS2(j>9@GnSezthd%?Q50 zSrZpbS`L@4HM78C9h}}41aB8FlblR7MFTo-)yLFxLaqYtT{Dt2v2^AY_Z<&AXo@$~wGI6ZVVirlj!Se=DG8B57-*ez6s|NUysV569OO zNun0(;y;U}V81SxEAOCu`l0c#BjymhINTO{>?B``%2n6iG`GCqwt~G)PsyN__pMuo|HkU#Um+;yUr>y&WIlR)SjRLIZ& zrh!AgE`*ftuWl5B(zaHn*QtgM*PTJ3u1dmnQ^xWhh0u}z zm%ZrYjOQQi2m7mM8_Q2ROaG48CVtQQfuxx{50~S?az!D_AkB7D=u*(&N=04UW(sAO zHpz5`#^IW1HEt|alBXr$)Niy>(-Y4(wC4ZlYoh~fhO5>unMue=1QlK|E>5l}R8v zd4esi*TV-R65wv%0@1QmJ^XwxSe6I0m_j++n-jt5WC;5(!WPqLZyQr%!RZY#LW9@t zu*K>Fo3-mF+UKqk*N=M4^?tfvupMJ8JBL$;8)5S7Y^W}>V(|{-i#wPAW~qhTwm+)) zDR-W1)~$L<-UG@4kGGy8f#){FJ`DiXgNY%CPQs|a`iAnd9uiKTr#iePk zA1~Wr7ybE3u>#NSR>kp3&am{b2h*J4BekixDVDA_1HEl(csYtPYaYAU%^Ux)ujWGW z%)k#^SZwrv^e&4UZH{x} zC%~Ibc}YR3kMw2NO>w?kHYmQ)!s|)-@Mcsh6YCM*drhcJf0(PMiO1CFyXM>_sVOo+ zCyxN=9ACtp*iT&RlOpgS-@>2;KT#0rh%=v^67AZPBUryu1~X#QJ)EtB68%DmN*KmI z`TR!RBXh+5vm^O}Iht5Nd*P`gZ?R_7!TeuKq2%jw$(`jU7)Ojs-#4q25(quckf>HYTre!?{zSkww*UJcH}uppVVJ=fQWM=j`8R zYusc-ntX|aB-e5{PO$L@lS^m0J|TLD-O3?k$$B<@ECFSco*JTRS}o$jDd`| zzuA$Oqz^wyfX1ckC9_r$pO!o)^XBJqqdzKPxRDnad(^OSeH*N9@rQ+VS6siR4o7S9 z6?FC2=iL`uVIFCTuuE04g#I1=tXK_8%Zph$`7=#!CPG$J#382fEMp% z>^be)gtkO@|7bQRm)aW_IQf8Ap*(RzDUZKrJanzTCHXSa23!C5L-qYquAF}6IPxG} zc~Qz9H1w9vdXzB>t5Mg2rdAvxf@q zw3q|?8n-fCGZSp+76APc4v4;O&K7QOIU&;`j?bYS=p9E`>#xM*K2DJSI(SnoSoDP8 zzk_i0gY8h)_@0doRK#6(0%4?DA%BK=3(+%Z_ffHy^)ffXm>vPtFQ&_lbe8`N z?EYjmzkM8a1SBWI+BMS}LTK-{dQvEy?pw$8|E7$o>%F0Ea}gW$+#0>t`NO}1OyoMM zN|<@=j%2b-nl+{qP&I6G*JjK9%&_ZN=NP8MHmc+Po#+9&L4Fotg% z<%P+_WqNLz1%#`19qAkY_rEQgMS95Hd5}`)DRH6xniKN^ zz?pC4E*vL8<&`Up{I-^5jr@tr zcCX(A>1XR^@#LLmAR4KT)#N2GR^G!3v%5*B_Vp7N^!?1qnZFm-se{b_rZQ3uuU=R{ zOkh{GG0hlF{i(OE`vNYb)e_^#*B7?v74!8aPNo9!ZIs&^8@;sghh`zniAZBxI@&So z|J(_%=X3X}ynFl*Bf)@RKCJWJYmc|n(?kiO9>vxu8=MH#av@Zf%Q4?A(% z8JimY!0$(Y3e9H=t-VxaTJg*0npoGB5B?G-HhpOaHr$va{?{#%pX8;9=EOUiJ?AzX z-lT*3?uEee87n0nHZ%kH2Ed|aM>sF)dPoWa@H>^shSSeKq2dqSm);V2F8C)@5-acj zyS$cpS&QW`{FO(&;mr=5XtFx?P~HUTfk#&;Fbtg^(#&~Ik6*aN z3g0$YLEocll90-t(s4$s#Rkutc*i1DyieX;rP30nL1*u}+pD2wmKwM6fPv78|DEB{ zy)|%5+f?w#7{V0ktS(lkd(GNV&e~WBFHLg*Go@opv(u8Et11{BzC`3sTKCTV8Sv9$ z8LK~`hwTQ*aA*Ep?(vUaIH=7BT2ILfDwMU1RhSMV)SpYL=y&$&@P}DZrQAscB@A$J zfZ0bkv)dPYO3k#h#L~bFK9TgOK?m2v;CEZ zRB-qDd9d85oMmYk<9r8Vp$t19diXs{@X8nS1@p|rMIQf04!vW>OZfFrLdy(?-M4tsqu;%cA!U!}SxZ;eRBZbyyYc7R5;ck?xcfQ4kd{P|nOA zQN%#NLc}J-R??zFBm@OP5EKwZLhM4$JNsDJt=OHPgFpZkUp;3PkYZ}#Wkd9I@)FB>r_M%dSyz?+d~W!RJeFP=_pb{%ep z8w?h~XzE4!E!D!A7srC4^#=BqvL3z2mp;&qNzz&y#He#^ogD$|(=91;R|UZrzDe&K z(Zy*uli*9mQTBiS`Ee`i@;I0;*;-|W!8O!_bNVCKN}gw};eN1RZ$4`Y?S;48LO?Fj zo(syiKxN9R{GY|4T-XyksbK zqz>D_DV#9CfEs$=Z@*-enn6t^;%4{slMemb3#Wf29)>gYNi?G#2;J>D-583w-)9 z0Q%3r$%ZsJ;P$WpXz)~#HmMq;Hl61~W~Z>TU%%nZ1yhBLxPJUkUJs*3FN34*U)a_L z1AL!IJ1>(z(u51$QU5{+gy!aRFM4XDpaZbcXFGFR=8j$K=fKPB>XMFWYsDH9?M}a3 zOS%E>eYK8Qrf#fj;5VFAA1rK&Ucz6QN50eOMf! zT#&N~-aR_VdXA-xXEdGRe|mC{9-Iv!Qgxs;eyqca@2juh|gk(pP#$&YjK^+O@fy;C?7rU}$O;9M>sNwlM+XZuqj#q~5rP8>rGx2xANyeu?CX}tEi%=@mid%p8oq}K%n{3I zk6_h$*0acf`p$0A%sk1AmnRl$m;DW3pQa;)?(VX60Xv1ev6@h_QU@)`qdsqG5xYh? ztT)<8aBqqp7yZ#(^iEvXsZq0J1H86lG7Rt2pVi)T#H~F;;lQ8y+lh&!-hF`V+sGzim}Ul?*+6??#mvr`y!|n0lEacf_Fx)!XKoiPY8(fd zFO|eTKecf6&T+8t@@?s1`u9s{em+8>hTOU#EsEr~lxZZv#`bp3x0?=bwU`Od3%0VW$1QP#QYaMH?T|c> zt`&bcHFtWOSCOZ>Nyigr-q&YoE$T9sLFf6zgZ!9@7U;3C2u7LTV=t&@JYr`PT>nug zS?8>d^Dl>i;nF<*i6XK7zApqWErZ#-vBVK{FCLm=!ey)Lq0fvF@N(>1W)^TeHQZ1Dl#RvYI2zzx?Hkl)pM1!s1+JF&=WApG2C=Jml1 zC)w|WC988Kf&%SURwTlIy3xG%VB!lMpyzY*bo$?z;<->_di2ugob=SuW%EeDZ=ac= zu`&LoUGR{o^U|k--LU-F9QeItD;M>GvNiz~aPp@=vm@S@^6wZSxFdmgT}^$#?-Rkt zYjX33rNsSnUIJ-W`?zUmv@j)N99X^Hz-G*K#IUs?5WPz(8FIE>TyJ)(b8k55JLxuy zDnYC8i!@46Nw&-)UMT9aoqtC=5$Avuh?*;9U;dimj;ToycwxPykp8}Y%a_0~!_VBK zARY9q_XlNz1?(a?;><~;5BIX?mOV7bWEjzTwws*qfjw(>f>XK)XXU?L>~@d(ur!p# z#CUV`@XdyuEj^ig3UP+>lVHM_0#44`0CQ7zFmclG&=`YO;lXdBUFbvAkE18XkX_3gsGI#08|)Sh{AxM%6vim{{_I z6(qr}(!-qWmkAn~FNSR40^9S-0@a>|z~<;=PkDPsj2#{d#u@7T`*3ZXH)S9s7Wyy` zw^6cLFRu!>>uurj3O(F(HWv~yYuUS5aS)N&4C)K(=DWUEx7<9(d#! zl6N;B?o_3)1$L@3xA{@Rd4=J8sfR8)eU5}LTD`Tf}niKV~ zKy?yW*0iy_i^TM}I2GzzdP&dAyP+Rt;pe_R&K+K6j*jEE!H|tbtfR|c+!+-sOo<-C zUnD;BGyQn@@8e$c#w0NAu~B;V6fp;$FX`;zy~t@{cT+!b^V`cb*Yre#cJfpV zIqO+)$rYO@qon=Zl&?}EugjKl*tSGjS~9VJ=+Lu-XO>(}t_=WF2u$1KRN zXlElTEYYJP7j)!ZTK>CDIo1Kmu(;wAXF6O5159RvZfynIu+sudb%?L!w?i^dmMQMB zZRVF%DvJk{jd9ar0NG0;w(^sjEcIEQ5Y8Ro|C?=&0n#Ff?01iO{}8a%w+ViYu9GPF zcf~ZzaHyV~$6qGB&f~;lc*(C}N3L7o%2CuC)!&3`DAPvkC@*kW{F)u3y+dN+aM0L# zM7m&w7Vh4=k@|WR#Te3&j%pUbpkDPYXI%%#^sZJ3U9vSnUm(rxKoX?76*6}n;%o#i zg$$K4iTRufqRa4-PW}9xi3aXzQmRb;_l^?t)8}=yHQWs|L96+-uI6AWV>R` zz@2b+Y_23KjdED(NuaxzVA6Ci3#NRo-r$+cSb;LRu$25Q`rPB;>KHVB6pTsu%G~wz z(ZIn6&b?`s#yPlR(w8~J4BW~sI!8U8ZQEg3_aOFIh0dJlIN@eyA|G8&`nF;+)KvvG z-<@uT7cMV_mEZSq>ebYF(dY*!mlv=L^8PU-ykWvPBX*WWpKCl3pZ+oHvW9< z50g*NXF)xCqW)rHfLycV&e)pcwT2Pk-1Hy&R%VA6{x-t7CS$H~V~waBL8D0>&!8nJg8P7)Nb8HJPwIFw zynlX#`}x)cdwr!&x9Jzzz{M8$=MUu_WXYc2^m?LdACLs=DN76wuG^v9ChOuoA*?x*LZ>CSQ~oTdNH z8;CnSaW8j{GAXmGMu8`>2((=K6Qd~v7RXwZm zsy>)J zsD(U5j#tij?%B~Fvo+~EzSWc;Y;J?Ap4LNLkhb*uMt9lKv%3Y=)7o%+uMXa{OYO`j z)*L5xlSc~l?Qg)X?QSkU`4YwZM5%~Aje4l&5eSkq{iw6p0W*9<;ph8#+|{$xovk|% z*vupBZ3^Xc0~)}rEmShkdVtJl{2pQVi#1?IXP3*IwUBx$l3g<~$GOQVkac<{SASax z7tt;?_=1vn<^l2TJ?Jju_gw|0VW@(xKDr-oa3 zVu70H@uSFlZ2D;_tmvJ|ywc4vq)#aPI%>?hNGSXKeiRg@wzGAj8R|EAL#+K#X>K(A zT`Y=$3sn*myAvny+Xgsww64Yax0`H_-8SLv8cjGy-X7m8$*`rzMmEUY3>9WX!nPk} zlI(Ni#SG2TPLJO~%7=>m_|7x@V(`3^gWyrNTsiWVi(eP>8H@44P7bkNg z;ql5-QfJTpI6ox>_84yEo-VUM`%g76zc7#mXv@ito?Ib}i%;Ss$ro)xS)^l{LCt+? z$Rj;43alp`;Dk3?`07XiB&;iBrM(>R$qmx3zqCmF7uJa@5^i_0L2O@GA=_LBU9#oa z@}UZ{^C}6Qb9baTWiw}~M}71o zhQN_~Da_`x3jQ)rgC4KQ?>Cs3JP)#9=)yhHYTA+cQD4v1FU_1C`O03AUaeDpiETGE z#)SRT;s5>VNh2IkpY~9<9(3hxW*OqXvphiG@oc8|NZGJy*E(nQebf(iBrqR(^r&Y$ zW~s@Z_ggMp2vXpe=)Mr+>jh|iuOu!a2AcPoWnepH46~nOj^BS$|JVIsZb%NY^r-&EEwqKhp4LZtAws~6uAtBJ$9ErC4|?d&-D zh{9qcfq$UPY-6dHjeH1ucI9zaBeZc8%_M6t?qK1${cuXv9JpWCRWi0VLp*Az)42n6 zi!s57_#!xQX(;PD!2my|u7+dnx0nYpi+Uf8gv-7wrQc4OVZq^0aO<|0lagn^W5{TD zGJG8ixj~&EBk0{9dsU)u^Ihz-``@`;HNhFn&FaCR?X5I}qs}8@8}?nli+vz{`)_y@ zXbqP44E<(?>3?Y+PX5iE9ZvgArO~iy>P$A@z8`8f(Ej~*U#^=Wd9-GggSPZ23x9G< zY}0b>+;zU9_wLE16gc2*#9BxTO+6U}Hs_{sOS5&TYiSZJ7~IAJ##!Ol-@)+uR4-|W zUOzld_hsjpV_cjo}L=P&%PCL-|uJ=TVN0jo>I;>zfqEf^~x2@ zld|~r=QOePTQ(#-{Y1UD#2hC7yjP@4i!1ptZmtOhzu8snS*#f*4I|d$_F9QS@fz{a z=%akyN$R2{e#Pw=FOZKkVXul*WNym&!r}A#d9|<}cw*Q#XfArk@=83>jkNa(2e(Vo zY*g_o&DFo9>-h9RltaWw>IThZ>%+}(QSVT=H`|z7MOm1y`^P|p`X}~ILK&a1kzhCJ zsI;B9g{HonpzC1Dc6k`0{@4Ogy;0XP{XaL^&zaT2&Oj}wAT6bPOA3s8xshf?>WCQ{ z4VQ0~OZFHAh%qlqI<*vI(k*`k_(G_MJ)8NWFMgX!`;D-EibNo6Xe$r^(e|;CyUedtLyo-2ifF){Vx;!14km zc-5f^Y^w%vfeBB=;qJpavoPRfibMNF!-e%@*%IJ+BzQpE8!%<-j??DpO$A>Gi6haSW$_F4*qrS0rWE$w2oVnFv; z7p6vkqG z;M?4ESb46L^<7{hzKV4mF%Y!E$R67we#fm->5v*P<<~FhO3{dOb_H{A&&0c1#mX2Is=>&0m;_jX8e$ zz7G0sacOz5Mh6GJ2q*1y8#5YiiaKMd8+}-fwP9I>(Vj~>?-3y-0HDOCv zD9TKJz=}MFB45x5v6b5;RcF%q2PKqC{;p^qc>InUh|flkE+2<(s897Sgt;{l#CaOFJ1Ib>8Gf z>=+Aw)9jdOqYJjt?xuKREa$q@5)TH}Lviv?7Cyc|9;w+4=(Vus)+u(r(gx=Z z%7PoaH%pGX&|T(X9MsPI$r*U)V~u|>*d2;y@8~!8?hAn{qAj<%zycS49RuaI?X0+j zJfAtcK+naLGx$^~`ncG_m%hp(_lLN|d3mrR(}}!BzbPLPC|LH3;cF`m@P0OBcptrI zs&%w4TO10m4ZhOSVmnl;4~3MfBV6-f4eVGo2zLHSWbrA=cGbhL+^Of==iSuFeM$FkxYISb6@7`=OtS><+^ZT zzb(vfB^HNO0kju2GHcmTjMi%cQ;z}M#_A`c>33pw87PY{W|*S?gjksH-j`X9HpPe8 zVF2HQxwEe=@LqB-jC^;GJ=jaV7_+H6K2uxzYMuqk-7bT#D|6V1b4s#FkugGo&2V0a zdPu_tMM9y+CuVh+GAzGhA!UsUE1pKo3TYU4pULCw_G{s2=}1TkuV?SF`e4H_$}A{% zm4x(66Wi2vz-+gYn3iIMh5d_Rj*2JySg0y1d%jv&qLRr!O*h14v|lcpc%Knu2?saD z(vCY`dU^_FGj+q^5x-1*740b|I zyGD3%^}TdPh^j1l?P?)=dIN7n?1Gl`6)>fC4;yote6wkBAb(ZClQo!PU2ZsJs&sJe za+GPR84DiPvza=1;J>zpK!{ae&Mnvm&F}1j2YOdn#{NHeoVJHN zdnq!`@svJRYE?p6dI1ZgewOq1iDmJ52>*q6&Z+BDs7pvu{7!R%zu`LAv}l_&yN4Mr z(_9XiT)=5Y5Mz1wB>2D`WY5mnqBqU4K~qnAmc8tQQqp60MVRo0^_E!n|Ne_eZE2kE z0GXNfL81RtefVgoiw&(AaOC}FR##*q+T_M`Y8P71b#e9Uf9LaQWjowKder?X5!|R? zYn*bt3DW%|B>x2)V^CQR?AM87iHpAD)lrj#Ib8?vd#@`{2VX#^<{V9&!{7iqlMlR+ z{(VUqF*-}1PN9C}7%fbEG6aUiZDn2Vkq>Hmws3ZICV%y_CjQ+-jH7~Y?Dx?Dc%Qsv z0hfGRKAhCSXoYz&@@6&LKr{9>!*F=re+S)tGQ@@IEuA`ZWS{}|E*b{+KN_)$TzT1< z?m2?~lwJJY#r7!gQUh|CAK1q(9=Pa51NB|jNUTpPqkd}`Ed7+r_nB*ockjl6Tv-;Y z2`65$LpW&vHs*Y2ZeMoG8#n`E9e=0(vd^QS+rbv;O6n#{RxRl~lNG1;Mg_YD*jaL- zrOnx0_9(Pgm>!`618FyXjpnPbS;cG>&8wfrEC+>CTP3o)eq#Hi&AiqzWie_jb$`T; zgYt3q>_B86tcoLtLt_lL%fS*?j%a{=D}ON~?Y@{w&)%4&>m+{G)NN{-3JRN-^Nyt^ z7?O|*yROb=<+M|4t6C1duNZTuW7VKFp{Nx0=Os2*YMEn6>I%4W?J!qQ9!uR#lOg90Wxp>gF;N+JAOL-EyiA43x(58v0LR< z=$E|~oT^GC1+L~ePPzh)H2>mG#u(#tj`m7_SF@X$w&+FgTEF?W+ye~@tZNzz6K1xv z(dj+Wc>O_e9&E*}7+)!>YSD~Ie2E^U`RjS*fxeCtyWi_K9#5GfWVgidJIMF$Lj3I{ zpLVuos3~529tJC}jFW<<9VRDH7gFF6PHLfn7MBLW3zH<~nEMy=U9yCl>oiY>D`SX! zdgnZBNHdS^^L4cQJ0QKY$QXC-j)J-Rmznk#%9H*Khry4MJteOwqesv4W!0{Hkd#>T z=3a2kaw4lz^pdrtTo)ow*uv41^j`8Dme*0cTBZX+I51yl|`> z+W1`daMAaO_$t zzwf&tDo#v+2@wxj37yZk4laii#}lMHWk%e;%>~bq`?#0@eT+8uhc~0wv&ja|czG^m zQVv{}d<*_4CiT$GZ4_*lcS%ut*O!8W63Ix-IhuD)O8+11hg$oy2J$IKn zqorvme3Ccequ!Wf>ZS&ms;DhpNxC<$kO{S2%bE5uIoV%j^7C)~%?*|}6kSd(<3H;v zizAQeV&B+lU=ixZaxdE8{!Ho@xH6X;anlkmae@hp4V9C149XGy zI_=_}>AR!jL-!QP2lhC5Floq*@FsY>#OZ(%Iy?&ly+gTtL!2p|ky`}MJDM}UNW1A7^-#%vFrAGqcw1o)oU+K1m@U-6U7J(EN`D3K_nJJA6&awl zFPyDOqFrj^N_c+Igd4bA9Y@6mfXA#3)~0EMPrproHq|TAHgLx5st^c{E$8wt8=>Cs z8YmeunYDjbmG!u_R>%#>b?!~pOVo--IsLfOskM*Y9M+D8%dwMgskRN!+C`bs)iQ(T;u0MHrB*-#8vh7k6 z{7KJ=lCr-vZh#F6=jeSodzjn0gm{nc9&mVd5X=P`F+O4Ex99H8?*J@$W90^=+ zAIk;?gRI!`hLCrTbQZdw&Z^xA${(88yo|xPR;P)2f84n)Cm)LZ;eY40RWfDv*Q|up zG=KJiW|Ev?^Wa^~3~mwm`d*HiK_1-)%(ROWs`8X~tJjjQ%Lkc9{0*TrA&a;<|L0ki z!?&k7EV5i)mUB2tcrHJTuQby@Rg+k-G5X5v$)7yIU==v^Qe(NXrpS`#!Ir4?Tr_3h zEEbOjhbs;2v9c3>nLsnPpPJ;r+7xlMs&1#YJn*hL<}BU{KXXU0MJ5U|m2NS@&5^16 zL~SEfUYQE2ZyvG1@uoOTZWWw5nJCrVVv07V^I>G_ey)@>9BlQ6XW{Fax{?znY^U$? z?8}m!`#*@5Woez>kAPhc*p^%mdz;@#-;Y+4`CdyB9PTvn_h;$g=Rff<$Yeizeu27Q zQ&vI8BqdKR`h8pa{a;Ogxl>FBuPcn}Ji~Pqov?om&G0%d+;r-(QcT+ofqkwp82t;c zBqs``>7Th3@|fz4$OV}n59uS z)A`ZU;LsRHY1Z%Fm`>W=;t=E(m+Ir{pW9&i{*A1U^HGc zf_=t(1ntD{O=^VKVf2kw_m!<_xgtb%?*%zSbTQF;EqR-_uubW5GP6aqgp7S1+>mVs z;vB;$UP_+fZgigC?=b@^r?|6;@z$6@KB5l&xm*BwiavS;z}`Vu+2~=GShuGMEaK)$ zKAbhe1#8#AkX0+#fSMmT^h1y^Y4Biv<3f2nWicKWt1F9IGz%$))Ax~P?^jjU_`Dz# z>W^>aB)hb*{V(yZC6!D;`!~*boh59TyN0(U|MTvs^$@Z77vmk=@KsP9gl+R}Vb@({ z(+`vhE1Pv->2tc{|6T|`UTtRqA;iHD=TWq%UUF(*n)u^IOQ&ah>uCdAWabSwW7Tlzo0iM3ucKY|$W`!d zc@8rs-d({P`hBS>H!w{TZ!H)FLtnpTe+?5DCtGe%b|%6q9X8J?X5qxtx}3inOfFVRD$9Mv0S0BAvv;F`5#HW72?{KGv0HC@ z_tjjVYHA zr;b;&C&0CXe^}gW4b-BJzuRL@O4oepjc&C2_$6P?jY%`a0MqTTL47h?ZLK0x8L(Ec zO32|SeHo4eOB>v%cKD5d;@Fz zaFJ%48HYLZ%iVCK+)${CNM?_1f8xR2S%T34FMi5f1zbvc{{QpoQG<-p>u4Sr?>r!l zkaLqA-(4>BHh##vl~eZoeGI%lahdf?HN`Ts1&}o>)iXiS8VAyMAu~daA39eHmt=6T zW`{5P_JWgXFT2q>d&_6*;qqHW@Ve`6mQ_6%n~QcqP3r(|XZQngRM+8fMd4qEZ}Ixo z)U_AD$~Vz`GJZiPm&w}30xwUV3G*!BKMIY9lXhL%hjnysow}ft(R3<7 z3)Mc4f%E$snb((IC|ymy9UV1EFaKom(N~>LpY|Pf>e2qZ6<$6Z!M4(U)>JN5V0o$h z!kI=WZA}Bo!6&Q>ovR;=;{gkkq%#?DW#y;`mKb`?wmNvCggU>n^Vrf?y|DW+VitY9 zB(WqG%9HzPuxhKaxW~c*>oqIkV!#9G+Y(io+@NG3Om7#zy+j8O>`a8Gix03Hs+6lb zNqJjP_N4a^SN>f9ql)GDF86hCXtf`FJu-*+exwWw`Oi;bAFlfjW31|^gQY#ru(yVe zICkz%P}pJ5z15S7UHZ9$wyUx@k+K!0-`B#=Cl<_N6z#jv^z;J(0`x$tHi4@Lhez8K5kf112bthtGoLZUAM*yLbinGLP=+9O$Yp= zEItXbKxfk|D0x;cbz4pSBk2h+dQK5{jovAblfhtY*UZNLpsc~yS)gxv!jlE`rrICc z+fFm)=YJ=!#pNcr#OX@I+;p*UIx+KIwlZJY58TuoETnz<#=R>s5-seO^C$kOh^Ln5 zVukliP<-IdrY^BUmDQoJyEdG&rXHDGANrkwa7l7kVs}5zhX9*+c5(f8oY^#0NKP8e zd+(6LEsMu@=Gk}D8DQd|Q0SxnRvMFSg@da@p)PtOr+Y^W$7S>2>rlnwZvQ~xZI+NQ za1Ea`LJN&sH^7b+9qdd8b-|xm57$_~md4kvvd8jU1hwtDknw=_zlRos;<;Kji@Z{+ ze$un&*Fb&cX`)J`v{N(rQb;{w14lxbzbU(|`v?6-_7C>3@cxg$P73z_8?f2>smrdN!>oEe{I+4ysnEXKPq%5Ip zkQd**n*Q$Mzq49@z7_WPuNb<#5T!+iMp!W_4u+k%!hTaKUMH{eWE?(+d;Z=RkEAE$Oph`nz~n zfX4B4OzxGOZ1VAFA$7qpe*Jw7TzPB-s5<>%%JtL@cR2x6?sR4DLy23<7Q$k~0#5h7 z7Jh0S3(@0uGP_~DaLv;>u)0cBVm>BGeArj_A8VTY9ww_Q;Cg>=7U)D7s~K^Ej#e69 zd4~3J8u`#L_bc0V#uTOf62X2&vXs9$`b>}tM)`Pv`878_p z-~xr6pe%3CUAcHvtV{cMCjZjxjWNJ9(HmoL~H5#?8yD&4>Id%gD=N5hhu^#|V4f%!jz5)$C6%HQB)>QG$lN zFMn7=4)2;wfJf%aVzIvo4k%jy3vE722f22~hx3T>)n3RIywJiXWdZK|sA6}*$R{wg z5csUWY=a&3DSK>y%+LK=GQZHySGE*f9_(NpbPu}pY7v-CXq4zgq>48#N;~J|Y4Z)x zA=(Gt+&5)rv{wpPn=4q#?dFS}yW_U))eva=jwPzNVGsRAxV@!XGHHiA4k4afd`AvH z?k?@7`9z50*0Cyj24d+M7*=i0NiJyOu`^>~>fsM;GO>4_`Huwu(TAml3)RqfHu>rq z&B?=!k&i8hUiJH0%(HdzGI8mHPH$k9#M21)oCsF0wn=oaj23Z3S?AfC;%SHpNrCX| zN-tJl>WB*(Ltv4A6gTQN^?&8n!JGNtSe$(iG@cb@UuN8S0P7iIO&Llxy~b>>1~z4Wc9ZJs^(6+%j$yZ-C3iT5wMeWbd+- zWop0I3J)&l@TX0jusm=RjE`8^yx*7J{m3M6ijZ=%r)uM-*6A?0u#~yKu*69n#J9h8 zL~^`hn|Sxzz0NsVb7@bsij=~lR~qcyG<8|ITE3vSznQlm?ufQWD?wM`B{PctgR_s! z7GfG!ajz=O@$bPT(sJc_!y&|rP+kP52B)w;^!u^&PFa1o<`xP1c=4$>L|eUN^3^@@ z@ofgJLwj(U9%bUk0=v$=;oAlJIAQfV;v+dSX#9#w--CrqL2-OBF?ji7G4NvfXEs8Q zcn;qdLBsh8(oouITD%X1E*lPU9twK6q6aY#7iF@n;a_n`k8I&rix+RCB#*p#MrS@f z;8%C_K2idDg)(XD2sfEpZiV3M`Ghx)HAJyw1+;fuWv|KiRqXu@{?44pY-#3P+mF0(8|QHHal%r&H2zh%HTICphuWK8mcY_P4O4#ow&mKqFHl)Z|H7yd@n^Gm2R zV#wWOC^>hCT_^9;u~d3~UUl)zZ>N5-FH4}wL4nurt%GZi(O&Fb2e;4S<>eWpUAXI!hO4gY$b!wq>dfuS^ zuhwwRX{!OA-!&Huc06ZJv{SzDaSp7vbC$M7&@>zK6EwWHByA;O#`p=G-^D{ut=K(uG+`pSf zyFm6fTw-|K5HtI(hsiCgnS7qAZ2Yun!F!f3pFHM|=s#jY=bo{avVni7FK@y6uhL^? zmS~U@3McCeIft`a*mv|WFxa|{%{})QXa3F?CO78rzB9-ZlD!e4cFKuW-;7WU+5ly( z{aV&oyUDVzR0!kh^ufYJ7h7LOf?}6?R`kFWyWCy^^C$0=^uLrMo}a-w=jT$f8=iOM zK)XPfm2dci_k8k&n>PFSFA_Wa6WajVY2Vm}99NuRx)b(~t&!YrmcxZ(!Xf`o4nLWm z!z1(@9`BmRCXi>TSzH1+=@#5u@^5?Y_wAgYH#9n6O7k2jHM=4;^;bpt;!+4ZtSsi} z8{w^O@Vb_`38n?R3;X5uZ)7jPpEfMXc|G@J@a{`tmZGxU}T(7k+S99@79FCOOTkgUs<|N-~6PVBG3S+PEclCaBEa%)(kM&`^o;8evBy zc6X}8>b3Vf&+x+J{`gru3k5|+%xi?7Y~$YBg07DSv8Z}tQ*jm4UV6#SISROY;ZCSg zkV$S)cSbDrN^rO3`8A785qmFz%jT(UYNZ8UCC0*%Ro2{`BH}u3@}oYEcJ|qNvzYkG z4vq{Z-Hbf&wQGyvftDMSr#_v9yQ5+2%a80uZ&N%@?{c&8BNq{jcu@*{ z?(Sp78Sbdnb2pUD7{Iwk-VxKMjeuF*mBqQAOtIdA&Z2LV*k!u+P3W==QZI&Zy%Kd% z{nLmxcNh@aM8hw|2ahiBdZf&ZPjm< zOkB#rk;zce+KsKcW{NVeWzhbqkoy=)eMU?D0X=rHhCl~wC9UyttMnu_NUD>Fp1NLa6|$jf52aZ$i{c=|hpb(`UU zV}6H#XO=Tpc%?h0_C5qxkF>G9SM6|JHOpxl7he z;{au56;r?{EP{K#*8qJ>=RsiCm+Y6HIr@`+?l;U?n(0WrHsob$i)Y-HxBA#rRu2uA zOPTyb1zER-wSsYqFJC*bE0#HvAA`1B&%i{;%7bTr@k7`V!P4r)IS*a2cSdm67IGq&9<%p6n1PbN>uRE1&?56Fu;9}IDR z`M)!H0`YLhXve@!rv|3+mHbO>%V2LvlVt0<6mj@ckvG%oA`UyRk4Xii!F{h88{+X7 z-)n3Trgb~OtL4~WpP>y!0# z%RVmSMkMH9#*XcY- z3&S^-z`>YR&A%vv=~$Qol`SGyoUM)fGG+r?UB)gnnWGZ%SjtR}NVX2H5^ek*bb6k@ z<+@J&*MlaT@uDQQEq6=_lZz#aEhg3lDIKx<puG^2`-wmXk;N?U}N&drzSkieiH3ii7X|T2& zVlSMe+|%Wa+y&A$mF@UJ#h^xdYs(PIqrw63r57gWS7Sny$ z=5c@V%-xkjvRgW@vcv{|1r>lv-cJ@l{+8JbQee=#ROu1QU*w*Pf`FGtxDF33Vs4Lz zx%v4_;RpG^r6KV7!Uc(9(F<|wp?}&%OmTNqsjh>`n_fw`rOC^3vl4{BjC#IVf%;s6 z(!ja6nY9L+q0R9W*xjV+sYi2TcZX=$aZQnrrQBuN$|+E5I-hm)>w$6_)YanP%q{$2 ziDzFQ0)>&cSm`7?^f=fAa_8*1+Q)~)sdEN&dZA~&GeJwz0MeY zsLb}|x6M<-mFqHK!#QP9r6=9%A7+7acDeLnvl+JPr@}SYQf}5o6J#%!!2s=ZY|a-$ zl&+W#*W5%;&$T^p3we4se>CLBJ8EO_;q9=ruB$ZVxgMIl$cI7kHO#HDi)`teXhBm` zjW3HoYLmS5*}Bm`Xh$oCaq1 z_Ur6ku^Oq1W~Dw5r+HX0Nkr7&U%8EjvX;(Dle$M+UEtNz=ecQD6-oN+n_HU0K_u;|0@ADq7 z*Yi~h#~thIR#Bg(c49Nk49#Nws0aROvI%BAJ|MA~I6>q;pnSAKwqp*oQq=|2&lARlfOZImy zG~{n)`?r!tbQm#GzFKkpVvX>y(+qk(KQMMUN9^U=Q(j}cMG(6iav*H}*8{c&g zg~$mXSuW`r92M7rS?xUO8}gg)H(3FyUdOrAk$O1m@g&gOo5ao;G^37wi17WLBd zm-v)zm22nx2bg1K=iRWrSG{!DZcW*A!#F|qs+!kaPub$%q9Mfn2K(QbE`aL$$JtT$Z|J-;L>T({7uV!}OI-8x zUyYrN7L*~l6;%IQ%$$Fk;1Q<~2&wVrydHGNLB>nrYyW%f{@)(>;NWr?QKu>WK>LJ# z5&J=9L^^wJtt>0yHVIW5r}65EnmE;(dH~Z-qCvGawyPw9p1VGqN6+NOULi2IBAa`^ zTnp#!ngz?%kFb8PC>y1SGUI%@NLb8zQQKBe&fEyTX@Z0G4?u@>GRw--kllZkBsks4 z;P+m)#)>YPFy8qm8$=rQQEEwWVqUUz4D}mH6ZsotMm{n>+WWq=cQ`@`PPFDO6S1Qq`-hZ{%xNcWNlq}sp> zCf}BF*WOvz8H=$<`T5NC$>uIonB+emy*w7UwaiSxuYvh>7kDve(A92)d6Ns z--RsSwL-mD7e1A=JwMm4gXG&|*vMM)6V;QCua6gZB+de7=q`kkn%gYAe-C{AK!n$i zBPGYFe)hilSST(jfxLD-WRB@@)F7Izq1^CME&GMVo09n42|vUsKW4)$CuK2eoe6eo zSqHa!(2D0<;~dcK`OEX`}2f% z88ZHCh!u|QSq7P7zp{&U1F`piRnYg(LCGw=pJM57(kK5-=8JT!@xsvr2#?>%K2qk? z38hd-OtIottkuA^snejX=sj~v)WMET&Ev<5A2aghOpGBa`sjUm0cf0aWXkt?;DPq#a8)OW zLt=cHv=jT(`wMGT?}1kpt6;`~6iM+s%AFsc0vetCnKg0ym3A$Lr7t>*A0)J|R-^a3 z^*!k^#h#c&eW2TyU7VzUPxR1~fpKUk%W~D0ovPR+RA0;ExBMB7S&I(C#mvOo=imRL z`_1{nzWf5dS%);?k5)kJ)dJ>Cb94sXOxrR~O1^&FE8f2SK<=C7Q*AKsvlNQ`H5qtn z$;O<>6(+xG;8PFTWPyA?YUyOx(i%onNT&rb5=XoNs{&=%%EJ0Fj4l>KCG z&AIo|#vQh^#67$G)McBu#|n$?9OL7Nk9V#<2BvG> zV)yATVA>Q4(~J^aw$km%+}s=5N2v0H1NCrXJ+YmO=Ck&PdU&>E5A=^X$>JJ`&pa?x z7-{pH^ESCD8q66l*F}W=XNhY!BtY_+rL4QHDcZS*L6nOx_nZ8ouj&_pr)L}c-eHU0 z^d6iSp()iTR`V{a12A`6I(z^32dZs~5Dedr<@X*ZZ|^cxc) z^)eD+@emoC$MZ`X!9+$?UFr4H64f62YtA_*)`(oF2m%#>!exKlY6E@zZaIQzQq8|X9Pg9 z)hl-LficEAuK*qAzS5H|w)o4IGU@!JT$9uc_rEy_y|fRqS?d&Kf3;JE`h*$$mgFv2 zqa9Cdcx6$?&;kvw?0~{E`=mi>)QEX55WX&s;amS2W068A{I~N8bD3&_5AUsjKARg{ z4%+v?r8(r?b1~!>yW8N*3=xc^7Sde~`e;;}0ld{A_9(;l!n}MaD3526&sAl` zuF=AMeipy^)HhMKU=Hl+sVoi&B5l&iP^fSCC4EzEf}6v<<-3AC*4pGFn*jHR9c1=j zF5$^{fr74=FW>k`3uh8nB&{3W865}U;agQ;qBXm22i-tdI7UEWNjclxkF@m9!eC3* z5y_L$vEr5$DECb-aMs6XQ^~Woz??0#QlC1cLT_Vv$GtVawu5 z&~`l_snGZ?ejMiwN9vP#|7&yytW5x8VJCaii`d9_!=TB_ntOIp9n0*d%lp-{#7T>s zJPArlPfE{QE8)!3yJ05vaxPOWaOCn*xbRL^SLrcSmZ*DNFpD>Z+V#44fxhF-5j)wJ zY%Bb}A`zncR7e5`j2CCJ0{-_K(o5{qL(QiP;oQhROtZiiU*4kcoo^tQU!{Y^&86Ue z?He=SYK<`+70{B9EO8}`+`{hL;K`8yR+jM>w~SsW_)Sydo2ZZdqU8aDqm;y3OXv<8 zMqELad(z&QZPAx9>3;6m#SOpQ0}Z0;;neFe)~BwMtZV>za~`GevD1gqt@AJ#4o|H8 zarX}n*|$K5eptXSDJMNkA?0c2=ug^`FgIt`6s06< z(hU)I*e38}$;-2DWC*A=yl1nB`!w}L7(_2xAl0C(cGD$3(3E$As|_*0M)m2ip)8dR ztyhv=i^vl+4=mt|Z+sW8sm9Cu+woT&@jC6XTU>5RPlu|@9&L;jhL#`Wr)?sQN=6*q z`qsv*50Gx*U^whlNpuNVO>C1SAL#l+mG7IQhxgY^fuREyuqDs*agu!@NGxla%;p=` z>4ys*AOCQd|J)Fr4vdEm>cM zFk6(mE{6%)n$n^+BU~H2AI84i!4hMCV9UA)VQlkQ{-H-VyfbVQ_})_xxdtozFEtTH zrs}gg;&PvU9}ew#Ib4&GHcrl-3-h}kW4pi>o#!lvf!9?e?E^x@&|p2VxUD2U9ZNN2 z-9dQN;Ku5M^|4Vo2@=DfvvZb~*eszu*&m70Vhh@*vGve>kd$+9&_Y@BTo`vTo$0J2 z*3Hx9u-N;uOlxCGc`#0J~XZgO+0`gH@>y*Lz40v^shQmYH<0rI~hk%J4X} zy>#SS9ID0L>xRj-XMNg<@lHC8Rk=27olbz(- zZQTZDW`)vHH51&e5Dxj*uCnf)q~EUdf!~MDx%j=X!Hdb1WzcHCE6wSRc=IA~pY5cR zS5T(>xGXrHb(lH)8i4^O6`-vvaL?w@Ei5t|P7fH*Dwzq+o!|@hyS%w<(lw3pSpcWM z-(*WV)8Dj|(f4<~q%+mwR9GDogAJ5oS>&WCXD zivA-#eV+Q~Ih66SAd5>Ir;URrOadHwh&}Cj5$k#e3CDR~-hl39htu;wAxBv(O(E^a zkrK$7<5st*Q3uuLL_uhC1=~!VoZc_j!_}grlHt>1#Ipe?X9rDcrJTpdQ=oaD8LOPo zh%c&xg>O5u_$J!Lo&8=4dM;mB>74%9wEYOE=^c_x9`sf08tn}Ydz1MkrABC6ya@)) z-oc*J?r3q32YMRQcWevd|8i%3u zN* zw@~VCk5A%DU`BAObkB{hvYj_$1@p9HyvhqhbicC^?k>2?)Sj8(%LdAEt4MSSqu;~4 zaz7Ya)s^SnbTIpp8?4NBXL;fJ7&fyQl#T1y7e#H^)5aY_;uQn_oqvm1HNaJ_RfwHI z`sbo}&GuSq{}xY->J z^{8gcwprt6(xRB{R*}SR3Kq9^{M*51>?417&|&y|e=6%+t|}`kOcI>WrSmJ)EbtkZ z39I`3U`>O~aZ+UhJnWGuJwZOQsa>LA&?d&!&LEy`wL8?E&R`pPYy3tm(=Cr1CAR7h z#6g?3%JpN$_e}6bV+kB6doIl#G)2~Ouvy4lsR40neQGv*6wF+9J7GsL;)f?-S8TUMuHg44eG zLbP)~>G84FIR6#pM@*{YK1{bjzby5QtG-yc=pD;1RG_)9V?7M`*u=V%4^f{yG9JgzyTmbT97R3t!)OD3 zs<}NLSaJzedi9bj(KAz5o((%5m$0$T&gc|b0eUt9_iiz1xi>_>^+m4iO#@{nnyv)3 z2R_^_@-$hhE{6WfZLD^W11kGn0rBJ(iSaY)?Z*|sy>szQ^@M_~Tw$G1$|mvq4}TUj z9OlaPV*xai+I^0I$-n;?JJzDx)EObeDf<2(v;f`l{e8N970?ZZ7vq2%u;ma?or$_5^Tw=)h)OcXwgyoWb@ zq4_i@wL5O8+XNHrcCcz1vIu-YtjJX#t$xT^-!Kwh{u}ezO(hE%0b&1$f;| zl8o857`rTa3~qVN{FGKB{5mTQ+8+k8emURpO|84oW2_>7D42NB13f8gPgxv6?@g@$ zKiG8sp;U3THCp%Z0*}^Q&b7Za*8h>g%k)rIq^T^so0Bf&KFi?m3?70JRwZz0RbuVd zBZFn0qw@v(_3ivCCtVz8PrI*%B4&M+YI3iYu}kCp9=?Chw4V>de&uBl@<%F(R~sS=P0JVZGELzp=|I+v zh=iqY;@L@hPWI4qGUd1}7Zpg}{QFa(*x@xB>*Rn#2VaHE@&O#}?!|>(|7x}WR7>(x z6oK|Ij-91<{UXIM;c-F&?_;Zpx`|<6#y&8gQ=~0fM7ccu7fW**i3Krb6`b06ifi}P z!zrU@z_=Z$Y}R;XS$fIyB9WBmcsQdv~xJAD)S^g>Z1wA z_^w9X@u}fvQ2+5C`_i3QPukJs@l0~Dc}uLn+*L3>MvZU1p^Y7fr@-tV?ksJfCHm2f zwrO@F8{F+1W}9vh&b(LP9mif5k6dttcO#X>KD$luvr9axsT&_w`d~X-U9w- zI*Wey%rV_D2}(TlS>L|I3|tWn?tZ(tkW*S{b8rFt;A&WJ@*wy~7s2)}ijwO>km&OF z-!4~y^q%^VlJKr6ogeXzv{<2;0NsDEt*vwu$w>gC^9j-uK&;m{ z(Xc&9|I!F6fK1tXtp@ zBuXZcrz8L3Ug&)+k>#l>$db>m6Izuf^X0ccic6-?mFvg0(M`EfB^m~t?ZocT4o#}M z8rF8*$;AxT#w)`qn@>FIoL)GTQ8wsfx4O6s z)SsM+fvexDSOo0Tt zZiXk$RzT|6BuRqiB5b(%7-m#8^F^MNS7oyuoX!Wau@*mYNZUf8?0#q7dV?B{^Yw&d zxyqt@hzZ_UxeB1qV`mkhR^EDVMQyGd>=-9*Uo!{AxF$0 zojx;oV>Bc`NMK5I2RGzbLq&NHE~!}yPnNpDd;{W6`wS))&0X+$HHw?`J45`~@^Akz z{=OOBsN4%<>PIoz!_G3lArZn5=OlhsmL{%NTMt9jKd~xTQ@sB@8ji17B0ad7_7Cd* z5PPkbJ4QFk-dpB?@to~!w$XV!A08~65qtB^%AdrDf_S-xp>u98d{56?S=0^b^`Bj2 zm*QfDdnHHt{Vu)Gv@{)TdwpTSGV;LU26!Bq>~f2=2LlHA%elv|_vxV7glWWpTEJYl z8KD<>_Pqw4VVy?z#-HoT;pBk}Z6WI+emUi|K6RJ!RRNVMzjaV+TKVJG~ew0Ody#q^|V4 z{Yk!qaleq;5K0+;;}*e^$SgL?#1fx4d%>xGjgmWocf~^Gc*r=bES{j6@8?zqO}}19 zJJKny*(^;+3}^g}zP&L#rV!e@Jz|$tN8`Wv$2GbnQ##O)tkC7yI0F5d&YIT)gb z3-vRNR!n1>Ax77S!SFdBn3DtD6B|}T?=b_UTyINUHq{HFt4?!Q9}-h*u?VpbOWBpB z3bLz`9fHM@xqM?sXUw6$*Z+NRyY6>KqlepJO7-6WpL$4IEE zzs7v1mRha$2fH4ZTzKLa;XBG?`K`}ioX`g|@><{n=OitgFOeBJ+!XTnI>41|eVn*8 z7j|zhXa006`Eh##9Q`(tb)$WI`NTEQ_x(z)S)X`W{!8H4%r+Ler58RpeFes+Y>`;I zt;eMyn!>g%*ZEU@OmWkay-;D6$Xt7LmPNdY5Kh)j2tyC4)-dZnm%J4;ED{6Xs1%<*McgqE^!$-l$AjG$mfan`MhYP1TY0G`7S6 z!@c0unl)Udqb`OmI|eUJ6vW>=>BFNcAbD1j9(PqRb$byUS0&6o&DVNrHukiQwGhTCrE)JUz1ToL{u>p#-tI?w@mETf{mO{RG zu=ugOPd+r<4qsSZh7m1>Y+~qd1b&;~cB+Q2zSt9W{7Oj=|DIW2rYx1i#3CLqmHcoR zB0D;Mukf+J9BzLz!G=*WFl}EV^Pp#JWxq9`wZA8~z(N}(MN?sc^d&1%9Ec_s|AD8T z3wN)2huGL=C)YWgon?kgw@{z#Az@GFcaqKc7%GG-B=DM(G;#T}Nb+5NVUsVD78he6 z^}dHRhjjbD90Fj+h0|QFV2Di#?qGj$2lG4FfR&F!gfU8vyoJGgakPB`EOS;77u>hO ztiZ!yp>kcSXrU}~*&8D~Y_H<`D%fC!#&!_Dzhg}T^`HG?!C_^JOP~q)f@1^ZS%G8U z>fpWkGa>TkB6et|ISw>F3WDur7LaR)CZuQXYdnDa`{$~tp*um&F-|No#!JQjYVw6m z_k~Xm8*HL*74RzSN`Udw9b52Wrv@0`cen90JFe8SK;zO<6-)hM;=e zn^(A?iNTf$&@V<=JRV4TfcvR%?o@Z?NIk~3s94ZW&f{KE=A)PA5_lJTf{ndpj@}K+ zp(#dL(iZJ6n(x<_vnE0st#DlAap+XHnAJ~HmgPTA5-v?n=RZx>$Iy~(;J)cC+cwM; zbEhT2osWsqSw*I}>}o8u3H4l}JJsY%i(y;eY__V!92e6q_*wcTiD!13I6@LHzs-$a zIuH$#FG0|Su59rC+2e!Kgnr`~KV%n=1@}uKyS2YdMWZP`cpnQDhr9Bz#23Ajw+8AT zMzi@A7Ff2?3p%zsaPGgzcl_=Qlh6zBXOIbYJGcgxj2S2m`b*yMIbL8j`ZU+yi{_~i5%N!zGUJFZ z*t92E_;YRwzw*5z&Rp@Y4qJV&!R>eQpdhbOI{bBae6%_W%uZZmPBQXSZy{ZJXrs&f zg%%ipkM_)&`uzMMeX!~94bZOWC#}pHB^x>Lrtp2a15{+{qwDis(BonS3oIOp(Qhij z@vy*!+$Jri*H-RoqBbj_okQU77*HNLnW<9W;_xg0p8s9NJtAGi_Z$y6{jQC@3vs|X z(Jc^ak|%xj53vigs4CtzRgA*C1>(Mlisan z+O`;KQUbM-Np*^(NqD#?4hB3q%3|nNa<@4a3a6crnCeA{W@h!g`6^{Ga-uOd#4e`% zGCLM~tsb3>gN2~Enfwp>8HTl1!XSqqEYq(i?%z=ck46?rWQuP^yJT;eSCqsbQ8qz6 zx<}MZ&1UvAH;p(O3o!|HoYOXS(%{Vlzk6TVjMe(Y_L&O>OJq{d>fd6Nbw2rdRm7); zrWp6F60W5-)ZGu6CYvp76NJ&jiQT4)M+T(A_qTa$RH1<3RpsFQs!j4`D2V&*_R8z? zu6y0kL1QsI=;g>HZ)uN5e#ZF6{#^M~@+~f_fi?3L#V5tIFAb@LNsp5x8r|mOjw??< z^+7YAK^oL4{ySimRxtZGPfhkc$Q zEahc<%;Am}TcUx&IS{iW*wjJ=*@jo?!j8lYKIG2;+`Xn0UY|&;&2Jwpvt3juEbjV( z7q{!8O>{7L=p0}JXkNQGf;-d$xqH|-X- z%st1?Dei%LWdHi-K7Aga1UHBxNxPnwu>ydmt03-Oa0rgg+-uq--YoLlx2Ch zVugjHw(*PXC@=VQG>o77m6^OW!Q=)Wj%59 z@qe|t{m&I~@AV0=a-g!fRl^wn4kPy6SPv!~GR4T;IEWb(#BEF^Ud?%5*lqZjEzUE; zLA#g3oJs0Z&So>(P3sK za^^{``78U$GrhxVN%ek3l3i9wol!*1fD zQ0BsfC1<#Yg<9lm^MHd>cCwf{Vy00aqBQuD#Pswn(KjSszTfz!+7m}uN}(mD6LXL2 zD$CuuT?oA_@{d+?xP4R^JipuD<@y&>w6)j>vV1kZ(2BA-mIs2PaSYq_$qd&K)9j?J z1LsGY%*U(|?l-??{);}LCngJqcAfbzZslVC)Zub2{k1cc{p6VjMV?l)=kFrB9v>_m zc|Dsq++={bJOa1}AK42q!Kj^q&^l$1w5r|=UjykarM29;Qga-i(g05Hs@O*LPdIo- zvRnh)*r9-%5)=t?Z#s5>aV{hfSIw<%*~&o#DS7cs|r1cC0d%PteG$$xi| zv>$!-c_-E0*w)qp<3IP6&KaqXDj#=4^WjR?xN!)6U04PEFAAK`S8W#EeVUKk zd~Am?CVVV}j=za)*=PlsLSCehmokmNG4riBAakC4zcHpWy>q9>!Mcf^*-g?dIW@69ybHb&C1x*!1K7yH&QTL8OXnR)fGoQ$%ls}#6)VMUHYsN=-qcxT{_+S zyx(txV)trxjGpHy|HZ)*?~{^^OV*1=w9m-(6^>hs@yaF-`1Gz9vy;eBCztMh0h#>v zquuedtQ^kW`NAfQv&FR!N+Dosp(MuawP;=G4e!E|`0UOmnCg)v*H;)HrhF6n{F~Xm zxD8qA*pxpXevJLjR$n&4y&+3rpXCMVAb&qv%Ke6xj*%Yv#S|0uV%E7W%o5W`)CuZpGm3y3rj_ih|vc)iSh9lcfd!$&> z@EA|<=XAq$aYN7vxKP|#yfoAdFMd7>Nr9=7`3dvTYiv7cero0qS{V|5^}a+vlusdl<#h^$GeSorff{V1*l zZZt~9j@>P)B|MSW?V{86cru~|E;gF7%}=_>jwkOHuIQiRUrLP8NT3<^%Of`0U<555aGCu!j%MqLEX$;5D%iuW{*(cp)hP zQs=0M#}3)x!4ahp*3cr2KcpyoHE)CPs&^$HB9bT9mApc_pIC#28Sd=A5#|ry<^p$2 zG0Qj@0$McrcM~ZS`QAL(^l}+fTw#f?_8bT6*VowV%q!yLyA$ME3)vMT)SK|HR);P% z!%LwXA*yUG*Wb?&FQu;p&0|kk7y9?2s^wrjT3tHKaWfWI^%AzdY~=@N7^3r?Qn0qm zW-jX$Wqa)sg@X=r`8|aiXutAbk6r%N978^(!kUoo>`x43ZxPq`LRkUlwwY$b=bkXM zu9j}T#%TW61J1uxlnmqi#HLOLaz_29)Sjr7Cc<3}U#9+BO;#O~A$(}t#b2MShsXME z2RFy}tc<=dOf40*S*1t^{73pa@+ri(o#iHyhwe%CGT5M-!&KwQlVa@!{faM2&b_=L zHdMz0Jf`n>sx59EDTRg0IJCC$mxohF)&lvXX1o{1gykJvFZ!Y+e6@Dmfgg-v7*=X;pcyMH( z(B1z5cdV^cyjd|EMl&Vxw z_c)KWkUV0rG&SB7(`XkxdPFVv_n9T`TyqH)Y1gorZ`aUhc(Bk-aS(6c+6iy(Pmt>| z>Z#{rf}gxL=qs_T*%~q1zi#Hk@WpebQr-FWzMf24hneumrUY4fy{4N?t(B4KvMf_xHgkdi$A*kbQU2JDP3}{b- zWsCMOt>Tr;aV*7f2@M})Po%+-uphf z|L%4ThFg1{Nwu#ND~9gKMy}+A|IZvPZ=8qAgQHmC_-`2CnI^1BNh7w*0IZ|z!i=rS zwU4d4$%ae$L z&m3N0&mE(Asyb*6tf+m@7TNa0Wo{3^M1kWTcyALuZ}pNh+-85Eo_6;Exa%me7dOas>9Cog8kfS_ z{OWOp_j)0^wh!O9wWw3}gx@1~W&7_IA4C%VTTwCfwVB+;|d~>KC-Xy-_up&?P(#{;q%}&VcvkEa_{{&US zxUmDdEb~V3zsQO5TAjPu2sf%FLptSUSmqnh3_|yss&;lGlQ^H`aoG4wP3qKjBf9I` z3!fgg@{#K(yJu?^>}twoHS1`mDB31uc3Z-aj8((BbyO?Nl|_qKGi=9g@byA>Hu9Y@ zYJ~+uar$|7jBZuu42flQT1j%|r?=R-yMera79aOOvwaA~ihe98PFc41(>7uGjV#{a zvM#RsupOF}KCo}0)HADZ1FN}F%G%RHrfQcF7Sde3olBV6kEj|?f>d< z&>$N;8z}|XMV*MR*jZ*+nj+->ImOpUI^okW>X~!iGNH#vjO<4&cZ+^5)}-U@6tE65 zN@7``G~!*a^MbkKdvg5zm9+ni*$)%aQdr&gADCfAy~o?h z{IT_~#7!CQat~ekB5Sm`nE?Ki)mX~{x;L4ILYLFKxlR@2i<~+e+B3?TbtfsN4ht4) z-}&(4N2sFuuL9`OUqu{pf%FD}q7ZZ1FfkjhJFsIwr zxSLOe89Mb6=U!oAoBLV0uQ{E#aAN<(@XNO+b1sr%|E}wV+mkZ+WHiE|UPqzxzF#a{ zs|RMblYb|1pCqO0b8$ntH=O*Q$om%R;<6W8U`q22cIh_t&jE{JYuqoUq)oH)@#UcK zu#w)0Uqv^12L8YIkgn>EKU%8bU_nFOL3ceI7QF*1Z|!Bx6(ex|nG#S?z9G4j=_2ZV z*elo0eWcs#?J*&6C2bU|*hcI}diFwmR&xVJ>0o@>DR^{GNmN~Hi-w;V42{T^j0l;H zw|aMgpTTwhfy@E}ZsdXXjX37k(M5JyZ@qBfksfbvse;#S$fr4+bnH}zo%)8rNb)*; zOeMa@S}!=!yptPD-<|8}4KP`0J?r@U8T+hF6FzvQ@!wwc!*3mwJ^eYU*2=r9?A^^s zAvYp>gUi-P~c6e@8E1cCbW5p>` zWfknBFn_ZNY}-WN$B`9~Fzpj-?>P{&%&O$R<|(HwF*_(8yxexML1DBnat(z8r+afp zo)AARYaYDc{*jemazve}_uz?!3zu$_D#rfkCFcSS&M+mG+CliQ?`XDSo`!6|jAY^5 zw;Vp0>ae>k4w}M$vDOf4)ZUi}U+n^<&$^R0@J%RyBXSKbT6i#h4rs61#tdtvnEozA zXf|`;quig1vQPi^8wCyKXgjO~rtNH&a^xjHQ=bJJQok`zx_xv`4+H-lT72I<`Z%a* z5sb@U!3I$-)%5HWw99Q~E=9djr_Tv!KkLkSAH66_Z~m*d_YNE3gLx_7*L69oR{4p~ zPRtb^UK+>uCy%Xq?iv^}_$eE*!x*oPr@864n$+Y?EKc>Z7aIPw^5=C7aZz3sj69Uf z685OdWGga+BK;M7)8DT6yH_HNO;r}BHyWdUa4J+=(Op3H2X`qg5C-+w#GmY9f-Rdu z;A7JT=0_}=l29)QEmo3j>F^SBC;qF$FAZ(6Vg_E{i+kLbh|3A$?*|~#g`lZ z)nt>a z1#H|}%Vm-`WX6t5@U^mA94Cu#Voe8eea;ymr{)23 zX5V6)zT4q}J47{iOqK+v1)|bOEg^kd3tzm#2=Ct52QwOy*-fkOsCGMCNOp4Lqd&h8 zumAp6hyQFPt;@(nxa6b87SJryF*Y2Q)aP-<`?PT5y*UscRKYHcm*O0&P@%+YCEsk& z1?>jxfz!QJ#0z^ZiK|lv(m#{ythx-9)uhx2=cKmqjdr1Per<)Yndi~X>(a*y6!(%ZysUI4-BwygE@X^$KQVvL$nIuRUZ}6`=tY(sJIBF8jtGyy6WS-kPLWwx`?@6bjF=aNCU9= zhNQ2Si>TCCDA#YiA@)n|(lAIm*+Pgoc6w5bg?jS}TG zS^L*a;%9ci`JvbOjQ8faa78{G(%s0G92$v+X5~;3@5T+Dp^VdV|JCF%?X+v17zQ(Z zUP?dJkXCJ#H^emLZ~?1{yFU6HTu5BcEc-U%1*;4(+kRtc&F^dCEuDc~5`LwW)&Ig`%XExKGYK;~}hkJKMLGSawd~u<@`1 zce#rWj(ax`RxJO>Zhjep9y4Eo%>!3%YjcX|<76-Ijh|j5uUz0k2&op>s{(bIeV1e* zI5mfNFzkk_u5Sd(#ebMt4b7Wd5+Fp~U;6Z(De`UM;JHc09bBo6)hhGg&e$~Ox}Ra< z(=Z{!%aM zEuT&duI=k#=w5Aph9l_#NZ-}u;mZsMO_#ae?lPMDI1yH>P!79SEi4_^$`T*jh=)_)d*E_b((@Wf%PbXVE<{7fPBi8udlD>aD#p+%E_81y} zh>bt64s5@AvThetWDQ+11ee{pyy0hUe0hM_^nLly zu$XszuZ2npJ}_8oH~a9x7@fNKKwJGKiCy+Jab7$zQtVX3&nJ4}wcF=G_^867c-n=2 zN)evdpW>(1^}+R|^SPAtj+LDqiprfzAVKKs5}R&v;Hkn?}ChMJ>Ow*t5j*pJ;xP?dF!+90fG zUc|p3U#i!g2)TZvl=j1hXTrf(947s}n)rC459BnT=3Z=}-IrM-OnOtzenlzBPV4Lv z#Ocd;Tf1N4fslW-T5-Dr9!x6*R}Ut=rlKS}qaG@ZKAXbtJY!Ww%6-r2b~#u?s&shbB&kNfH){4Io46KmLi!@uD=>jINv)CN^4tD7m0b1U{TuYiR26iljrB_-Q^_`e!cpD~JCriAe)?lWWmY}$y zh2KMbAvfJaU^sCbt61_4PrF9Q`I%;^&qa%k^X2*tk19)aE=Yvlo7LDTUsLR(9RZ_L z^0}_(w6O5VJerp)*`3R$QR_meaG-i6pZ;4J&j;_3_snPLUHNBV8En&;To+fYix~qG z$R}9KVx+-hMCDm|2H%xC+IV*6eE4?GnkksoVL`tzVdB*+KL4Z+I>nU(ulAX#k*4M2 z_zGARTO=v&(k>pZ@rK`ViM;UfzkyE&yc}h5cy*NOVRa!uXVLdy8qei^d0V%Z4itGKpTn4mi+l-DdJ9eZghEU!waT{}}% z#&_Q!bTX~swYBtc_S6mVpsbYH?IC@FPXxRj&>)%cdZ&0bvO~VF*tFdaLv!0;%1TQ% zMlxA;Df5%yx6=gX>rzf-MV&6L<9LhKcJXprBJ}W55v|F)uF9}ivg0P{mWEZAkL%w4DJ=rxlj!vJ;i z;8c-Uf*6LS-_MCB4^EP6o458i!fO+@!GtL**xt)O(ev2?q2$H{K3auzM;F#Yo%0J; zde0bVjr4`4wHi|9wE?vhdkgu4Ztw^DTHwr=Qg|-g$3_lNmn~Jy6}l_=^OicQ7+CnP ze~u0|#+8X_ute6K#b5i2lGr7}+9_N3v>ueBm%bic_(ry%g))EyU$`Rq@1ue?4=r({{8Qxd2%cy09wpIz73WBCMQwivK*& z0gI29fyt3KjB_81h4!RBH0^bRss~<%`{`28dAf7|)c0akNuYvBHhpk$m$Mw_fe)Tz=vL#UP|I?4ZHS~vA zU;eKSzl*fTv~MNQ;whDm-``ngxhhPMPD zNjKb2ToiPFw2ph)i}=8smdW`QCSPr_Z|H6L?xORy)u_4uU(dXlZf%zRNOz==#%|<& z#UZC7g|r(}c(rd&#j|(k%lF1lZd+iZViIiLtH%6uY418O3heh6a2NN}-`9RVXilwS zwsGBL&lKu}AE`(AzekjCUj${x(B62xx*3l8Q3}qHlj?r1pCUWVng!2gqhP+jF3z$~ zgvq9-*-MRYcvi<<2phVS`)}l0u~M-?uBkh)i!!XO7Qun_woEbTG`@HfE>xCe^GapJ zqv%@+#wuUgbhopzcx|u5r+gZ^&wMJc&x*z7II?38{Ewvb@T=+n<9IvTrJ+)k zitLdTy7#<~O^OgoHbq7nl(b8GXM~JOd})b9<9^QjNTEa|l@w)D*^=V-`Cb2jN9Er4 zd7sz&^?JUz{BX*1n}M_A3*h5EJK^efX)L|B4Nh#NUPS6wk+(kxH50o<%@62)KFl4u zf=>uF^69KLy9dM129xPwHMn>9KK9l(Z>I7n&G!wV+@#-8WrM5bc(dh!ELs&a&fhgK z;&?DD&d4K&59?#d(g4^!r&>_3?-(~C<_)u@T9)eyGe!T1rx5;pI4K`jgHNwfFO${@ z=1n2(B0QW6Qhq%ot7018;d_a_=3)xRZWv&wTnv=zrV>l~Z@#t|sdPszmMa|@QwO<}!C7cf_9 zJGtjqW5oBqq(54?Xzh7e^1N0Q=D36}>UhXbQ&xkUv_Imq&0+A){YDCm%<$Q?6qtWI z!)Ea^AAG7cm(K)5Epin}Rk zE1u8M`IK?3kqCFAwvz4id(VKSR(N)Da&Z!`g|Aq9w)W?@A(;!7MMbvGhhO>%xg3h>8WQ!!_)?RXl zNz!$KEsyVUo2W+AY9Ys6qt7)f>W$xsgUFM|e^JvYk==K_jM-d28XceH!C9Yf67paw z1`VY=gpzSKj?xyq_k&aHgmzQ#y+J+vuL59ce>id2tcM-UPI#I>PN;&$*kaxS@#}t* zrcoBSM5&dsqZbR$zRKZtie`v&f*q=c`1)ohczv8g>Sf8XwP0Ic|9E!vQyNBgICLbyH=9vDmC(Js_MvkYG+dj7G zpu1VQ$1Z^1+RU9u6WkWt3WsW@h;07T#16+CNZ)&d^0I#8%hV9Iq(O->y|0g-=)J%; z$&pl3U;WMXLGa&>{X*TjTKLv|3%pZ!N-V~X#f^Jk!IY9z!IZV`C|#k-x^8Y@h7Z!g zo`DMxcPoM1X#S4gV*S+>fEoVt<{Pya7&)jsf+K!Q>bHzI1O7f=?&T2y5x> zAVG00jNem4GA=e_c1JQhe*6Em1!=rG_$*9a_@!mV z{H~z-=b2dO#0oO-@ef{kvw{7*B|}(yeJ?kDMU^;{;0HIgIA$t&vE_v13m zrCkZ$NmNT*QV5qnWeHwRe!(qxZv+|Q7 z#%EHEZn`9AU!#k2R=dNr_6MTAsBX@>{WR=eF2|*;F{9lOH8AV+iwd(pny9ra9Y(LZ zK%jjZUZwu(|Le?CBdobaxmjXvn+Cme6*dRLfH#olBAWLs-6`g_?UqqRjbd68enXy9 zdp8=@m)1e^v$F!$#2%+ry%B2~FMMcj)Zi?f$qXlN{AKuih6mY+{X>{164KaZ<|^Kw zL#a3Q;?+RFo*vOVnqQM0x(kZEPYNyS^>N3u2e9u>C@GyL#lKfL&E8Z!#cUWhie_!- zdl^QR%`leZ1KA)pJ-(RvNxOrssD^g5JfD=_q-@6HL2xJQw&3gaqg>v&x6I8(s%bAV z#V4uHpx)ew+z+b8np`h7I5nLqs~C!h-&}-Gl^@Bl!xON#iry<{@PY%1mi(RRdF()i z8EDGWJkhNv2=q%P^BeT>Lvaw)OHB~!8>?c6yfdt$xsu?%sd$k2491MD@Q5IWoB4FK zm}%_gr;BH9Tmqk@xkS%+5ItLo-51ccj}<+p(Ie`U5Ux9pO|{o ziIp>6z%0J4jrS>+26Vbe-6g797VHG&5h|jIHxJ@6H*>aST_dw~g8`;lbKrj>hcwTX z;g3qBv1^xXVf^06q0WbYyYxdFWBk1SIDEKaM9NqEL^lg3cEtTqX0#05oi+qQWPKfJ zr~71n#ZEC}v+SA+=Qc%K?9=!{J@c>ZMKIQ33)$-`#cM4}Ww#onGjqnP;%Q8Sjmb2J z+pCM4FcrMVCX3o#)zGeSH?+<^O)Q4foc{S;@L=A3!MLg#PM{bACk*8{V-r*ST}Ij0 zwu8uf^8tL_o4_u%E@OgZN8oG70mIx*GPZaMx&&SVw|nDkLf%g0_sgDPi|?7i3!44B z@Gb~iF@mI1UHa@qnghBrUYOuayUu?-g@h3Uq&ap9=Fg?G+H|q-o#-5=I&CHlUm(l1 z&!CKJ=PU@HJC$_(7{rI{31c09ZDQ`sQNaqW09d5)g*5-rLwB=asB)Sq%A|AK=kRXu znZXGWwJ{xPVbkhj(wuY`3*Pv#1!>cm?Eycy!4|RbQC5x{zS0a2KFFng$0E^vXG#9| zTwgY|kak-z=J+J$2ymv~iOWjLQSqjJ<}-~pR&x3nr?>}3UC?1x-8IIoiLDTkIz_bk z3uP(Kya2~$myy2OQP}TDZ*Ar_LXsm*d}*IU(o-4o#f|m>t%`=CZ!5`l>PZl^2Ezt( zKjB|LEj${q4R#!ACC_e;!EsyOz>lglL1g%LOjJ~3m17#1V?rIA`1m5M(@P?fG2bvn zJ&>)nwr3Xpe97tEa29JFd7lmO#rk;Ixm$@8S5r^pqhL_UJu8%drHUgvT);Z~3VB~5 zg=^>ho7F4n@1m<)AZBQYe$nnfg?Ol6LCEd%e=t5|6Z>-NDPfrIUM^u{HS@P$mdlb; z!=GB~Al73fnV46FQ;r^DO}a7}n|7*g{8Ew{xFLUE$?} zXeNa6g>ELr!R&;ir&! z$5C#<@G6QWXDjsZ^oiXtQ_)+Pb5a?Lp8eaUg@L2+US=KCcAgbnOId=dli$LKIgc3S z)?xUrHxqh#BFH0ID;#>P5EQ!Ygdf&O;lU197;=F2AS|S8nH|CKWY=d=sewM$(hNx4 zfehgsRRb)lX@FfrB1rDiN=%sS$;LT*Q0A~1K75=D{f5zHmlEZ8ZKDvjW=#oWRIh;{ zM?&H0G3uo+qx#A1U|{i%;G^PE>D-Cgi&;XGwV)?UUPJx~mZx@ud&?pa1(ZkGIFU_xh(`V0;+|n_f*lOc^w!rsig5| zJGa`1<~`|rF3TB;%``{se*cl^YJviPwl#@0u(`#o-J*{(rH{Y}McRv@ZGvuh{_WEH z@6eqyHU#DEhGPyTMh?hww4C@bKG1tn1?2jLH^6#EwenjcX&q`tNx8ek{A@ zqaxE*cas})-xm7pWVv0%+IS;A8Ma(>Bi)z2~YF3olWz4 zHhaKOM^#ko?TbOT%vs^eMrL3-)st%o41REqbUy!%3GZTARqIvEjx-reDvtrDJ{j)l zU@h7$m;^p9+Qfp+H=Vd(7&GeuaZsYnoWHw)OC2Qe&v537H~*W@*WOZ|#v&dRD&0u3 zy(I6tHKZxgbBm5XaeL*4Vq7}m|`1rZ!}`V{Fl*~9kt)(I`+XkNdw@d65G^$1YvENwF7kbN+3%`e=6wTB9TC$S3(S2K|Jp|g091uR=rG;*j++bPGGZHC5`?(t4 zLTTt>fsMZ_(qbewGQ5G=wnZ27s0X0ME|p9(l;bVa<5<1kEsS9R?OPweR?M1nZKOIL z7Yj_B0(tdHA0L0FT|(uVLMs_HTvojvoU*SHhfoEcE2?1C!>=&08Iq`V=qv=<%W*La zby4YdKD^4Yt?-**&%@+q_PaU2T+R}&KQ9E|&>rF$&0>jnJ|tUx75wtr!~Hx`ExsZ0 zwJPY`=|X)?#>DvLBRr>@%7}U~! z44Gd(RE!?2g_B%Pg6hCU%EYt4AzSld;;TkM-E&LMTq0XMx3jm>ca1|K&{{v6I8ps- zMyv;buMhPnE1{DE2if=Kxt3F=cwkE%l>43)H2hkOuTtMa?V?AF-(`Jto}LBm?;^ zcUI)Vjv-}&lexNdc11&pWD1$_TOTu|Lt&i7B;l`1O4yX`VR#4kzXd zXHARbBv1UC)z*)v;z)-&7_@CC`JN`rpMM(1O8q&;=si}(BMLEKS|`mVUev|fm>38& z-X&t2=}kN(6#hKFE&M`z5?c>%fF`vxVm3#M?-{tqzN(31Eacia^X32M_RSTPdtaXe zadT=!l~xM;zytc3nO4O_P>)&3rvwJMylq0Fe+%FKTbJeRApM7&p9h0}M0n8Pslzxqvx4kgo!bD+91NB{)G(*75U&M6p6uh7L9Au8#2~UjA;u;%giu;@T{!(tt z_be!0Ih8EFB*_=icmMjjHO#{>Wt6A;`F{_;l4^D8D_al>6Z33DJLq?C`ZiCn+raA;0E+4hc!%PY;4pab;YSc0X5^qWus%w8K|-5gocJv3CkZ*)+*9OJ*B>~w2xrHL7`@> z79JYC1J22}lfC!NF>}}lXuf?!Fg0;2LZBL(alC;EQy+@&l?vd*v{YhHro>-#QM&C_i zm!64ZvOOg5aN${a%gS*A>fs+l8JIcemQ)n>*ztc~wXiMDEJW>^hV!U*tA9%mvDyfD zneNG9wqFJ3mh9r#_0{6Mp)t*XY$;v`)#f9~#vu)KuS;RC&%MmdRnWi_O(n40T!Q;D zf%dB3xgzcmc{ArJSMu2vG!I5IL1`KoMR}XwE6){iwGYQVH@Qo<82-C@}q zX>L8uiSM%C3-7Nth|c|e!$q7p1NytD9`bB79!YBeN7WA%HVMo4Th^c18Gq-)mt|Ub z_G<<#_Q)lRj4kkeQvtLsZW0`ev*gND&M_U-TlgrNdcyNUVUOutGJc@R96{TfMR>9M-`t)27=>l=gpp6X6VcvsU#2m8GYJ!%L{w>rn$#VL0(n*XB#!m$OaZ zOPQ_nN8-5>n&VE1D%(^i#mj9DVsBr#${eD4(Zkema8J8T&Z`W=$HT(lYfPQNuvauCauqz~srs<}E$K`iz2W*_F98Rq0g|?GB!0V*OTQyG1omrn zarea-$T~y0Rnv#zav|+T37IUkcT&RON@r-Z{7QJMvG_`@3vTty7w$TLh?^K@F81JE zn>`u3m1|*7-gcsQi*n$Dfc?WQa_pp*%t;? zx_5<{Gyeb1z7ZU&(um7yExxg;jt!k3&%C|4euc~Qu?^I#1ouvs);h2d@yVB7*;!`k?EUagxy_tq0^**ggSl4 z@agfa;bW?{^h@Ip%8L2FH!t-X&6rF{0xh97IX8MRziE&!YyB{lNuhek0-I2{>-mtd zjWj#&=?Oo^DF}q4S8=IFwZ%OAt&}xkw27y)(TyZU{=}_M64_bJX$%PH2Kwe0tQy%z zzC=&L{~Gc@uKhnzSE(`|Xc@wuA0c8E@#@=j&mtqY(S81`7hF+)B&av5;-U+w zXJ!`t?$Ca;Eaow+)=(jin`!^Wq?7E6V>QeJ9bLS-BMVG&+sMs8OVld5LNlorHu`G% z=(8*g>~=(v{nW2ASkfCVa+8F1lruIb>EDiBeRv|u*|&p=_7b5;Et7lhGz<8HvfO(5 zUGtR7fg6jbk&##b;LDl=;+%L+x-yO$8UmgX-^mP`>z8*5gUyWsk?_49F7fn+WtlgH zf0r8KrJ8A4}xu96Q7-lfNcDwv_{?ziyTcc#d#jdrGFU57VE zYDu!4DcXA%f=7rz7`IKAdX{3L;P`6NCpiok8-{~vTY&Hh?Qrj{bEjv~=Oo?79RFH& zfy3vcg6h1@*jlZ|R+Kd``)jl*-LC-pN2e0)6HiRqD{=uL(jQ&nl7L`U6$)j zF~Fr4=-h5sraB?b80v?E2A?f-7_Ej?zMH|L?i#s~I*8vek+A3XUu90${o#fT%7h_n z<+zRZLvfqTW!RQ&SMkQk0z=kahLy{DNbn0GPU^`AYWNZSS+J9H)VnRdE#9)Cj6NqX z*z|HTS#5R?eU2oudq(Fm)ywE!q+JS?v67q=eQwIjRX}1(*Gbg3z2BV##nZO*{ z>%A=ruD2W~9m#`u8yP=#+md0-3P&aEyu1tEXUcHli}mpFelO@ZZ4`~DeZ^Hbo`FMN zl=HB06c)Gto7J7{GQP*+E8DhmAuOiPz7JNY{DN=mplwej_xtKW^ zse!RaB4FT15t;Li=65v0!7JmQVDbJmZtC3k;#r+jYm81WJK^Cw6LP(g!vl;D+j=#f zk-Ie%N5o%-r?lG?{~F=ekGWt+nf&F-)A?tDt84;04pu!JipF%mJ*JRKHn-?g7GfB5 z8BY-^ty98^02la``i-<*A4ho|UqSwdt*}TG&XI5CVjX*OF@2A&MR>B&g)FEX%*%JD zvZqbYFy<}F_-$VtWMs>7_MHZpdp!x1ZtfHPM|JXx=fk0IR*i6b6J@du-vUl$he;s& z0E1tpu&3-6FhyQ1T-y6sc$*~0^~^NJxYlc?kB^B zw;#zzgOM1YdKk{NoVM|Psf&Beyuojt9|6X~p0JLCgvY#IdPH&t>Ae*fFI6P4)Q$K^3R|Ef&BUAO0_@LyTeEJHX|JOULB zsV_I=1Ify?z`X5OU`yasn~j-KRM`iknkNgB!l_64Ya5)J{g?cv z_gu2!8R!jOEF2quhVyrwCEmB^qskxCAPa<)WN(QoQZW5O%dnD${(|6mPj5gO&4tkftbOd`DtH@$D;{@d-4W zxpqG+i_vGA$BaVZ$&YaOgh1p(fA`EI<)C@~0eROj5|#W5VY9VBm{l!F?!FEdUOOU3 zv`6dWh?+RqeQpgAW@@4FmtCNk^@7-*9EFc&bwNwzQNfq<8!@o&->fzWH^f0Qr7-r# z31YcYmXAJ@$hvcG%u}6qZq;EI2&URT^L!ZYvP=RMGZiw-QVq)-w!*>A5)yK@9#=W1 zvGvblnQG^L&dE4ayjOdi(8V=y6*Bc5DmE;dg8o{U;ag}osWzL1Ig~T}k?Rr2bnf7e zh5eh)1)zsAwmx9_VG3DVa1VDTCA04x3YdLsHPA%89FB^lxakK*qF*C{(}OMxI=!B7 z_S$Z6*D#v7P^N)<_$nqL=@ zaQe;_c4Qy;|MU|&`3=HLV-S|SlIN;UnWO2qX83jgKfz&>`B+={4$M|RVpdqtOvU%7x zN=xM;^WTd-9%;8mA?)vh*Js9(`yX<|mnSd;|tb(C!$Q z8v-Nq>3r>nVpb}FcJc-cMYRcW5dL2(dB0qOe>v2d4T&4VgwImKWQp~#?&^24VA)t) zFZ>3-mM#%)JRZh95{wahq$5H`VyPCwUYoT<^%m`>ACbyd$ed;>=PIGGK^!;?p`R-p zhGRRDKq6(IXgAHJ9@E+e>kE&NYmKse!3Pn$R4SBNxwMJ9(;o|E^m+O$+YDb*4Y{MC zTNFD?nh!HcU_Iw@Oz+Jhc<#ScP!H-M%6Uc@9(Wk8?>lXCk>1F5yYGVw3jXBjn-REV z-2{TXw7_IA&E(=XzzTM zEGK$sj5;lu;L|jkwAaY-FAw^$Zm&|A-M%{b)i{(gHtWeBXFdGUPkUZoDGCnDFX!IL z>WDLg`2_~3Syl_{y1htak2G)Mc#>UddzO(-P{q%xCqdu;50OZsJsQtWLKSyRw6$81 zpOO;7p6ae(j($|f4W|C^n4BXDXY_D+?S6P${#dYi8_&UT%HemAw}V05Pwr?y|{ zv*rM6CUj)xWGUma#bLnky<{eRcQd4Sx0N^MiFOX9p80rRSff-WbfP!h?5)kx!?g#(H4`Z@|MqzkG5BR@iM0Y%fqeWLa+$ecKN{#>qIPO{KkSwtJzOa?U>9^>g7n^1J8;(NYqv{tT69}Q{#>a zWb@Wj2Cq7MyQ+a%L_a4Ng391i?@2;XhJWmk#6Az+&PWG5QLj!S4D(sq*L81o_<|n8Ivi+@w zOxbTmZ2#Z^TRLUA!2vWEpGI?(_nSm}r@!Eo##3J3HaRYuGMDTt8-WY?SfM@5jz7BU z8+$o-A^dcqOq-3FV6wfCxYuZtuW zKYyXK=K*%q9(86$Xg?ROz5_n&mF46 z77JsE^Ar)@q`A43o4lBK>*4rkDD?}`9XR@&B_Hwk8e3E;0nVHT*3rI?>aoSd+tdg( zb7Nqz)DuDS%M?!2?Sq)ZA9TqSeTR2J;n=a{+T05I+4EuN97|`uDH&qY{4zKYFTwHs zMp&;~2sbyD3r0V%^!W5 z1ub#lRYW;~fwXrrk>)#Mj*>O0cTw|K61!vFT*hi*6E~C2u}kH0+>a0+c&{ZtS3L-Vt^ZpGN5?E0rL2XG(WJ*n;mQE!kk~C zfxBz{L1Ixi5zyx^3GoGgn<1jaWG@ujPhdB^YhhMyGoZQPS}?g#K)f$Y@h@7BvnAJe zGUK!)(SAi7EImy5-k(O|A0`{t*^D7$Y6tPI83F9Hg-4k8+O)Uvc_`FQcu0zj^|2(w z7Y0yC;L*60yI`s#)+HXb49DIZ^^g_kM|iad81&PZ{VfP)`cqVC7A6Ch&y?UE$d19q z&6i+|%6U;|mI9x1EQI}avVwUxNCTIz3xMwDIpkfs9xf>IgQT~Of=X|W^Ii0B4kv#y z!(`c~Fn+l@Svl91*WdMxJ#yR-l4`6ARw}&DZ9S$l@ zQFIT~!&LPHp!;L0&`FJQQEokfYL6de)@%!09Q+Y(JFFI7l0LF%WlSzGw)2H_Ul-077?F3;!q@ z;ECm((BN>Jj22bk`cJ;>?5$Iol-~E;`LsAlHmulc47wi_D~KgBl7nhhGa$= zOpK``$`5~|9%ZB`@782Ie|#2|C3*`lQZTxnU?>*bCxGV|XOfih8&}P9VlV7o%49cb z;T##-%N+EQI1_X1EB+2)bteTbybC_`RcAMMG%)Q>hWOK;`q*7hk>3WA{L_o^tlX0= zl=s`pJ=?wxX3(3$QC*rf`<(>0*Qt=v5BpKk!I_opj%3apRKw+Kw}bl9QZmF+kAG~{ z&d%<4NGz#s@=6G4D2FCn$ueft;0yg;;f=la1a*MIT2Q#Thx~WUhpy|fV zT5(6LQKV9zdHQ}oa34F3BzN7#;cyuknGv$xN1 zT(yFB5ABg4TTanin4>>9+GYv$({vEFKZTM>QDny;HU90-ayH=a4aQL00Dm~;0=h<) zO}?sui;bgU$l`0{e0wrip8i36?~6z?#nQYUu&otj{lRhOFug6V8@K|t z8T#6U|_i{43rK^qkX)z3E=hlI*)n)R0(`~fM-OKK> zwqh2&`okT19tY9aWw|kLhtX`vX=su$C3UZ)`Av*3J3J$WNgAnxE=g;mp3}Ghms(5$mY1q11k_-MZ z8Y>s(Ld)dyqG9I-^Mngw*9BBC&E^{Do)ZL4iWf*#nI2ZO`GeWgCc)d0BJShFSeoUh z{-wPmu>M8^{QRy&j881$r#${9)*M_kiq=>X>sfljZ@46+FKMhDOS7# zKYMA08^0xkVACg?gXbu}#W?`t=NU2w=;zA!IA4baJ7 z1UV1uN%E~<=(Hq;RamRZ>{RU&&HEiFtllX@UTxLE|4I@-c9S#NO8Yf3+}5x$lk6Fp zHZAP=;sqlbUXgblqi}4^cldbeq@W^aGfIEZW;+sFnctM56my~+T0AmHyVoCVe;LOr z%-qae^Jw9qVx3rjNH?YWfPFIj*r`H}SpP=ft2B@QDw0ustA-Wr?x6F&jAXC>&J|qD z6lb?5tQ&>Hn7c6Y+K!4#Ax5~qfcBXG*Gj5((M(4R^$chA2(FvEa=%93Wjf!>avKln z;loIO*gwybycl*H`GYBJLQMhFYo~!b`Y9`5nH)Fg#%PT0tbute$^_~e_1s+}H#i>< z#k?>Yg68r^;MlFxwzW2WwSm;_Z)=x<$=PBjxzX*P|ghXU@Yn~#kGH*LQly> zLBPUA814BD7`;|TjcN-kUC)D+Y!s=S{0l*sDx8W#n1PwUxT~N4&EB=khU4@Vu@I&w zNk-&R91)G+MXn+N5JQDxRQHBfF% z4CE)35SWn6NjQ8I>%h<5M&dG?9$2+t9C071iO$kjU_Z@Wb~{p@?HbC>_+2WviFW+n zM-N$3?FDd?>fUj}6eymQP7V$3rQPnU*^(*h40~D$U0-hjx#T`FZ|OK}8T|*Ep05x( z8U}N6ietqYK#$GCaIl34nj}|~10J&c%G@;8tLrqQC{Jf^LOd+u=<~%y4K*9wVX}8R zIgnFDGkqzP&o+-y;U02hF%ItL$Z>y4%y4|$U1*X1F5=20`Sg=XtZzQgtlq9gI}ZNM z+rFPOalobs64WbfnrvytA@(4IoDL!PDIn)G+J8zI*h7$ZLm6L37>Mq9dRzLSmDqgHb zSjw4TqsImCsu)kc=*aVCmcgu|`B7#H?St4X5dk~5Hjq!$GvBr~07e~G5fpdZa*sqh zVs3M{9@RWU>csp{mCF+RD76gs&#JRbaGNTU`ZKUGi24l8DJ$mKDHwAuT{KKlj(2Yj zWS#H^(_yB8tDXjfuiAg)dWRlP)eD5{H=6}ZmX&i3dt=2}?2j${%7t~gdwYmI9583lk@Fp^jEY_rKDEB}xv9}a9 zDrsRh{d_is{3f9^SE920GZfBTD}1u<1b6QAza98#tRddEz6=5VLUOq8Cl=9unQ>Fr zFkbD-c&YsmL>vAgHCu<_v(9K}ahNAEUr#+tuLB{d_KvVR(h#d|y$6pibp!`qbJpME zV3)oe*GKbN+ur6vfJ3=xXe+&2)x@zUeNHi_!VGY+=rE*@{X|A=H^bJF6j*Ei*~Y4a zdL}D^;K0t|%(pNTe3e;#xM<9U=jdP4*&?$(pco?d)w6w8j5 z(PAcz`6RllzF+uus06Xf*TEEeZ~ZKEArjMjF^={fTbL|mD)qIodGXFRI4js_w+*k@>9KpPUNGS$21pKa(BgT9*nR26Z6jk@ZKVy2$Mj~-bl-YtrgzNy z^!-TUND|!fR;GE7Us$|mEo&+l#U%UEZfp8EEZTR6B$rlUs~P3JtHm&hqA#3Lb|!44 z`I>IUQFyJr20UPA#Z>w(6S(ypM9z9fPRm$f@~3=QRQO3Cn!S}R`8Yg}|!fKKInp4TQ_1nEPI| z^YrpjD4lbbB@ z>D0@b+zR))KUWx0kLa{xIk3lwvPu?A!jLt^l>6E$h%}wZg@xpZ_ud^r!_d1g8k(|~ zki=w~skaWI_wHa}gQ7IbYVgq6F3)B9jluICFQH`cWr4AQ9o~)q4GQBsn0`fVOuRw6 zkJY0{?T?>WNAuLT)(v6q<^1Hd_qdBSVS$?=?)fhk3P(v2!$N%=>mCF>v(5=^bw=PG ztuB~yKZQiqD)F0h%ULt48%#L$|D0FMgTWDzWd|sqWQ$`g~P$?st8`RR|wXvv*TwjX<%DT7J>)O>`z~l0!yUR z$(6D`{I2T4*5wUhR);HLROB|Oy8oM;a~p@tm;VK;%9X+?0YRM6gt21HK}*I6L&7TI ziRyatH$;Jtd32mj@y=mHVS{NGQan^0k>z404#PhO(xB1MU(|M+=KCUd!9vgDBzxa2 zl$@Tz&Rac?IcV{ad)*iZTKRIEx6U~HA^#ArCk%+1Z6x`3`;*wRtvsViJA9Mg9)^$n zXTqCW;1Tu`d`T>}QI*igm5Tx)=VUN>wrU~ot*tfNc9SzS_0ay)yr&@Z@;kY_%nEJ4 zJqMrCb;9J`H@GeH?ZrEA*98N#otz0}13_dfO7Mww-mJRATE=JOP)smB1aF=CiLE#7 z@*5mP_hfC+ieg{(-G%HEa-Re*}y&M zH}NLhL#lAd6>qjx%Aa}Nt%{G_GQr`nG#7u!6tn6sL6v!qC`?V3cOD(Yiq76(8a*^n zV=V2N^}I-KQcv%4?O<>m@>F2$Rmx>tj1}kmX8VoA;X9te7)K3a(sv7&D|xf)^D>wq z(4jlbMeteknj9NC3P0`11C$?UGxG$^!7Yt}vhVR^zZT_FO%H~XF4Ki-YpDJ}+My=< z51Dvq0+ww22z4&2go8|ub7fKju`l9N-%uQTDi@Yqok7?S-*G(?#D;%e&HR;7!BJzP z;H-iKca`QHuGL1v>3efUqdoNTduTAkD%A*$N0{QtO+TT^x|y5^tD-;8AvR5dO3Ga? zxiH;$u?{RXNE1&CIu8!n#iG7cd49x=I5ub4DaO)(zN_XPhT~^?Nc^(dxIQBfGF(*z zcc{m^@HOrDST}+>);J2~y?(>fH48<#ja4}L!XY+k>H|j5Wr(WpZbJUVCnTNvA&uX} zuo^L%Ok_l#C{H?6e0Li+d?;RPPKLw{>&g4sKT+ncGwXhqY7w8bFpBcH?i_hb6!wnB z?N0r$+V70uE4X3bLIZZoyjRTAe#)L*$U&R(8FJ41C(b?@%dYm>z$C;z;f~x`58J4Y zS3>)h^p2zh_G^*few5X-I|$yKy-PyASK;QthuIGoW0^(9pSfn+EV#2$jvKbn6bY#T zpDOo?g?WawgEbpAcRwY?6Roi6Xdx&@d=cES+`=`s+!gzcD@tg#w1IX29k(LxS8w67 zp=tCUeVH+~RmYn(l`#CBJf~tk4u9G%7<(QFEJS5d5f~|7!_Zeq0|Po(qO7 z=@4P&CCcBP!-HRoJQuroENV%;1=*A<0!_hEe6vP^9dh6`Q~XyO8#Z2qIZ`o1e^f92 zxE;(siqm8+O8($np8cD>2WSSZR3jFAoh67V{eLO?5e$7HIYOyZhUlN!1v~pv$Tqqw z21g!Zg|EVxU6j)@oymv2OjMa`%o5&a)nj(?P%YS3MR}e#;y^U0lx74Hxyo~0%yY{3 zu$CEz*doDhFtsLOZ>sRvl|!t4@Ofq;)p?c|UxjSSwRl)beS~&|~9Jvw7WsEV#`WYyz z{Uqx7Q*qYVcBtIGR(O4C3Aba?Qt@qWb(=mOXwQVmQNg6+<{u1f@L~5wuVs>s>!QVm zXjpigGCh9lp~`@8wVag7JTErFy#+~d)ATiA=nX4L6b!wK)CBHP z3%K6Cf4ama`nigyy+v8qyvY*lJJ^$z4|)SO4$grW`@C{kV_<<^0)?uhrpLjtpbg->s(l8EL@pQS=Kqmc&)Gv z$bbe}+jSEIet5Co+cKCIX=6-_yADc4y(B!y6dN7#VD8zmHt#6k;|yg_U2Tseax`OA zvLys2Ua%6zQ{Pc*ZU5ue7KhrA|4A{zi=MY%|P}?uVzz3q^iI7xUu=DbB7abcFiF z2Dq&CCYUxflDD=#Zuxt_iK zWH}=}Nt^m?55V>1@5$%YW2n|A$sU!=7A)Vq0}Z@Ku*Z+QV|*6UtdIc*QwmO#(<(pk z#mG4J{ErRH`ufM*(XRDktvF$`4zAjg0_|5+h`Y4~k6~xopfgpBFjEg_(fnY9Of8YR zslh++Zet~9K49wi^>A0ZsJ@yf$4$Lrh98sf!-J=LDh8b!g^no&@KxnK88gWeuZ}B( zvXIY$ae14#0h1arGe7A*<+w_P(2gN%a+LNN?O1jT%7+f(j2Df=yvRnFHm6c>=}!%3 zw9XCo{E1{{WoqJ%|4x8RPd1q#H=TAM7DD9`XQ5q+Jm&xLgutt^Ttq$1drF6ZUt+r` zVO=8^xIYsX(4Wm|{%ADa`WlK<`zsbu?s~u3MW}EqA87PcG8k^>9T9%xDY|MogBVHw9jtzyAEl97lw|h4W=sD79l99$v4& zo*&-JY~MsV*nbPb&NPucy=sQ{j^x82rG>(CJHBx)Yj%p+`1y42nzJkxI#x)KneEh* z{4xY`oz4rbY2Vp6nq?*mhsn)wUHs9O57!Sxl})GbVlP%Cvb!X1Gdus#9zc@>*qmHO z2CbfracTwdX1$y+w`yeQDXu$*hK z<6AHJuzV?>KfZ-ck+FmC`-b3~V+jx+mqxTy2k|S~yx3FojG0yCN|>Lp1FDSvlJ&ZIr`p3JLHjie@=G zhT-e@W6-oISmdOr!WVuIVr!g{@@Ca=w1Ov`3O-3h_f&XFuVoFAQ<>T)wcH-tc(Hb& z6ladPw3qG1mA|5p?m>K>Oa?p7?IH7uvRo9m9))=-UrCGPG`dn0f>PxToAr@2XAuwr zp|la%GkF33%Sm^3|K|;`(1EfF^V(qJx?W;Bc?$L?x5M1vwZe?RVlHd?Qn7aNDVq9i zKL6X9-3JZeLUtc(acC{$y;l`WSBHQ=;R^|Wt%vF@A+TIxs7RyR7u7rkY)Whw6Iez) zNY+omTe^%~&8o&_Cl0Xs-)xwQ*FU(X%kkiOk>2mJ^zqENY*-O6nn*pBcR|pS=TncdQ|W-xc`6rWDHF_htN5RZud4vM%c-x%!L4v14u$ zEM8KS+jmkM)dHH=t%Y< zVcL5I@|!;Ul#Px;(V1;TPhE+BIXr-U@3@CKX044rE(c*G|ABb5o1?{CDK^LUoZzwF zPMmXoB-{GAi`ltu7|toI1Sd9&=->N+8{WpV2Bz^$%P%#lZkrr&<`;K4z;94$c&YZi?-oH&+ zvhD~`UB0k-hfKwM9?$z(%nsg%$y3)|QS0M`kD?0TQ}a7|3VP%Fijy!irBOQEaV}f1 zvRuKMd#-1NF5K(h-gyumQNnw=(@H^NtI4vLcwp4DYG}M)BK>W5lTBIe51RL*g*eW& zm>iG}E8?^1hpl~ZB=_-yocmNC@Z76jIP`n-LZ0DxpVgi?0%y-k z*hBt%aZLLIM92QVlDpMM%=A+B&WjumS`i&N1ML_r)V)L}zjWjsrUjr*E2U3=bY?S( zbA->95~j!BSw+S>;Ma~Z^mn-xK71Aq)hEMcFZTRq9XE>La#Dl2#k*qIhxgE5>#TIH z+Dxoe(jkxDe-q}Jc0$qoBKYL(q$zWpaZ$+$`1^6VOz&JXyL@4}LdU4c>-^dgurD}Qw(+JF`Zd+V*0rhhjN3i@W1m8Ld`J*fN1Nk+jwcm!dj#()RXdwV z3cHpGtE`OCXj3BZMlYs;z65vh-^Yic5?S``c$V9*Ug2}2)7;R`N||Js44_%V@1bS? z6rwrfoZxZY2$c-?)nVfb)3#=FG>N)qAH)?M`0 zW6qg86F_=DwigS9{Pa`?GiiCxU^iZhzk$<^@LvX=Q9nB}|9kh)%->CWf=)t(|q zL#Na3?>XDbCXqP0r3s!VB&ak#0cKxPXQ7;HwDR#@5aUDTmGOGw$2%e9nhgr)4GeMX znE*JlE}h2AbH!^jl!!`Hfo$%iTP$EnJj^*KVY(|c#FXOw#C7joLA{RwdN0@uUt?P7 zd6mBSXxnKR<5}c&!N&@(tqq4Xy9j!Dv;!6#eE|WRe$ehhPh8vg1yt(Kl!bIX$8g$M zh~aNZ=eJhaN6z1a)5GYJUca%tC5Tk$%oO@h?tmmR40g+!>Czj#tNlqhOfa{QCs}U5 z1>RD!&HIb+gmXu4%y%%_awVk#?#AltuQ(v0{XTOl8W?cBimZwxMZfx)O9y2sQ9OK1bTKwpMf{Qzi28=)YlLPswa{6`?!Zws*e>7 zaS-!Tg)P}=i=XBu!EIe%`8>Wa*;Pis!*3O`$NU!AAo&iBpB_`)&J|omPa;=*eT7-W zYuSqD@nF?o!Uj#W!1EH`vwWV(TZ7fb_mdOIBF96*#u`H$8IlMN-2dPk;eanX?1ZVo zO~~R!Z z@>+6=C=2&iE76YaF|r5~J^F%chSjYHK-+v3t$MF5rdVwuCN(RCOPoJ{des(C9$H6B zL=SA;rbc4ha-@S+twgx*LX1eW@JDWkF@JADs&_68Xl=vCGk6ce>V<;6!9CW+XfBNA z8KPN^#`u;d!MDA-)UaP~F~55z33j|8T;;cq@j4N(GQEQOeS3=I&gGMnD-H<(~hJ+4o9*m9uBh<{VM@ zF79$pOTGDfnAPLgl}W--kl4_gVk-mW7icx?1#&AT_*?Bf6ckgI+fBEZ4Wkb zc#gssSJji>$2ac)ZE*~B=6B@zk0W5}q6nGarys1(B@vPeHQ1LlH;ifc3|Bs#lj`r7 zhAz*v$qe6bLY1B!dK}|dh>WzQ&+F>#cj0ZEd5VPq&lrXy<~S6 zwGSnefeQ)+@wE|l&ASZ4FZ`y7{5#ufDTjUTH>3@T|B0y;|K|4M!NwT%C<%H@+fCP1 zOGMo>>&T{O4uZTu7iaWa30KvW+11TXxGr0XI1QU5(_InB8ig*3xn0QF-P2~=hQWIm z(?=O?sAil*vTmgbZ?)9%)VY6i+gqD!Ci8e+_;9Ga^p~#K?i5BcXNf}GO#@5|3yR+29mHA9zc-M(p0kA7znp9884myDH`8^Tv9t7d1pKJ6kmq#`z^-vp^4gy7 z*l#Ux!O+Jbe|3?bQRW)R=`BR#s!Uk*x|!WHOHkYgw+^zz{9{@0WxYGqNK+Ok%?%|* zO1p(oiEem*&prs*(#kP8yeHIj8?@RQOUKS5tYd*WZ0xJfdK@$3-EGxy-*5{(*^S|E zc@W7u7c4aV)WeBuv*ElJ=aYLlqQ~x&K+fjM+k%boYjP9_PfyUGMQ2z~yB#o9Q^MZN zbwdxK9=;s2rq3?PQL8qPOq!T3Ty{0ZNXaQh&bnlZJsM~H+oj`nnPW_s9k5SKp#4Ug zqQtZgcJt5hs(szD{pELvjhrVNZoZ4XTqc7${^vzDo+#rUs;gb5(TQQ|qVcgr;+(!# z7_mklH%yHOgKw(LcNN$FGm;=d#aBM(MJJqe;TPDwdq(wRYM7*N0<=t*uygiqIM<>S zY_%WA&*^h^gm)5Iubv^mZ)1#ok^+S*KGKiJ9I$5fE^r#s;uUJ*g6(Tm$i%iW@?+sc z#i$}3?;&lIU{_Z+&iH)@=FdLUrJru$mj0{B-3fnX+pQYqvwDOnctmMQwrD*y9YThz zqI%8RqQ=M&k{q;J7;&&8(s>~uOZ!5%2RdTcc}he-_K396d^N^Cb0{J{1arcU&cVv~{jxH$F1W1|yvhz`R9fd}rt_+V06B8S8Hf8?KsQ zYyB1oyLO%SaC(F_C3)oGtb@WO=?6B)_ussAZ+F4Snbpv6GU&>jjibdMXB$XVcRzTh zXOA1l7C`dHx3nz27k2PGqsZlTE}6xeGjAz4MT`2{VbaTJu-ruGq0YK!Iq@1y8Lr7X zes{&Z+=uWm_^R~f$ZPCDpg)k6(L$qFN1VRzFtkm`qdH042b;B?tVuT)uIZ}dufRZs z&b%$h5w(xUK}~d{e0lsGR;zYYp<@^=aYf4)b#T>GS^i+N9m?7-gT8 z(Iq{+tjaq9#TNSLh!ZZE9uF%6oaCzhtC3q6iGlhT;cAE-b|`!ei=vRKzZP-wsLkZf zTB%Svx{2N2o&fk%ok?T4zw1CQB=_t>$L>@TzXgYqtGN!=%Q!ikOB!6f9PRJd`9UD&Y$Y)47h zh$qgd>iY#QKDDAvZVcUqZzPLb4hd(*+T)`ZIdm)gOZSa-M%~D>AlcvDEAMb0aqXRR zWL|!Mm>y`3>I36pePSZrGQ||H=r@4Z5Dn(4-5nRa{0X6Y3uG%(Q(5&I8QkTWnx5l3 zqvP$HF!t(iNKSu5~-yOf?OUQbU z&vbwIZR{XPC3~2k@H5~kGn4@Me-aIdyh|{B)YPXy2gYZJ{z5NTW0A40#B5DnHTH zQ(AG(!6eeO*+PhV`$RtT@(Nj*ajSg6PJRz6J^;<1S5PG*fwL3; zI^*8S58>y=^;cwlM~h!CH<8U*rIFd)QNp=8|Myp{teL@l(rzhq zi9)$8W~IbHk)bzz`&t{@E?tB2d77-<+8rm)dkQ=EUzf_}US)gN`NQl%(L#P;N9;EC z2z-8;Pmiu_$Jr;=lNqzjg;G^D+_x(b{NvTxhV`~MePRq0`h1fAnR=VWlA~aIS;E?X zxS+x3dU&s`A`g3OhhK(Xf#&j?bk;aW95VYf48Hb2S|V{{Iz4lR4khZWd!7Ya^Z(zQ zg?@D3uAlgO%@o4!O%fJQ|H_ICO298ugBgwRz>`@muy|3C^x=X@C^66>qyDrDspZz_ zxbG62?7fRlIrA6qJ&GlhAK41$yVo{g|5u zmctYOYH38Mk2teyExA9_50>;X#tEFw+q7&iojH*Ao=CS6-`B3fiWrVKv>Mzt@njo`(w3_+&bW!B&PF30BZ_NrAT)&uZiK;{^?q@z?vrTB*#hIn=6X0|@ z*C>{F;)PuWK>H`lo%ZR7cH_dxI7d{F zX;(>@<0&_EfA9p1{;JT(k7LErquNQ2S|_j^%QGXF55UwRKj`h^ZfNxBB=ifr=%u!} zkN815myFRI1dD?@VZAQ*0e;+0Gv--iAF&oHlfThLE`70PR2^Ja^OtSzcZ!AV84Et& z)tG971-g3XK*8Z~`ZD$>9xo3j`Q7ITJBM>^vmyelY`)S);Iqp!fqOEY<4!RDr=uM{J@XodZA4n?T7nInnX^@2Cb$+hvOPfw3SDASGiN%@$b+g6U1$nb7XQ2m zBlB175eh3iqW%rupY{6*-JZa;g(q=vZ@!f@tkR2}D>YYS@m98QU1D4feD@5e)`A>| zFWg8{FK-cE+}6PfHaXDlDPaaPZLlWzIDG4tCC^&lN1PzLK!V<@!bINt^YmN{IDI=s z?;f(lh}FF3<@rZx-)AS-)uJ7WEZ*RLyf5j{7r6Dpik{af#%`N~$fKroA=R@JzF$wl zUss9Q+u7pI|L;@-J-iI}_Yp1TUm$r+10dok&-_Lvg7?8>TFX5}UG*oEv{z<=t+pw~ zMKriQHBr2`y}BHVw@jlt{nf-NbxGuKbAaIH zqmNt8BtqtCb#{7C7rg!YFf{otkmsG^y*aD@Lfwt$G~N6L=5I|VWqxA>udK&xVom~# zSjzc<%N=p~)DkF-s*)!xRS_ea6G*D|A>rgJQ%s$?7fPmZA0zFH;pg+=z;bQr^hQ^_ z;I2XLs7#jgc$;{_T-V$2?<9~caYXCB)i7oHM{2XS47=@HMN;a1%hpe|ME#omFr(XY z{#&miYNc|2PS`@>UWy@Bglz`fZy%}p6&IY*Q$nssS2>TD);JS!?g*6w>-p*gg1Uja+r4oT)iXw^b3uK)bofpzA%;tBt!@O#E} zsaBrI%1-*j5|3!1FsmaLN;2X3yyNuJn>IW(tyB1oqxyJV#lQ3Tc7t|Wv2&;~$$cMhN!RMEX;m5}t)X~)*U5@fB`HuV2lhH2h znR~86XV}B<6l-l0;da0{I*s2x?^<(O6`&LW5?3cv% zb5(lg4N&c)vLHOj35mx1JetvpUN|~zY zzBY+G`+QxfdDRmQGYg^jusYglcz-l=J`OrBRb-WuV%hAk4T^rKi~M_Zo9hgTzxz=u z`As}{^51+uHI{dYT5}8Zc@;KwrU#m5@t(?A<2 z!A*nk0{3{IS-DuI|3Vj|rU$~a?W!zRr5i^5)+2!zmdP$@u3!&Kx+r|e*}d)2y!1W{ z`n8e{-dTa>+cuCr9kvPYv{g`LQKCX0p6J1O1<40MIXzr{@{E?aXkr*qPekEXl_4G- z%30G_j?hgG1JTafjMVonmn94?VHtB1;L&3V`>@poyFY&l%l%Yo@w2gF!@Qrwp_?mM z=XF4{EeD}+!7rMu;ekzf9H!7C(H*Bm2V#gGAjNx9-^nr z5>k7%(++hmsGpq--$ggMLG4n^{3s;@?$!xUcXq-H!JlAa#WlM30mXv7Tgb=HQek#o z9ZR|RPk-nf>WR*~Db#3r(-*Jw#TegYviEJS@ZcGLv*^dc(GySTF8P`*<%evNmoiXNkw5;k~V%Gk^|M;quZz1662O0gS_`g z<>Lk!A>WvQ{60-@oce)1x=klRS1-yo)*ol{KkZO3-~MJh;?Rf&X#QeN2e)0ufP(ep zRLDUgWHrw%aSO8{m9$p((j}pCvJ7mjsKiHpaiaHN@2Vzztjq+(j zi>Z@I!VNRwTz}5BOKbw=`I=0bvk}tPtB`RgmdR$`Nn%hfQ+VXgyV>HNIyo$wHkwv% z{*B}N?I5w)%Y=BI4XN79Su{N*tm%^-W@PP#p>rn6b-VTwd*>Y>-T$-*b2r+dRf{rN zyXqCae)JlCo1RR{U-$}<`yVpvy9r=BU&3CfIdKiP6ugZd$S3wv7R?$Gh|jfyLM`td zm}I&S!g5+@!`;4kv)^&pIZsELo@k2)dn*(3u|D#zn?{POI-7W#*vyAZciqtMXf5w` zZJ|SZT}QfpH95B7k8FMM4|(C~Sea?F9&OpcXVIDrNa`0z-J6ufm6d_S*LR^XBZ{*f ztU1%Wp^k2e?Sdco>XIwVPD}T`T8CHjY zm}J*&g-1@U*#@VZ^IT-W5c*VC6SHitL)|z{=H};udJ~?3M#FV!UIb(D3;n_Fc9hWV zd`C1roCP~>7SQ93t++LMBf0b4T&Rv!!M5gg&{VF@$`;vTz}8sU*5QkM@yvhSv`qdUG1l z8W<;>{LcGm?)`<{e-BXS_t!CPIG?Ls6NE5NH@v9EIpk*PMVSLt#05r4WTWYIL8{@1 z-8yE&r>Bo-0Udy8|}QT z52gyu;H0wPk6ddRL zgi3pByvz9sgQ{%hN&5a+@kdH-=G6&z<8AR-w@+}??-~`|^~9cO#l+}#yfD@7Gh4>{ zrvHDlQ%&fCYsWLV7VJ%}w|5X1c&C!)7x_ZZDkt3UcK}@Ge5E^k@tiVAfwgJ&QZ@U5 zY~D@_sN(m;8J|qhc-=GDHzSNztLuvwT;#-~nF-q4v~Wyr4(JY)u(kCT`1tiPIB1b6 zzvty6YBg7pt>etVlHaOoQevU>!Wp_JQ&l`>wzg<&O`50ZPJM!r!Z5a3dR1sqskg>2gQOC4B@?F63iQUU7;bb?#Q)* zi?5;U>Du5t-u?GgNTX?Q+Bq{nmN@UR5ne9-$Tq&= zyd$nRZa8m`ff;GAAxDSe{_i+hZ3a1eIZk+;YK1>$DG`GO>9j+S8yH)+lbEC?3DT!7 zSi7Pel)I%DH4$ZT`{X3@&iT5qyC>&|7i58P+e4aP(jPBIpM>PEYBK4g80IByQh4Mv zI3HNMpM-cj$>@p!W$4vsCz-nWyzuU@F`DI;!lYH|3_rW$B#%3A>%e2FQ3&@}?A-&o zfA>@S{sVZ<_aqovES3$>)kBk<4bb0Don5)s7kl0{CHIsz$p)z{W!e4z&F7M34mddI zF&wT6pt7MAxFI;09GVj;Ji4NUAH+oH!+WfJiY(Dh^APNqu}!|@yoRV(A4*1TWWs`0 zBU~NBS^6`xC?4pCH$u&bUQoF#zmzfa(+P?@-HCfV`!MAxbS_h&I=W@3|2BX$z0DAO zjv1igjtq#KrNkD0a6_AY1u)6!oL2&8p;!CIKuusY74Mj0zIQG3v~Q=rn*BI)>?_pd zuaZRt9cR>goI+>z;r`N3=W<}-@^GquULtM`j3oxc*9o0t^)YB^G^}0mgFfRK@R}XG zi}0tdJZj})Ed44arO9rAqwY2jX`fE-H(QsxedESsO_)oV%JI+B;P5neiIk@5{zf_PHI!JMHf0m?e3E?Ny z*~BJeJeyPlI?uwW#uiO{V3Z3!vn1@WI``XL%7Rtx>GG#v3~^Rv9CZ0}ma6>8W!L(~ zD|X|Xi#y@-fsHUp!-i@tvcQbD#ZZ>~lg16>%&T_=pseKK)pz7*QTNe35_xtaJhA5) z7BQJKv{NZt^&LI)XAHRm1H7Tq3|*&b@*kg`JeRFbx{@`r-98D-DOG^lY;`u6 z`)~b!|C__hR@$LG41zQ-tt6Pe}HrRI5WTU{5AMF@PRx~_6G-# zN+cT#4hp?zn_^b|ewbMNm5LAg;(pJQP)_uu6N>tZs`HN!^%=w9mZdem;CDUCN51ks z^M{IdcZ|J%N#?;pLub^R$9LleyrZ^r89v$)MDFRT2$S{R%Om@TEADzjIfL=s=nS~i zC4i19|BJ0A>xkO<1%in?=WOu&m;9&_3pn6{O9$u>XTOuuo}U+^f4(RAJ@bb^`L14g z@)qX$LDS#I^p15o&z0wq!@=o7ONSaJY|m17-j*+R!s6iP@M_Z5E7N|C6sNR)Cwmg6 z!1;7DWbg9f$LAOH+kF=tpi}^LT+7-ueKHd#RVemkWA4?|7!wO#KfLK-Uv=D+bsfTH zYO+|4`Vh&32}!y;;Ecm__OpBJ>cJp{nu_G#~)h?(+ZVP zFC$3de>=a}28X=l{OZm1^2_6{vPF8Ciaj}9)eTh-|Aa%nn)2gq*KqLRDDvsQC&Ctf zqgn2M75*DoNuS7h9=zif7$5jbYSHA#{wU=OkB4zSXP6n9x+lZMVH4n_zO4O`so*}-G|a6J$x~5n+^#JX%}qWtgxm7h17FscuwuWhsF;o@t! zwQ?s3@ktUcmpbDthg7h6MuoKTytnH^R zGc|}|@9#A!d=xu6bwjtwMx>$pSUPmY7;)NoEAMED4Aia}qwkOFaQ2>r$#gyOo!J8z zA6YBinrnoj^c3s3u zk9)$aed=u3SR2%w$8Y^lS5ax_Qam#+kgOULCLFQ(!qB3m8z+mUyW9fNOe@$!J} zs-n`mEo9}vVqx@5Bh)Mjhcyebsg30omRORY;0q0z>xkV;pF>oP8m;Pa6<>}HAj54k z1k0}-_+8*A91T=vL#v$eKg|MY&?xkJyU`Mh4LDakGlupZ-w}_easO@a@ARhViTm`v z!11w*We?KwneDOh@QCkeaXed;F*6SmrbW=VCr64$_ueD$;i?-y|2r+ zUN~gYE!br}hRP4?ipnoii2O;O5I)`-^(uBl?$gioxqlxvJk~;y>D%eaZ(f`gCSM*$ z-?d%EiVIOZ4-z97_SeASJ#xXGe?B9k4N)~M3v%|Q%k6t=iyiiIj|!_0%v6lQ(adWD5y zPyF*={BSte{YI{!c~9FfHL|3V$97~NaE zMl;B@9z)^KBo{0#(m+7@XCcpnjB~+l+g`)6mtj}*?Hw?2^F^4wqM7!Z<$@YUC!kN= zCuzc|iR|*$3dLP-%SdbNpt%FyX$+%5Z&dNeqwCObiYCjgamSjOAKYP-gPEp5wFpvmPD$r&dR#r!W)L9TlX>4T+>IqGttWX z^Ia)~YMbzk>P_f3Lz4ye>Wpui@55)kT4|h}m#EbHAt~?~4*IW*@z&*iFyYie8oKTe z4t=wZe>Xb`tC#CykBneg#hHF>YTa@CAXAb$ZG%i3=d&-h|K{x^&KbV6wH5{xZ=@Ns zui~}m>&Sel6N{d z8^;Wkk&wQ1!hh#&aN?jQP)RMP_l8&DijK+T-T0{jc)VrtClcZCHQtkWt0yj1z73K7 zW9Sr-drn5Al50AA2QD*4>zj$tEBFO{?%;rufhlk(y_59R#$N2|3k$g8&6!%OIQx1` zJ#3#AN6($A!s#cHi9MtWQ_Li|XLBy}=bX$V{H}CuU=CP(Iw+S9(h|44N+KrrDg^E4 zhPa_~0!*H9o<{xw94I>p#VJOzRXSO0QP{sdS#^F_>~m6`T$tIFu2-u<(l424zrQGy z#u%Zc-9@+@*-B$#%&~;O@pDQ&yiSIU5hocwC27J8c)y-^L&xuik2ChrXEhS>bbbJt zyx2qV2-3sZDgS12MgQ(N)l7ppzgsJt85PG)HVX>hMIRG$JZef|!R%4=zzE*A^?CLe$~xP_w-NPbbQI1n7x}5_vaeV5v|#$qfT17!X|ZgZ?*1UmQ8| z30axGPiX&phuK#p!jYpAW_6ACo|N5&H9eonyEJ^quL+5yGWZ}r(U{=zb#>zxzc(0T)l@3zq?)je=vAkP!oFOyA`H_BuFi>NjxHGc8&lo{kw3``1z(;w&oWf!C->GLq} zq9;+V{VvQhu)&wT9>aQv>E_5o@l zE2XtvFR@Pit{2ohN-+9vf`typ;Cav)S~t1{Z>|g_Czo0aP2K;nm2|yAE55SU3iVd( zQ0&0xizzc(@NWk`^w15hRwh;7x9LBRYBc4f=#^<`gSjes7&rBEb`!8?bR@F!3*gOQ{JmSYoTV#v$WyWpt)xi?V3=A&;JIKMW&HL zc#ogVayaLxXR5Pcev6;m`v?pfA0>|*!TaAohmh7^SA;a~g?3Ypgvi^u)IC#6oTy$$ zCj3qpP8D8e6`c~n>7|4{wsl6MDQ`geum=Ah7dbaOkbIw%!Ec3z_~>9Z$Zo2#I^KKI z^-KZWo>1u3(22jhIUg@LF^0};G{tVq-g7R{UwXQ}8y1dgflQ4Rvir|+*!j=n6#aUK zUt93+>?t6e-DGQ_B{p11B3&Fpgr^tu@sdRx1U>pouLsznrcM&{ig1?ae4T~*?lMwq zQYU=&_Vrxu}YKB4i@${EL1s?sLNJdRh7PJi2 z@zA|on8&>YW1}o_io;n*`I#qg+ba?6c$PDH_$?t+kF)E!=Rv#d0`)PLq2sp#u=g^Q zU7vH5x!#M14N(#nqwj`gqf|(8i96NxtmOXx6r%O~lCay=2-8+xg80U-G_r>S_LUSv z@Xx+p=i7Y5KjWT~B_15d}^~V)!)^Qv0;fMf66MMTd^iS+?NcKZ6(Zv zYp}1@r9tD;$?|J2bj1!sLP_1jQla3w0}8%+M6a!to=9>=VWtx4pLI?)&a8qN{`oh1 zKX&bmmE9gg7xNGDx$SM};*v--D$<3ET?{db`?STC&Gg6Vo_J&LNtpXsS9(zJ#BB>r z$!Bqee6NZVp6L1(E@3;pk=q?tIJ|%<+n33HOFqhP8%E1kcGIFQDwY_k#Al0k5G~I5 zg)=y#Z|a&w!ja?rUVm=~-2SG-EbZM;y~U8|4&pvo<2ktKvL|5&z6<{aSmFNuoQ2+U znm#B)Jo;=MdDx!_g%+hOdCLNYKAffOfNc@S!BE4QUMo`;=Na#N!JS=kWzPQp|)o$>qrcQ9*Q#FY)R9B|ygV%T}0jb=tU;BLbL$gKPzo!e(T ztBt#((1h!DTH$~k&dW{tj}Gahj9$~q6h618Z>|_|;S-F?yeBOlc7Yv;_J{PwNa5Y$ zjySki0c1}vq%9@7V$9oJBztIIA#mj{_Dyet!dGnm*&4;?2~gIfS-$nd753&yCdBJ$ zu(nh;9CTKN)Z6LFZH@mEP0e(?T?^(w?hkvM5`G(Asz0Ga_-{cc*FqS6vs!93uoJ62 zn6J=;FY0!}(ZkZA$F&7?H1`%BR?8%#Qx6LlHos2cLwo)OL3t)s*ZgK37=m`R~7n+-7H(k&$PMVy~+f88ytk6 zyE5n-{~tKlFo@)=>Li2&X`{EpW`!1U{dH&b3NaEIW=ru}>B35 z1z)J&AY0rnUW5@j3H0Jw4RI0oQ0 z6d9?0^I7N>VuM#w+Mw>x9r|GBZS3(eiS&$}BCJYz$ufo|K|SYgeYnsSb**o~ptnA> z=RS4umTw}tT9+w2A7_H{k`!>5_=bL}a6p6pyMT;zl*aV!#tzt8Dtr``yR6W2t@E5Xt1X08bB@V3%GJe^i-{y6oM))O2=l%r z!KE>m=>3y}a1ZAIA4=^YqvJE!_4n~`WW9vtCOP0JyT5Q<)rF2YSAi2XQb@nemxRH+ zjj+wX2&@Ktqi4TaqV|Gw3fA$*KBL69v!0MwkEcPNC%?5_PX|AfgY@VGZLFBq0(Oa- zZ2!#eSUX>vsE*hm+jb|0rH=-Mk0Q0w4);I11>4t7r9Cg+!9Df?#4uo_@Z^*Rj=!4> zJIuKDTiq3B`4oV|!?p5^{#v40YcO$XLgDHR7fhdML>ia>rlEHnv3k1_k)ApyTcUM~ z^>s>8=*F*__>Ii&DHuQcD8JmQF222afLQN7E|hT1%H!-lc-Xs{Mm*?_>;5|laZ_}q zUkCLSEq!vxuZoed`-umtj^I1S)D`kJuBAI2eFYI`Tj|`V{jsUF4ziAIkhu(aBR`cC zspvV~^UM-^EX{@|!bWPa?I*tX*+`zNEEZngu|U!%9)1`pvm*XJb&oJ3GbD1U%DS0& zq12PaF8nT>`)+}5@sDAz(iv*2cNM4m1`}Ulm@qu2gmqL|2s61>8F|DJk3T#K`x;zn znufCIb2EgDs!kKKy1V0w@%uq;+enML-e(0{v!R~*j$*2K$E)5unEx>R%B`msm~2`I zdV9IXWn_=mW;|!N{)5y^^kZK>{+r1i`1>?rVmv&%GK_W${mc9|mnpmxEvz%{Io1sM zu}`Fv_n%{nZ~BA7he)A*w;fiNUxtVQB2Cs)7KfaOB@d^&3Hi@|u&;R=K;)i;2@cly zcTys>M{ySJkIU@C`b^N=Ct(BoaLs&~3Ng;tm8W|T6=zS^@&0&k4!FfSVEEL#JO}iQ z4smfpR|f{&i{41{qimTlEnmUaw7+hPm*%EJRMZ0czHe`F+1e~JAwNU#z4e0iD=vjK z{Ee^w*byftE0NAECDOrthM}QEm!Mm_@L+65G+so(!D%lY|Ku)qT^C6Hv(pwVHC{6D z?iz)ULfzI5A74lZUkiP@aDtX-=(?F~+J8`xr|_PjmmNq^#7Uan{V^sl&nK_KGljRw zoOyVwnrB8bi+Tl(6NgT2BcZu&(6P}T@2i~vy&o^=Wu0Dldc$eXh*OuXxwehTZvLCe z_S_qD@4P-a+;1c;vK%I!U2EmN+D{69c6C6Z_9hrxXfpLMcYHeRF-*^UC2izEKqyhEoO9vEXq8h(e!POq53>Lzqm_$YjJcvs`x zN3inUYC6ro1Q&GPOw0?n2@}?|v5k(&aQmY=>y~YgA@UQj&pb)KUC9_bpNfXJ(~i;W zeGJ6oT1wuxzvc_4Warq0m5I<+!n4mou6QS~9)^18(ekHP`1@!bNm`pBydPq~d#Lka zTcbLg4xP}{uK+aM&w70sZ;lyxJ79==EVXRii{wo-F{->O1TQqjm!9>|sa=Kn-|vP4 zB7T6IG(gs6QYQN~asqVbx3ImdZ7}1|C0J*bNPom@iQx}+l7oB0g_uS97-*CLvouxM z@J`%A;+hPk-dVnX)@1CmQAQ3{eiriMT+sNdDlz$4LuWp@jZZJ7kj+1*3C_!EnaaE* zxb;e%nM8KRuyHrR@a8Dm#a~Sf;(KiKiA-S}@~)^&sSu$3mTFHLfL%u%1J90wq`Eyl z*`fuO3Vy{fz!FJm|64-J8Y3)Po&t*=UZyt9gYntN6VPF!q3qnSL+ta7j5< zbeh`&UaK`(%&$&3=<;9K7IR5a>Jk7V{12M^34Unh=)<}`Qg-rbC7#;%l~tg^+xPygod$3cB@qNEO%PG2v( zb&1ce^V!foY9rnF{ukQTZYIhfmI%jqCjEB7Hh5^x^YS0u(J{!3bh>s$I=*2V9((Oc z8b^E=w(T>=;~G!kT9-34c(RC@`xik+BZ?~sqkp`l2 z7}xp33xuR|9r3?Cv0(b>0o|-p#p-WmgJp|^1#fl5uRaa%x*__?tiCeQE2o_twwMTu zxt4Xd@B%FU)<8{+oG`WiG+fwKFP*(~EZaQ)t|D{S@02-?;yK3`^M=ukyT4fAt$(}m znGY`5y1pK^Y^|0aX*kQ4=q`br+DJh|(+;n;7J;c#2@Q!-6|IgYkgAtmgo(!AnWfG~ zg)Z@g>)Tz+lfW>lRsQAkMK=3UCVagnVeVJmadfqW-c`jl#Af zg00hRRrn=JYnq*K9{m(V{>C2>#y#a8 ziQdOxMx}%;v~a@kw$pH{_JY?*%YNb!lMAGL^Kg((;`~_7y{uamOM6e;iwnx5$@#-q zg{n_x*lk=BX!HD6z_QMG<6|on7Ojx|cmF7B?KVNdeCuY;^?!c*@bOHb+cv0)sdTV@F%QR>Y5w-u^A`T=jXQmE(W3VgVE7kNK(w*cwNXnBO+ z8N(&)`3VOMb`#;;vJ3JqCsafi%|s&Ba@K8#5jtN@A{+ivm)AYCqE~^n1#9b7ca*cX5U!@8{ZUehfVB z&6ZfSsY`E{?jRSU3xpF>`QEBfk2p5BQ~Om9uaMS+%hT_+Ee{^is4Pdf0< z*Ju)E>L6@#YGI=%Y?1laUd=Vdg=TRu=}Uv8b>DS%{nr^;7Eg4-25Vv!NpZ5aWZZFE z1nE-h7!( zW~;qm|9vTdJ%iMk7x(#x4^kmjrlle;JA%W!w20=PX2I9j9Cs&{LQ3CLG|zx*dJRFO zX1|8;{>v-o{eB%B{L8&+rTp`CKMnp7`n2*NXHZLZNJe=Uy}kJ%{x>Xxg#J4v{J$SF zWz93NSaLSkg5SYD?SXmQvZ&jdOHB1&m(DPDj4f_` z^%Dv`bm)GSJk*)7g(w!B=KgjaOd^@Eb~o>ap2a&*PVsDA^HtB@%LYlC2HqkS1I7TE zZj2j-?}uq_(bV;E5{~{INxXO86^f+Bxa8??IPa&zzAxyHS2Y#LyRX~CqAe#GGoK1# zzWW%-Jqb58?m*z4I2xF&AXV*%CAlxR3DL`R@LEP3*w-sE&A1`hYeN>S4)>8%ZJ&ha zc8E!@MRh_W*N%)W6v!C==k%0oAzq7%Bf3MU3s*0L72 zF|-&vo+gr`kx7E`8adqAlmXdEDl9G4249RRfOp+*OSavSm$od7B_GvGg#B;zQI2PR zuUkrJtlGgtP1;BWPu06<;d=9c68MI`{*((k+k{V7M%9z z3Fo$dk1N!UblHC%p_wqnsR556il21&zO=)pBkd{2=DTKzRd=Env|51O9m_oDHTKG6}OpBY&^ zZ-eCYT1&i|^%>lTw9!u?gYa|kFBs<^EJk=Pd46!0%%3*qgE4N;KMTsSo2hR9P82WN zNxFxx60TEiT(UhJO3pRVrbY)G_{x;{rlV-m-Kp5Wrwh5Q-zL0nGDVvF9wuJ9NvB?s z;HCe9iLciPp^n!mEbs{cFFt2f7xqQF6BK$_4x%=Fb)=u~#F1`&vxLpe0I%6`&*6v1 z)OJA`>pwOfMrf(B+A>?LUDE*7^Y`SXl=(O{L%j%P~Nm9l&9w{bilF+UE1UXG?Ix-G0ubYG?kZyneNCzQ9tpdarQDpC;ezXe)k)|+O*hG(darj@|n))VyA>q6{Xv6@tUP!S|OU$Vy0>t(ao-Kr<% z$)AP*V|^N1H9-1f+>9OEC)Ed_m8IXWGSLlde6_~ytgP1g*5(b@i#DJ}Dp=4iX zF8SeveqZlEqGltVHLo8A#b1T&rz+xUKX)<>)-{I{vdyvZs4h8MGluH#(?kcYQdqb^ zjqQmYh}+;NOigVQEy^1qEk9dN3iRi|xOOA#k)H-Cv(C|mfM#6%WGmOKdI|H|R8Yes z6hb^y*rrv3abJ`p8ST4Q-0V7)oowp5>n2~aM29oA5O`oGeb9OvO*=P}`C(y#-uRzP zpT@&`{_cJg$eI7CnNU@|PclV$f>hzzL((Z{2C>{5oM^fizUE}p^goq2Y=D#`joc|b zra5fzlsGVSQe_+7_eO`04bXFhF75d{7YkQyC2K~W5l*>kqsf1n@FGBk_4ctuyT3WI z97nRr1nD8gDk7B&fSswl&nO`l`V8Mk|NctA_J5J&;gY+8&K+YsezOHe6{xaf`}^X< zihrOOx=Fl&9%tCxb?@EBXHCNjgMY5o^pjfw*Hq)lVviZZ<~`5YP(z-}>r`g` zNh@T2%TvMILmh^4zs!l%MPp;=kHO(XH$N|oI4Ilr&2cyjE4}b6^J<9eh{VYio{qN_ymI-#@f*a4A|%J4ZIut`KHu-DPt>b=`a4 zjj};?@*E~)f0q2`dk>W!uP1+(h6`Vh>SCeI3DCE0qn+}O*mq|Z1h=S*$_xfd2i0a0 zt)~-Unb;8zxLOc{F`Fdw`&ppwoG)&c{m`zLq(cbzK0Ay86x=I)5hi_5wJz{o1W2hK&od>;IC8^J7Ws=9^^s}|7sPU z2>e|iSO@EJC|xmHS1KP#NfYlw9OIeC)Mp0BG~wXLK^Vw?=c3*~)9z|Xx9*A~sV6Q7 zvBNA-#U~lc)IUpjw2`n#{9*R~h)!P$`azyJTd z9xKOYSy-UdEeHM-*NS>-jAP$7b$X4l>Z!fsKxpv8BH2JQtA{v^5>S_)<6_V{|<8#w4+ zM=vBhVcnSuaK|Rms>U8HJtI?=v)i6;iJ$+Tf;hG1)U#7gI`sPn61R7ykQw!uz49%D z-@|#H=%W*|*ILA|;4$|bh%hWvi%czP7FJI0fk#?OVS?@{8hX2c_foAPk^NN#kId&R zrfNOt8mX}7?UtB7=rjyf*QW_{2TJ?9T_CUJo(PX!IE!XmcmCbDMO}n)Y*08)z6G2X zKJzoB_~A#`y(}m9lbSP*x-NmZj^DIq+)frB)+F-==W5ts&lM&l_4ZV13L5A;w-nxT zy-sd{8{UxC!HHA9MIRoFmUho*A{!@)O*b+@^^^*Gpka#@e)fBvL!c^mDystc7wwv?l;NDK}5}6KM=qx9_`89@k&p$0( zv@$_m+Z3ofR!{p*8jNx3*)XWdL-aDFH>;>Km3h@7>-d>+x&tKr5@}FdA?_?lB4Cj$ zxR3tJv{#&mTYUF1)zc9b^dG>G8~Ktq@Bd+mJm*G^EfHvrB^u2+14G9>pf!7k;GxSG z;n!fkIylZ1je44_= zR~^IHwKD{!rz$h&ZUgbfvEMMMWe4>REWou_))Ai*qXcn^0uGcTsAbjYYt=o0eJOcF?8!A(2QN$(wm71q_QMi&=_KY zqoNML`Td`0Qq4U!?n*km?5@h5q&VP~UVouBIwp_KE5ct{5hNw%laMWN2CpfDvmtHN zV}JvmpPUEF$zM_G$1&`w{X@aeoo5ouO>p#o@!%dhhU!HBVo{tm{r~Jn$6N>8_W#+w z=$&ZOrVA`xekthNh6|Zftgy%Xd>GTenEw0Sf-Cp#B|G#Sgh5^n?9cbDvTo@9+1B{7 z>tf|NDxU&Un%U$f5?D;Z~s4s zhXp#~&1Kr;=DccAtfmJ>AJ!si7n=ot{=Vyf`3a1ee4cJ=EXGm0w~%>FnnF|UQ>JXU z0X}P~utR%oaOL6*xH8d%GNvTW8x%?mRvZ(wYHYA!rYTYI&!zK44rnm`11NiEG9Hu9@S)bvpK9T)W<%)`(g2ei}cCEOeWmqJ_NBUd&}<( z%H4l*uDCX(-wW{6^$4Oo>Y{MQKogtXF2Kty71pPW_h9arUJny_5D}A^15qVG< z0NYQQ;79EQ$mtbB3%|r*tZEdQYIIj{buq-F1#NIBMUCm(I%79ud1BXZi@5w#DtmZo zs%$r>mS~Enwoq6QlR%gEYsF!i`$*Nd4T9lwZ8ZOy2(4VJoLtxgC4G~??vcGDSA8@# zhl+_@?pI;$S|`lR(!h_ZPyk5~Ylj$0sU-*6pBEEZ2&0BwP zn{x~~pm$0zxo?OCgHpg-uAV+#Gyo^^T-z2m57EBez1UlknM|)37h#3p-l~w73sdRX z)pv2#p(OGmKS|hZ_=gos&qK{+750hGV36_=FuQYzDj0U6(X1enr|l@H z_L0MbZ+=6;2{qQqcgLX%O$hxSA)a_^2YX40te>>p(-os9)x%DuU|Q~T7t`|AlQ8$u zg4s2BJU%~BwzHe#$2;ilj=|{Zvm}4Y6s10~p(MWug|HwqytKoRG+h5j4{p1MBf>Js zly0kpIt#|YuWLRpQMSNCtE*wE`Ui>Ftr%w-ZzJKIQNobdx|qy)HD`8rP~AFPELhC* zKFica0RaQ0{rcpP8FG_hO|UKI8(I>H$7YG)1D>Oi{(zee|L6;={ul&}u--dFJgq

!mi{?}!4(Y@z>!Ib+si8}e#Gsc7TK30M>8LSA3x zcjJA$FX>G^9DgOHi|h-q7w<9o|4cs8dW)TD2!JzEWtKC~9miFafPIBPt=4Nw7v6~{ z8+K#~1*6PyOx*$Ky!DByA1GvZKBt4dl`31vKchg-$9p8n>$WHgJ>Du+WHUcTsD!gm#c)RmlbSnY$1%XQ)6yZ`MvaIHxfMeg=opQq4?&E z79rc3g-eF!_}cCl)?H}2nP;CtTbJUa^%AIgcpjNHza?rxTO z(#j@VVqZ@a;%qRLdQMWs_*~Gy9!5*j3;u}4hl|FzOwuc32?fF_j`UZ!$+daz&)UnbB1ct!CKt!>QyOpKd+Br z%VXfw+e@_YQU?1|*rh+bUSN;ze!O4L$e0$?sbfdT1-N{RcXq3DFOVB&mM*{Qd2GoT zY5U7Zr07`ym<-~+sRzk$D>9xQ`LGYu)uTwp*L-3B41FBQMEK2_lZ9KlV}@H2 zs7BjMPO6T;0so1K<+QIt+8HNY$M-?5nT_<$ABGXL6Un=IGX?kKRqQa&{M!DXy~BI) zR&d{VMqf&(ITZyPe1s9Ae=is<7Moywjng8!6TuPCuxQl}=e=<~2j=1*3@p zp60$v<0Z7f->$z@MgSNilEbdXkwj zN@(3DhjKw(_g=UAMwroflruADO0wh>r9<7elQ&;b7<$7DH+?iFpG)Q0r)lrdKn}@) zMUleemOOTANxW?DrV`&9Bl>-S-yS?m;Z=mQTepzQyrZr7sV?4;OM~%Y|LC$#&I+!- z0GSWfM9(sv@xm-SlD9ofqTgtYK8BxR*QypOxoGkO_2Y%kbYkF2oIh}AYQ{33+J}qWGB`wk$EA8KJAY$Y|Fr}2&lANL#jAG zf!MZX3A5eJ@VMhasLlRF`}VraX8-Ndg!}U|;$&wBEcA-a3nV>o3Sm&w(MtE{_eS-9 zcfeD-UF3ddB-E=MVSF~H`FtEf*esNBs01g-4fvumRV%K_d6rjyYn5!`G+4k4kyE zZg(aN8Q3*fch%XW=%Fr|+0sLz5NeB;H`hRDbv@0AamJKEPoVTvhv@SRV|Fm;f=pXD z#>{ZG=nP2Gm(#(sJ5fQhi5zHMC1hBZu}ua1{=jn?gI77A8|lV<*Uv@Eng*j=dDmPW zV#7P*VxGXq!VLQQ%47D!ItZfrsxVC}YrOF}10snDeXv(v`iblCXD_7+Ug_4Hi*8O9 zJ<6l{CU&SW?j!h2&(3`jF2yIx8^}-pG@(ED$n6<(2bSdjqyhJOW1qWO(E3?UEcFXv zfqBg`Z$m)66%P7qN>1C)q`UtrV}yAbXlzttV_bQ^fZG=cmis9xuJx9NDz^}W!wcct z2qW|zo(a>RU7+)mwWagMCzBcKg7AE?B2H}D&igD>*wcDfd>!IMhG*^-52+i+PKR~P z*!mm`ME_s#WllKF7+#G_-X#*lSx1D{^jdZzCIMo&wrNwVhxg~ELt|Q$4HW}aiSLduab3d^w*G6E&JcIl1n2dYz~>3^wD*#Kcw$=uiH;2w zHWDpt=kxX$*GX!&cE=IBy6&{SNBE$HvzWZn|0)bx(g%lU7?9Bg&Gh?1d;DU_*|U{- z;=bdn*z6ba;K6&=QZI8JZ^kRwG-eJR+R=*N%VNlc&{M+EO@^2gn+l$Xe$ulm-MJ4r z8{oQ!$X>^iEni|L^P82P}ftap+8J_mn7jH?3XEV5G<8~_d z71-F~sj<3bdfgBzx;9GcyV1;RZK@Z{9B+Vs4wZ4iSH0c!78qet(@NkhceWd>43htW2`Y5nG-I4Ef>tr_v5oXQkfk+ zYKr~KpTN`Xg;XqJSaxzf*}Q+0klfM9Zk+~f}XelZ@l6>&Bf&m~R1_7Rc~Hb^GgBAzVVK-&9;3kC|^a6;i( z@ckjjGMsF%?RXZP>#Z(&{l)<=XxNc}USX1!v7CYV=nD{)HfpEkin)`yUVSG-Jg-lc zB&#A^{LNm4>bQ5uGQ#tcv%;u!i=tHj^Io#0V7stbh39l4csJ#L?X>6WKA0BmNM>nP ziDvg6jRkvLi1xx(!MKUf!@Y83%=`zmS)~GTYaCHKus~q%uCq&byJoDzZg&j&SOKpM zylLO@hUmfB%Zq-#qLSHFXi`~0`W=-B8}1|fVt-DycgyPIfZkpTq_ij@??{0K4s9rc zfU)u{BGd-`r{{sIb-PG8cm#Voph~78^yJ>2TF+$AE1f{ukXqI>uWQCio;hL)_aQ9E z{VI~HJJ-@HswVbT+LGcSX-luEF?Y%ST|O;sqXuHx^SAenx<=adzGdX)j){utBG z59Oo_EJBDc=SAt86gnOBRHe%88e!Y~vb2i)`LLJKYl%8!SkW)m(aWmlEzCRR-6WtFcM1`e5FO zUm$1HCi>>DKMYCp9S7nM{H(bYXdWMvw=Y!xrlZ%=pFVsfH9p`9i) z)$9R!k4zxeS0%#n3{~7^kR|hyS#Ur3)3H~;yW0&9&r%f zuSuZq-$tQMTO_%)Enhf0L>J{={sBp`8f$#n8&wPCNEB`o%Y`0dw?n4MG=$L&Mx1X+ z;m5~#dT&!Zjy;q>JWNA{>lZcnJ245yS*b9$bH-TqISI1z?IlTj1m1ThCTIWE3enuJ zcsD?gbjCGMG;9!93C{8md;7dYdk?F4=PS4S$R^_JlN zH$s$JBOAFmQ>G!@X?MhtQO{s|Xo)0kfUoq|)J9Ts+X*Ti&G2yaSvZ_sNsU4WpyIvD zAlaucZp@Emx2DI!U#>sg5jc-`oi17Na|qSnG(vhc*vxCdYA;aUVt_m3A3!qixUu58 zy4;g$xM4BD)9;Cwbl>|LqBCeA9LzPqcX7wyz}8e+q}PVt*ESNViKE~bz`OY_G{K|m zYOKdfH%#YmG#BX}aZ||__T`F~tZU=9uPN?7_YD5d@~7q^ifVZqWEw)$f(~Y&mjtFG zRoMAYR=D6qCRn^(A!*)gjuyt|WV)IP`!oC%zVnxo%{`)oZJ)2C4dS`cQZ>;+%RX3{>P&nWMMz$* zF~;;;bui?4JJsI6-x?MjpgD4vIFvq=9C;QY-ma`lW1K9|Gv@|GrAJcMtSD7Jv!57@ z*eP7q)WL?!`(ToK2leHj#jI_P#Iod}NXQ$3WhY$7x)H5{@{e9PV(dS#xKd94+$%wU zzW21Xo-aH%zsBYjE|F#5oK^c`=a6Dpy+K4r*sDrcbc-hwUS$e-Ha2+w;7OQAn`rxS z%0lL!lWDn1j+P-_b!$=^IirhW*XBw2YTXD zi=L$H64J*#ow)W=4|ej`bK^M9vfx?^S+>?5nm1ZtwAxMC>@}HSgV%Xx$L6TKcxKBM zmT{uKWKruJs%D{x-`14LybX%;`=H3W5q@9(Bia!J(%y+JM05K>h&yh9 z9fNPe#ih6CLl1dr?e%El_N70e3A0*en^>t5dnt?G*5 z*qd_CF(-YbH@7_|V*&%$$oBOH&ejUZ3B+}5^38~vQyVN#VE+k2xI z`k#>_p~E(b8w?IIv$xY=AS$yRDn?k{k3sN+1e(*?ibLZP$lA;hK_OHfYYrsAXs(BB zm}-na-z7s_yn`gJ%o7iWiOK43wZcrkUt6B8N!HOXG<&wTbVK?ZqT`$<1f-NPqj3o` zJz??*d%QXJDb!m|r>DmlV$jqR5Inkx#_;?0__Y^d(-BY6X=x93FU3r@I}09Wg&M`$ zqz^q!t5SZkS>rCiE6%SjZE(QJ8=k`g!&1p}iLX@P`I^S0KAaEU6LWuN!HqM|=|KB_ zctidYh@W&5&rIFV%zb0w!+sU^TLdQJKQz#37j51 z!SiTdM(|1Sd7;!72#%29=B zjuxN(yOI5Q;U&vZMDV?{%bNEvW#md)5-3IS{B7jM{0YLgLG5hKuq2sZcRK%>`|_W8 zXVz*--SENE-bOb_r@sb-agK`P9ZNFWO^qoodWPQ;ku>{93a{mFvTI-C;m;+`dJ^07 z`PnsBk6y~dX(NNk*dF16$Kq~yBj7wJ%~WKI|DQRH%Yv*7HBtUaey2U>M3zT{OFH8Y z;q(`g#3PI6O}K}|-L)QCy#CP?zMHVP-2r;5cZu8OIRnS^CQQnYqzY%1q;fg2#PoZZ z;BBjeuBtI`vT(*wQR zuuwjcNON6R#olq##SON-qRsTKL&_*1l5sXyjAX_I~9ngxB{`@>|@*xF%3@`eY{ zoGf{C$?Te?k=lK5l7AB{x%pS5kRz6MK5HRPYZpSDJ=f$<--g}^xl}tvQCht}hDf#y z5`tgL;h_8-kjZ;({@XbKOD+r|6(m{Q7VX1)zPQT#x@KEV@%q2tu(LLTUb8922X=Af zP;IhsOY(s&^-Kg`1D>boX^RtIN#U&jF-hHCMd`Yb7~(jkLU?ImfVVpnU}^Yudf(+V z+sysF|MwxJ6!7z!pUVZ7-D&T06{u^>8JLU-yOmW?b!-+Kr7A2azZX^-Flfxp_e}rn zC9QCOL=?XIgS)2{?l3zJiWd&k9#Olo&MJabA7z3^vlf2TY?tW<$^Uv{@brH$b!?D$ z^zQ?VjhhZr{&3#)VoOwfPzsGNQs}sO4>06Y5V>*FPpF@!j*s(`pjnSIXNuFh_VRizz^-^IX4Sqil zcnmhKe$?;2vh>2cqon7H%R=NcJ1wg*gDOFOC;d-Ml$G`;{nwJPk*PCMMl^QSe<#gdD2CrV>2TF9l>eIWC;HO7`*ge&h~ z(I8(p^u2Kj?40$)!!q}>>Ab)4|5`y_NiUpJuTL&@^Q7{6dg$(12@xmNSg_a*Zx4C~ zzaCBW%m^dWxZ=;mG0-3M^bE1()k$a{a-2SnZpPy~Hk0Vvj)K~jdbUfwnR`prn02iS z9(rv-PAKjZTL>H2bA4~wjD0@97OO`8fDQgzXaSe}|GEW}mb()K??r9w)4?RzHcN%| z9BzeyoWbR_b+shBc%U@f;|B5a(SReayzd~?ni#CnU?0~$MmWoe^U(+)UH&?oW5&-c zuG_1Rw8wq?jh6hrLvmO<4-YGBB84x)1^YGKu%FchIJ8ZPt=_{ur8$@2dbXx$lH4Gv zWZezoB0m$N5Ai&*qcdqM3zsCEIe@+`k!1FnQem{53HDjt0J%fu*`o|sRGilViYB|n zMn9`1-plsMG+PB~id9Q)!rOb1RHP#(&FbKMw(Ft7uf;leH!>FbAC+Unj&Pr+;6nP% zd@5R#2k7(4g_QD6b`8s3sNP$F_>6c+k1O57dT|_?xOBd-=FTPNGc-`vAJ=io3Fj>> z0YO1bTQgOp-a`|~@t0Xb0M~7DbCcjlz&lzr?>3t<_?(Pymb+AYx zeUXBD9rsB1IHOaKQkW)H5f^cUP~f>L8Bg+YYIj^)br|+)`Oy>R@7TY-C2*O0OO!b$ z+-J8uDe?OxT6XRvi*#NJM#64k-xM1RUHlkcZh21sds>Rq%r=k}7xjdb_dhdh{}7oc z;V0)sKdw&&3ws4RA@LM*QcDLrKUL-xWrvq17;{EVPl=n3E$Zt30ME;i7ly83t z)*kZWl0-e0yERLu*=Aktjz&Mu!oRkaH2W{I*6~GfqMI6fGRz6J(|Qow@XsRXaK+LQ z+9YyFv#{}#IhIU#4=(dB(M08;*iZ5cZiPgMi(1Q>#hHz8X&~=F>~4uxk1s&XyY95{ z=0ItM(+!eT^G^81-xret?8#62VqT!&j2Dl$z@AyTx$35txMRs3C<&>j5`q6tMqQM7 z52opCV$RBK!f_iFw!Fa_-z>BvT8o#`36tcoQ?Xp8(?P74M$ z&CN|VZ{L<%;*~Ht;y!Xe-JVv2Gc@Cgar6NpfBai!wI>n$xxZrAc?bM6q8R2WpONSl z$xFj;$B=rf3gLFRJ_bf5!IaN8XlDL#b~>r+9(z#U3T>DiITUG3XIK>Djk*LPdLj|_ zIw@h!?<{!rn`ilRtkG0n3dsWsJdO5&^jp&-Qf#&uM)P}GxycD|b3Q`9Tkph~?h$0l z8YY}n(7+xS+u_I)HTEuu_gF2GBcI$iiW~HkSi$1yvU}{$8dDVgDSB34{-L7 ztz_os=|baiRdgGd45#|2up*xK*`0h0((m+>s6-FJ>hEF#>R*MMiWT_rQ95}#W0UYW z=03ZV-8EzF`TO+n_eT&tU=K;JJtHw6Iw8IC! zFQHrbWX}>?A{}z3mgs$449lk);*ImCA^*+^IBKF5`^dX*p#pM0_NtmVSdc2uZnwCiQqo|uEANBo!eTL=wQ?ojg;v2t+Zs33 zD3IHviq1KD54-y%ke>4v2@V4;vdd=!Wqm_$>K$>%&QiF7Vpp;?5=!fN zx9P4FNcO3t#j!Wp{?}caz!L{Y4BMtoR*R10jbi$^I3FR0w9&0mPG~>03|hvkiu*SR zOsD3Nkimbq%BQXH+>}#rZ^1lTxhD**T%*WK_2Yu5&ucb)REbOuw>8vuZynKZYk|&!~1|5vCqrL$U&Nh1E)**qD;8Svvo(8G0W*2EaRL zJjb74h92qgcfKmSKFbjoH<^+$LtDv$1D4o2<1_qR@QYfmw8sa!uOQf8UK~BA8{3)N zHA|b{m|#l+-`(t5MFaa#roFaErUP{3JE4ZyoKz306HWZr7rSv!*UNs*LU@QNew_Ob zidJ5vXHN`9dM!fS-@S~v{@N(pe+BSc3U^$Z9Uz+@|kG$CZy&ye*p_8cU1j6dfo)|QfS71}5 zBQI-86>W}?kr%v$f&Dt!Ymc2WU%>6XV&NraIFm~zj&vf%;9*?xvhf%OOnf={K5mz;qD;a7*|b( zYz~0=J{Fi;djeKnIzr8a?dWwSg2Z$(q5EhxbnIw{zHimovQ-vnV=qs3F4-i08Jxhr zL`|3Ju7_9j;H;`rpbw7FLx+k``R`itA=FoJk5R#%JCmWsmh(4MtM6+Qa z=L`tM(C(|SjNgF|{W2seyIQEJUO8@c$RGylTZFjlMa)zo5dwWwSP$M|Jr-Yrd-hEF z@$fx-FnK*0=(R`qa8nl#=N|_*p^+waIO1JC2WIscCQ=DBU?HyNGVfN=+@2U+Xh_T^ zXVU)Vwd~6FuKVh`<2HD3+H-jBP$KDm)(T5YFTsITuPK||jP-YdiI1dAY>*JijM8Fd z9<9qmtnlVF1JeHrzoRy3^S-u9aNeNCo?f@ZQyX8yk1>9pUl#dD13%Xj{~OC8Hro(& z52V3^Ij88Unnny7u$7FP;3Q;S|H4W++b5m!{ptEaIG;H3{cN(hd$-l>+#PQS zQZ3xORl zFg^!R!hMD!-s#}M{k^6dqKT%0RLP)#7%yH5b*V1cUvVfYUlb?tJ(hq+l%hzmU#T!P zzyue$wZZOaCDy-u04`pvOq{Ro5%1btESY2zDZYL{h33z&#PIbDR*lMTuJNLRw0vX=I1!$<^T86^Hv48 zZFM{`zp+60$TI@Vwgp1gLhj%2w!?*n#qi%iPbw`@l76U3BzmUV!bLS>%=vm4yo0{b zJDaYv9V0TpeXJ_m*w_=7Zcrl6)+Xgue$+=-<-5@9aXVG_aYXIgW!y8bDqiwi#KxR| zB-2_8XY!;v|dd21><&B+W!Q@_edUrjHNNuB~@A~7=D?eakl%}|{MTeb{ zX33Z~DV*)R&i@=Fj$ch4UR5B=wvH%k|>jxIP+r5OJiQw)C>VeR4T) zJXucMAX?9YquXTOtrX7KxtG$H%(h%lZ`b}|t|8?xaGM%?J;n(mN47)LH#u>8XHR^P znGXuZ`LyAzhBSirvpC=M7E<>AWlQ$%1Xa!tbek<=Zx6Z2vI%2v^u&)uiFEH5PfHYw zakOSKv0Zya&`N#9QePy(a8u5HRI|bEwuLZv)(J`AX#$Ro zvEGE7Tg_PkJ&M@cny&ljiFdYWKJyjS44Or&2RG+OwP){XoBPeNt?CQ5i0 zUPD1PY%3flQg_y4`vh~D7i&hPCEf`%BJ4vZHP!sWmb+#_!)R6ZuF4Xp4yuN1-6F}7 z1`{lOa2`TuKc;c39q_+t+2E3`Endq*wY~GZX68`dzP4nHF^PRFP=y#R^enH0F}wKN z+>PgbqCNsAo_Tt%@sdVb?ojQhxDl{Z7T zyK2nvk~@CVbR>&+B#VE0uHbodZ)ktO8Na(mG`bm=VN?V?7O zwJ;ghhp4bie&)Ddk^`GguaN|g8YeAZQ$?=cv4oX3jM0B+FLL~b1{>jgkzK4zfY1gN zwsf5>j&E*;>zn22g5>ei=chEhQqLPf!2n&1EY5+Jn=0&OrYXLBn*}kNYNFcLBI&o7 z0p5g2uwXKS*iTkw_O+87~fUhF)=3(fw!j-%q z*eV2kG{VZU(vau(#-IHKc<=_7vXO9Wa$Dgv=`z6qk%I^>T zobYNj-|wtx7dhIbvg&S2VbRT9Lf$(Uoc5{?JR*5!RVm(6 zdy`iC7EyJpBgUj_6GxL~VX6avFDHD5FVVNCYsmnNs&0gZR*~XeCHI;B^-Z#O{ZGY# zxIDB34%@ra!g1PCCn15%U3*2?HrN*5JnBb8L#pZeC>M0&UW>EK?&dx}ScKOPMUW8b zRbj=}UU+X^5lrHL%jLn2_#jFGbBZ*@M|Z4c1B@D5_-S}D(VKomSRi`NCJx} z{Zq}|ao|;BvPL6LY_~X;<06%<(i0tik zSz4^QZ11nyW`#|syAv%Q!ZhmkktH=>fLTo{?BZezR8Oh~6Wbz*&uwFD(8>hoDUa!X zM|+G*$cBEWw8b+scd_kqak96(`fhvNSZzgmejG=?n`z=E!-wD(rN#z*utQg#H_zHX z!?P$7r0<&Q$xzefP@Zap9eg)>ttE{{2#u(!9!jqG^%2h2zhkC7T3~#o8VfM(hkkz@ z$dZZ4;_MMi*^nM2ILRZfcbk_Z1AvwwLC|-qqh~_Ms z)#-5Ii@#+2<1tdpswy&6Y6*Cdd(XmpkxS1sm~&eeJMb(4Dj%ybXHOd(65b3Q#`4r? zZvn=pN06B=@xqA;ZS;AZ11sXV4qVp*PhZG}mJMp6!M{XOlfWW!cJ^{8s^T37x%~cl zBTk~59D|x#Q6#6cL>T+r1e5(&-a8GO`h3nwR#x~@Mn>6%5XuM{ zrO-|`p_EiYNcWuQTJ4O6qU_xeEgF93ckf@|rF-xDJkR@i4+jYxpe|2qdl|OqN#X_F zO!K_4QZS<+hO;VGBIF9w^8i7z{xL+7?*<327`%erD5En~A+DeCmZ^j2cWVduw#*GL zT>RaA+}F|I9X1@hsrB%O)|-Jvy8=#XYb5S0WBhqmJnq!>=L?;(=-cIM(ez_13;K^a zJUCj8Yv`p|SMM-^x*e?%X|6n$>OmO3h}K&B z5ed0aP!IV}tIQf}E!w zHvVlcc)QyWzWTPIl!hLn`rQE{hqj>X35uNb9c7vjc3s4m-ubT2@c#xs;f+Bd?s@rr~t9TZ@_u2t+K3d=+g+K1mKds;~OVqHG?&8z54B_v+R&-_DJyPiH z0`GNyqg_W1acg~x>8y1-&_(9QPy6HoX{>j$FvNwdX1Cdj!st zuP3+Stf4t>0J+^Hg*J^|!UJ839%ELFLyKPNK?X~}kY~Q>pOQ9^R7OzbE@f{0+>LZe z+aFQROd8gQ^`C6COo z5yVJ7Mq06t$l@qTVUk1wzL+uPBn?j1`u zW@-qPo!;OE=G~JFcuDo66On+;2Cd6kKFN>AXz%j#g1{3Kgtb0(c=HrJRIx@AX1zR# z1_ueqx1%XkYH&PS>MTe1+S|e0GIji*$cCgDPZthi*}NU!r=T0z1N7Yw@$N4(#unxr ztwx8cYu$2ECkVr~*5QTB2i}~c3GYXoLg`x*NrT-s@IjHdj|lkZ}Q>kI%!z$nk?G= z%ZjyOdE{9Xy3Ora$qK_H`(M?f#MTGg(i^6>`K-Q)nx93U~B+^C_#E=tS3U(H#4mWo&kAu)&|= zk~sC*tLV0tiK1L_>pKQ8Mxq^^r(tB{J$YgNhWl7%Pb%+W*hZHS@$Ub$Mjg&+rlYOu z0RqSWrZT&9H69``M3Jm-V%Hl}mUE><-@VVGt9#IL*XxK8 zq~c>hVQ?g#SX0K2H`9UJ<0P@1k^+r-;0kns0xq9&luLQ@P+)siy!%7yP6{F8vvYu`Fdn;0wYqQj841F}!*R;jZhqWf)^!-J zi2GBUh;0Xe#qdNt-f<=0|K%z*v|cBgY1=AvV3(-?jqr3PD5VD`tvZJ9yt=|awPYC% z(U*{$M>ko#A%~8ryoyQ|$kAj+YlyEqoWI;T3Mtf9i0dX1xpf@(y0<2x8X9A110eV(wKbjyaoBl}1^J>o21Hsl5UJ-Zxj zDv+lMEZ0l#@L;T!{m(tH;smYUwH5`XNAMM_x3Q_QiD|>$lbrz+&h~7=3iS@tKH>Q<$r)vM)b1M8Yud)oqgz8@~Ae8%z|Ms^_QGyTMF zl?{vt`G)>$m*WnqDAA`j*Lm0V>^(|i`J8_WSQgfPqP$#Ms1|$#|JW13|Lx1C?W)Bh zoxsE%NBFYH1|O9ga6di3bdRknc+cQ2-uJLE*m`v$Z4*M86OhF;F0@?|ER#V>2ILr-~NjHv&)w-zBj=RYu?yM zmdyD@4PB~G)Is*HMOcE-rUA55M~W*mK*DtzG9K^wU=*Wn1eeD@L1_PD@?O0f)^u*h zHcG?zF8yv==dxeK56};zsGqE}h!DX`v!q-RY@Z<%0$a;l2_%RGw`MH`Ll}w@En8)`2p4r29ZNd7l zI&S}LLvBs=5|+=_^O#XM1x=hkK!2ee^n0WnExTe1r;2J&%g;Ku%g!FcZ|C0NHGemt zu_0REx#=|WWZ6@%y0^ko^GIA0Bjo2LNWs&`eQ4W9b_Z8x-1T8?yf*hZ_x$EjIwjHv z-7A%$=|%c5S^6bv9-2m!9E7lK#1?!bX*Pdtgf#TcPDV3anJ0^Bb62y8X{#5brBztO^1(LuR1G) z5C4gO_N+tey0pNOX~5jSrIW~K>cRk(Q}|hyH(xFBiXPtDjXspiQ#oT75VSht$x}~q zk>C93v<;qU>th)@c(WcPE&hoLDnd!mUOD0T^85J8iBx|7!WNohlZ@7%V}8argCQ$6 z9R>Rb2nPR>6<*za9M4)-%Xiuj2Fb6ccu|icH4A?M_it8V&v~)@f~KoAea~_ zx^t~vs}EPcK0>~`V@Xg;KX484c-rCv{7x%XXtzp18;8i!{gSNTY7D|sf>!tUPhDWc z>EXDqyqoX%VFE)ZDr1S!@5p&mOOW3zf!78-=H?F1pt}F96M1GYR5?O~QzLTyIfLx| z*ai2Bk6{-yjpg;Uy0ga z0X*Hc3D23O$|u@4Qk&=DB5pQ{>6Wj{W}=*AC9)_K9w4VJCwcR$5u^~Y+e_?bc%ub!t352d~#&xN*@mLh4YG926XxTdUB+f47vg^ym z-|60Rlo47+%6?Tt#LR72wpEW`>eflaR_qt?4^zjDfsDX8*rzFzyV~SJGku&z{Oxl! zWAJ~eg!76|km+;Ogu{K_u;0jM-r?s9YIQ47q~p?JIn2w~zeFD-uM1j-=tK4ID@fu} zIk~?#f!@^sx~%W=t$12oh)3kL(k(<^b|Bh=`X!;BnP>e%h5kdHZW^r z9a>>t?-o9s7si*q!C#MTK%#o5k~R| zZqvqg&yRCs+K*7d6CcqnY~>b1_>(~?HeYr!-;w7PmOjDWcf-<1!7Fr zm}?Bg3 zjr)p5A71R1K6(g5W0naYca=EZA0+GwI))Rc^8D-gIyyL8%tiES4~K=}j(FO`RLXo zE04+uH?uB`skDY4BlUkwGs9;zmFSD_>GX_$g6RHbn`j0ZegBYmiVXSmtsHdb$Kn<8 zr}zq6MHq5E7fCWr+U0k;@cm{!noO14(Q?{}hk2T@Ucu zx+*YswHR-G@7uwGS)SPC)Ngm=8BVbI=5YMwb~hh1+X%MTvRw2TZ^`P4D>T1%9qR95 zS?j5mVEm^VjU6uTmUe@rL>>d1s zhk@nc%jjyvabWA3KOExspW9o!6lz zcHz40Zw?!hz95^P?L>hI}vMFIia*>9PWCa%Wr0x6mO{Tq{UlEVN>LFiv&j>=C{;x5Xpy5ZDUfr$|t(~XMC7xVI zrHgt+vu;<1A(WjTg;CKSlCwJ!cCx&b`>APs-kxU4C5dr0_`NxNke0+z7o<5FXatYT zS&n*mDJk3e6uNe7!8^a`@&Si_)2HeC(V1XbI^Zx8R!^RTFPzWheA1j~#u;aneno~h zd^Uul6lI*ZHI*1TJg5K3C!sG)hc+UU^%1kaU=95&K{YW3g-zK=#iN>-rpM8Jaq%c- zrX1}rvV^Mhns}(69hqh0DcsMzMfVp@LB=iJwC__6Dn@d&fc0?IOn!-iZr8glka80$ z7&T$vpg`ovu(Z+l9GaPvLNzrb{v3&hGB;)390u77V7 zT_fcy!qTKg`k>n1h|-kO$=*>#@P+w01081by(}kIWl##5$-G6AMjAnCYZiJJ>Mk&E zaD@?`-uUg~e%^719ynar$4R>+sa;h)_^}F=A(M~tKOzfhr$!Il|27I#xd`YUt%um`%jgt z+qs>Zg~p=TELob*{La1pMp)^T7m1r80}X>-h`5Z zjx>~l%IaAB+J7DY$@Uxlyf<0I<-TCqeeH4tovqv_=z1V6Ty*XjUcI`SpZ;D6UV5A1 z8UrQzNbU-~lbnFA{*k4n0uwkSBY~fW$&h!pRp1z!fTKsB0Fryo}@=xM!4nmX-xWW^POjh!bF$L zs9LF;%)699o41KEGjka8KI;y}i9uJ3lKM2EAon?XI!BhKOmTqW`EO9Vss=aQVHC9} zsO877`$*=oVeoufI+_#bPiDB) z-jH2~_8pAiPk*+6PtMIq&##T-2i^w-ZVMiNT#a9Mznd%N@S&J zEOncbfilA6XfK;X<_0+8(3cAxFf` z9%mh_7sCrtfb0QLR=~#0Iyk;MPKe0^8;OL?4j4w5mR3&?pB`>>=~_!H&u7? z3v^7NNAe#!ulShQSGvF`#;>+H#c`4NyANPotYBGR@4Bz%>OVF6-!{N`^ zDrEUVn+v+ThOYeFE7D?>mgs}8>S#Q}Dx8dsJp_lD7UlGoH2z@GH)`=jjG5CpQ*c`^ zfy3TQar5&g3TF*c_Q?LW3u)%+Lp;-?zPwvZwtH8Cm)#cpe2*^w@P0dOc_HQsPE-%4 zT7_bsc1XSnL+?4LPA3 zM^&@pk=YXV?##7-(_I?)QnW2OwyK+|8{{ItrE+xCH%qVytwS|cFWvk;xe2E~eS-sx zHlUL`v|!oI^T_e@2{LE%T39qW5|5lIjkCCw;c?i!*U zC4kF4Ay_Luia)YL9W1tHp{X+^Y0Lk+il*eCo}FXe$NZM2+V}L4nT-rBvM`0`{>&G@ zPCyRD)zk1f*U?uGIclk43yrTkP;|pP!D2mkp=Dn;mh`qmp)4!@q~d*~_2etjVQ*u9 zThAhT+-Z_X*BZEmbpqb}i{u;jkWVDgx7!3Rx=`e^ zX1~B8$wRm?y#{};HAGgi3Q!v$o|@xnLf%CT<3Ml`%>I5>ZtjmKJC6omiX4^^uV z;k@)>UiGdTeA_LFLyG0;IWr@Om;Q&EllOBC>!=|6z!B~;l_yodS$^8{V)R2Uo>*m< zLH+8@xc87R@7|#ZvSlf#Qj+;fjIBZK#$-I#xy!w8nH_w2Jsgib*v-c)o3k7eP3(H1 zne=JDfb%9-arUVFd{}B4O^X&|tVF6cENgj%uC{xT_1cxNdr}CtdUcGSXr>SQVl&aW z%mJdSe}&%Nnu(SM$Wg<`*3hFi6u%vFwP?Uo3kt((P(qs=J;MIo=%a5?!vl3L#%l!C zOso~{`=BxmZcJsK^kV_!#Qv3#IwKN49)6bRA3mY82Fj7e4S71L!3h>DFv9-+%G}iJ z@w8NVJ%Zm6eA{UYcpTh{d>6Kpx-A6u6@}s~XH8zh?Ilgk-iw+UhL8C_C${_=va44n zZ{v^Bh1MBpHq!##ooWmJ2^_I*^%%jWOFFPq;x}sHdPywP^lD^vpoNcBI4ky+8)k_y z_EI40>}U}nL-#|({MA2*CeirU`w0H0;#K;pxR~`%$YuPKV7oB!zAs}7RlcRj{g@M3aX?l$>KD@+ zN8jMvJ8Yo5X)1oH_KO^Jw1SPlW$>8u#f3vBmIGE!zz?KZzVUP;a4N4t3PDnI?Q=T_ z-BXTov$Z(y*Q=)n6rZB}Bl1+U z(F9KAN@7`sL7YiC7G5z{_V`}03rU?Zgi&8A5hzxWl)7?IDBFV5uIlo3uiEH5sR+^T zZ|ySFP|oRMpx2j(MhaJk!k*qT0qu@dUVA2 zy5JNTLq}#V`f;$1R2(`=p(I|U*NSN}fwT#lxHQq0>||cc-(I<>X*`=*$O9VqCrK zUJwj(DN&P?i`YoF6Y(w| zTCNKZcw;QRcsdDLCnX*SVc5ohuAYQSwO7IE+TjVi{%I?lS*l zKG|6%C;WOp2`jVwKohnbf>jR+V^|a+;Y(9pCW$!JJ=6d`wfsZx*B&5yJ3mshuj2W$ zWdCs3-~Jr+e?KOeH5dz3x@+*NXND+tChKsFHp4-~l&Hd+3)JLgf=HM3RL=-5Uun5E>*${fcbhg=9JU)@k5A(S5wIBe)Xpm=lcZ7|+mi zelCu)yd<#Oz7G^XAHo@9N_gc)73hnT#DAH`K_kNmw(Xb1DEt5y-*`_jS0z%E+2ZY~ z2M4puQQ5^rQZcgx;8!qyRqn$JKPo_z{0R|$PSR&wT>4zRZ>bcg*~oemehlZo$ny zNBM0(hCys)CbBp;K$c~t(VJ13qI=ee>sAnCsf#NoW)^*!t_kJ4Ytj03^7Jgr0}ndT zh(5Rv=8oID(vv=Qq8W8J>!a~`m5w%?@+UC|mxHudB=%A}%TLRENOgaRXVmghc5rc- zK9;_$!1;E^(){7;Q5nOoA8v*a9{3pz>-b8>E*cGdemhc~c#IpryOxgnv=Ky0A?L?N(}Kxj{0ykEgOu!nNK)a- zSzfTfI9J4%^79O#Z<+w5r5+@L`2+B4WDI_-e}FfTze0Vki}!l3Kqp9hF&eviC~)p_ z`p~gY73;m~8eDkQdP9d&T&9YKAR1=CIFko(tK# zLq@pQIsq>{aDxx}V*}GR&%k+hU1WyP27GTS;5o9Dg6NL%0{GSJE2mevuDrOFPpr==0bu?;uINxE~Y@Bk?e=G~QnQBQ2Zp z6v-#a)BlFE-?gzMZt<4pwm;Pcd0{EKm03*M<4fT`w%3oDpv%*#tyH);0xge}rN^9j zkndZEw;=&Hbfyjc>g0l)1u}Gqr#{@28jPI^Pm`RH+HME zI4dLg>XnC{{i-9I_eIme?c%-u!+s-Jud9iJu`SWa`bp~<_Z2l)j+&@jvU|N4GtYKt z!Ug9`Xlu+V(wgrFVg8XgR71!InzU0d#{p5!_8&LaXDVZh-}+zR_R1cl*|okRUzK+5 zFnHtm0e${2lLVv{L1Xt$d~VZx{(8+{I`vfw)44H^SSq`-z%|kS?(~^u%SU+Qa}oV~ z!YD&%{$h#OCo9nG;%Bht9(%&(9px9x-lE*>L{UC~W2_Do-)Ta64hzZP^dgWj+Jzl= z#qiM&2E%+m=Hn=krk=e9@L^{TN@^P8et5wEnXyeD1q%kz0c;2XVOCgk0U;q7)%0oR zbx~HptW%ay>febx%HIhtEuJR~-m2n(S}^jSZVDg%Jw%_Zf0K>s7I5cA0Sfoi^uYWkF?5v{)=M&O@T~{WHI-0qNss70l{0=meY`@9pA%W1xTdEB`o<`|>!Tg)**O<){gEb!YYYd46^C)=;}Sl2m@>>M63?O!=Zu12It0H~Oyy+O z=Loch@8dGJ4G2aC=)yeTa&*Ntkwk_(0V}=D`1N@ozOq^#_(@_cy)wcPj?SBpC$&g( zfy>yNHP{Ic3Fzj(#hAdA)FJqe66-)5QVF&bui`j`{d|Ydd0J=}h;ILrp^i+C_n%fH zTCrm~G4?2ie620G&h{uD#A|@6@FJpazsTm0B~Z?|{d%kI{J-57=|0Kb}VVx%}=$qc5v-vpS{em9iXB?~D@LDaN}!K;3U5$u0X{Xcb1|H9I5t z@X2Y^pU9`h<5Q^dD4s|qdTw7_V@ zBlPD}7jX@>1=L)L)TFezhiU$_WnRCC7oF5$0L}klyvqDAxqNOfxEMs@#a65{%jq4R z8Tk~soRp`0oIU6kso*dDYTQo7QEWA>L02-K6N~uAU?CTbGsARvedlI+Jy1Mzp6Fp~ zz~v42usv{r-quuL=py1pUuLqN^kOaC*K~n!E6ZpK!_WWEobFC$5WT7%-7d`*Y-cmG z+T=WRpt6q4cUuCJbt7@t9vA-cuOpOGOc3q+Tgq5Atgagjc{6^apZ{cR1Y=fO*Y}r@RZE`J zX@9OG`T25`Uuyy_yMLlexkkY*iMhfi6;+SGa1UglWCq{gJweBobdg6|Z1-0ss9Ii^ z8yUZv$|%R7t4xDbS7ZvhzZ~(ldw#^TX@G9;e zC8C$?UN&>aaF|)8j?XXEA(gKl!ie;Ed^YJcKXKV0NOQY^-ZAgM-P2Z3wzC4Aylm+1 z$M~Y`qPcjyu zBiS3bQL`MKtx6!8e;&bj zH~(R_G3Z2VazE6a=*WgTk(Vmr*%0{Vm4Sxs_9sL0d|~%O=287}hMyx#XpFBI zCnvNx!Uhj>JZbh|u6)r^y3A_5=w3hmDa)%&Z9`ER?PTlfQDA?v6Ad38%cW?(pnfa% zA<3z%-e?vhr+jY z{YXAVidwnaz|En3sN$G9_jSB9?aR*<<*vMDd41VOgy@Y^B>Cvy1I*lphbl$zn*z_% zN!{XE^mgNLRs-RN+gp`63FfDmQlN_0(@wr;zbRDP$>BKVXRO5X z$4LC_-B888d*9X5c$vvfbm~1ZmTr4%2Y)+N@gXgBE~3g9ejR#=ZWY!L!LUbgJ1rQ8 zUDn~-kAJ6s1QDogFVm(Pj)$mGL3kIleDR~qsoY{QmX2@Jf%ScAc=y`VmVPIhnl_rn@; zT#T`m=2%kD^Ml?Vn}-y(%hBmu*zNn^M-+4LquV-nE%<#t9SzJpOJ+Qu4?gQ6aZxSs z#rof=PwoJsEThR`g9|kLXM>eCo#!U8UXnMd3t2Zb%ecO50IPmBqoVP7Ol^N&GpcmD)ElAGwT?rI!kHVPkJLx?3>H z-TA+65?*3}_FtEw1^>)I(!>>C^)4qX-&av*;~dmKOO75$HG@?ryO7n2_kv?xk3hNL z5Kgte%cnopgWPtCbi!JQTNcY+n@CW7*HCVOgFhuLv7$_sRK~}mcTPA&YB|wQ@1^M9 z3uL-co|+G_1sNxHyIC6S_M~nYL=+L^`R5KfTh;}CTcYta^YMHF2x-yo9#M|U$lTeK z1M&P>=cW(sXQi>t!^1=(S3@{SzY$Mny6bvqqU(}VL|kZqjXj(iUV{>!9T%*Nu=(IVBsG9kat5(~p%rxzBNSfK`7N<5a~gfns1NtQ#GPSLBxRwZZb>@>>#{ zQF%IRkt?+6=wM}?lbn*AHUzReY)yUwxiaD*q%wV=_G2GjqEZ%CHJ(6!^>#X98zNIpLKq-F#s`%Tye$k4uLAAwOD6VRJ_&c2;9ETlZ;t`(&V~-%!26 z3e=W=ME9=EA!i*Qf=TOU4B0V!(&E8D^V86u55LHd%Ku>Hsz}_fzn$02Jxz1XvrzPI z#w%J_f`ywQezPH`C^uXczL(Xa+e{0TE9D3=)y*j4j4n62)sfCW^OBEQ!1#gSA@G>_ zv%+o%5P0+-99_od%;#tL1$~9od|n0W*v_)rW;?+7!4`Pd`@!6zkI_`-#(L2$-tvbb z$i=X?eoi}?66?xxFgj4c)Z<*$#AnnyPK=)kwJwYsEJfe0niHRU5j0&R1C_pD*>SA9 zBuij<|3Op`X#?wG{vqwvh6ex-nq{H-PqLR;9xI^!C@#Bg(S?@+ZRJ5i_~;~c(OfXn6zv}v3RIbYuk znPtcD{B_s(9WK_8e{w$7n8EJvpBNXqNd<3ge_rS{Y^JdCKRplAAv4jp51R03atTUh zS-b!4xeFgo4kxAfqtQ^hbR(j|GmhA$1D2% zg_sLnwbTxV`3=V37HV+gzZ=1-%k}8=@mgZERtWL;S(ZYhHXnHQE1mR_X)c0g>E`0m z(6%55_dOt7#$yv|9qS_U1svRE1aY%;@pbDmyvD+@J!t|ICW=D_qZk(i(3!arPaknWu>#!msuVoI<##xLHEA;E*bQCl|4$ver> zz?T-#u;ByhG5g>)`M4HDBr#p|*K_3aw>dC$Gy5(P;Qt=|OnIh@_&n@^zLo2*JyXAeeEQdyeWQvOX)*JT9WI>qQpOD8drwT5C}imsl}<(juGrSC+^r{15bler!{_|N(9?c9 z7?rpb|7^P^(A^gT79NrK_K8w{MYb#~WSzg~m?qZs(kKXN(8F(@oaN-4SpRPCQO?g- ziAZVa!>_xwD9HE}d9X?d`L^6FKzcUomRrr083OB0B5LPS{ zV`;6c8LYi#fIqOi3AQW-)3QvgP_dui8E}d&_$S`kT{9fOrMVT|FkDR91BI~BWea|C zF^1Q08VqRgWi%wJgY;H-!_Os=_|f}q{M(5qX(*S4cs3jSUd6JJk6Yrt-FJ$fsj9#c z(>k z?$Vqy707_;ikIATgkJVt{U@)*d2BsGr+Ed6Zb_+e#^Cdj^_m5;9d@$|bnov(N)L{6 zb3&@<8zRQinLAv;d20pAj4Ex8>v0*+o& zz$wR*xd*McsdJ7POIs?-qvW4}VEX?6QzO;tdyBFa(rqc9`fi+AC zQN!N~YYG<&yoBJV=P~W$4D?7v3)bE!LxxHNS^?Wtqe43ZgyD9^Gz!Mp& z!)B6$`{!U!?Rau)c?jHL8VQ3}7x`&xU(x`rXChv-ZMqXo4%WtV7Y*eW%UQrkl@G`* z<_(#ZK>_z|!mF#a`TW11Y2(NPsOPvWP4wkqq*55Z^S6ZKz8KSor^Q%G*^IYu=1@F^ zyG&Z;9#L;T8C{*mFeJic1LWaPdp;@RO zUtqsYZ)jZ_iC>-pzU}cRDyjYteb!N+Nh}wlcdsp8y7&TTsK1w1r7aZQo6de>IhGGw z(Df5}BxT|=SlxLXkCfWVANli}h9-;WQkP6Uc<6cqo!sLg_&C)BLNmQ_j9EWF`M;qs zSJwuQR#2k$4cF;shN}h4ud%qr7^ZLPM7JY1l7gb=P}>uW2YouvD|e|uy@nW9*R#%% zulNSiX&UG5&h8V_j0}-u3F{C)XbLj|M&oG>PstA3GHR2SgIqVr(M|1E5Pd=t`>bpc z>`*ad`45$-;e8*8h*?DAH^!mwpIKKI(TC`_PFN*<8F3aKflbnp_@Gt>zv4?LJ(VQJ z)vj_YSh-6Qci}B=G0G-zY+o7bdi;QVvX>P)Yo5ZgESJykZz0{F^hd;nntvV-d*$Zg zLuc=D-N9Zob^T8KHtoJV)b01;)@P^tp6yQw1WA$7OlZOr}70eBZFbv zq)0p}q?DiBJP0(sq_9V$Jf%vbKxw%FHn2a>ZF-n1xW775wBtKX*Md8qm8hyZk#rSP zs5rF+&n7;|kEtih!((}#i(C%nk2n=h(10-VKilLG&c zhuMn4n~&Qt2`=FC@2Aq06N5xtXkRAt{rR^bs|^dupaKd;2e;tl^D%tbq`|PCTtP!K zy2zPtGhpcINIa)x8(%AZf`&z9p@L*N`elj@M7LSsr56i|211osw=e57VfX8IcJ`1P z)`rgf9LCukv7-(T#JKvd!4RgV7BIefJE?m+1Ew%8^vszvJZ!p6Gn*UrPC@*E&Ro1)O*nx}L^t|9!NXz6 zqf(@7ZcavK@1dt|ig9(Wv<;LNxZ}%$DT1?uVqg~+g^dI2cuQ4XQ1Kpwdw$8WY(`7i zJ4*srXJ~T1D*wou<$0nV|3Ih?_^lzxdE-H1l>Qea>SM9{hQs`HnGJ~f9;S}o@QzN&3qPg^ZjwN)|EXG$XQ^}6)!O%4!5-S&9Gr0Tg1DYrEmbAqX2vOdQJ3Msw5|d99uN7mdgx5G& z-yDh$TrJ_|6zbEYC*r+co^cfKQw(v!(=2ki188GSGJ46dSI)u$wl4gF&ej(Qt~*m$ zy>lzBkI3c^_LzYE();M}^$*0MYZ~~n--5lh3r`mBqs`Y7(4Z}HwB6Gl-kr3?Ut=ed znui~0pY#nBbyAM*>o$e-ppPi=_y@NOs`G`bM$3ETEjW$>n775pk$HkDFA{lGFW`4X zVx7al&)@ZiX88U?bJY~+<-#!f@QZjx-N0_d5)Zpk#f>{8`ey}lJZ zhq4`?Y0lkq$K$@l8ZxrDnD)HMK~tH2Z*ZIikm-_mNpiE`l%_FgE-pulcK#*P=DUEo z-cvL*+k&h0SwI^ZuKu4RU7=(I!kwe=#uKYa(}PF|QDlGH?sQ(g?H3(gF2>ci;}+29 zC5eAr*z7jv>Lj68o|4DHfSu$~jm~`3@(YI)x67nv7x@XQC?0vM;=punu>e>|Rj^2@GR>+z#_EV_(v#Q%;EH z*pZWLKzZ0pB+@%u;?W%Qt&IT}rh3zj*BguFb>n<%lz!ym6l3_}nAh)U9%4J=1b1qIxv)_-TTd z3SgYV7X1F_0$w9t8bTsdMZPD`N@s|)-GrCU)8raiKSgS!6P~Ev&7TM~0EZNP9H#Y$ zobz}Mc|R#G+?K#E*E&J(Mv5`^aU1J&KJW&GuAM>loFHJ3x)sk-J<6|{HW(H!%RoPK zdx)FNG^pGdiQnXG<9#nDQM3Fkrk9bUvU_adL$VE)izqCT|Dyn=d&L;*XUY1x*sZ+C z)`(j*!j_s&s~6<}94NMcuUi34=-5Y2NlgQ}4Uu?I{24waDxVtu6Z5F%rR-++-Uc_^ z*5V4357YMyV`n!+@LYfi=xX($H(LFq?HB8u4IMz{X^C8FaT#^g+K-%&EcL(Z00wtU zk-{r8BIy!F-}Z>__uOv|kmCZVYLE@drLXh{G3LbNDG+ZDH4hRe0u71v+toEs&8z@Q;SZLU+ZN$JtxLnH%FG)tF{Oaf1W~Gf`XuIWF$Uv z?jmn@;W<4U@eD0KCr{_jbp+4+p}2b9FfLEV0`6*lMN^wU5T7avofg|LIit%@9{+(p zOgtdE>7Q~O4RI&K@J+2!Zr$c#bb*a4x?jWcpG}P6{tIKQIpjKdlt<|2cge_pt1KPT z!Lngrd`8+M3Iq?O<_iN4DR`V{$7uCd#`CYgk6KrLAh)b0L*-&I-uCR?L$4Jkh_YG6 z-8O?2(dPK$IyW+M%6s~Blo)R(8QH=JgLZW5bDP`u(+2R!?k>9jESsd-PloLMkyv&c z@ZLXOQO9U8#x8t3L^$+{w#U@5$9NCx9W*UwktnnJlN93{AN8Z!uKOg-MpkHr1h^{a zJb%Wrm0G!^qV!#|H2Xgth<%qQ;#5y`4u#)uz45KqK0c>R9b%5z;IH~hRH;3KK4h6! z7uLv9TR%N;mF+|^%Qg^XRsl;Rcl59 z#oQ3tU67%#nU{IZyzzK}bPX9{_?T{L%n{wE{-#(k51kZVJ)uo7)sW>zb}--fr9Z@8 zI2I>3ruv8y%!rBl4fx zyE1;5Y1gMt+u}CznWs=DUD;!A=wXz*Lm$Rfm!MG>fdoIPgyEOAV9jo3ZIea%s3Zj=IA*Vc)I2F2o)_*(z8AqCd@~6?#yGp$r>(9tVblt(%s;XxA5HRZrq`I9DUOt0fB})uz55Q z%sa6bZnAsjNXJrsos%Tg2T9@SERRcWj01A75$P^IM=Hk)pln$P zrgwe$FA_LhN{f5& z=ns)Pktgy)o$S(sjrJu->UA_}@QJ4>Cri+s?{aiA%OZ2uo`Ok&7T4IN0y%TVxTO`@zIiS4W4eW@cTw}}JaS&c4~B1y#jP`duTXBJ>&^_IbTtJ!ceaLb(j!fu zimCDZ2Yx#pyL%p*(8l~kvvfdb)lZbNrGPXTR=}*a3HaRG&HS#Mb}B#a1ezWxOCJwt z!pF}y(EG_);5bDa8lDE=x6k|eX`6<^;Jem%qo)%6UUG>#K21g6Pp}@PL5AQ~)r(H_ zhLV(*&menu3jS<&fj_!xFf2A;_}L^&uMRc=y$%7|hQ@h==3CNgZz$52n)MsQ6ax;| zSk@D}$`aaabzQXkAFyQF!o#w-`(l?s=HnB%tDJ&gjVkAFsTzXupenTT`z(7Jjm((_W-04b+RgHHeN&#on!atg^Rp>WLvGOXfxT!A(|!;A zIU4>LF2a*rgmNk~$IbeZW1~ z6gq#sL}7XHg5>A`;pBZYOy137BUx<{{#QO8fa zwTadwEZn_a&u7|eGbF9kN6la6BlqEQR8q$RM((LYUxen~?$QB5$!ou{+_9s`>!A~5 zhVH-%@`%9c+;X_UbnLej%lT{X{?Ub}rLb>eL~wzzLgmbn|Ur4PbfGaJ(c! zf?hoK3Yt^_8~7&kv?hg`JFFLJ0RG-I1JC-e=$-LgGS;h@WrlCVAq_|Px%X5d%_SE( zr2Zwty)b+TV;sSrZTy%Q3AFR8_&)Hf*aln&9I(0-6zi$UL5o!#8b69@P%m1;-R@sV z9vg56|5{MBta{Pib;DRQ&WIM?%34R zh;tM~Qf-xWqS>{S@gr`Y1885~07>;34Gvkdxb9;*CpYskeR4PgZCNZ!&u+E`hm0~b ze3uC+d$*BRjLQ-ENs&t=jM^TJo%g@sEmo<+;b<9L!}Q7V>sU^^jU--Zq0U`A)k7K; zZi;RK7jz6jPgse%t>THv{0i{x+JxObmN5K3N~KH6MBdVs)CvB+48Zqp>T&+vO5m_r zjH|1S&0ykXHLU;d9T~~|HRJF8Lx*zWxY@t2(fA>IMZAAZhbfrm)}W2r9>m6?3aXh` zqOB*1zcbhxa*waWiK)tTb+r{_{-=erLf#gg5U9h6wi+aHZxCJWVGCQWU!$=jjkzKI zv*~Iz3B;+(QuFDSaNcGOu6vY8s@U&JYDz42+?UC}JzB|fTb_%uRmoqL0lU!v+dMVo z&NVRqqhu@6Ufx2!Jt&4fv$o@b4jq2{nb&lu`~eZJ_I0y;N?{M4{->N%8>2z>9b84a zsjRX3unLCb+_J0WMSc;Tv^))6%aEl9mYPFb>UR`%qgap_KVA6OLeb~+6d$ygd4a26 zJwQ!OU&+5M9L!?h)Bj=Y@!{KOPHQr%4V0sU`*oq2)D}y09E8`ux|HfFAADga7>Qp}yHy$@O_0SRRhWmwka>_VOjI|0BM&`j`z9 z2JF}JDJ+ZUL+B=YwrC#Wn14|9v>}YrmcTZ11*9VX5nR(uz*&`{eBj{EblANUXeRrn z)G)uBxdtHP8Pf&V2dROQ{B*4Tq@Q2hIv9?gw8q>|MOrI&k(%osLw#r2jqy3lm0dgt z3&X=n^MuFXKAr72Gtcsw(-dJIA6&N_qq-Cnc~MGO@BQojHyIUS9^(- z67xbvK0#kvO}NMz6X}pwi74=!EH&6+4808qyY1deT7(f$sve8yrDpS&M|`GJPSv1< zEP3jC&JwE1<*;%8UN5yaUU+-lV4u3OX!LfuE||`%Ksm`mqCC9}7XP;i*H1C#A4p!M zni;*K46D!fqu@=!B3yw=xLvk9{oOC-yo`r1yqYlt2Yyc^Whb5i|K}2ZxH^V^z2pUb z{`WYV+sg3D&IAq|uMuhf54r^iFD&?jXAky3{=+}et19L!&qRq{2|P+;ZBj+|*!Z~N zkULWix4+dQ%|c$d(?Z{;XSF#hDD0u{ObXC37p7fg¥JLb@lcyhDNlgeHgn;3(Nd z6t{`-N>w}XQzmJVy|VoY$BAu6_(PSd(9)NOHq;Cd67J1-J@HJN=^jt5o?H?6r!1JxfBstsysDWN-`Fez zgWc;yx7pygmhj1@6REixaCe`ZQ@xM|k$zxvsR=AiEkP+yB1q48Z`ie)<)s8>@CmOk z)1zzIw>ydD#$-FeEapqv7G=x@YDUo131aNER@MR4o*v|A@|&clkAmPnS-eU&gL6Ip zh{ivTKw2AF2fl~?J7 zoV_TCz1OK^WvG--hnJ|8Z zge~mq(!7$e6c;`Z!yHGSB<#C`z;~r%r7)G_#073Qy0E0 zD8Vl#Z05T@HdEoW18C+|SsLr<0E<=k;*mEhI4q?`-|uln-HfA=&ohFm+m_f?vycQF zx=V%Y(vVaHn-#yBgGb*_)W@W*0eYs;Wcm<&fB%)V>LWP4>@ZH(9LW!$P&R23ktOMEL(TVxG# zgPx%4nt|S~ck9TiBZjE1NQRDlUMg6`k7DD=XN#PIlY`%tu2MzmQ7eN%$T2c?lKL_ z=@n^N`4BHEDLY=2aXpx2(Pz&bhQr!YiEPj_%G;a}Vd)gsHSE8k5oupY5=_1Dmflh` z$D{Wu(UnV&uzfQX&C-;kedCSbn4=m#cU+5DZ0e#*))$~|=EEJ?U16Q|9ig6x3>(9HPpMU7?rr-mM?_*M$1zGu6$n+H5~x4}Lk zx!j%@U5ImOMan-iNv%v1=+8^SOM~|F#9@FwCnwRW1+sKope<Ttd+zwrp; z2M@mN=KEBQz~ZkZ*0f@Oi~K|?(Yzi7+R9R&i&|jQ)q;{fPb4?Lslt%Q*HEykB<(!r z4Q=ZW;VXM~^HC~?sj^zGNROJ&-jQ?(4@^qRi$~}Wf~~1_BHjLF)}!RHsvo6IH{r4u zno-AGF&@_bFopux60~Gt1i6;%2@BbLYwDB1d;ZC$(Tl6lLapHZl}a>bry1E@ zvx2TTCC0`^699|L}%Lx4&+? zE-Vjwf^?_ElV*p6WFybPl2%E@!?58K+p>kQK)3vwW}`X+s<|_;b-KtO0qO8&P&W(<>G^!8yY( zXww2KF7nh2`fs`f+TSHZJLfyVBcm{UamjVk_-+B%vwbH6XY#M!Jfa2iFGTrK6N~M@ z@3awqP+-ihW}3SBx4MzB=?~Is;|^Em{zT_Pk8wBtHB#MG;<@ysq#HcC9*K*7Rdes< zhS5hWT}2wIeD&e*#J~pcICGnfSbm4bTBM0`PS%@PKq~G;tXfGhU@}cOWV51=(=s0v z$GYc6hdxBx%-czz?IxOPo+9F>{?rVIub*u2iV4bAKIQUFkqvZ(VLmE< zDo3@hSi|Kly~x$G$BUmaO=y{{=u`eL0U3AcL(u{O8draVB%bz!nK7|gLJ#=K+n!O2 zAre@TWo9mtSWhQ?ohRb`f2kNj#8N4o5)MS;-a{ZkiMTFh3txG%jm}d!i2|9o_`gq< z5SCrR?gI-1uM<^Z-B2+e&RL=e@lrNe-iE#JYclCjjbkF-f6qQW*#6}onq#${n0zdS z{>~(<@#!4@<%>MXS=~Z)x^i?}v@@hktwsCqF7nP?{E|2qih2L-lK1Hf>+7PtK7ZzM zi~6gKLq=@}Pv*pnjT@uJ)5${<}(Kc|X| zWKzflzKV`td;*z$mZdwZheKpqJ@WNP6iicYrq`X!@%eC;2UR&2j7G6sFRjsh_#~#2 z+$hG$&2;V1o!Vm$IzpVKP6_Yt043&9(s=a+C0{A(!}nYC~bl zZRY8iBt_?}JV^E5T|pnmvRshowqQKN1FLkF7auq(1>v*~#n~|2+ru(0hV`SCPs6#& zFcUg5tU8K~hzve<@I`uiYZcO5DNomIcY+;Ly>OGP zIk(1gAB{I#kFIJ&@w5MFK~!KrTKeY?F*GcparTkuF5}1D4;aD?2O--0LXY6N!F2rl z97GrwY%|Royeekkq|OBb^_smf%Q6<%oO#J_TcQG5b7gUZmjeC4cAvyQ%2;WZ33t%( zJ9*T6gSXi)L(^WeJ~D=xL5A_fct#nNWo*O7Da-hVfEcR9m5XvvAB-IVge=7q-dl1$ ze`TP)SOqUV-o<)_SeNv1P25)hfz)ms0W;Gz@%t_3xhis*4*4bC-)&e2eZ!Sz^ugPk zy#MeJ)~^l4f6piIlMfifv`-r_DI7xc>*m4{cH4ZK7RKMmW?9ochWOo>FGU|MG{Ep> zGpeytpxde);mGQ*=+rQ4E>~hYjXxva<+~(;;NIL=9N?D8XGuJux5mB@arzhEu0vgA+VVNzBy#EUmIA`?}`KK&6Q*+)6yxfD0#aKEwC_zn`>;b?c+P-l2##omyjm%K&g3~gY)Sg=5s6& zypt*g$)afNb-$P&5o!$AUOYr&6x&JVwaYLhOwy-4?-GAUel@+1Q$&1|$y8GqV(E-4 zH7Al+*+*GtaSVj5%^6k-QgzWdyL2#W3eW@R z6DmA7d#C%O;5D$*jWDbm8)2 zs47a9E-2H1pe}~hX*&s$DuE9RlJKf8XZdrdWFhg$E##oVexKVd;RW+WZV#B{t5SL-ffbmlkc1ZGSH1>_qOnZ(xPd^jw|R}J=1C)w})1DFFe)uS#hFV0!(}zi|=~0 z@)xBf;nn9lk)FTmwGG%Gk-$%WnQ^MU#&lX$;=sw)e$~oZ^a!tzl$n5t`}*geva0L(LDo*^#_x98K6eCks@B{ zXs$Ut?XN_PwIi!fE~G2}iLrFl6ni*RF`sD~R|rx*?1VI?z5E*alGj?P430}=@dcKv z_oUtiaHb00plrsOZ)+#3FN*hZ)d*d%{P!H~QcNTfRV6USHxx&VUd->^8AX52EEnzL zgZf;+TV@$vf5(d3Dm4fewTksoCM<*0@`eHK2>(I6LtVk9NfWP$KhJH|&Y>Rb_94tP zGpAWrSa@hN`dH;fMmj!#*840o^GpICv`e4;yX$ei`VcDjEfCU~j;L#E82@6PExfHY z!9KL3NHbLpvWK)FB{K!OZk{~^rhh@Z$60Z{#Z&2qC<*jG-RU%yS@3*bEY{P_q*|0W57ySCwJhZ}j{;lttIMlqIlj&p;hGF@o+tu$`* z$~x-&R=khr>Slw=7D=C>^3(WWe~0%B=b6M(up_HL>{Qm zjAPni{TCTTmI`d_9>TY8(OAB;nAcD+1EYzRs5Z2dZ2Fl6xjQ9&=Eq;+7yh@LX3ZC4 zsZ^mcOlMenrrn>IT{{APERW?!MlSzzTQyBsl8?5WWw~>yR!}5h8+}f{mxI?t;UH@z zpDQ|vDEWjgTsu$E)$#eHq1zFjoo3x_?UYx!@rd4SPccQlgm#s6J>ZvCo^*UKP@3tvy44;Wd*hiDkU$=ra(`>}LX7jPW}8WtU|atlosc{sNETMp zuQSa>nyBQD0W3eCW$D*>^3#oC=!`t^{5d3iz${-ze zT@QXrx1+@193pe;B{Ul*;h7i1`L?3p)N|u0)EUfj7R&x`&39D%#d?0uAM<#+%6N6pQc&zkw3G>us2 z)S7=tSILxXN;jgsf1^n6ls`|KX|@H((Qhxw>u`Xq)L5*dmBGu5I75xHs?f+e@^r}w z2k2UXaODguE;wvEJ(D7yIi0p?!;6=aIDLsET{_1N^8FOBlHwWej31#hmq&^?qn9%+ zLDuv++CJBk+-sOirL``L=FiUi&Tu0?1V?Y&B#>>7gHNp|uw%z}zGSr$v@DYq-7vc? z>|ya{H7x06#f=&Jg*2$=i}<5=UYamtbrqT!98WGJ2qDXk>CNb3{w3K@51uR+Wk3lt zT;ZYVDr~pRj{7hm2^S<(MVit(%p-7Qn>miR`%BbwJ%C^X{4wA%7Z9IKl{LbU+Z|cz zf7${(KL3XncKMJ47lg3ScQbx|KY=%s(qSHo^~}GoOm|332M_;PJZD-MFJWU1_lKI| zL(LsUTG>P4(fwvLl>Po&-R)rW$*+h$wBj7nrcf(gN%TM8({`Kbu#4?7>l8A1Z({-N zJt>|)pI>!^bwSqnx4aF=z1l~x|}l~^c8Zkx|`a zJTm{&m)f&Co8B;IEK}xBvZRiH%C{IiYi}+;MWLG7+{#CVOm7CW?O>{-G#+$R(mR>> z3mg2De9~+Zk%d0XW@&na+z0NE`>hUe=uj*Us-V0u_aSxkm%!WEPFMA48ND4lU$nnF z-ZX`;%avG#GlMcr#Y^DB3?dq zu@@9Y?!x3_Jy-PCnd+|@FY@MJ8>|oNr?v6!ho^}D_fmRl-~@_hnl9A9@^zixp&3h$ z3AS4^&(yok`1w$~Lz5{=3ZzbPlq9@RllpVD=Q)&$!6P+sgRwi$BqA z%cSvwNvzwRt!n6trjyQnz2@bGq@X_}-pm#d56l#rN;TV>EWWAW|8CwH#`YAX< zIfs8HH58n*ZlmM5tQ#o%B$P|{U-SW)lf^a%&>vgDHeFq%dVnM%(@;%x1hz}<*B`@4Llz4RWxV5elv-Fo+XLqW0oUv zXbfykI)=a9c}nW>6u7oF7BB2R$5$#9QJnEY)YCV4lLMHXvcXBFw%p&eqp%*fW1p%< z-sPYX%q{6cKeWG-`9IuYoz6e>`CB@7^T$iNaeXvuZj_~E&t|eH!(5!RO_86j$a)$M zxgv$d?7phVvbo;5;_gr&m3>#~H}B)9on=NTvup>e(F5qfwa0?r6{g_g^bEPJ`Arnk z&%n1>Ngon=iNA1h0o6!LL3h{4(Z9|5pm@^-yDpwY`mP-WZ>3l~W>GHhpHoHq+VfFo zi5$IVYzh5UlK5ELfY-S_6mOi3;52c}EurNuQAzGauZu0{0`q`1vIXdc5!^T{iEANRz*v(XzK+%PB3N6VGkEl3jaK0fD6VD^l8c-Q1O;@iIt z7P3sC+TU6HpM!OD?}u0D&OLehZIKOJ{Hl&qSI2q1YSD+PiA`vm!*iDTAb_p_)+hMU zh;MK{LDz-!iFBdMgGWKapj}uPSkFmsbENTa#k=|6n?{ha*ATBcbB-)&dPt9qK8f^M zuVNJIrWsrR0nM6lLg2C>P&iCO-se=hFWL}ZPOZYsMf#)zXz9P9zowv zI>7at@p$m$MuEgKe;B_r7EhQ_#*fZ^PXo6}W6y4R>Z7bJ%>SV2Q($(SpY!&j;LAVp z&9jVUyIp+MjSfj&C$*oRKosNtw*1`7f8W(fliE)qMdpt-h>(VYAZNVrQa3MItOKo5 zPI!H{BK7w@NIQDPSnB^*A52Lnx*orftZ{t;>ogMZ3H}1F!1}Bw`rJVa82_^0DV%+wfwWQ?+@{3tLRSY1JEk|{uBg5I@*hRiw@pHbQ|WvYh0b z*K~09fCIOT-77c!6l3XQ_J$18uR(I>lStKG0%v`;U@Oxl{F2Zev`DD}EkyD(+s^~y zqjq4E10%WQ_kZX=XI0VtbDWjTqiu1I5UKm=Aak#UJs$;X%R7KZK_?REJ8*@q{vMkUa)-&Hk zT+2B=ZTKB}v+4y>+$K*iu5p4l8je_Fmm@c+{|Lx=?7$8G8u{ZZ*bH+^58;cI_{yT1+(3e#p4F;;B%!EEhlXSLFXCOH;YKuBd8_47-);!67daQp({0K}mKV{5`z5dgn@?8kp3g4z3q(76H`AHi zdZvWm_%Z*x>??RU=MrwqKg@UDY@`N9PNASbEJJmr1r&d-K^ZheaN}|VZPs(gTW2=# z@ppP@q_Qn8+o41sgdU^6G}DmGCFaMUU<8|P561pyVn|Y9A*Xz`9_YLIDv>%jd`y{lZDpstkmU*2{IT%C8 zoZ+}F_yTF&*Z>840q_5Hf;T!>Li=W)6wRpeuS_6jR2wRsb3#y%~-Uu z_90zmY#P^kaoJB+J?2(XNhU)cy~&wXqQ0 z3X!AnCYFF^wjp*?PPqeHkmz?V=hXXnZ_~PR| z{OOH9slYQG<+5A1^U(3&u{xXSTPAU(%90=mbH*$4yZMP%w4nRA6aK}%v&)ahP+!Z9 zqI>Bm=B-N}@&{c}Tte-7mrQgE494)1ti2yDH28+jDV(D){6xKZkh7ksHJ?hcCv zsa-L6tL_^f{pz9xjV#NTaZIm&nzDW?Nql;gIj2&uOY`40igTilGA_@xRCE`;vF;cp z@2k)QFL^4TXbYc8#$oeq_T1~k>u9(iyWg@IbVsym`Wed#Yfa_s z@7$#lO_3rl{>V6Uh?A~CQq-D|=M$-9{AGlJ&DE?kB4puqEaS9au*7UN=(6wQKgE~4 z&UYDh!x!`NBP<SSDw`CMbryLhENIlZpxg6P>o>*9U@m z&-_q!L#RLp-C1Yosu9o@u@e&$5AN-k9x4bF@Azj&TS82z6?Th}U>dhfn)ogZ4ZhAa zg#E)|_@EDHn9W#nc7gy-cyATq>bPktAXmQuj~h3HMo;i#zF@`;{oKc&J-~WS1=je9 zN?%a}oPvWr2XR?c0dFu<8T=*LtgEX)cgIzFd@O7Xm^HaY;jG_K)&YX|eD`BHRTi5O$gv0kkl2TzO# zJtkUQEqO6?-#?_F zJ!#A@W@`bzcOg7+=mMfQECxm@Gta(bEYf4)c0#EEzOyux|Zbcz^bgTAvIy!T3Y z@|-FXGQI}(`(DB|Cl2$O{SEZYu2bmh8(I2>Glz?;mnZ$wa>4Vx4OFGZ9iOvnex#xQ%JoIsbwwnwz_hc zF#n&3S8^F@16AkO<35%dl1%fc$z}1p8suUD^W8M?m0z;t(o-yyOV#tKn=u`=C8>ee zr)mUB67=0-7qFT1k@b|hb7T8$=+cxVl*V$BbC}lR#I`kfv409_HVlE=6Jqg_@+|)O zju%wHy%t@#E>Ax_v4YEow6I_DVXuu#f3xvvk+ZDuoIr=1qK&-NBtzUjeuuPgFh05q$_9B+>hr(O$QBKk}l%$9p;Y(t-wn-dDLXi z_FX?cwbmJ1Z|df&rf9(N1}E&iMu}?lAD|&g8$~?+*TY62S@#d=d#)fa0-r*EQwlB_ zpTm<;Do`DD4~;t`M|J0Kqi^eSMOjj4lO@Cj`r)Gs>Wj5M{-o1}HHa`)@9c0GrOtA# zZ<=utT{?7^dNcp`j4YiIZwLh}^KeHZ%L26;4(}}E@ca1Fyk$u;T{HWsNc*&7o(uT+ z%)o=Ej^td&uBORx8_)%dDE@aE`=+!i;0Y|#z=-vmzl<6{9zn_6_paOYl6n;KW8S@u z&rG3kW)0GMWKFm~esodFWwfS1j^?(C*cyi^NKzG(TJSIhoIQIQU+Qy~s`ZD7 zbfKl8=Ae|)jtUp}lLLAJSd+9JOYKYI`MXN6@aP6M0}r8A(=nK_-1y7I`}pll&!*w* zh*y4-xSzc!4bH!h!QV1(@aw1&%Vl~kns1MJ*}%=Mok%v)o^!7DWBZXLDq;6Jmr_sg zGCYf)#5Iv?Q5ez~_R8Nn$LF};q&ZsEqFX_bsS7w;xZ_wackbtfIB@IOfj_x4@!c~` zL4T7J_U-N`)&4TV(JKgEcX$nNKKUujI~HSa{fhC>lynv6zgOaibo7&-FI>^snKHD< z%?c#LC*aT#b;K&?5`75F|8h*0_C^ket+G-$va&)jw-5;}bO-xrzVtz6-b~BgSc&MC zUu5R-6tF%i>7(d(iQlt1fG$-@72$BeCYD8?h;Ur%d~%yaf`%3Ia}CYq2N{&o&aDNa zyTO({mf-$b7QZ+&$UEl&5=M?1?6ZDKA{thzd}1!Nm9)GEK;4H&=1p*oa28Ml+PAp?}SIzpl-Gq50gJZ z9@s905lk1i>sl7?8UK{V?Wsj2M4pz*T7roLaYqB)`9sW4 z{kDDqmCg+~a_v0c@2CmfSuc%;y|_m@?>vHYlM>jDyoWcR^o=@IrlX}7W$CIB2=~{~bw$0)sScf4G_{B-$U-!*8D{XE1^lg(!SD*h)52m<1LFeOQNKJDB)!QM)&tJD4 zS+B|r9F{qft7{6O=GVmYYB=MhIHHIZQWa>?{ZSyty7Nv;=W&5vw`j)9D3K=W>jn$( zm1{&HY7XSv1Wb3`6VIzMhwZ`q&<8yiw?A3Q@)rwQ3jZ+b(MBc|(Igej*as@pcRe?6mm!~0h ztdINm4s0DUl5_v|ok|^7#e%zC{4C~4FXAk4#n`{(OJgq>zAS&}}b{3ZV8qRI4_dn%jd zn9rJZLJc7k@WCM=mPHLchQ9Y#;q0PgjUj^86)v^rX_Q|`h|{3 zv&DC_l;}{i1bS@07$-lO>46#Pt=sfd86Ddi2Ohnufn}fGyD<(d@?~xMeR*=sie6((KM@tU}6uMWY2U(0aLfqK4@X;C)QU+B@y4}?0Z2{ma6 z{_rV`Z}&MwwXaSl!T_{p(l=s0`qnSoD2M?{5BoU82q3bB?HS2uL-{x!SU4=m+PG6<^ zl;FdIqg={oMWWeg2%$<+cuv+GqLJ|c7O`Hx@Q^)xxyo01q&FSavb&v z@#Ld0O*;(_n$pYP@@}VpTN^~ZBzrU1cXosX?ipjs4H?j&f|*UCUZ+39^g%Z1Dcbxs zmZY9r4Us#l@sX`R`K@h7s6_ZvRIyZ^mh7~L>n~>Fk;^@}>yg29?mID-n)YfiZ-OG0 zQCFbZV>}@Fg(iNIoX06lEueSTMTvY#rv{9`xcnvR{?Cf2?D3*Cr7Y+Fo*WJGaRh1_ zj&+V75L}qH5biLKL(AoAUS*>M(;>)VlZ6U2g>|mgRh#0yFGg`(L?a2mna^wI$y|E|!o3yfu^;P5QnZ8n3A?fW)KT1j9bahZJyon- z+Qru~-B-XfE3C0wf;zMA4BvihY(3~U=UbUh?dOZJG}g|miiMuotzG_p$n0d`elT57&<%cWvOLU9e~qTeDNxOJJD4E- z4=Faea^smc+y1MhNRwZ>*$;j+-Na7}x=CiSCrHJ{;@p&T{I3bQv}ZxJNFQZ3%oXCQ z#^8w5G2EBsF>t1CC)P}9;yd3P!|vPC*y-IrGJ)3?p1<%K42iPuYI$B#DL2 z<$@Ru6Bv=&P7zvzBMCpA=8yz$@@&#r`Tfa zvr5!<=t3xC*~NDr`|zGsM``()H01I?mOc+*nIV%^@#~9mWYg$Bv@GflikQLf$t=Td zdmrP(f3EcYdnuQ=-ZDZl|758D`UgP`%X>H4lf~PF zmeHY9da>kdHN06aAn`p`d@yt1evw#TM9z92SMV~0ICUHK`JIZ0?e|k$F*niS{Id|qkwg8{$$U+m@b8U? z(+ONm<$X4ylOv<}nX}Y^FIB|Lf)r?N>j*gXSQC5B&Euvp9nP%#QOGt;mP(eGL)X(5 z6nff;wAOo2<-eCv#7j9^pJEMj{P*Hjb>}y3fX{XrCUkmMj67V!Z6rVb2K6NXtK;u@h z?AA&f@Y4&!d#grsD%EZD(PLFn9@K$2){WRufN$~nZd-&z@O1+YBbn`~MFK7sTX>JGRi#)KwT)F#M0f{ib zGX^hqyTKdi$$_!N8>TN(pjkhy!8*DhnI3oHHh)5N<_sy3J}TN7L*Ti5T&3JYN^9LA zj(N{B_MhXE$K+7$Wz|S|wmkJOcKcsF9lq{}xIn=HkmPq^pLL^|4y*YqZnD&r0 zJGF!gYH#uQfrEVd-!eK4Vo-`U<5>dML(8}~IAMn?|2Og*3Ax}V@;B+Q0+R*9g0RWH zPh`*POe#M|Jc|w&>cY4nNjzGoTu{D!qVUxeZJ!|~Gf`Z!5f~0IkI%IMvSMHzbojl& zalwhagn}=P3l`6%i7xCWHZTo0{#{2N9oh{IZn5}k!4*FBA)&*Z3elo=*4KI20!}Sc z!s{dCy{!ul!F;~}{6w>k54ofb_JS((p84q4da1%py;yv1HQ}#*&7mQ^Vjrm4PG2~t zvJ30QeB!Q3Os0Ds7m9eRDtj|<_SD0RSVq>ki)GLPm#~EYVO~S(In_Czj&A77(O?%7 zNGNSYTO-#9_!UB`b$uibyxPcrbACr9Ufbf~x0Pt-pxKPyWY7Pk4?pPNAzEK2#?nfb zZ?H9p^#tLgw5!iG4d6KYZ7WA?EjC==;iAk%r1-kR6JJ4Q0kdA`1lo)6DJgV>%m>W~KvpLPwenI6d1 zs<58lX7L=mCqW4w9CBuN1|@nue;@sIc@x_IKfc~V2j-_pU_szYk~8!HOkS9bZP-nF zR)``^;%dy_YJ;nQO2k24yG2T@=%FTj*eJv0T1$K;O3ca#k;N?0EsP$ z_}$6x{6V=k`o*mgU7aUS_uR4tUmI1t+GZq|bx@6Neca6FtYW>`vvpxk{&N)g`ylyK zvJkeMsmAA4{N%emW9im!VjMoU#{~|m1mo5%V>x^I1=J;KBhuibc<+E=u;Qg6uJu!( z9;vSI_@O4wvCQM{Mqj5gSEEEa)tVX;F!yRkZsv}}_lGOh{vn=Y4>P|*L2Ec3>=7+! z+&T-QSHP9Y`JVWj+rlGYOj>xzZY(p5YM$4 z;khJ#$|1)y{4&nAeKU#H{%W z9KW4F2mIz4YpVaD>f}c5({U$F+!G$8<0-!btpCprJLXJbpDw-^vOM?0n0boXwNHgD zYTVahKR!K`87=jzavy6Voiu7Z9lDBlE4x0VmcNx?L}>(eozlqmPTfg{*Af`EcsIS0 z&AW1zI-`r(bauWVM)Vsb}F9@BCYYwZ!LDRS;NPD&Sva( zIfzA1t|#snyJD+aHBC*Z6g-r*v9ThN-_L;rnH_?sNb9B+<8_C2B>)FWku)6c`9=l$6C+mFaT`zMfc z!=7oRXhM+6SRBbUPVw`kq~mE4y!@fS+vEeLXgtE0*|+ZyR{i)2AC1q*@2K;(_r;H4 zZ|Umn`995a4+sOcD)_AXE5_hvj*VsFcw)RU7k=zJMNN*~};6AyE-=t?8`qbeYOqp~B!I&Ofw?ZJF#$ zt~bZPlFD`(`Il?{zvtupD3LVSF`V?Q>j8_~6f^C--xgSI=Fal>mI_xdl)=w=nR4Dr z;CG(uOWSEyO1^Ad<`L+bX2ou5X@btLeC)}+a%#E7r0L*)(78%+Q&kt4u;f}oaST4jBtg+-RvkjMG2!L3ArtNm&w;`7tBJl8!& z;$-s*o+!I9p9HS|e<;S_Fjv-nJin>VSPQOS7t=ujYVbD97)No;zZ>$O;AWwLO%p0< zHyttbemx5pELC7>)v7QsN>$9Xtv8%_|I~Cg=f5B4voR4f2Bxv6%|A(4%S#v${)k?f zAcl|J7cg$UK1=vCKyvJ!9(de(BG+6UwKT%DUOWRiCP63?g0V2Gj;$KeN^(|i1kunM zy0btGGe3KvM(kWRq{>gyJ$n*d%va2`0U5eD%t4c-L}|cT-ZAlf^hUbz3D5iGyN2<` z=X6eH^#QoMOkI5692*esyHh;csxiPJy3kKU{Fx z7&~TAKqTpLcZD5iO5|OoKU%tBY35rxxguLgP!57cU2f8iyoV)sMqgahH=dmdW0I=s zXRts zjeX8JCeDj()Cpq?Hh&ayvU9+De>ye2r3Rz7+TmCYJvMa23z;hK+J47#RNQrxz?eU0 zK7UShz)tdXi3BpH?xt@Nd3T;W&xm%M$_BiT5-zh9*q?hI*RCogFGf_t`+lYL*)?_e z8fJ|j*J`uBVV!-Pz9(VT-5?e}p`I*^>WVi1kb(+qoLYraM{HMv)`GsAxa+v&B?c5=Lf}JpEuJI;p%f* zmb_SYaAGCYb8NJ|@rdl2`4}Fx*|VL+nlPyU82mYa-;riWNp(mPc=C>q|8Y$5+Gglx z){X6hox+FAuW*;1p|LahyLZVJBX2g*e!u4Vv?=J~8 zF#xOR6zacL9q##f;OOJY>{f7z-~s_CaBW_@&mj`H9-!4#fs@<1*kXEnA7(Z*&HJd` zCcLQ{!Gh8rl4o2G4~^exVZXP+a2r>weDIChzRZ#I9J3abmHyB*JnzLvGnn52irCu@ zL!z&30?WRQkmr^h<=&{ek?!pJ!BS!7*AfW4o=KN8br5G;VMApHeYd?pHh5t^ls>nT zcbyE4&f}TPBB|1zVsh!=Oo)4^z{$~Hd!cQ`R!|DVw@*@0;g|ARI|**};9$ zl8$0ETz<}#?d3XzNgr3j@OO*l-2D&U1-YtR%*Jh5Aq0I;NB8}e)X_u?9=em^Y~3-c z!{6J2H_kYs=YQ<{*uUpP^EYAYfHZdV>`zkru@SOXJ)&w{ldry<VdGYIgDVL`lo; z3D725OtpgINl2*4z5%++@nSZY_~~X)S_hqK$IyUQfdFMYp`5JKwko zJhcH1_A8X{`@atG-+RV37CSOUHsE>yhH*`1i)$UJn$ijxCSrCnTLZepJ7WKUzUP-Ecd|TINIJi40kxz> zY?YS|oGkB)|7H2G*%_LZ;u%}eRg}nnTrVaURx0D@f=0O}s!yR4MvPNqT|>MjcTNw6 zpcZ9%j%PYO8EcO#cO|mJQjU$2_e0v=I{L;<43crqSpR+q)7Bj#In8@}%?(u8)PxQp zdNB9*WhpUq$dc^MxCoEuCej2SuATlGg%RZ<>5Z|0q-V}EoF`=L`0%_t+P~?>VutP#t~q{!4IeA0 z^9wcb;C$kiX>VwXDAH%TQKk^7V@{uFs=?vMJ@DD^^~_483#@zYhl`hUez_%%4BoX5 z!mgi^dqt=4EI1XJ72DcsC_L0Nz>^awcngnM>|}E`4<^$WE(12?4^85p7cY;oxL^eLZu~MNw2u)a{7~%d zO{KliDBO!RWmO1m{QkLa^gi02q7G{w^+Brhk7}eA$V^po;fjN`TvM8GHyizSh@|}! zi^F7BYGV~YAcko#cv@m>$ zCY!ZU176JZ!2ThoY=vWqQ4Pzl^fCv)BVj#Td9YI;UP_qquB*R9}%Ng-7_&b1;- zobiTPGTU+^RhISI5Bsf3WP^Ivk?{vU!BQe-)kihpFF2t{&5@~vNhLM$HNu@&rKFVe zbi0T3#3J^UdgkN{TjHznvLnBR2FHB`+@}VEOz_ zEZgq`=}~He7Y)_eSUnMFwLQS=`iI#ByHP}WT@{c;iSqmB!dyP@ofAourGeyj`9s09 zuctikZUyC&Zo5F%?)8d7SF5a-{1e?XTY9JP;*q^Cob-X zgCZ69seX(=@7rN={^;;*OB}Jsl9k{7EDV`{6(kW^a?WV#nm*WlL=!FAw?cL)_&A*R z?$2g?=d-2SZLl+PU_pB{!7pbRR`Y$?VThFM%Z-El;JwuQ2FK4~78ttQf@Lqx5YqfU zz}(|!sN-;Tn9$W4t-CkV@J$PSei!W#<~y5HcN4Dnw(o{JoYphZ3mu+?=!>$&JSX;k z964#80V;n_(aroW@%}+y98qY;j(eL3`qk<9_GFVM7&9A7WP7H39_W0u9 zSL)u`TasMb8H!eWL)HY7!mP@es$D^F_&ZM%|*pz$GQ-x7_7k3BL{8J-~?lK9Yck}cemlo)p9vs zKhBD0u*4~`L05>+4L%#M3-)1}kM5J@yO-e}Wo2ph6JMbwyANLcpO$#uRnp*xuwl0f z3v$qaEB-rVQ~vFc_vk%#GehkMnk;nEC1H2oJ**mjn4Q+!MRX@WgL@0J>A40q=v}c4 zRl6!nCw9t~{J3`xhClDg>fYCrsZ}D(;CuT2Zl0G%EQT&CmdLsLubfk`87F4*CodQF ztR7nRYg-R#{19ha7@&$S=I3dJnHXy4jfNAWl=6A?5BG%LFkv~_Oybc~8>R*-FxIWo2pg^=$L3JbsgSE!Q?qprljuN+#FJNWrBDTy-2ZoNeN1s+-wsx&v<(hd3sM3}D zlv9hzvKt-HI^a3Y;qUX|EIwnuP-5Y}o|5am2Ec=$PPE4~-jBfFpL6{ENq5O5hc;w@ z>W?})i;3Z>Zz8VzoX8T^esy4>F`eQZecn+b;_V6pSgFH>#QDzbY+u*-^$L- z9a=SXLl5ci#EGnMGrhYGc|jj| z-4;3m3qbOW>!MGsCTnhHz`hY8c|OUN`vZ8^=z8{X-bcwp9RiUWQ{}VhgG+WeHN&3e zsLtdmL|pj=KXB9o2;FYF~5- z<(dIcDfy4Z!Qusb=~(`E*G*!I*OkrKS*0|=Wb_AkYIT;za<730_c8VV_mP^+UE-t7 zb_uP4<}}G#4XQsFV7Pe{8{1C@e08N*5}nBA+=?UN1!-Vyb6S4S>}&my3@0gL5>?4G(zdw#4Frn*Ug8?jy1zq!)Vi z>7eT*pM=0}s#WJ(Wh`&$N)mT?He}cSp?aM29k9$FFX9%uYoAW+k71E)_D%mP=Bh7E4h*6X>eHbAB5S!Ozjb*U z=Ijwk4@@g2G5vy}+o&{J9Hm3i*t>sc&Djd7;L#diwd4 zKZ?g&nLe!e<$V$!FdsYVC`&gy^c6Bs_rlx*{9fUImCW9F9%{2y*gekAuGrQaukY7m zFGp7k&Ex9uPwZi4*L@e+EPVp071=c8qZ*uznU9%$m8E|)vn3G=%R#NRCmZ#ebC+v6 zV32{Ee19)`Gau3l6ablaq6O_AolqEiUcSGRB7Z1h$LYqm>X13Z75}hR zY;HewS(Sba*KVaTzu`amJO2Q>T0WNFHWyBJM6K~X*n+7;Bx`du!J_D?oUfnMy9avn z`N1)9r(mj-2SawcvajF$$Ya-KFyvDWO}{CIWjqfmgYREHbrU5gGyTCiVUfJY*~d}? zyS&n5{VRCh5izd%8KW-UTAx7-iwZz=Y9qaMh-a6ru)?j=Khorj1BI0Mp73aUA$9u1 zfBt8r_;+~$8`6AC)~mY|_ip0)laIATGP()g?iVu`p2^|1iDxx;_hJL3qa=4XT^CL+ zDwW?k4}CGi(p7({y=#&1U*lCg*=+~g)VhK6JTVYf<=mtTvc!;L?2Ezcja^V){Z*CN(T0h_ zwO7~Cbjwa=IQ%FX5&H<#(-*NN`Z}@Xz@VoJ zzTRrNGbZb=W(%d;go)ZSF*P`m*_#xStmtBx!LyG4cNdlM{A3*3jr|>D=u>v;8|I{6 zV!lOww6m!h(gUyPx34vVUq&`)wY##_MXSlhj8sU86R{?~Bdck;;V7jjCJJemY}hss zc1owpbDJyASz#8>oSX>1ge8s_q4jANEg7N?Q@K6_@3qj{?$NT(qZ?sauXU_;ni2OF zUV;Nt6nGnUMS?!F6WNx|Qj*oS9%i4~OXoK6yQsPu9=Gemb`)m{PVr5!YaYkjP3l~$ zXo>y9K2c;#eCn@k6U5;PyzMny7iaMtY?Yom@W7g9{>LS<=E^v7+j=($!xebjsdzVj z<9RP zv65?vU*(g#Q%hi1O+DR|D~8~Lz8GKP%%V5udO!3u!}`d7w8f=G@LZ=-)i4m)`P-{V zdg)YHr}dYXM{2;*;-R=D>=@5e>PjYb(T34$M$jalZ+u+T0~d@L$R4>=3NO1A!KvZ< zkOlDLa}7OPDTW0+r@f$jH6sHjN;(b>gV5g#smYW$5^t%F+rMkFs3Hw` z)TwJ#&KPxRKvV`XI++h&1jQZTy{RQi%sGyp z$acC&&}1{u|GZO6d?vnx_&hQD&9etLy>`KS9{t#vaRHJYlB-k(gZX@NLQ%BgBFRLVnKi>d{d_8tY<2!lg z)*T;A8o+AZv|wqbewD+0W9izUJo0b*b~vzHfw6PSyJOuIe*2m@MyPAQhW8S8u_uEH zNlfxxFj%yRseRCf=6)_%ac3;Mb+mis+G%lU&oQ=?6_YampJ1`}xtxn1(#afW@XnO~ z&91vVJz>X+PI67uPXj6LKJu8|^D~AE+&84Jmc&ji&m{+QQ=!g}Gae(kA5ha3d(@0$ z56D=_b0-x#UoJCH#4tNdM}pgK#<= z*;SEroJk;wD7+zDOIGkrIx!B|qhdAtW~2)9%))Ui*KKx(wtaN7>{ckLsz~Z7Z5kg;Z<`rn*oJy)W!xdGnGlY9`SaIaE+Dx&wlG=5JEOU0 zt>5pycy-JQmXN(gSZW%M_xaptq{Mls?#IDvNEuzufA5LZ8Vwin?mvm4&jOnj`n+aXdr(lRmBKvr+l+5J+ zH|)LwV{er@V9JWW)UH)3=?;Gc`@$5O9jXpKy9hq@IL0p4*9+!8gK#RJJ?x(3lcs(r zA&z70xI{5HjJH9h4rjLLP_B22Q%_tx@*l0a^GV2G(yglN*=IacYX@GUrq?Ql9Uk#ARjn;@->BXea~yihfGzxUTUhgl-{o!{Wzx$jBuQ2eoiuZ( zZzJa-W1_IKhoSV=sne1Za2!;ecov*e1F5~m^QEKRST^SzS9ghk9V$zyj)xlD@7n_d zAL_944l%--!6HmOa$c@?%4wlsx=?|uAGy|dCda*V57cGDrmn;hW71gc_aDR+?(m$q z$24}97?j<(?>o_qeHIUw?B=h zLAw1N`tlCXXxij}WA?0NtTb5iYtazsK7JA1yey6gzN$FWL5qF8paJ`?^v5k`c5JqdW^mSJoTP-TOp4EgvN0b~XTqJB9S2x)?H-48|GJN7%PVCuH-64MJ<4 zmHMW%mQ30I49aitmZ{qsP^rcB0Ab#2n(=r^n9*gS)6_EgO~4|w2S$JUOOvgO1kt{$ z*xe(A=`Y<#`Yd*aa;0iI;er@0g;Bis;TRkDZ@nb%)fFfb^w@gc?REYaek{&1=eie{Vv^|f4V0^%%Q>m}!`(4BL7)4TMoA*4y2HI} z1+KQNGC`xxn^|s39?3hp6HZ1duyoi2Ph9mdl%3QIk-R>=0hg>yVpDE?CZAt*=iSOW z%;mfojzsWVcexSk<4`V9xpfvk>LQbuzgsY88`J=&c$ zWt%3O_$<$h#m8^PvQmu(61u@0&unj|R=oQ)#CtE8zj9@-=dUIfU3Y+JuL3`J7I=Z# zO2v#y)>tC>>%hK6{1L=~2;cuI_^B^Ltnq?!8}&(zl?_U2fOwbn?C=(2>QyYj&N&MF zyb-<{=J33i|K*?fMp__V;(p<~xx&I>ui)k`j-Sgp4i|8LR_E{3>hx-#FUj%3M<)e- zE}E@@iHD9xx^0)-^l0E z9$oG6_%EIf+jEFSoY^LjYbkU&$Dc8N198x|LgvQ%88iL*;j0+#b3dO?&Wt_|w|X_m z=Tfy&SG-v7%@zzg?(OdzkNtnFVCzS}C3T}LF@WEQ68m%r3(}3N!nL0>`%ycI^R6Ix zF<3F9YCm6sb6p$R{V+<*7N~<^g9ZwftDY)f+5_z(E?Y_eIzMb)E@1Bnb_lT1lJjuStTVk3zsSQ)cMcK>C<{hSpj)cJr|&+`Tm!cMeTt zqERDB+Upshy>cmSoAAF(s_xj!TbDKa#|qoTO1MN%CZAVVs(ZtNb;s$z7wWKh64&0G zjbc~7XvoI4FTv8WY3%2XAEf5MEl9%0G%Z{VzdE_13bA4Vqen}`f*Mq4JR|@9sKVJ{ zhWNYJV>%@=S(q+Kfm0t{S+JEqi7J~8bf^MX`~Ts7VV5Xo{cV!OFPuX8lSOoXK^*Be zs1xeCY02l+3zz%h#bkT7D(ZryOf3(}x^0rwTZY=8ENP8c#scpR()mqkT%lZ6=e zEbWhF>?mv7Q7qfVyT31R-`T(PT5|I2BUn){W}P@z7k78V@S#3z&!_Q{0J{sqCf73g zylOMZ4EMJwvvHG83ZWj?Fg;9i9J$yRye+G#!!0p%@8ykz`_R|aMoT_Cz5vBf z^w@pV@8qj%SCriwzTYngjdGW_^Z6*INucKtx{(9hE5Sm2VKUFJ}GQpVj)>+ zeg(Q@D`r%6-KBUXq>)|st|4|kozcs5G7Hn_RcZ5lJ^ENBvd4PGB+a-LCMdm-Yxtw} z+%Sdbxf#s}kc{l-3gb3+l6#6!&Q6lwU3=7<;GFC(>{+S?lwR?|Cqs?d-GXw-goX;J^hlC>NZr?sL0O$hTCW;N z2ERi=<&okJFe=drNnsp2?W_fVV}o&RP$K&~Gm*gjWXL~}LBBrY{Wwo-P+!bDp`cCX zwapM0>OQ4`B4zOEJq8W$i=<=E6p$Xxy};5@fvfi;`=WhQG<*Jhhj4C5FkX$|d95`^ z$w|W_&^20ttD4z1c;~Gtv++0aIhzrUtNq5aSi^_p^hh)8bom3llKVhtgkhp6}BHFVjLS*&vb@J*gmC{gy!3 z2ZaWp=X_KA>}OU!upou=xo@p+gWBkbC$xC7)rP{sC$ zC?+$}fth~WV4Ln~dWGks&h6hDKYes&Wr3zb?d@dD)k$P`wwIDO8#K^y>KhuveL%Kh zcKEvNAH6bYsKj>YM?u*pmFDxT)L94IvB&mArcstpq#=c{%%MTfTQyIM$G_{=u++$A zvbm`j#(hy`I}Lve=hXe7c*|e9ce4h3d^is?`ZqG;KuVVM;y$sNesn~FDl}GD;D6sn zvcbD=3BzmhVd^slmR6JQc*Il0I!+yyB|qH=6C7=r-WQ%D-Z~G(f&4ikdr8*TVNhSJ z*!Mp!u)<|Wf>`3pal#Fs3y@h}LGNeqtb+s_l#J72AEyWTL{~)Pfp-!%EBFB!|1BO3 zI$KL$L`Mmlwz{~L-!!C0u8^hoj)P^BLi^P8a|90f8O<&m{*w%x#y$8sCM@>K1EFMO zHGcU~$o8*JC3VGjfou4vp^iFy`5li&de+hz!Pg`OLk~gU2vZi{vwP4C-ZV-6X>YKO zTtu_S#E~!2BHXoDiyh-LWX@3!Jn@0^o@rH*WApbz-fzY46U5WJ1^foR zkmu_6Gjqa44SMW^)<}u|6K4o$SKL%bEj2`k#I4LAB%kci+zM0P-<9X`70-iFl8Kn#{v?GmCH8xS)W0la=lQw zt~ItFGh-zFn=G}2@Acy6)M9rha9;0+J)VlB`XvQqKj{J5{}dk5x_F-dIcNhj2~QEm zOc=*I#W-hu<|v7bI0Oq1De&{>8#`>D+lRefXXevqU@S(ZPG(zuo{>hLQT%GpcN#dd zQ8>6{GdR6d{{QTEyg{t$~X;asYGMnX>A!}_kbGGY7XDFS5vr8Q08GTEA3UE%MNE&;s zf^@wyAL4Y=<-FA?KQp|b=EN*F6%1ygt+v9`!fm)qi}P7iONm3HI^HgOL!*2& zpd!~9A1qX5qtix7+7`SLLVKpt8C+|0cg%1+Vs(MBUta~b%^7cV9o_1@eB#ypFbo*n zK>gyx(3EM9!-jdYWebjZx0b}=g>UOvb=*gCz<_6KXsff0&)bCsc60-K637f@$pU7^ovQY)zXcw2qyPe&LPGWBgvSqrVh-HY)agyIglXX7L}((2Epy zrvp51tB`x0J|DEk(`&TZo@ZlxZhu&ZwtWe!2zfw$<2E#_>nAPp-7090*TQopJSY79 z6*9So-yB}5$aAFcB@e~!0nsdHaEC;7%?6prJH>r9xSr#=v=^JW?wK%gQZ4w@C@|Km zA{XXtHf8B<4aDNhYcPB1#%6;i`1~1z%Xp9E3zLy#x<@F8+n3Ua|J2}3T@So^uq*3$ zwNYqF`wfR@$mE)Q$u4)8^65Bz+@0qY@9&E{zsE5g(?ymPG#51@(%9tGAEbHCRoJTa zM9x(;hP&YJ@V-pLe7r}tGY40p8lj=Wg_fd zp_ofo{AZ6_CT(O{p@ow&yUD<)vK@zX7POz7$$hrRDFNx5ke@~uO5_X_J9?V$4M!C+D zL};$YmWfGhkLWWIGP>f!qg~jWsayl2T?+2o75lr5_i&8A%Wst*1IXLQXN9X`FIuC* zxj&xoy`#%UX1!e-tbdNdTci0q!xD){#8%LFte7+7Rd|QjQ4=JM~T_)e8|r& zlXu~*8*PWK+xxJeDP}(6n;X#0IE+PCy&%2#{8N4I8y&v*nJ~{O37THIvi*Hm6RQMlokIVzlf=*u+;oqJ=`88;T9uMD%i&cZR{Y^wZ_ z`?DIXutxb0ZJM%CHsj%CSpO-8t=eTmJ3TH2T|WnQa-1eyT6~DlY$EB)(-owL-F&#= zoldv@;k^c>7Wk5L6DAo)gt*I(A#dS18grP>QLgqlN>`cLC&l?F)hrNZ|7R}GHT5e0 z%Xh;lrtPT%v(!@Yw0|>;nEQhC_fCY(KBwtPE1pTxvo9(y^k!qs`U(-(wqTJ_A~P6T zN-n$eZYl0FburO^NUp2@(@VrAob#0&p72mLK;v_!f(G8c{5M`bTn>`|o7KJG1k3O7Pyq8ydtN zw5&`67L5qUZ_^stL|;n$cl;CV%>3oOPA*rhaqPS)O!VZj;I%y$w1#KV`P_pLoneEj zI=bxT$#XKBgTty$&M=YA?>d=IAFvwAX4|l4u@)%(7mkTBjjU|)UUJD=0?8lJsOv0s z_}1GA&vc)~x;=^zo?SQ(1+og-9L{g2Blzy$g=ZTkjrFmLTZ4O66ZU(}1Cphdgij3m zORvq_DvYl^371~GvJBM?Wai2OSZAUt=b^%{Npakb7#8iIM8dRI%SJ{i?xju67C87r zPv+R^v2Y}~2HqL$rzIBZ(0h9pOvy22z4|v0rG?LVX1+Tc@`m3ff&y{hH2zK39!a!$ z(zefg#Vq=O_nRyp)q|DX-z=m{f5J3DMyvbs%>UO;VDRfW-DxO>Vn6Q7z>O@) zO>*D;_tCaEag2zm8~6zi$18zdgaRi^2L$2n(RbL9%k{FfPh1aqi0k*J*Am`;Sut}a-?hN=#+=)_c}^HSMYn21-4nLX@hS=b)D5mK zuBLOJ@(ie>V{ks!vhDpcB)wjjgN3a=d+f?_GFls>`VM5aJ%@=GPPs5?pi|Lk6Se80 zWc>VGsQ;*#Cy%w+;vsu$*8a@g=U?Ck%-5aHhAenPZlCRil`%i4QEsEqy*LKmd~jt? z^;Z+`$n_woE3*sX8sIc=KiX~=Nt605A`Nb~@N|7RjWFlg&gaeX#waiLI$8xp?sb^{ z^fr5P_b74yS_WfoWYaL7(KNK#5`B5*fK)3%_VxN<@VutDc}DB*#~Zu&cO<`pyjeI4 zW=R$EWW-)m9Q4ACEq;1Lc%oGgC-TqH`#aU4Xn+kC@oep@%^Q5WUzjDt&r;k!uPOh4 z_2bsF*7-Wnk+lO~4rpdI1748Fj+>y%x6|^hr_NGy92@V&0`K$|@=B7>QJl!4#ieBE z5fz-H)kN>xYe2Ki8gCpDF}t8)5{Hp@g)k4rY}pby5>wXHvZ&>qp!*LS{GQIgK~ed{ zR4)%yLmFtexnk&%WP`tM`mn6z~L%du0LBCLDvgxUCUYY|Q#zNe>z`QyCsM0V*NzcFr~0AD99lh2d($4yYV#+VtV zCkUauCwk=r89iVih9|%Kf<)y69i}6OJByvs^2B!LSlwNg|7#jrC#5mxH9yFAQUwJA zpUAUH?x#58mc@?j&Z9|^{fCqwRJTz+PkzeifpNdT&;wug@jAWru#4~M0j++-@Pa>7 z+`L04e&D=AL;xOqT)@1YcSu$qb%#~o7s+{fHs=QfztCcu&D_^Hq81mPyUi9niX;mv zGT_-c#cZkMVUBI)zv%TyCTKYR5Yo04(UNI=PailErNe5O-SGxlqJ}MgJ(eDtj3~ zeD53+Ea!XCUbY-(E?Z)dZX(;dMHj^N!*TI!{{Hk#Bm-V-f}8%CbpH=E@X@wGlYQ2# zYMYWUF{CTj8oj5ryld~%R}UQgn(wWt1;lW67f3&|ho=AKzM-?jv1%FbvYf|pvOXIQ zXq3ynOK}hTVp>99meAhE=TF`Se4jUqO}PJ#^xMt5wEMc={IF;O0g#&>W=%F!?z2bitO3zAQq(P4S zZh0lu3ZvhNST}YM6qk%)V9Rj>q=}=eXP$8t58Ah)c@=4r?deAn!IJTMnb$>y$ zE90Qnu0-zTytds6>&{D9;d?t_+1Uhqub;^JekviqO*`SG*-i4j`)^(!47seta)qIi z{jN8K`QfQlSEdfrx?18??rkiZmrn-%$%Z=%8>kBB8rVCYgV(|JKN-iplmEqF-q=_c zKA@Gf>6zeeeRY;$*Dhqf?1P>>r==u4UsCtg32xF3x>?YG&^^nr*J+V7Ofr@1+tVhr z<@-}BT{V~A(j^k;7_wFYxx*UCce&r%N7c3%=tYCH*bky z4e|dZKTG(#YHr28b#D?f{@j4Tg#C1ar#iUaPlenD1s=8!c>wu?-I;1Nzq`f_!{_|| zBYWaccGQjmsogR;pZ-(Id(DnnFs2(!F|&w^rxN}9$aujnWr;b_+pCWNZwyzRLwJT^s*|vPUhL>JATpA$8&{P&E=5M z#Z9jNJn?BLu;x27_lp?na{O`K<|C|lD^FiJ;|dYFOKH^Hc;b5CD+pb+S&VXLFbOiQ zsyJ;d)io|6Rn>bT;{GO@b6gFYMwsCni(gdi$%NhbQ8<60h~9`5gH!+I_({w?1>4nx zVkb*nd^(Z+99&BRo3BFsObs@G@97Rab71Q@U-rs8Oj77mE_5#|Cq*UPpIFxmmx#65 zCJmWz{=fr#d+G>Vabqv>%G8F88`X5IiU!zCT#g|o%2M^gGKuu;2?!Xim>YLRiScLQ zKz1}i3wmg6fT!Ub=k~_$L0y=C!9t;E#367vx|prw{HZj@6C-D>V(a2PDy=6( zqVq8B$KQT}ypp|uqA@S2WuOKuQ*yzEfFA6{>|janhqln=xeD#i{aJZg1>kwnm0iCz znm7%Pft{Q0(I?4b(B0{YN@G^B^W&FG5=`dfj*&^MWm*flb+QYt=%UMx&(MH*Yjmr| zwRf=PN*N?A{{*xQ*i21*)uFY@4OepPlHCs=OK%nm&)mJ_+RmC@eems_1h#}THinCb zp$GTooYPGtH?22;ZV`w#iKMl=3y4P#9T-)%hX#CCht$9Q@w8e7+uw0aSQ$GE|C`VClar5WTC|!#=5jde zt-#58)zPTVH91>XniF#uOPIAST&_WSEwV(rR&VC;K?BV1mq5p^9IDItkp)$jxZ|*h zJ-V1E(-j|polOq%j8L8QOgy|zBvp;6Aajm}!<*c6dR&j+0}IVjt?NK$u%%ciczPGc zJvc}0xAO1H!rr*>@ISh@KE~%ejul)Nn9DothDqN-##aTWWB4ZtWns;1yZH-p)jSp+ z*_6nAomWPhVqM?>_Na@Muy*%GOyik{FVaiMw3Q-cJDcPl&)wSgsKmr9KsiWK(sV({ zh*aR@+kxizAOG&Znx0Qq{mcZ7%m%8%wJr(oZE)M2p=?8GiFdW%dYm;gmO1xnC1VUs zu=cf>Eez}sGHQCG+9?s!2tFj)^vVXjXLZn!s~W&Y&c`(z)1G-uCH*r$32ia{a$i#5 zcU!bR7s>yeKL|?=GvU&mESkYHAM*5Vaay1ed%!Np%;!j}%#ZYtUfdNzUGhWWWwQ+% zHc<=OX3WP0S47hI4<|@!vKy59DR5H%k}G~vS;eNrtr4t-MPMk;U|IBYD~VubaA3_D zx&HI+emh*aw;QwHGTo(%?9&oWiEnD0v7hW*fe zel$xc`70S&w_Mh_dWYQaDRi~M(MqZ zbTRA9_mA@V^!V=@1nY;S4dy&|}<7Vq8n;y^C-=K!e>st^s>% zz0hgeL}sqJSQ6U3M5rHLF89K(;&ar35CgV0?6P2*cps;~I?7B>rxUH`>M;0aH9fDP z0Z%3;;I0k>>6Fp+lFem>kg`;tZ5{cYoO!Q`^!`AGJG9`zfEcKVQedgo(q8D2uEWB; z76_@aInew6Sh^0soZdHF(%zwnmZZ|qP^r}WoaZ%CAtWQEvO{Jm+D4_2S&>;ZXoxiA zJ@=h#5+Q^V*?T1W_k7>;`v;DXI$h_w@B13%%cWf*a`){KjHBrir(t!0i|3;kyF1&g zDI-Rk+CU}lDL2Dg8A>DU(XrH!j_H^wy8LD^gnsYI-Ahn_C+wY>S#M9fPWzGaeQUso zzr)Qu!17-9I^eFMG4z2_l&BOIVtRQRo!0Sz1Uym4?_n&vlHJE0N422L2B2z_7ZAs) z66gvMuyjqsV4UztR!o}46Z>^}{IwO%+%Co|`py`DpW{-f+7(S$(St*m#i_KQD}`*& zP6m~%yoq&9a-RvCcTC(8ls5KFoVVZB#qR{*iI8%J-CX9{+a0 z8sp!Lrwgrz^IBEw&|EK-F3LYe)EoXm+yjAgI=^9D!d!+b2agn06`bKC;#v2~dFD5t zI{;NrGp$I_5z^X{4T1aabDe%laM;rfZ|RJtCO1xbTsg7^5633a%l$u-jAcy2)>oCj zXP#e}=Z@V*demk=iVnUshP8!%xjP-oF!je=oWi`i`%Pw%<$quDzQ=@H&)|A9yezYr z&53XM%YU<>rPqG$0=s=5VI8=&OedTv-yk`>+8-_&ThJLXYG9%>4<}xc6`y@vMka;Z zLQYgR7s5PTX7_FJ<)>)c?!A_OF=saZ^h%}jZ!?I^v6G;gC*bG%offEmt1n$u80I;3 zYdo&;8b?E~KO^cj`=I-aJ$1dGM2=Tx!^AjwYQ(YcV}=vn_DG`Zy=BO@szs8oqc)39 z?^fUwPS|1ZOlRt>^N%-}ei6pk3-kEQo*B^jL*SoXivC%4^C4aB(p!1)Z#}Fr`NlOz?dNAIhQbnU2im{Y zn~ZdK1201XGd=aKAU}5{7oM@6G+%!MzLVAIBo!5yz_N*Sv>s5+&r#&D(k{5uFGb2Z zz5W{F7#A5@9XW>gn)QJ1zIL4Zwn_=sSgu3vcQ5gf9{u?A>-s2}m_pY-zdXsDOPN_ zOd1}=g63gi1_yIPTpX-P*Nj}sM?U20w@w)#u5TX3o$btqil58r^934^aorZ@K8dCk z`NQgLSIou_?4APC%E&C1`IC8C;G)ln9nQUAL@n)uMVns_0;RvgeaGnZJ}CZZPbc2< zBL=HiL14ulE^Pzry}B_J?I*6GhyO*14x2B;J9X)_=jbow<}X!rJ*-6som7V3x76!X zGiAg-{_Y`5jvWJ!Wt+I^Llwc6`6d0n$%;)bjVFJ}e*TodvoxD-PH0~|JST;A=4!(4 zK^_>#^d1M^rjWj~5i6ud8wt)AoWtumJ8)lc9101h|A)A$t{U@&PNE?M!0mi>4_j5MQRg4Zc-a-t$w zytc#_V<*sA!Nd6ld=kbFWO|8=Q=~ESH^j@ml=9D{CPU0VCQHL(MvLS{C;7?Cc5<#| zig061UsPwlvwq?upJgq34N&sPBTn{qpqOL}e(J4VMf(yG5k)RFN+%VOoeZb2_%;6+e%h zhjZ$Oq;q=8(lc;#*$g_=S(p3BwD(^YI!gQKS4MOAVs8eWR5g)Qe)NJhrjeX6>kM_> zuaC8E1L@cKnY=dBBgOUt?ikDJjC!F9^^eN9j07ccI^==Xe~aiJ_2H6(34Zu4h2_!R z?;>Z9S3>#WM_h-l60DPP!sJ&TbX@Hck)GjKo}boEww#iOkQ^i2Goc54?^DPR(4Pud zOdKfR=1p!#4+Hnfx47PF$}pvXVEL)z^sLHG5jklNarFXzs{DQd%ahdUV*?dfcI^h5 zC_Z3)Oi|?Zm>n=-Mhf@zI?HfKAAkmV|G0ApNAsfkCSLx@aV}&n%idIo$6fNh#V>yM z<(EI##m&r9pnv8Dxj5l0nCw=jeXg>daH1g zyzjP#j#%eZ2hp?8h+(F`OBva0dmrN31kSlr))gD&htQoai$!FZDHwC|QqH;LWHvOh ztQh$#e(bgq0p;)Ra1MKvVAL*KEIJoQQ$%Y-=alB+*;5QNRlktf7s@#Egcj|Q&%VXo zz3N536~$(k^T_-gMezQ}CTSMaySD>y@>k|Z#_{BGbS~dIL%_^kZGG_7jE(eqtOn#; zB`|&1Ua1#e_o6Kx33Z{4dg^?9_YU0koB24bYe~P!TG&+bhO4^Aatpf$p!lz>cwa^V z`IjII&)*39%(c%w(Qn`}s-}p1^nG{K+n7p2EQ-n7QM=*TvvuJs}}*_(k<}J%RNKjU>fTlEm4N_-fQsG(02MU zYy$b*qz{}@D0^=e;MT_h*fUB*V_4_-%nK#3;^YCYifPEdO*F^V`;@3*-d4%tXFFlz z1{_jWjVUfU0X<4%1X%FeoE?j|08dK-7qa*?4 z8BX4xe~P4q{s0&*;AB?r031GFmS#U1C3?8-7_Yx)C->r-B3L%`#_PvZY5tHSB;x0G zXzCL7nJ>RvW6Gfb<_|jOG0AEr_KZoQ>E$dV-9sO34{Fk}imZq9rZYBZ=+UoiP26tQ z3*P_y%Z>ZP_FDW@3}jwfBV~5qQF_cj{q4i;msbFmxQ8EaCsKI_S?IeX5XZ2Y`fRg5 zY236Ep4sf@8kt^Q_wqn2+NDQJW;RG}jG?f0vITYArUuLJvS%_4#>%T@#KUP3&Ww+ZyqiRV4sL^hEAsRy+Yx0SH^AvH%;{05*Zfd}b1>gUz{#uqPs5Mi zfiyEmmx~yG4yq#@X;g_STwgj0?EkKkYA=IU8DZHqOIoCm#b2NI67m&*n>v(vUPkD^ z#&-fX2C91ChmsQN_RU?go8^mM*^x!pU+!XgaTV|mgneebjsq$l^q|LWmx$uSKl5|z zo=9_#FCH<%uvc=7{}l7uN5{bzYXKX_ciY0s_*>i;mL+xd`%2tx+D>n)fQZW&1fP1Y z;zIVVC*Bdy;9ZS69ps?`>ap7(G)BO~={E=Bw-g0xa^H`)%ectbJQet4*R?csxo9RX z8)L<5oa>F3kEK%6i#LfvQ4J^*3wW65>WH0lf+-1#7M(wLoVWNP;9)(>SsnAQH$5VI ziJwq&4UH{|s99kaIVSs_f9KT5-5jJ0=L$FAxvR$F*810?rDo}{=J-EuOzB-_$@mQ} zUIL$7x+@URu)9qDA}ylX7zv}=lQ}cy94qRM-h@%=xhLq_Zhns!(NtXQ_j zrX6eOxFV;zYY>QeQ`xRyU>ON;xeGQ1&$#!KmBDne6GnWrpkayOBGn)hnBp(bty!i3 z>wfNl2Bx|C4-e~xECjL3U2bTN5=>b;1W(+Ir5)BWqKj&w`2JuzEs}gDy1Gi}^ID6> zGoR_TkJ|Nm&lSaQQ}f8`&H@-#D{#osqjvJz^PIW=vO0a2XkwA-Mk=GO0fSi1Mo4Ws zRh3I8oO3kDHw$>EVK*3$U2&ivLX`R5Et%-qKb1Ob){-r4>gXT#Ryuc&nfr~eaTI3l zn~&UZWP2%X(>u>6taQRZJ5s5SW-({0iOO`|&+q&RjnSag*MSChMw4~xS+~)a9`r)4G9(2p#V^cP^fuz+r?0yNX15q`Jj^;J&$A9_2UYrYce>~A zwRU`u8e!Is<*tG1%y_Am@@nT2oW8i78auR*W!oa4;Or@`xLgr-Ofth^Fa7AL&8~dV z!?hU7-XE8_r$~}j7sy7xij45Y3bIlNui&-8&Y=^M7wEbeFiPNdci|)*-|uEpG3R1e*Mt=+O&b`w3|me;pcKa>RN{)yWwhZY!2(B zuu*}UWIr6i@M^!>EMgaMj}K;C@jnb4b#*G{vUjq_1Anr4=5{zAuwS~XbZ5CjFhk!L}TuBt)uCO_a72L zmLoQ*QL4IOg=j~|d%kV=6X~pdJ#HXg?pCCFqB8!;G%@5ox2KM;`(q=b-oc) z?3S0_cdUPHfoJLtG!Fd8q&~BubogDaocU9~rZT<3@AY)*-(-=sRuDcumQI6@ekOWv zeqKZTE!1$*@wePT6?T(qd&}=w zlf^A!J$m*PPFVYx}3)S_)7Q$W9*xwNb|>h>D*?l&nb^%5Nw$sMZ z6Ud^i+Hhi32&b1S5B!HdSl~tIDOFYYUQqyjtq)3P=Wj**u>VV0y5BBUVm&bhew+|^ z;K>CG(1bnb+PDKG<@p%c0Lgvq22(h0|aaZbDrlpH5K8gyV zNp55KZN;ncrbjBBN=}i>MW5kN&P%EOXA$FgIu$zfL-Q<=PsAR6eXf9kH5W4Aw$}rx z&d2$WHFiA-rpX;wJkG9Ngl3zP=$P6G zH)O>JJ_eJ~V_7Dxp)aTROCA>Po{SmeS!RB|KXKB|go}y$xw#t|R?juY3zB}c^3nxK zc-T-#ykJ4MwyA+uJA2MUS@FfwOy4`o01^s?yUbl;jth?^(X+df`IP#}*d5M1M@1QA zyH^qX@~oBKW$ts90OH63Tax<#wgPKg#)8Gz&FRh%!sp3SfiVf;IR z`|Uft8UEC#aHsAlz|uX|=sa78K5Gc$fAu=WU-d5GOe>Y3?vEM{XicT}9^NEjKTm+n zZ)Ljli!uZ@4Z{ar3uw~wBvF6QLjGpI8j`A}2$${-L=D{m)Xn%NpBZ?UFB{Xy%{Nj8 zxx8qMKWi+0oBW#f3aw-JKY`=Dc=`!mq`Fgu<7#lGb1X({B{RHICI{^!;DO>g>CL)9 zVF1qD(ue*ojOOR2#e$RkO8TQ+16<}=p;yOxx_t$yD?2|KW!SB@;cqEfPIP9xSrVpk2|ZR-fiy^8=Ti$#Ju?~p6^0p@zAT~bl;<| zB*ShXx@}RWO|{?o4h>f*VDI^VICdq`8>YYRL7m zncL+1;Bgs3_uo_jO>5S`<#CX!X8X6peJpUm77ZG*aF?WH=SG;(!fP)_PIF9+VJj&Ey#hD3G zKIW3`Po_6-hI82h$I}|jcEW21(bAaP65oD<;o?^d>h@O+He_-5s6$r#tgMV|ebpDT z4rNO-F$VOvKtt~h^s)Iyeq!SU^kZ1}H#37I79535Gi#-J>{-8upz|o!l^GT3`Qb$p zMh%}uC&hm!MyJ<92sN+`(X5r1b7=^oa4g z1_!!n-+tag)DEh}z;z5`oe@b)KN?leH8e1Nl=38;cl0Lhu{}(p;vm91*;%yjoGxPH zUIZ(L3b=RD(jFfU7|rz0t3`=}P0)9h3T@M_;1@Uz1zA@InsLdSoOUpP*B@?izlbt; zkDiPVI#@pZQkEMWpbzEzD(=$7_2gghJ*ZUHpz0i(b1Ty!{edv&p8PimCH3kwDDV z(a8BReW35|rT9!@Ebg`ZwaAKTU=I8fI9uM8xA2yCrz21e7A#=>kDkd?`;s!5g5mIs z6F8f8vjHB8?nh^TjOSC|M?k&GN^1R31NQwG&N3dmY1x=gqTk}cbhewRqi9^+JoXL* zvv*+Hqf&y?ufex<&$vJCOoO+5C|1=Dp^B3ii|kAKv(y%0o((7KVM&xdRee2yoP8Mp zSq$s`n`ejgb;CuQcd%RJHc`_Jf82U9oyG=zCj3=d{5wdSx*b%8?q>t)`)%thW}ZRf zZhsh}rl)fqGg*)A;r0BjNCEf0k5RzJ^i+B+Q45wkErOX-ayb`$MaYgf!TxE^^y+I> zenaUd{LJ=I?YnBonkFR-?fZ_~EX(rr{Nuwi5KzACKWrZqj$d-|}yAEit-) z?Qk9yk>Hd~Fl%x(ry{QecSkdQS{%Dm^ce1WIVK8!8?T^OE5DMeaRc#YjT-fp`NL=L zF^6ON4m9m-G-*EX0kz6d&TVEvU#jSR~F_-I`*xF(B8JR*-;I?^o_@xAS*u8ubT8;DuRftJ)EL9 z+vB+nM(^ApI;-DJ{znkNcyd;HFE)N|j+Yv=>GSGso+F(5@C{#uogOT%g2Jl_wBmvW zY>l1;H+(BOS;kRsOt(h0qIvYpDqsH7^`*Fg?Q%b8og#-r--6nRSKJz3WjJxr8qbYn zJq1m3L>D{Kc)hd29`Dw`5_ojqo_41O5Q-b2;HZFgi#`s;Wl@W$srp@yv+ri(2!?fT zeLj&hR(hCj(TBceyWEfK9^?HJNNH{q*~IR?9ohdlPX`q^;^KzmnMbMpelR&U^ddhw z*OxmpQ~}g~+2Y-An`xM`1{h!U!E3C`6(arF&Mh4rSq|iX+M9AVpLX0eqqCInO8D{t z&?Rq4RpixSBFovB%=BH4^UKJ$us*P4RSp;4muc`84#mm|Tj)lMt$fKNA9QAOiu;-j zqM@D-u}K2fWy)J&wZwv6eHQJx+A0bEwujI|y?>Chl?m{WebXB%l8Bci87_=dp!+M? zjo{b;yq+d2jvtgr-cK~a;(0DKP4*v8({3R$J+rOP39{gN4IHjJ#O?2`2wF|<7?SNR zPPp||q<6Ix$~HUFW$T%TQE~uJGi~ZJ9>{Cn1?ImNI9{i`0cx&ypf5-6=gle}f!ivzLe~%_4a@+Y*?`d_yzFq>{3~Md1HhnSQEO zhIMJK*fc(x9vQVsG<5S}mRnsd%~yA?H9_qiMl?PA4(~LN=PyS!az}?Uz4w9`XzwRO z51hG6y3=1k?*{@lrYs`3raqD887h%1rTL)gzm6OCNdY>h4#fSo#`N;r_5ArAp&&P9 zCAF8)1pc-?7X1BA^?P)ZKD!+;q+%OQK0m4M8hdAa*gKTCA zRkdX|pk<=xQT-r<&9(k+N z>^`_jUI#{hG(+36RGQUPM1qu4VRc9~=k!AnV&$w+yJ8gGddI_)S6zu%zp{z>}H|I*8q^^LTp0@O=H}hZgUyaXsmK!f$O{!enA$W(t z1AB?g5a)+b&ArXM*!L_1J*eaESuwrUSSxJXrAyW3?)H3jQH_rqU?R=+t#>GgeeMag zc##G?N}mDR3=i8I6=9>99XbwPMq}&z`M*6DW6gwAdh-2AaibLKo zJgh*z{~_W2Yt(Fw-oabxnpv7~a;O)Im>213v_JWlk_Ou!33Kk&!K_1sv!Z)j9!i$J z64ytcuoh1%U%_oY*9*M$+3tnqRyG7X;yb2I{kgA<%PMU1z&jom~!sv2_;akAA_n&&Gc5=Y)RdHXIxp9MGHoEktCZu zXk9IELdyiU+c`Rs9?MA<4O8ggb1XZgvv9!-L$uqiO5a+a;;C}k({_`J&9V;1h@1w=mirM=y+^eAM5QQK5Tu5 z=xC=x$lz4z-Y+V}2&WxTqfK_x`I%8!eDf3m8%yN#aXQ1s2AxR0WqBbiV>%@=GL`I| zbrfh%6={Z#(nx1~9v4lGy*G(g_dCds{~%yvO|ucgTO-JGmq_Y}YNL?buIkM&>Y zuYgxWWT(etIS$n?r_&b4&m>RwHyqB;riZU9Lu9jFz55$I@uT0Bt?s(OI1Ysi~=6pC}8IInKyYImVfo%4zO)sBn~^vINoP%cvmtA6WBB3D~d>)O9~`S zua@@eI{8>3yMNO0Up+iuH7&=BUCXKO=&!_U|3F+eO_Sa`Ap<&f`jFh)o(7TC#MIph zzEC+je25Cn-W7>8j6>?qTuPMZFg`jqj8mSi0BOV3aeXSGh3{3sCX@A476}}(?g-1> zD(ubrzxGN}3YNh~Ut5~Tyqq6*Mq(^`&fxD=L}sEJ#BCLJfa>x?@YdD&R59ZLKRAC8 ze(sw}H;A?op8;p#r7O$C4rh88=KVjWr$-gqc6*+Tkz>85f|mPWP!X770-bYA12!I- z0&CV+a;hvR)5FgO_b4o<`5{yI#RC@L^FWqM^YA2b{m==`X|JR{mw*d)sQA`^TF5RF zsf}F8ch?F#z+Kbwz@WpPo|zXwv|c4bx>l>SOSi{82TZJrrU^Hncr3}BiBonYQ7d5h znb8Z2*z7E)sRE^bEjVZf&?`$;kqZ_#nQ}+K&k^d@c=m;?_{ptcGUdh@-hHER6G4X| zsJ}0hYB8^qIvFX&&m{r=WYE|Y==D|Llb>0h@J6u}jV*d8>7dzoPo8O3ze|X$j|%i> z_{sbd@Kehgx4mX}hizq~N3$9%3C!W#pDRMhGbgOh*hA+}*vo577>Ok;+bw2x2DvPM z0B*F@a;m!&p=pIVp3oUWt(L6u+;CQK_?Iqh50>M}I(B=)#hgkw?S5FQx1VDoO+QSd8D5=IKKiLqgJ=~~vdpIfYZsZMb`aj}c+3q_Qi3Zo zF4)*}D(!07Alm!uG4HpA`RPsA-*qn&OzhO8$2V5iL@ypyB1Z3L!IsU!+`TT=7$ap&=`W=e{!7#t zxb$4WOe3d3*ysCqdgk6UviH(xeDl1Jdh4yKJ0c#*1SSkK_mq+qMfI?+>KUicG)N^c z9dUE5Gu<>MRuk!$J{Ud)T5ij;GEhhJ01}dMsw$F}GWpp82C32Hkuoy%#sXsprj0vpC}^Z1+5T zA)dP|D=vJl4bEnUsLC{QUyc;9F1%zIa$K0TT~h{QmGWq+_r$}K1p?wlj}>&b!&frg zhUFfssM7hOAG~6S3LKc}Ko@mIliO=7z<-V$4PqQ=>?79adsS9kIcX``SkeO?+Js4U zhJK|=NPZFOs?TmEmvZ5)#vx9V-FfG>4#tF?x^zRIeUhaUX0h9nEwyGjOMMa-;4=1{ zFCVH%)J_L*uM@cCo(qF9-}ikt?%@y5BFHhEtn$quFURLX-_}~`P1(uB8qdeu)9;zd zp82by(dSnPm5=Er_x^-}1Dj8Oav${>Ge6cWAT^v(}UQduxY^1gVp z=&iW|Ka|a$QCBDpWqSLt_LCraa+uqe&obyD^qF@+z)7?D2jQICF#5Gk6{?w5e*@DL zg`WmuvCRgo{i3*%Sqh+e$pF9Z8^Q7?kMgQ*cfht7IVa{po@?69>(-TXGj1|Jnq(bb zQ0Og=I(WE=Yo0GV=nG1%S6?2Ld~dYOq0J+G~+`nKl_R>gD?5k z4+|Hn(rJ4tcpvs|A>*0ah2BJlb<%qjH*-@m*=%@z9oA^{7TbRQEjrq%1|&3+liXWR z+)^$<>R1iwO}S%^Vf~Wn9^xf$ZtV0AfRhhy7+}Y94ca(nCcoHfJ>M_Bgxh+C zX(=Q2!wEU2?HQIzvhw%ChCu>0Mt&WNWhZ0k%gdWYTMqBx71`f<(@X_;CNaU?mj~1J z@sD|z75n(##~Qg#kun_do&#>2Fn9M*xCgcUM^KwHYVgT%CM?)5%-TsxrWj*jLFLTT z`JhLxQ1xRaRT-xVaasmA_r!PlDCHTc<-{1FP)wifj;!-rKrozX?OZZT$wRgj!3WPc zKSgEO{?`t_Bsj4&xX|`cthy;HUNvSZ zdD;IT&(8?sx<)9#)Zg+L+mDmtA(y=e(z!$2T&7!|`-f#^eAJ~@6ZT1tU!4N_7i?)p zjv7=uhN3=u&ZEvMGJBpaIDFj0=}csuyw^;T^IJ@n7Cq)K-V4F+-YgHtVjF4LRSBkB z&T`3<6+z$C0!?N0>57>-p4UHiNb*q7U{6}L7rbbqwA<14qz|M$t>k=Fm0)D675@Cr z`c_P5@)L)L;Hx>T<39f+QA}uquL`fFd&qyC))-Z7NI$?b(IV$by!lIE?j8}E10hU* z{$*wWS-vk49{ROPvvW;fQpG4#^=CmxXx{ZW;9RaD$Rk{zQo@v6Ko)%u|feu>Sv z$fBNRi=xQx>Qnr{o-%aP6ctcRHb8l%DGj|8O!DH&d7T@++;M#c*s;b0sa+JU_8KHqS~PDz`|P8`87P&GqB0)D;c?Z;ZuQ>N+=xxs+lF=fRQ z(#nWeOi!q&&Ea+#DM9^8mVKR+N)?7@kl>meI4yrhnnRwDV~cy6ovBL5M$c7dkvK{< zl-=>WNrT2T*h`sS>u3@wxicT^*9*JH6w7TGyIc&eUtpl1WwYBdBhHwrU#Vxa-b z+z`?5Ek(SeQZty>3N!VoMR)lJFUz?Nui0E;n1DSLdyDl74oD8Zvc!SaS@hx8Z$$BO z4t&1+n49=l5sbe%W7_UuI(Nn<(ZYs%{E%M)*3EvWhq}?KR41u||90RP|J=iYUfJ(W zR)opG>if-H{1IjNkfsb}2O_ysuhx^xn;W2VmVj>xC;Hb%hkLNP%G=~}STbx&N#z1M z6(FuB(*wI|(p#A`d7F?`ynp`^&UgXKhpfp4J2!heZgUD*es>R8Q5C7adhtzLoJ8ZO zNoj^CM?IS#`$xbxd)8YQRcB5YZExexeBQ=4G&FLx-mKrjJO~;l3bS)b>n*r7W(1vl zMGc-GoCehw)^Yn}ndZdb8X^X*q9jBUN|Qx6MD`eMcoJ3D&3@OL*zfvUL@AN@)PZ%M zPHE@D%|s`3)bOPIk7QBs7#+y>QjlgoXuq5a#|Jvl&vX6A`)F4f>)yf@vwR^{cE?x9 zE2X1CkBLfu5!}IM;c@thY~B9>{?%(sJtpScvtg=c1{cFJpw90I;=`K+P2jZQZy`%F zjjCPKf+fS&;(_t)G|1~QF<3YaZlZ8c@eHuUz@Fo&_d)~y`i3O5I+#KWhExYY(5B+gQ5!tJi00&XP zw;5r!IK#r9R=N6kru)vvEQb}8@AyI{F^#4D91Ys`{x2VR?-zf6uE6&y5{w`vTaLQT zQ-S>@v+&3z#?$PUl0_5$@a6Vl(wv+IO?e#FK& z8e5n)yQdkhj@6^;E&C+yz5F5Khb?^vY7kd33u74f3wTgP-tMsh=bn2xi&=`0@y8w) zze}W#iazuIzRtof_f(d_vW-j>S3=|Uv(gOPrL3oWv37r|J!g;SlR-BnmtP2(Ib(P1 z1ocgc^n|x26z&=g?>`CLuY0*AHlJ8SN2dnyLBnTaEz=LLj5|pVIy{7JcCWdnF)Zue z&lv}vw4`dg5=Dd4IKH@ZCpYP~BFK90gyL5$8^JDsWQQ$@P(K`r(cquE*KU=s3@B9*+Ilw>!o>gX|iR1r6o`zFq6G z!NQ)d^l)2>=ZOc)ah_o)?Ht@qu62%sJT}YB-k3x(*Mz|2A_cmuQ5l*~ufiOsc6w(- z5ZNvEkeKwykZNWgB$#4Uf;WvEsRpC}mO^O9Va{|m%U5?i0YUys;)Xr>BJaD2;oljTcvtag|B}d7lhQZ)eC(OT;d6^d`6RM_B%-;%Zf+ru5+s!vEyd=tN8KOSXyZCOy8Y!3i5N3$;R$9=yfOftp zWFxco3xAi=CCRaM@`r|F(9Tpkd~qr1ty2S!ojaxTtbxA^PWZ{H zB)E+tozYq_!&~5Qwc<69w+SdWNe(9e7ze40=U0aNkuRB!V7aV?oBW&2I~A*NAfP2yJ4DThV+j7sm7PrcqU+Aqc6*#{?2ZQ zxmu8Uei@d}WqLM;$7IgZiNN*SC*^f2vgX)#>_qyq+K8`M$9g&(*gJftnrOcK1MTqw z1}+Osgn%Kp=r8jWBJ;F}?>RV|3p}C(hFU4O@TZyh_bfMP&d|ZL=ThmdICf9j6a~p9 zHQea|%x68+3I|jN&|?wfJUwTJ;>Dm9^z-R2-zIhnEZ>t9DGb6BKQ9GS5`zU!m z-xLgGS93d(6<{Qri#?OaQLlxS{A~U@Ty?IO&a+RK*YnRB1ue~;(hca|W3V{sb%msI zstLZkkVV^?zLD7pJ3#l_V{XR>=3l;Hhrj;@(-{jliL&q(fAsWIsej~+WDwRQ_osP9 z7xTxK zJca|#Iy?Bou{A`J%KpCrgK*eZ*6BR@E#KG?$?y2x$TiMYhVy^MLk`2b9-r=#TjUbN zgbH)(@oC5K4by5WEJ!6Q#S_7s;og57Z$xufaYhEGwU}umAI5T4Pv!jtm5cAC8p7nEhxpXLSzHd& z&quFH#)UeA#a`iVU|Ony{6(gnjwm8;CNGE6!)myz%y(IM*9QBu%-GEV{+>10gK*Te z71TcA3y}-d$K&R`D48b*;?@R!{CMGZEEmqQ=9}c``cxH`smbo_?XqGm zMZh;FA3Y3k-%dX@YQyx30^G#%e9C@bB3su+!>?Rnk7pV%1m)!1sp#7W$t|5Nct#xO`4_e@y?s?pG5pH!3 zrN-C36Lry6m}n?3UO3g8$G@(S;v(?6vndnd?o9>i)}{>ebQfUKq;}dgD2Oc9c9cX1 zY!V$h(SvvSXn?a{c+>J3YLHh^3`ZjJxV0?jVeG~2uz#MCxZ_B^$ZKB)D1IGAqutfu z((na%c4a%gIOQn$*k%N_@~fqH4daIeAhYm!M7xPxw zUEr@Qe#Fxu0**aC{+CZSkKzW)Z6KM~s^R%LHp_UafO#)}lw~*;hkZ$LL=4OSOy#=2 zD!`+-0a$#y53TDvk1tbp=lz>XxV0~pAS7%POl5l7G)=aPi`)vg3RP&@Kh`^`w2fDq zTr1T-o7EZPoM<}=d9V2gSA+S{syA3hI@8>;_?UWqH*sLNBKi7t47@6oq3Zow$eWgW zP?|h~zC54?gZ480IqUvNWEuMxZ;peRPV2e(Llj{T8X{$P!@k$H@@MYL!Fr8ITKj-~ zyRS~eKbvk+Wworjb=U21HN&(J_fq0pTmdGj0+;h$`+?Q1qOqOB@HNxJ%pCcN zTvC4q2jg_;gnlfWqINqZt`#uN`>`kA+2PF9-I0fJs&}BEcN#rXqy@g_3$P`uo!Y29 zCUdiVAckciZ(}>FIvX1-TN_Lj^DO!7{?T}jaXF9FYVvyO59qFa&-G;7K6m?mzU!l) ziw^&`1t)jAh&5uzgVkAeH2uf8Ur7MJ18LZTLdlJH&ajYiHhH%9b-p(i zTiayCH4Rl{g}gD`D&E7*V)>JSVt@QTjdkTb%_QOBB@j7B;At-=+TqbA3;Jqrf#=OB zdnE((Or*N#hd<)sfL;_-Sr4^9^{hp13aMRO;Dt8GnAMA4V==yFUAq zq5bnn2aSzrhGTjmLCM*(o+Liq&(4^-?MXZPJ zXlE!ICA3q{=P0ooIRIw7jFM`e2UuEQnaND*p;6E0?2N*+9ch#-%p!}pOK>Vlz_iDg zO8K|H%DE$~55=P~4O@B)7t0O3AbC|^0rmyw3B`QA&t}N}iLpDGF^L~y{VBK?R z>9G2^iqz||M|%t3@}owY4-@4x7-wa=(n)Duyz!Yae7wmGPCZH)WUsiOHp4fYFh%0Y z6L?Z4Lql|0{>RdF_*41)aVxGXnT66ITV@#<_nzn6289;wRN8|kQW0euS{ zanI+Zp`D^VkkmJ6FU{ZSKEHp!>*e0(zMs$M^IqsxNj*G{=J(SJ9}ZCg)11F$IvIz1 z-r!*vEAy-c2N}>g7S=dOe+PMX_zhXHA{1MyYl8e8rWKEE!n$8~)wQ!b^Ml=q*u$h0 zb;OiG9eE+s^=;YXK#9#5tZSSouDBzFkb6A$y1a5ERAm7!@lj+Pw>``s=ZJ0QPei5{ zjDRTI=Zu|H!Mla^t}@N@o!%c%=DlZdc`HAseQ!tyjeR_(6?NE;WB!EM|9BJsfU_ARwkO)7VN>Th;96bIL zvd|tt<1O?tw_gR;aXlpAh9aIDE`*g@p7d3Ryu?n9?VAbD$maJ!+{Q7?6aDr*#P8?u za$Pl;yv&!*3QEM;edi#z5os`>v4A_9#d4g|&FS$Z6Kqg^Tx2Jj}8ZJsx}$Hhkmxg*Ah0sC%9j{&_uGeAMxebbx*~n|*mHX)Nip!1-PxQ^_Mxj^XW(6Pw4lf50DZtb4(V4KQ8!ryNuTy}7L1pP&bOlN zJ2?FA>o=+BcM>&Yd1#Z%>e2Q3bYgpj-CH)O!$zN{B-ACBYhd5$@{c~$G`k54-!u^= zk7Rl>{289#(SZaF+rjNNk7=I|ThWN!9DY;1L*#ROA)PU6J}%t)4c-4?3T3vAxO7bn zDyYZo2BLy3w1f~)6-m#Wm6tr+z6EWqa+Ef#OBX+$Bp^CF_37yB@%Zh*-r!+*7_QJm zoN_+Xy=>UZGEJPYoFn6p?nF{4yVK^_15)YH2c7Z!JoYNijJ|LP#FwNE#M_D8Uc`ww zyd@i*Ty_DXQqOT;#mu{*R7Ad;mUFk>Grp{`1nyR`toSo&XpvtsEY5x=%W~-_cBhs1 zSX0>aOE~95)*Ub} z8d{k4TOgN+%xV%q>zWYnR1|`9!&EBXU4obRf>>{S3dw!U@0(@mW;E@y2mW~f2XQU7 zC+^~#oKL(eCEu$?xHiGyUatD0Z7pS+QWR!J&co`>No~6 z++twl@Fbj(uC){-c{G{mj%7Z=CpWWDH>@} z49lusaG$;lV683lBfp=BUoA@$Uu_e>wN8Fc+c(by{<{sBtWyMYZ8JDM))BW)o`|ZR z4FIpv_qoCTOsBdqiXPBbkhGotBYtpw7}YCD!Ka_SM~xRALH2%aY$FtcVRtIiCv4|d zBr}iR{-Na2HC|7WKc2$wT}k+_wie`k5QE}2em3i8Y)z+#mazO%dt!7km^Mvioz&CL zpzNFP!Da6|ZUNhQOG*>SXbm3Iw)H&*|82I%{sA-5KGz_qe8jxx(*zLxegrM7U5}^6 zEfd|EHiZt(T#I*`e?pdL`co^7{`jW@yEEjyCJAkd*gaMVAFer3w{CgKs$U_<)aU_` z@8RdM%e7r_u#>}cMyP=>)tjoVNyIw@b5PUs?a+0vfLoBD0xw_L(3G!2PUJD|(9#fT@mqe!e6ceK!WPHit$La;Z<7t&tEl46j1@3_iZwOX zPsP83HUR0a$N_YEIqBHldLZE4vj5EDD-5Bv8M!X!fxS?Mo_{dNlB$*5Ff zyPV%EKWPc+l_eSY-c?Po*|(1dWywplDjQLA>IyIs9pJj|seqb>8TCmMMl&cO8a$3mJ;kjI}L;%0k66l+VXL$Lg4z#a52@Lks$~s4~ zhg(y{sL{AIEM4RrFrVHCoR2U1eM1GW2Y|kwBisFB&?cq{|6{I#C-xP>sTE;#H)UO8 z(OXb2V@v6)_bKAvznO;da$jnBbv(XvvNvSEJOt@)56N^O-z_#l>?9{Vb$)Ny8x=-V z7$2lD1klzseS!Fd%d{WurpENb-r4xF>p8N-b0wXI6R~k^HnKc;4%Qt%C-b1~`kYHN z{+#6cTopiEZXwM*7A#qLfYagN2=wD zr?0w57QgC11{KOMq7(@8U}zY`2Oc^sQC!HkAH5aWwce@L%*19DHo<5)|NF`Z!U zCaIpIf=(}RguRXYzB#C0CEVEKA%*ZJ&*g-h#+KZ z9(Q;g^SqB;NzK`PY^KW@q!-IN^-|w)p8Be6*NG$XtQ+Fr45qmE2<+I(%fR~9nsS{`^5lfL?*H4n$o(La-L<&{6E=!P7fX{?7|y9r_J zUbk~*Yds|r`WCe=HX^6}*e@x*$ooO zZe__HEFU!|8?}ERu>Hw7SysTukr~9-g`c~;KIPG<)4`Ivm;Op$)g1z>ItQ$ppN4wt z#zNbJXR-{^TJI6`vExR3rZHDMcTEHNG3f=Gd{-I1st=-hp+oQv?Q7(kVJT4$Z{`Lt zZI!{>b|Uc)lkuBbWk+HAM;^P(Qby6A?796fULUy+Tn=xhC&}((_T4Ol&Swz*k6lYy#@eI;58S$sd1+te(2|`j ztATZ4T>K?s8KkkC*qG(;_~eq-$)VWviw68HSw(j-UGyT?+Pdj}Ml_RYT#J8~Al>>R z=#cM}&0X`^Z|cF=>3ES_miU2nFUWFKk!g2nKW!kR9C07_iD+pnO^TR&^q7{L61bC8ZFBef0_8Z@5at4`tyoSD}@3~|T z*4nZr48ZOv1Ntmpa<*mNm+|k z&woS*%=M^RzX7-}o4pH6ualeI{M=RIVNO%N$xF6(g`nM+uMtRG!0Ci3!(fFrSm4Mc zZ===VeK|+F+1@w!{A{#;XCfRAILOu2F^?5{2lY8`h2_gnN@1h`eDB*~br*Hm%{0AI zrq>GESB-AnP=mW!d%58(8>%e9k=`Gji$AAo!jedi&S0~ge{wo%jXwbS-=s4A#zUsZ zI608zW|$Oo;hHdb%uoou&(B?>?<3mEauPJ#E6^aH z3-B|(OU74XYX^FCuQOgAog{7@pDVp#!RvKTMFhcYwu7&M0Hh%t4Jk(-bMB14?s|eL z8hH$lzN9aD@DNj%Z%KH6?jK}a`Ww2J>tXW+LI}I$a_-g&Pl-j`TXgt=5}6asG#kf+ zFuG+cxt`-I%K;eauRwQy%D`qL*-b1rh;`%fbJw}NVRVY7AAVG!NXF=Fqst8v@W4;C zX#FcYVyA9}cOF#-t;qA_XizTqZn^*-c*a3=X&pD7Wf8CVY(`D}#^S2X4AHWyGnvM6 zKF(A9hT^_3y(7!3aUCCn8n|JQJzWK_X1-k`SVCVk$V+Zb+=6t5X;KwSA3WxKZ;(ds z2j9hoT=P{Gm?`5V4P*i{%W>LuCMSC#bc3W62m9kG#OBFfyc0agrC!z!*qFbVOd zfp1Fj^$039jowCPxYWov%3`4j?Ytwwo66;(zUHnpC+jAsTCEC4ZTireuKcWZ!omcq zSkGpN-#tW59tGe3Jn$&?nfDiE)8Jg@dC^Klll|Sn>=1w3x0pVVTDQ34LvwS<+o~w? z$2|-m*rW-0ma$YUuPce@Zmx4&K9D*yz1D#LN>KZ%gD_vYle_kUWtDt#qWVrVa3^Gm zy?QHxleUV?(>m%3+xZ_l;Qgm3pvB)+LFLwc?%j4(IJWC1>k-z*`YaPw>31R&IPBn> zx3avBBRS-3@d=C^1gONi7a3^g!u`vsi#9j`g-esM<1H=dbI}p(FY_3+J;#QI4~f8* z5>L|lbw15!Sp?fu&!BrWcWU; zhPyh4Wo17eMx*^VV3VyYMef(wJacp{Hazta#jy^fzqteO5*Hy{IwmFJAxe0Dr4atU z9ZVw`MxA&Vg7QXPByU0%aIrI#;j;7*l&-?~?OZk3<0q#6sY$qIMIhSc6%X%L9F+BF zbpEuW&l#SV_?(f-|M^AyEqP(fK1x$NzXQx0Uf(E0;OY5jJ`F z^avej*zZY8Hz(rbThfvC<2)EPfXFavKFeV)9q59io}Uuslq*PM&G@^$$3YjyJIAmc zP!oC`90X(6S97b`eRW*4Ej>SfFE*%7B!@qEP{VYV<$kRKg+8Qkd~261$JnybmNvX~ z#`6l2#3Mefk)E~U@ya-7I(!m3vYx>Jv_(-2H#;A5!F^fg$yqU_)yJ_wy}zjAjfmF# zNy2r}f6&+IJs=mZhvV2SWu&^(x#B2K$=+pe(Vd7}(xe1A+|t0fk53V#I?Pv=UHsJa z7sy@Dz_ChNa83{i7d9T?{MmD)RcT2Rt^Dw?6N+R+Pc-fR6^{oTsztp%s**H4E4-*o z9gf_oC8HMc_pY{xt#Ed49hdTuaoowaw6wQB{(L@H^k>~PY7#vk2RD612frR8zL`z9 z!ErEIV)=_)VcLU#b65K}6X>&71)p3ggzusAXae&-Umvvv<);}-<$%9&tzW86t(W=W zn1{Wgmqs3_1{HFKCz!W7EQKupdIGyeOc0OrpTn{{obaQ%-jK3$9zDP~<%r(|{o0}i zi$eIht7PU-nqa(AhGTES=FuH9SZC{&Y^1uO1}v=_WIJQm!;NJ57=G@0^E?O4Z`tE} z=Teao-2~^XTe)N_rgs`?OCR0egpcmqE6%N}BLU-Ipx^tIna5}d^%h!SR318Yrz1?XgMWhKEH*`I?wZxqy9SpZ^p9R;ORmb5*Y*mSxMaGU&=7_jS+Q? zu*CW6V#ss59n#zVO1a;Cm~VGU9jKf1l05$`AlEymLmtDie>>y6v#a5=gBt!~Cj^&N zj*4a!Zp{K-Q>J4sltH^iuALmo5YRXyQ1D1LaCfQJ~#Fr z`r>~G);#C$_G9uhXxlM)NfYbYF`_Q;;$|$@ikT1b!XTFCgV@a~pA7Y58T1f}Z5`Nq zSs|L9P}P;3>}aklNi(2Pb&2@S(-Jh*c0Ua7-^sZ?7QpVAE_4J9#MWza!~pxembwO&qUS&jw~`0j8|VwW(FhOiFG z_n)efX~_%FU+|ujb5(^ZhZF(@C-9NIv(d%4X=ILH4tHS}duM6wfd#!BaN(($D8g(K z=y}v|RSN`gZ0s3N6GHdP8Zxo35{^5} zZju8B(em%|lB@Sakkf(lWb(oVoZLjFfe}0eYJ%}SQ#EMa8V6~^4|4zVmqONA(J6}= zN5ANdw6NtndCcakNPBfKv0&L^@(Pks`>WA^?A^SwdM`I_J@e57+ta)HdANI^4!peT zLGQ4RnAWxFXzi3da5d(!t3u6=u61(3?w?MHM((Mvcb?AgiT4#Op{hIvmrT}#0iz9| z+@qT7vq1pNfJ3JrIF3=DU8F^SB>kG7i1ja2pt0#v*vs;ntr(wT<0Gbtv&Q4rr#WJm zrFPOiqq4aZ8Uhe1Z-Sc#058;hM-C?W!Q?*<_W0`nYowqOz zt-f@(Z;E*N5JmELnUMaO;)8>#*zIfGY-&C^5f2%%81=iI3-wur+;Em(ZHm0eg{8-F zDC>Wpv|tJ>9_EbCw)X}bmh<+sOlt3Bv$^J3iJO)56=j3ni+YfvuZ)-MN`(t#U&u$h|* z9MW7bZ7k>UZJ_ic2*>dEd_$Lf7-{B-*WP9M>fx+6jiK0O=M`uo84d%BW4Vi}?0xs% zkh0e%?(p7EOjNW;S92KFy{!ok%9H8Ko2HVwIdAK_kM*T)wXApPQVFVV+Y5FBJ2|b( z0+1g+g0}VqVzbRTVu9Wt(y6Y(8F%)Agf*|o^*~2_TRagNUinEb|Gv*jcB_IzuT^we zYahw#JT+u@NrRTo+=e%OY(tf{mmoq(M}~DX=gy`@qZx;rWrU_F#({A04%r<{_(*|_ z{BI|IeC)M&(v3E0V5|!_(@+_bRrWz`b27eas||~WSix5Pd`_3$&GP(NM`ZX$yir|5 znupG$BiTF?__P{1Ikdvzi|;ud)~oUsbV%IP6Zo{tY}A zUjt_$zpY-dX=e@RoFIVUbr!T~*=D@WaJ6Xg4USH(UyGNo{)qN^Yti)T{s+2&GnBGK&zb- z^(jci3rZ@`bJtpEywoMj$t=_NpsvQ_@zV!LS%>L)s7b1ia=dz!fj8sh<xCY! zPhjteKzFJ2L3Yo7Dunruf{5N4o|g8gX z-}XHdUgWLb~eE%wOSBE3p;sb3+{tEIv+7Ow5((U`r;hqMO27 zvD3&GD0JCIxZljrYn^d{g67K^NG-RfiMRApA>v*F>TcqT3)y?>$NK4XqYr!Dx)-6@$8+G~ z(?ag`eb#H7+9RDaVb6Po@^ZaD;621PbNihQr0~odXxsuzZ`HwZW?+R zwhFxWw#s_V#wFU)Bm1^t`E>`y-f>k#;W58^_J3hWbyiz4UBq1y`F@`C`pW+J?mRoR zbzUSHRNl<>bf`jm@+Bf|593b!h((&WbD(;v2L3im2-T-g&<(j&+qzD1Acy+a3>$KC-;(E=&wpNTSviUrcW68G67XAo)6ip z)$kZLw`=rWMbpKt*sS=Qcx6gBnS6qu-|h}IqaWNRVZ$*(5RKN8T2=B`r`G)hHjm@) zW{!Vz;PZG-oWt};ZtRBn-Mtl4-4&>FustZ>;_v(s+l{I5X&-FYeuOkQur6JjM4S|y zi`FOvc(srZC(aR9S*lYIC4vS|_)PXC?esNjy4>G`8g=_zKVY(wuaF~cz-h4+4hCSfkoM4_= z;S!qE&12wKm)^87b{oze+>Q+TG(cEC9n5`Wxa2#Xb_`F%V}gv(5`}HBcN0JR6=!dg zwn%p28w=lxuUKA}+AQbwv}=O1;E#L?-V&e2g%vqM&9<<23k_hwp*{^28Rn{$nak&@kMg4u0UQd*lT+(eqUq3{_kp_N; z-M!e7{xThj$9<4W>%LObCbY-WacqYT{z6XL@8fD}m@nCCD9xF-58n`L!|2=D;JuN@ zz+yieDwpYrXWpn0-H$z8cVQ&2&8Q#3x|(jq;L|HKVe9}6Fb}Kd?2?&A#oK{86(!=y zITc9MRt=7AUEDTfrVIV)Kr1FlaBX&`ctw|aeX1$1$5?xA0<7Esc;1b-BsAL%elpMU zi2MMAuMUGzaZk8T<{eOum_g^HH{oe_JwyWxhtmv(fxpfFpc8$&;iRTMp1X_PUXG{N z-;HEi*(xDa*-j&>zP>WgJ1f$FxhpbpcZ3!wbuvw9a4VJ{UxEaU6JclZyZtn?Ie&?qkM{i_p2*yI{Xukqq~WYz?KS&m`lHndV}R zL1Gv;%^Alqp88|)INFD4Z#th4q*EgYqxCk(GL*cScHJ~26<=)YA!&#GX&KW(KXlJV zSzZ;eu#n$Xm+uvmlQHGoSWV{9c##aHtdsE{FW@(M8R*?@<#x{#z!zP2n(B~_x3-px zN4iv!Z7*KPIL)BhMs$I;19l(XO3a!|>a7>`$7$2-5H4Fp>>8W7RHmJ~SPo>dAY7)Q z-Bp)?m z)G4k&V*-Z3+B^J=ccjIb3ffsOfc*(lH)aFP8kvYU&B{f7`+nAs*fbY!8>k2$0@LV= zYc3L{UP|>XZ&bEkQxsvLPpe$Gzu6o#~6BW%y3oesOfsH)7bvbDdN521pM; z5}pOMq`u@iu^7o?o!rkr`kP_hmJBtt@_>MO#J1rHxE&qPBH%Gf2Y*p#&%Ccct*~aE zdJiLXLL&xt9pLA^JofCFuxD@lmq%j7D;K1<-T52cjXN0-Zp89K)@g&{%c0Qk1Me4j zT;@*?v%B2a+-h{X;SsF2{J@Q5ofkUg&+C&s#^H@$<-^rS$+lW8Ae?v$6=GuNKuWwCp9Wxi_Z-E$g)2AP?wp8cvp-Nd8jjc0Xl!dh0Jq3EqYu zJ8Hv=`9ipHn!n3E*k?mYNg}pLsX$w9pMvj$-^eoMVlEu_nCzF$>FEjJjjuaw3I*(X z{wt+F8bk;~*=#(=-t8-K#RIncKq zL3Ce4E8d~<0`gE@l5vI zRxd(|gR)?eW|53vc&onE^Ubma*xN=`Jg&+Kb{%%cW)|v@-XNiwOp~+V0YQHz{v-;A zcz&Vgw=;dFk4#!M#HL^X0oY4#)p>Y4I>xk@OQacj`85d@*Dr{ ztuvS}W8e*b#&bXFLJfAMWAUg8u^K)}EUY?Z{DMxWDfMb|#R|XvBX=I#dETN1_)DHG zdTKm@487aT-T%zEhIUsv^4>_vB;7&ikb4bL@CfG&b>q;5AL$@mr6KFhF-|U|mTYGU zoRf}vrcQyEzj)lc7jHm|^{jEy=&dAG9>ZObiFs$~q$^eHuz{>P^MxSwBYe>28mr z=9}Ed$ExsX;c2)S39vvAIz(86Li#-f>C9ZSJ{fW@Du1&$c-@&_)4v?q?cB6<3y(s#HJpZY4-q=lj&# z^N~wxCd{Cn+`M-zC%H^amrmG-8=H@d>&rirHPZ#0&SPbWsLJ!)@;nJ&dsj>J%& zgLh!dn*k&?#*gZ3Wj?P&<|kTw7kX{^z%@)`I*=wO(ZbDR@c>6TRJ&Y2W(4POn)xgf zY1vljZgjvy$In7NLq>w)9e&SUdCi=CR`K{!ca$h9(uKA*t;KDEkI4O{koMVSh>tKo z)KV2~(VAL)yz#w1YPMQIwmb2hg}#de-S~T?r0Udh^fBl#NyiJg`-;lY`!IlFImSAk zYG8Y#fM#T}OqVuASA#NWmohA}SkA2zOkJ_HimpK!xMRUzcA zFWni}gbfaPhz_o^rhEG(W2eu*QOeT}*fc>OPcL8^w!L~HX`CEhN!Yui2@!4qKl`Cq zcVP42OkCej3+mpp+a1$m*o|mJiHcruRIfmG-@E8-L(dj2#{I5qlVkf=)8oF0SiZUr z{fO}v9lLFXtGxPv$TWil@8x;b>*gz9!lHVvRls`X!X4?Yq+ooru~-!4JC>SUosS<_ zd_`kw%S4Uev+(eV?b1n}f63hUDmXM(2#K>js65mBG$?IB*XmWI4c5uxKF#uEi|Jn& zy2Tf-9Ig&Fe|#wYmqS~!2;Jz&fPvmcTqw)%Y*mgIjrUl94YgIp5fiOp_9kaM58(XFvlaolEgXzTmM^Gd@_Zs2WIs6CYg zcUY(7KRoRJUliTWvh`3)0@`J43T|?7vi!^+7foqw(QLdm=M*^*zMB4aPQ+skb5X_b zt)hZ{fq0jX0<;b-f#II^c-QW^$Y^dFw0_`qBf<6Vw6iq=N31+9K6c_g3G)|l0rkr8 zYvLhM#M)$RR#`{ZzPL*I*gufn`r;-}phLd)kz{UFL*H(c!n=1o28MmCf=ko+Ti@3P zAF9M|eZeM1C}PP*=()$wejA#rMB1k(VEOZfVsUl4bk_!c&kf7i1l9{#cUX}&YzWnd z0p|HK{aZ_<4J~@O1Mj*%mCV~ej&^Kk&rEnVLLYB4t?viUY#iea)vH94PI=?9{qpGK zfw$7F(|NA8zriMG`RRbYH_SqLO~YZpO_sSGDu4=CN9x~^fjc6SMKjb#(5}$3uNAekWY+Xi@~z4 zoN-U|}~u`x*STq~nw%IOu4jw6}F4(G9Z4H{#U6=hGunny`=i z-Jt?MIDLAmFdr{tcf0fUiFA6@Gpu#13;k6}h4>#t);HmhV?l>xayWc~R8)(Oc<%W> z$KiPK9QpJr1|MQPd%cPr<2b9iQH8QbRMw3y@}l!u zru~#Q4^dRAIgK((#w%X@M(VY#(6w0~A7Z?=vO}Ec-e!L1y>ieCZZ`FjY-(DF`W|p1 zAyS^7wKTm3G3zt&zPXHxKO0UHZ?h~Zw?_2)fCOHTF5pVp9kOSn9o>F47`t(LL}%AZ z8ayTu_fM=tX%kM0lKNWVUnkU|Yf&P(!1mvN9LK}g)2QNvc6_I@6TSYi2sZ7m=TLtE zd}JB0$3KPR@1CbbZ*@n}4bSIe51p@Q>yiHAu@2dI!jX3A8Rhq6#3vQzSr$ScbtgKQ z;URe+g?>Z`rD`S_GCxAJe-9X^_~Hp{-c#1{rc;>T)-`1j`k9ah+h!DTa~WUp$*N0q z{c#ZXejpHo*a(&$bH?!l)WOrziB4m@{M~Z|^`FyCHeKGpk$uXrr^uCZt~t2h#9rWF z#{9PIj=fWj@wPt4!P1V$!^1ysi9B+>@mZJQsK~q*3EW@KJz*Z4Q!_WfWot+LDLoB! zwoV1kwT%l{#cmyv$@JpX5lv@p#~dCvz)$v-{_-{#1TD%iF9=ASafL5ETgcS#cA4mVOU*#LmYO(4=7! zs8i~VEzSxdMqvS+{H`0Xu~I}c-v*JtI<+!BciW;t^vLI_xVuyxMh8q2t*yDqRbEpC zk00L9R;4VtSlS>q35|tu>LQ#rMjgu1!|6PhksER;0Zk1xg6RHnGTm=SgE5`kJ{ylI zK1D|4tfYsTckGX5F8WwdL|a)_=aD3F!QpY1@Dg$ z>}GOYobq26>HVDNa}SKx5c@eNW9Ohcvhph-cIzK-%WG9(&XTe8jJk$oYpNPLd-oXF zvU}0Lneg(13Q%67gKz&)g}v{*=n>|nDjsZvrYs19^IiPiFVinyG`U(I_js=r$2uoT zhpD>AGKBLtghAz=6nyoeHe3tP1MmENZX44Es027uGGP}Um9c>Q9^p-ES?-NsQ8jwh z)C3CE{9b(ceTV4!!`V3YtvdR>yhFNq29JkI`WxT_!^2VQW}#83jxflqmOFToW%chI zPxbE{!F1Gqk;i98y5r$mto!5xvS3}1KQ0*J>NFuNTa_=8yQhzR^aGILf-&U&BqgkW zT?nQlOsH7FO=4Pl94*PtC*?^CWLZhmUz}w+8D49b>z+sJSZ>&mhqsW0cr^@FI>i0U z$^6}6O~)#a!K`dcx*5e1`4#p!a69uHDL*77%l2_ijVch@SC2lJnU6=k(1CAp3DkY< zGu&3!g~m+Z0hPCiEJJwWWox>yb2N@gIw!IZdFSc6#E5HUJ>ao>ipYg)F*s%h(;(S? zB_6^v+~I2i==Glw-NNv&WK0EG(0Uvo?hR*St_r6UhSL?ZC*$PBdEyBx=ZFd=Jm))# z>1Mdzj`-WA0Q7gKE)nlbpKHLd}uPhd+9gIob?!v#_)6C z3O^$9{VIn)yQ#rfT`Sg`&ihP@(RrX%nOL$*3&O^)rWY^COCISqqL#s8*fxvDz(FT$ zsK$cTOp~ckPP04GamJ-ySzm`t9u9!YNuTkO)Iv16a0^+Qo6F^l6TrQyNt8=y$KB1H z$ZX#{s5wy2o#?~#|DPP`xXN&R_d}(K-ayo@Yd#Km^98AXY$d&f0{ouw_@^$}(C_~- z?a=Ee)N||;JgDMlzfQ-|G-hKW_T9J$Sy=CYxyy=V+TgQiO~e6gu2AdgCH8aIgDG9k z`1DwHIM;4N9skHnCQAt#zr2&=KIgISN|O@}i{68i<|xB=(P;XZ?J~W7WFe!CN8qE! zd6`CK@H+$X*`x`0aI`DxU(hbSagfKlr{hCFi_Lz!qtlS>)rnA<*v8dn2p~(tkJfxE zVH$(G;-PVeNuQ`r*$r?vwW1liUU*I6FS0$ZRWxs=9{%*g8ks8y$WZ4Nj#x6?`xyhe z>Fr2KkH#Qmey)gQw1jhi$Hbv4MsYCxh6e7#bUVEx_RzO%_Pb%7j`oy{g^Lc!GR^P~ zQH;nEm2$dvs-QbV2QD$cdEV&+^g-kfYCqNR&qBuO2h65ca&Pe$Q$=)kM8QLAYi(>nel2`IOIAWRv? zW7=+4OKR%A9N!8jJILpv&A;>Mm#SciU7}U}LCGOFI+Mq=$GwxF&$5@Y zJP?ic5j17)MtmaqxcG$mf8=A1fID?f8Ay|l*h@PZUvR7=zw0WA{$hU5T|Z7tt>rZ& z2g3i&c!f~b%Mmx9&Ou)HOF@{YgX5Y1WuEG2dY)xs6!vC&Zs%Gk^GoGES2KS9oQn8O z9|PQRf35ia+6mHxE&Pmk;O=a=&3d>0c4>q4A_JDG+l2=WdxgvmHQ{noJ~s+jR^%pU zDz|MPUIHu0uq&7vv+jv`W2;fF>oxHI`GGs>$1)1mI*P5!#^A7^zvA)dk4rVu_`BaY z_a$(zza#dEoP`b_vIHG*EmwV908@sHrVGX%!*^m1h$`%C=!${sWcVi8q{Ol`2jXq) zmgRd^RlGV>4-4(4poml2WJ-_{{>-!)Z<2SC?n?_~dA~)5CmDB+@m4K0FsRr=T}+iE zGi#dBk4Z~mhT9>o=BNr}c3aX>72bH6>rLsbIF4j5<>$Si6<3J)?tR?HCn_+S_MxSk z`FKsN4%}{zp`HoP@P*ti)RLYEh58`ld3%31r}imhal`WlQAf)F5qr0B&YUvX?oK2v z4Ab1FX~NrHZ-{~Y8Sdg!0c_SBL?_fI;)|jRlo)daf_J{*>2V9VQ4DiFl-bdBMjP<> zf`Me~nT2$de|&vu*`Pj|g* z$7SX(5eb?FC71bGu40=V{n8$eE522V64E@W{*U=s=f)Q_eA;wzg6TY*Gv>I|+3g8A z<8~Y0->lDde`_LlM+k7xH6a|^Y(@iE&qdwiC^XKrr+&`$Wbu8hK!)D$h8>ij>x4cW zbz%9y?sFHRPtA;Xh%Vx!QubNBohqJK7Kpp2DvMY5QwN3KF1T=}I@Iqsqo-9AWLTFN z_KbY}#bcf0WR9lAvRhwA7V0T2guau{%Q|5NLq?0AdiY@HoldCbeT}rDh{reg=?kGh z(+&Q^H}9-*AUxB?MH~=7>GH93{I+6zP~0q5HabMw7xJ@QNrwf!Gu0dWsr?~dNm}BZ z%l+^Ui8Z>ptW|n}YvEMwgpfN;gWmqmZZ%qikjLwMB39YJeV!JF7FooA-G3VRGV@&P zH)YccOvii0I34{~9R>fbO6JrJ*^I$FXk*87*q}C(Tr)W;dgoNi9kWmcr$ANM#jtK! zSpq7|7!J3LdgGCl=~`hrIk=VIVI!H}A#LL{Jnw-z=qERdHe9^PCEjD5fOk%j(7Pva zQf7qM(0x5L?H1v{9Ca}IxRhl*$xCK1{9J3*AG+qmac7wBC1Z^_ZQHyOJ1|T9mCA+m z#3a@i)3yfk)@1B-`;e?)3PALa!Vl>g5kO&ldJOaB-ntKl(^cFIGd59s5Daf}h{4 z!jD5)xDMXlstPAD$L`OG_>zthT2mbYQtwo5&mI+sTWuk}a#9ahpIj~WcQca~bG)Cc zw9*$+dvC{oI2}0kRhxe6{{~N3{t7wYQiDOl{oLbr_FQGTQ^nVXxc}4$a_p6e<}n?b zqf0e9-q8rzt{-Lhy}M3UV&ijq_?1qBIP^lIbpNp&u9@j`PEDQz`|KQXK*B6!@MkFK z-mj7Q?v3t=X~?sqxJ-CJRCB_Tbt|mHW6M9Fp%WFTKOTs8GA{CFik0|AYCpXG{Up@6 z=e5)+o9(vhYOoIPAc5cc-S*In<1k)Xf`5wDV1;lO^%5ybf-W_qi$4~CEz6hCW_sF+ zG%I>d!4IF=az|Ph<0x)ZGsGK(XOV(+e-gOK9>2|0hvBJ|JWk?gx%0_Fx@cBDj;_^# z$c2&gb{_MOXLTVr)p!`P3S_?f$Q~2wx_T_WQP?1Q24YdmWM0cRDtacdzp)KlrE7!R z#Wpf{^ck+HLjbpI`_nzZdSHiDpn6C^>q;VZ;zSiK%>Po(&u{(148$h~$Ybp# zYB1YghZw!)yi;!C~nvU=P9MAQ5iQbz}1>whfuEmsfhxJ&~ z`0j8#{CTBF$oj>`%LQSZBVUk%Bu-r8HV@+&$EEAa&Jj;r0e;19jK@a~rc0SWrS4%A znt$z6{S43T;t^?zB!A2+n8LK=$l9mQ^@ZCp?h%M95wibl*W#ik*5#S6p- zNZ(#BWqz*dPtEB0)#LC1@n3RfpQCs$>x0uSvqA^1os`!3v~W{K2qE*c5>1kGlVRH7 z|8^7g9)4!CS+EfbRW$KRraLM%$)u+HnRcabI=a^vL3${^pB|VxfHtl3z(+o%k`29X ziY%>5IT6zUWbgk&CJk`JF*_5`izaJ$dJvt2sw5da% z>t97D58mXSQl=kxzMZ7@9K%N*hKcW=Sq4>9gtJQ2L9=8&Eo1&Ti;4u)u%sWfE{@~U z991CF*MY9ty9NI$y+w3t=Fy)l6F_`^59;>W18H;YvDL!4NR+#kaVRf2JXjSLj$mC; z%B&OlR%gl|7K&ZI1^Y*^T_> z9A@8<4xY+%K37jJ2bbBYoI<7wEL0yMuG+{%fwNbOr*!H`*I^#7yw$wmPB-IT2kU?Z z%f-Xr^11#@BPxkL`~@y^sB-; zydvWRT2d}gHKz^4Htd};>a(NR@&6cgIO~!0)p{jt(8cuR1u106n+3AG@vl#gLD@

1q-yv zwte>4j(uN2Y?qHL=5KM{1*&w~)O`G^QU?~OZl-oA&+yfaUC1LY4oo9~yUX_0FU9tB z=hUhAuG?)<)At3UAFKG;%xlCDve+*cOPE$!u<0IIJBi1r^OO3~m`lvxI=BKI`Eme0 zf9ChizhgaVI$ef0$Crxpq_;({*!}IF#<(`=H7Wm>H$EW%%~V$awaBMj{6VIZSBjt$ z)O95}DsiHgdCGLk_Vrl9rxi7?z6sV0uNJ4Uy@vgdJ&Wb>iyAfXcr$@$Rx=&)MQyY# zSA|qH@iSY9Mls75+KK(TwP5UV2Uv5ApV{8;vZS+*MPQR+tG~cP@C3F z@l&QB`-fdB4<`_nqbKkX$0caAiVq36o6D^Z5x~H2BATf494{UG677315l*N|c^v!A z_!qPhdxf7CCG>HjrCLGQbH^7HnHV8Heaar|aq&|Bb(LhEod8Q~g;4*st6n;e$F3Rv z?J)g=FHSI3hiyjjP+3$Y^GAGaiV)Ylvd14IT10`HKagmN3wGS7&i>yfGABQRYkI)E zb$!`wE&2$KTC5F%#F4a^`BTgrvQUuEeppp=UX}qe++~q?^(13FYlw_q6xk7NW2A)UA3D{srpZSnv4xv8LkNxizd$Oxlgv>cg!;cuC)%&WIaTL4^k~Ie$TiZ$ z<~tc@6c$F)B}~U_8G$BG_khO-lewouRiGusj=FQh+ z4VxQZ?N30x4NTy|oZdL=KOwj&`jIp1dF)zUuT2${r{f{4*K*>y*-YD(h!<6apqXMF zaem4zt}9RoYcBc{#Sh1DiH(`M2q496A~C7^!$wAr02PUcJf zwcd{Unz4RimcjY?`fU1u-L>A9?Li->XMxvZd)z)_F1n(&1#-1taWmO{ev7^ht-KwD zO}P@WDEbL`e?h=~Em4Mw_z3apN_*Vr#cEO#oJIy#JmCJjq6(Jv+3<+zP7kN$Ak*Ck zq3eSVRXGX`(RIpcKTLZ<>q zhV17)JYs$HHHf0X3OxICJjv+mLTw8Z@iFCU`#ZL_NaKo5$;uaHC zX~C%+ZZP}a7yEg`WtLszv1}H4qun2#=J7Z-qriC68mFFB_!ehDYOsls-VGTqn}VGu$ucCtbZso2oRku4;n{q>_;bzTf#- zD?)1|71u1qvz6=et!TjuY0fed7kIJB+C~j zqQx7p;ceF+;!XNC$bIb`c>fjC7nMKfstEHN-ix4@pN|l)_#H2*Fdj&=`Zgok#5QO# zy_R^i@iUly-FzC)=Ko?%bC_8<1E`CnkZ32%3>oxRGBGw0jXW;}KWz9R*(mVn&)Tg& zm`#SZ977;>5V5re1aqb@IH}md|b10-8ECY6=<723h98R`w&*2=`%aa=ijsTf*D-<=QNpx=JGrTm$ z9$hF@CV5h|IN^E-7yVL>Xs)uO>o%Q1EzFS59%DKvDGJpV$HS8mspN7KKc`I?xerJu z8l%c0Rd#8Wm&h0JyQjm#Nn|CBt>sM&6wPVZdVK7liMj+ zf}UF>umn6UhL`-`0M4vc7CNCvl~s0feg2c!O?m z|7~r0NC2?{YUuVUMY3tgdb)NB(>raJn2s`8ui5ti72rOc zpVPhy9$_$tzq4t$>yy?XC6x0;krV~E;dR5y`|~OXUsa`>NAg&=u6{mMWcRU~F+uP+ zHU}X$>p2n2XBb}eTJkVA0cp)z06t1)6U$KmjeMs}E)AMR?=jt@?WsuUeN%-j_SxU> zp%_p-nnp8{uP3(=Uu&LEIhJ|Y9G?RBY~KcyJ#^61~PjeFR*7YK1nLY`~Haff6e}J*NG$h1#y+`1VyE_w*J!(W{$G#TQJ5 z!Ld({kU}RL^yPFi%vy7jNPcOcjiXri_vk_@w@q5SF)|sBEAk~bA`ka#OU5`wfw{j1 zqj$9%L0`ex3X8eCrf$$_=Gh#05ZR2(2nOZAEa~8mF zPc+H9k}}S|PJt9mu%|`K&#@gaM+8KMw8(4|IzQ(N6t4eHwj}Ypr+RH9_>!WH-YU(6 zlYL%QbVSM^@LQ4i@7;{$=lJ*c51KtYPEMT?qogPyS-(DzKK5%v8^o7ji|1T2yDp2X zsFx?+W=3@LxM}E>O@qW>=0VVNMh}^8EQM-URVDX`6qGNxlT5ukF4H# z5)HVhL7puNpqKJn(OdTqQ02{bVk==cH>R~yXL_5WmCMkP+@~T}^F-0vC|+Blv(7|P zEVBn$%~K&++EsX5$`x*qKtN`ssxV(U^D--5gx2=Q$pB#|XCq`eFbnKy+T#G^rCS7K z(iK6`P~P{tH{Dty{u6`plg{Eq){QlW^=|x!hxutA@S^VLT<>GnrQ*4l&e0ty#={as zmLC6@$9Xd{+0h1v|F}U4-}AcSq^j9;t(fJRzcGW~M_NgCGmp&VnVsNMYn!C{@N`bV zd^$sVPLL&W$Iv9vAQB!mio7i4b$4UujHC($yHSRM3Eum6HXXG(3Td{N!H||i;C9kr zba(n+EN3n)S(NOKDs=_0B*+X`xA8OH?%9(_pr?ehvsWO)Pg+q2CtoDv+Y4tOEC;6> zr=rJ($0aiYtR(S*7$hjX1&tLGaF#Q_pPp5kKB$ZlS9|4 zaC>M7XLC-D{0y?9N2Z-&d1V@8-E(W|RLr>4@^~n|pF&nBT<_PGqzaRO=5`bGYnK}Q zerj1o=z|N~Y?eV`801XmPUGjj>H=$WVk?htbw#2^Agl?f;Xp-zn9M)?Lb~&8mb~DYA zDYlfH+siojd50xI+cin_ZY5OuQ;`VF#rT?QS%1&Mu?tGn2F*tyaw_C%^K9D7=Dkr% zf?%l!0{JoxT-;^W`}x6A62tVj!g+2$-(f1*Hy@zD0V-rtl{%%`f8uI!I#<&nPb7^~XiG6cTQ?Jy;zK~QR|nPmR)N7)Tt&!bekPQf=uEZ`XZH=Juj`tlLG!m?n$Ki zP=lP5UQOc@T9KvI2Pn80O7aRA21dveBj%-*9={ajZF(ZA9CKQ<+@GHbbuTY)@xQqf zd9eHUPjnTVp18uv4-}BVkBamz!@$Dt7vNIXy%Ig4v;Y1U8Zw?beq4(RCtU!4R_TE= z>ikS-oxRrO5c>^(q6PTc`Bpsm?Q`xCoB17w|0GQTTTtz-HfT7oid1RnvL16qB37P3 z%iI`7HJHJK7aPHY(Dz)6_z%AHeyvL`^F&Wk>I8QUYbB}KyuR+}qt=Mact3LLA|kuJW9hC5zQ|xgFHA~o0J(G7&FXrJBx+NT%Zgvo zXjalK=zBH-cg$Bn&zlv=K0#weK_aiIo0-u-hVSw~)w7wlK`V#uPLLLB8a##;6L*n@ zsvOR9r#y)ol>_8A8ls-fM6?rK#;?QdQAesWIXtie{|yT1*Nr6Uji&cw@{kt0GnA`a z(Xn>X=!bhEJUT3il&W3t=Te`I%L6NYP0-ynY7p&CcAi>&fs-)4QqW~XzD(!mz4*G( zY95M^g$@L24##EMX(xZv?LNj>O zxYXGow27*ASrtmTLrieNn2YT`%R=C`3s?}Oow z5-X`0?6=9`&D%iVHGu*HT+>dKk|&%zL-i<@}jwv~u@hN!tKrGAvvPo$F=# zoKR0X_N{_=SBy5?bXSBuSl&$5ZPr=bBcM~_=c8|yI=$N zx=oQR9tB)hG%Z2WcZ@;KSV&@b1C*(wLX;j)q&Hr&F1GkcD3v2mI@9*|XO#!MfON&m zBsAjmH*7p}2F=(Sg>LOlf%e~yg61}5RC**A$3I`=;-kvG_isC4YUO^icb^sVa`l0U z4S~#8($4*vARx&-+4M2ymbMOf%Rh{ZLT9|c3>P{ zk~*4tGOetjt^_7LEhWP*cXKT)JKgGa9#BZuK?`~+!MFu`TyGmd8LY^a%N2G!gmLvbU&fIw5Paxxp3+J zqrolatNqV&p_Xz&l(+UEnlbDg)|!4F#|&uYK0FYRsLMqpLB$5u%Vfd4S_uiV)9u&M zg_%vKx0v4J5H^DbLnFYw(hjaY_%~i|5+Vv~UWyi55MUj2Nph=?*VH}oKSykSuX0 zC;27rII>tY==)@3ohJwNFUsRV9sKMU`Dp_2+raO<(Mncy;F3cuE9s7C)^u~)HNzL( zH|vEPtVW4$-qt}8V-~?3eL?ujDh0HVb!SL1T}@eti}>i#t58j`p~8xb?e9yyTU1L9 zukt|S#w(NLm6_cOFW7IfzsTjHN$e40^pF34UD^Pez(w=jK^5jnm8XAkv84Fb4~u z7QF586caI?L4_9-zgBsiTVB4U40fA zn4^Z~zfdHn{_dt`m!-u=AIHLxg0UpAo4@s)cQ>Gu7tch`<w8?XSq@__CfGx)H-mql;4GSY}+C-Ij|TRJ~0CLs2$mJ3ZQ#tDkLz{g?ckQJR21W zw+m#*@Vomt1$Q=wZ)bVh3zLxPx^K9dUH>u|x3z3m3Jkn{3e0_=jPxUO@%}SDqQy_# z(C<7)*miXfi4U?u0v#WCZuW9AYB`UG8&Axm9mZ#wCg(k1x2D@Y()>faugf)F+4QhOB%dwP*hqnteSq5I3dmcj%M>2ne;f@ z9Woas!wU=Nk+8wB+*QV3uo}IFS}r3`+MSMZ-6HJVY%;CgPA$gG;N-tHj+zh9BctFFA40X@u0{^kxtdUmKE_^LAe%vid@M5<)9VG-E za$)+24AI*Qd?%MA^$=EJIQgFr`9ND6St^r`T!fnBUe!E0<#sDFG5i4I4Azj_BYB*Z z3bm%qQR@(ueJ|4Rs1<1i@P0Il{A~QNgx`xBg=a|R5-a3CdO1{$KSI9eboT3w*By4C zF>0Y`kmfaz&r+&IYW!Y2aGMr*J|_XawY-Wi*WbX8Wm~xy_XMoF_6(6aX@zPtGvU!? z*T^^vT_n#u3ze>Jbd@*bCeE3`Tia&o+t;;)O?hrvwPrw+{drt@x=e6gsWwju!Vz6={X-? z^jftSj?XLt!VN;?{BM?IS6Gtht&a{WI_eFxbG-24eG16yuOd0nHHvQ7%dj!-D)jkv zoq$*m}ZBoK3ho1gk0|Q1$i>2y$JZ85u)gmc_M|G2l1?Q{vLQ^ zS`m(J59!b0SiWDnt4cX>RF zJTii|&t8fqvka@JEk&UIq!2AFGJwse=ZJ!X`T20oqQ!Wo7mtBb-=~t@g=%QsGuEM5 z98AracDKGU7EZJ_Bjw65{W$|;x=iSs>x)q6?Of~;>J27v=QuJ&K$^B|fue;8Xv)qM ziB(Gqh0*MWNs! zLGa&;y}*O{&g6bD&h+Xt(dS4W0}ETs3CaVgW~2&HcN|ZTFdg`i-I4HxpA>oXbw9Vq zPoA7&y-4m%`~Ao@1%}-_2V!n3q6NQBVcmVVL;>^MP^Oh5EIG4{yo$0yTSxl9q~Sg! z>Rvndob~3c)0{&O8Wy37;7+in={6o6An5m+33n9%!#P4^&GJlkok|wv?itLoVXfhT zu93K6a|>t7@(+{92s+}kquAiLE!3PGN@Q4ulIrnf7;ko%%$vz$;E~KU%CX+1U+&3p zm**@pcT_AltVW)k$tnVWHVRSv%EcgKZK=!Gi9A=5-}eyz%{z!T+|nSwb6W9@0DdMc zWEq%IEDt$3rv$!3#pL;`?tY%vahKyYFSxi7$zj@ z=iRZ^PW}eCyXXM8T7eS08Cc(ac?T?al}I{@K(wb?OrK_gXZ3rh}2GS1~Cf6X}2}` z*eKz87qEHW(Tys2pF!bwdPG@|hS9<`zNn|S2X4J30b>l<=YL?9q%gNd^hH4j1!;T3 z&qg-*=UxS5+Q;-8tOK+r-bEaL{3^T{EvXo}>rj8cs`Fq%!uNR~t>|9rfwassxd zK-0CgNdE18te>S7{XE+ZUq!`|v5RhSN1Irty%>YPlkK{WqaP~7)}qp^F!mM zRmrAB7;pbf zp@gLLgk<^#2YUXSg7|QVHdJx7#9eFo*>9*on(nt*fYj!y5S>k~bS%TYr#)-o*Ms{8XSx_RpZSaIkE1~&Zc_r6U6CRqwmOq&aSZ1q&+s5=Uwf|9n(xECPN+BX!3g*kAc5Gr_gPz zv#G}+89Gk%B$w@Dxfu5UdZq6zu$^Jx(anp&&zXjzF*A97sEVW%hgf1CL zleMFR@tZDw_WQZ&9x0fYj;10_l4R^oqaL)P${+9H)>+HQ+=cw?_d?#9R-^`_WeMG) znwZa`>Yc`%<7(D1r*Q=PFl;o{V)KJiI%#40^U`nrFyrR|!u59c`)!43*7VqhP^4;f z4a5l-gZr$*D}dzyNV?DBpXROo+((5|IvH`;3SHTd3GZFIK(di;f0mTO4vxAro?=s! z8N4EY76eS|;0ld?W8>*+z;X6qv}pWZ(2=l2683O9cT!f4yw_euykEql`sGZ^)L=^e zlm>`D->ZRk34_R-s8if69|fXSZcC+FPM{mIt~foH<$Xo6zKpG9aAQC*IKXsGW|wba z;SXmpdHZBEX}%nE*>qa+=rONP4vEm9={c{_F`IUH=kI88_cG6k1a6r~hp#?^?vftS z^duwNz1|lsz25^LkvcHRSBPYO&XTl=Rl#^?9kkHT8xA?Af%nBJpe#8dsg-EZp9fvU zanVA;lMRIjOfyhxw=u6tOwe zYE_=-P0b`c@V-4-c~6;a2+YLc7NPxm7~4c$x^^1NR$Z=14xS97Lk_m0hY8)#chx~M z@7HziJ>#{%@3{x=ykdXP&mSN+HcupCA=!K8uq=pyLZZZOP^xodp;_%9;uZdi+dNG` zn*9Ul-)`1L;$jF-rbS>S^L7~2&T`;C7}LXE{%Fh?Rg%3%0~+6$gl_y=2EAw97S+c$ zaa}BT`g+cNtaP;snOfz7bN4uWEtki}D+?zOPb+owcao4SRtTV1G0WpBjfG{t#^j`V zOursxrDGV7cRt6B_GDU-g|oqG^QGv$-wH|HfhXAEff5>K&bmDxTTy8xf%w&aZJ2(} z3|o&V@9+G2W&E2g4qSjvtzwxs5gdKFJ_=Petc5;*4uf^Ige#MiVi}NHq*flH1xrgmG{Di026_WTEc^_c+WXQwMi&&Y>)$Y1|Y#CaVygf6@VpT&l2V zu7KP0L5>(%-UAsdOJT$@5k5Uk6^zqk@2Q&=R9o^!6?2MY_jfhA`nRKa_zzo{ zJADPI2)03n$C6>8Y6Owa)kLw(!=g7Ok$NYw@5nM4YOHW4XII2>UMz2<()%sY6KEnu zlR#iRY>Ftz(w_TvOO}{)?!#*T4k0CTEpl?oP26&g--~Y*@1@RN8e+@a&#|?dKJBYy zJoxSsIM6YlOqlSszmuZNr5y|`(L{~j7?cI%i54X#b1r2Hw7`mz=HiF_KT`Bk1c1>GQLXQrbe<1|T6<3yU?(uyv>dk;lp7m=z0%9%56 zdLqlG(pwpfUOIJ)_TQEQ_qXymsR*V4<1H5Gu5=|%vc81hC^Vv<1vPN^<^8zn9=|&; zS3gel7g?d)7yd9QK7!2u+S#8~rPOLcMMc|DE@^?1n5B9Va2NOoQ#42@h^NOFS3q_Ui*T_qtF6cGHNvWd;`+l>t%8dro}p z503q84WxeSpywaMKyas(#M8;6Kl@!daUL1`Hy&y3&>%74Ms$_(0P)JI8aQqc%Tdob z#l^F{P0YE_yPl^})XG^n>AFk5)^6pBGB|n5HBedE!TEMq;;5~wfNtz0WL+i;XX)*i z*pE2DZB9`jAtwpB!1`Nf?T{hqrAl;{+-sDx=N+7PaU^+AFX5yZcQdgH(9aS4%n23_ zrCWo2k>TYYxLEEUxN%(?rTMu^;1MhE>7F(UzqJrHg}#^EIjw-!4-t~x76LjXjlVsP znO0gcGCUr{zgNV~tXuH@Ll4x-Jfxp1j?#hGq{YFvnqfrlNf}nhG>w8-W@a}qZO$h>V`|44v?g<>s%Jw zQ#6F1z!G~c^s7z=I(gQMQagEEE&m}!6j)}I8Hk1ZS16G|3|BLdfLzh_qqTiZi(+pG zkNbqwXA&P+9+1E%<+rE03A;Y26M_@apxE;56E9r{Ee*P1xLU94NDAs%aOJBwtd z90OhhZE;O~F!v&4KfE!09Jw(`9bK6zB>Kdc=~0>1=wd9?%^pf}7R7KTVwO?4Wh|YP z8-ki)IW`{^1I}(a$A#||kiov5Ky4V)qpFRUNd2hArQej0FT-bLeKYDMBM>)j)P}Y8 z!*OsQzjsGUeKpS^!3(Rs)LuE+FaYR_Kko57eu6C%K@5s}C2Dhq_`K z5L$?mBRatEVHn>(DCo~RDEQR~dLi?Ch1%k>16E+sZEf`OlO+t_TPFD(+rk}iW^dL} zIXaqYIRBeJ3nwii!$X))Bq|xE^@Wi^w=_{G>tKDEdX(0tN{hWsl3~98WHNdukGEZ+ zKY)GZ5Hvnu8!)1CMQuTRw)5onjo3Wy5bD0HNfx?X$G_|N`E#{<7~LnODOP&&9J?0k z(U0XUvwd9&)HFOpidTK*{_8B8{QM(m2-QRugD@z)eNkjnn#={V%oAk=X=2OX>;JfE zc(xr+++WTqGoAK?d0|vZMN^z35rPfIe@XS3rKohmbNJBlDN)~Ufb>2y{q3)BU_hfD z8elLV#$VD07az-_ss2jDF6StA{*;fNoYaTo7L34kG5j4ez-AMfD|AIZu1aKwxgYhD z86XyV*Ta_CP6S`g<|>U8$h{Y1X*CK(mlpk#%o+9>D817{S=|?)=O|||q|^v)XWYuw z2S;(*hytXevH?Ca_QOwp@N=nEXEhNVPDkQZn&i?xF{O2_==8()aEGxsp;su^)Fe+n zTpmM591BL%mUN3ebQQrD5zkrAtM><6>rBuLwaYlDd<*t|#A9q;dp!BF!3uqN>krqB z4=1DDKXImF0ZH3DhPqtYiB``l2Thf`L5f!bC+p69rptrDo(e0JX77z(#Kz;2U9H?C zmh+RWmO#XrJjV7(ogq87>asoy)=yVZ1^TwW=6e2o!~1$?gYXC)^ddS8boxn2p8euA z*c;3y5r35gWE-JDI-U)t;Vcitq@o6nm@Xh)=XqRJUFkx7eixvBHVg3UGL}o3!LpQ> zl)+0uMPSmyJKU)!`PkvtY;ZJM2i+fj2ZYbzBx&0G&i=^Y0!epb*>p!`$f7;QjW30vugq*k=ZuN%(uj36sgu5*J` z6v)5zQc(0mi`|7}p;)O;#J%S+Gi+QZejdntPYYrpdM``TUcch1HVMd~b>8#_%MZU| zX$XPy9{l5FJ8ZR*C&vCmC`|K5#TKfh#N{7&IY0|p1)IT{546FUtcToP9d?geJOP(X zOGHn`?*^~8jKHPugSka}_rvff=49bAb+pJ=NW{auY5W5oGtC2Z$r%rR7DXnObmxOT z=-uc_EI5<^)J~q`WY4ht@R7m5|A-Yz-)Se2%qqhQ?MlebhVA=yhWJA+zo)NS_nCAA zEI_-&Dn#l>2Kd@t#?@W=iN|aT24iZh&}cs?@chv~oVo#`fmtd9v)<15? zRtxOqGYjlo&feJ_mT<({yzEFP6mc(Xd)T6KrqAZu;}Y59vgdJNaGt# zkqDeqA&qh+_*rv0XUFC@=@FVVv4Q1%`7^D~qAc>J=quN0At2!ave36z6IEjjw(j~Q z8hnw*L(R;=c)^A&!W8}*5+V>{qCc597n4M%`!L0bn!fn=iu?i2H= zy{(P~kxcWD+`ACNQBm0QbSoF6tw{E39wF-)Hk!=NgkLkW$+OM6Xw4qhh3Z=l=5DFu zc8XfDb;njvcuWViC5Hiv;_M3ZPM)v%oMT63TP2{FQ_Nf6BtzyjpW=E$S8?1u{9;pRd!+umeGd#h$9c8%J zI)pfAvn-w23S|D^Wpppg#tECN11c-DY2RUA1jBluY3T>hZ6=MH4osAcAHM};M`@$x zfQ3*xb)f|1^Yi3`tYa10o#9|_;Wx?9J9#AblLxAt!1Os}Jw3Uq4Go@I2A}vZVVNhV zxiL}-E^iXuJUaRz0)(jeD5 z*3qSGhD`J9hPt!%5!n|vIQ=I~Yf-EK$JA>fMSq5e4QfEH?gDp`&5AoGJjQAPHt6=u zSZFooAKp9gHJ7wgKwcTmrp0mt#D7N`!W9-FxKGTyr|fRIe(7K;l39-O7pRi9Q3|lc zK?~ikFoVZGS%CF54>=}aC0z!eB^^5wkj;ag;6Snt_8S<&J&N8Bo8OoapICJi!~9kw z8fVdU52eK~b7SG)2rUxt!{cFrcN);$T*%4%V*Tt=M}T>q75Yi+B$ibL_@25likK@T zXID+23%8nzO>f%6XPa2hqd|E;Uz5ALgWUxdpwjtFzag7PYa)Lmmvc|p=U)H<29mio{Kp6(6}MDX+WcN?ePqP^!ES zypb;=s*(=wVlnH7J-(iLxwfHqg*q_gdI?^;K+x~S3wYH5vdyH>lW!JSIddbZ?AAml z?~R2slq@BI&ssQ{Kt+-o{gTXKT2RwoTbP$OnZz=FO=?9l>>9I)98l3hUO9>+;M95= zF|7?XgoVSsV*q(|hMyaK->Jgf(>lmZb_0+KI3*gU$!7+7>qSfMAC5%-d{s!0+F6{} z!td$3XYQjDyGMv^Gk@YJphhpO5pgmbV7>1_V;&hcOC-I4;_XSWg5ZbQ3~MU zem+0J)+1d~7M+C(FP7l!QMEW|Cd=I&>kSL)YwU^9DL$+au)==5e)b|1FJVP_Dt#ES$HHzMecGi9qJ$KUw2bb`Bx&#~qHLG=y{hB=d z@bxs@KK&|pl4UI}{u<5t9;{GJxj#H?7edlfKlS&rr6!D~+i!-W8LO&*ec}J<;YQWumn%fd1LqhPoz~ z!Qs^l$VqsbE0y~XlYar3OlkD7AXT(Dn`zOR*4@pf0fGYqB&R<(pr%tQq^xxxzWR^X zKz=+gOCMLAK?g2tkiPWQ^uqa8lr^y%j*AN;v*c>HT;^eUWNZMRx(-99SE|Fwxx>L> z%Im$)T@*`pq(!4e*_x7uY2El<*DJ1TwSdfQVk98DZ&Vu@!uD~Su=mq;c$#Hf$qdt? z)mqEZVNX>8Bh;Y0qZS%eV+MbYnhe4RKH`oo5)!XBV#xv;jXF{SLHR)ew!OpOGf}l3 z0m(dOPC77+{$ToQm>COy+*c=CGGe&unXKbR;S_j2?KF4o%RmzNwhZifG8HKv_L7YJ zeF9G(q>Og5ojpomLqm3$iVLdjp?JF{ei~EWuY1%z`HI+eEkK8YnST3dHnpz(jbd*; zfq^S8gQ3&QxaKcEu=A35aCNK^+Ht8}q@v%170V&oRmFH@K%@Le)&(vyWpg9K>i;Y_?|b0XLmWP-A{Xu-C* z$H*xtE8cucQoi~A1oG;F6`J*D35*->Kzu)RaH^F8ats8}J#KBNE=>o@2NdJ(T7K_V zy7><*QIbK^J#6vIAJO2gf;L(|*b-LnKVGrrZ3}0)UXgVq-X-BfoWzE|Y@uzl3mKSf zgIx9}L*=&tL~ghidReGQs$l@lp4x`YH-tk=%?YIE96wu@?`i<{9?jf_H={v)<{43j z34iA-)CH0|-jN87RUy`0XYhdMJbw1RRiV@FN1^v_CGbM_NiyjCSFTt?Kvtc*3q~w? zz^Px20{)AXfp!|N`DsWIOIl;1(dZk;@z8xYvD_(so;-_>(6x2;VmNIq*dzKt5?q#{ zpzY5g*;q%sVh#E|&hHmL2JJy@-1BmM*!tG%m zSAI051wZznmCCZ-p7FZL?B3^aB`Pis{OG2ek#tqbLJ z8sv!6Y(F|l(u#uZyW#xuoy1OD!_|LNAalo=!YHd@NU}(sMJ74|EpU+=m?MHIaJjC^$3A2ehqw#GT3&lD=CbU1l@=QqP&cBOw+#KT{_D3@87)PkwaD1sbALoX_`vSoc~30D`ILSed89#P5T%<{f?X zCpZXBLI-iGfij9+C?xq~CeTEt8*FQLhsWYov5rnfe+E}mc9^)6O5LsVVVczOH_~P6ME-z4?3{7;PwD2aGneWoJE*bW;E5YND0)#JRVv>^%6l!%*ZiF&?(Pd2(uJC)e^j&K*anyTG zszpFggT1qz|9)%X z!b6#FPUw#x76%O zW)+W(^>5w)|H5X@4~_x95^F`?Q|-A)owDSSpND9tTLc=ZtjzAyConTT@tn9%6xA0v zh@a0=B%$#NRJtPy?Vnfz8>Lgoh8JJ^yD~Q(dI`q%KH#EE4*=+64(>CY{Le$ZM0%r0 z>RvojammHIUzFgmKjoaimwKPEzkn5j?uOhBWFK_G^SzwtoiZAKEzAVMF0r ztw@ks*TuP<|Bb!-peXR$Qk0-y2O?AMNwgRz{$B>QO^1lYKXpY-=atB4MM$5rdzxr) zJ#4ogPO=y_{>S@_V2eR!rxpq|y$B~BN(S!JWAK%`*f zhH4>zGOok$H|?w36qYNfDhMOvSsu>%Q~vN|b09f?`x6(+_|u20=F(nJh%OlY15Il) zf&8)r?!Y$I!+30jXw5KPROw?6bs}8x&kwC!KFdFe60__k=DYlFR=nDkL?RyY7#Qb~ zNeRoI9lJ9F-mQ@U{pj;tpbW;#s`J6aFiq4Zw+kd(S>p2M4}W`nWG6#RUnHRI6E(@k z@Z;SnDkwsTzlH(sMQHB zJ%i<{jbh!^tfyd0x&qm^)02MGY((+1bif@`WmyyaAQ=aHeoHBVlW)ID0c~D~)H^YkuyohhqX>LCI z?jr99q3U93R1}yhQZ^|Db6FRmnRydDo8>BUtL1a2E2jnFeQBZnp6K1IGn9nqqlIEk zq83v`W|do`gR>w^vCk7Z|}a zXEjml1T)y?z70gFKH@g45fUT3PNZ6~7?nb2u>H{!NvA^yclX48IAkBoUM%Es&-s9e>#0a9%S)nr#Y~j&Lm$~y z1i@VzAvn%L85OJ$5;bB)_p)5;n5XU#Jr!X6Lp=BWIqDHncUp*oqg2R|z*;cJndf4% zq)S2mNJDg0{7y9g;~CtU$z$E`S}Ur=G>1E5DKt4;jr&&f^P%E{@ibZgDoPb-liw4} z=}pE3PwhyCxo;KWyeKKO-7E<=*c5`jL<_YvGQItvQRE`!aqqgvXreIfJs1Bg2i$iovn?u{M4kcioQu6u@ckm>KC(IwL2;x|d~q4_xS<8v(c zj^*!ZyL|x-zaDX0C8I&@#x~K1cze!plpHzgeH7OzXK=z%tRK_AkeqyGjZU6l1HEq~ zkZ$*${yxnE%AbJG;Rjq{XA}stoB(83@mV*Y-2RG||B6Sx>vHj|k%jos!*cG`7y+3y zvygme*`aIB6v4qwmE@qNVZY}kdDbuRwz-vaT&oY0LgInNxh`&B;%}^?cTr@y#2syz zeGR-WD3RQ1^59J+8NPeymO!l(}IxK_hKQD}WK?RVXsf`v-JdIziOA+Py4nbv? zHDFqm3Z60hDi=RPK;ZabvVe8C|A%!c&dbTG9)9*4qB)a3E-ys;O8$Yjzt4bOQ3;$< zwgSogS_D)#3DF^yvAEhOQBQ}b$FGCuNm#Z1$8 zc%vW@ePCSDw;gY=tpksHOLn=@a6uz-oxKm|JCCIE&PSmEo!4ORh5Mk!;TqSz`vhJ) z;XL?OAVib7a**btE0S397#Q-J-FaVNE}iYmk;mNVQNu=5J5>j~xTg-sO_V}i^Tm=L zr}H3@{n;^iDx|5AqJ%jDWPMvmP6?gK9{nElwk!xfNR}+*cjR;{OZa1m9x9$IfE%ipf;q!3 za%^Dj`jM zv>e$TR3(mP`#{!?2JYK^mb-GgMWhzA80G$*0Q&x6$ypJPd$nN$NN=+`$}SX=rCH#?+{Tja`N4YkTAtM$dw?GwgB|nWW&SrW3Dlgz2 zn@8Z{^a?Jb<`;hQiE(P{glK5?ZISf0c-(jmqIuO!|Fdc&J@MU9yyh^4ao!bp&DjX< zL!mtJP_m{&4qrh}_G^*h#ikU!K7guqj>FL#bzql+EHW!i#oVy-pe|X64)2nJ+e{6} zF^LtbY+nMsT80zv-S4@wZvvwIGMLtvN{dg8u!Jt2dH96CA{VPGPd4ajLW?N_5R|dO zlYcRNc!&^vzi$FJTFe)X>1^Q^Y*8e)b6p6q`G#i9`wY6O4M{G`-;VN4hDSflAd9AJ zp@Q>@#Iz%r?kSTN|7%Hto$8jP@GI|&**3ZxM94RB_g0w!s{T&YW6W#9I|dMu`X+>) zfIIlW&{#aAE1mOUdcvc{`DA;SHM&FAK%cyL@^M=a_h0sYk5e}osnx^{o_qkLuZEzB zbuj&>`59`h0TNUb5Q@mf`*hFXzdy^l!xII>q9UK{>a#{saYf9VNy$l1Lv-FkNDQ6- zg8kX8oVL3@G)YSW6J~aCjt;-^fr2}tM-x3!#k&fSD>yHaj^Mq4>(*Ek|H+fksjo^T zscby8VxEpckM2R+tp)^IQC>f_$O zxQQKyT^9+nC!^K`CFps&TQYP{8W#&$zJcBmvQjYa;UN7a1j&p~Im*24bIdUKWX7_8TaROBksA1C;)aIV0XWg9M>23ekBwamg2?AY z9vl0rmyoVWpScZN*>B)U3cYtwTKw@WfPEh>fE}!d?!Wut9BmAA^@Zq9-WWWIJ{GNL z)Ir5{cChHM2G&z)<8F%C98QAByO&m|Vp=B5*dI&aC_QxKfg*A3N};(Yna{;L1K!?O z0}R=nZH3BZ95w@kv6F>}^9Ta-GBiY`Excy3!TLJhUcx*$8Z6Hv`Y9GI&*Jp1D3H;^ zHd0r`0piKGv#^Jc2|aNo3fZ+@gHIA*!UCN z?bGaLdrX>mNDt|(Z#l7=UpVYqzpCQrA$9{@E{!jw93(&Hc%jZ- zmdjVVf!ftei?4{9;XB>QNR#8%Gx6|59y9+;eM_QG@^hoAe-4Ssu|_585Q=)%5V!p`T-gT&va8-6%4zGN zxeEpG{iV&IbNEHB^tgZ+9mP1z_caINn4kU2e4H)Q(XWU6$9AQR0V~k$W2)qXmNgV^ z)I`C`W^m#CXpm!cn{(C}NOq5ZCQ6#1hwgL_0Q+WUOS<-kaMvpK!>ZUGyuU^rStba{ zr@5B&E}IW$?}~-*Ck-G|KE-e=eC5gQEe^D9#tCFSqXYX%m4WXxl^e3_JJy+ofwNeM zIz_4y@rtLSRr$JT+tt-@?kFcbmvO}ZVP;m}5IU%b;oB2;XxR5ZmafB}%J&T;GLBL9 z$WAiKNRo1%ane%SOB-z}?KJJ3mWGm*qKtNk^E_`!D9M&6BPo(7N~M0!*ZKVe@8`og z=X$UEzOV6Dh(6{Gbr7d6dQOWy-SDd*McV533Mdt4qKzRRN#;%h-mPYxo~KLrCSpg4 zeJ#YnHHy?nb`+N_Mn1>?Hvfmw;V1( zrD-FfQv}lu&Wt8!a|yV4Mud|ROH~>Ei}r_k9(wf0?GDr;%X;*JeK^Fpocu^DII!j_ z*||v$S<6Y&B|#%$`p<7jHD?TY@{xeq_j%afz!+MNVqP%SH^?$tj<$yw(NiV;`0|Ht zP+p-%z2a=~!7Ue{RqrgSe}(z@zRJ;^Nj{wMQ*nV)&3X97)`Hrao}&~ zXiLsm@IXcq*v=5$rhES#Cw3DPQ0Y_|>YA3syn!~@C&3G5=|xjvgorE3aFX!L_gXZ| zIsz=ez6xYViDu!E_s^5hte^1!!_QLV%Un>Yw?MjiE$~~HM4vHF@uLk{@XqvHx@f6B z?qmL@&UJF|!}%suIb0X+H@*$5{(eKTBgN?XnX+K4sV=tq7Y(My1_}+CcgBb1-dkMI zqsx|wuyNB;bFN^JX=n?};9MyU+LxDtbXhO3LfsVZ?Yji5vdfr!bDs)_g=*rw_4lFE zwp-x*$X@hw&10gw+8W3%n}NmL<)K5@JztHxj2@b`!^Xl>d(Z^kPnS2UIr;66 zc8w(gCJJD%K?AR8oCwR(ehBT%n^5~grZctVvbwb!d6 zyAqR8BfBrWwAjWyWA_4~Fq!_?!3+IQxr7{_v5fhW3Ytltbu6 zPZ2h%{oKk~GCz3qx;iNT1k<(((f&{&R15a4>qlxMWB92N?}3nIJZ|4m36+oQfH$tD z*kgn^y<9hqpL;Zk4jM{oq~Vzvn$NJI6Zd<}D&GAAW+ru{1pvE5+Rg8?i*H5`8p& z3QVJi(`84 z?PIyOU2G5R8x5}+43duDB5aH^o4~zXAIq{0+ll*(C*V%jW#sJhgPf}1Kw!TF4$B=b zTvVk9UZiW`8)OT-GIkWXv`mDJ4MxhGK+;j*`Q8OSeg0iYYD9eU`^Kkq-x4?c)mxET zZmkEuKo+`V_lYbz@)E=b@$lWs627YB5+e5!;vJ=m^v+mi?l#X+5O<1$5m}i8av}~X z;bF$ftayZH-q4^q^+w#v#gWW&dKvBxQiH)g-DuQ=C}R4v0RUGueC~iOJku&i(@U5R zt#u7NV5UiTJr-eOLiScp?WMS2w1E};TaZ9@hl)64biD@5W!e~t(__fO#b1G1Y?$Hi^5RJU5h9`E((bmMRoF6AHnE2#8tes;@70pf# z&CcO%vat0}4T@H?0Q2+}0Z5tT!>5bMW2FlGXxvNqc+5^RXIcWv zW_y0OOL6ol>xxo4?gfuMkD$es--q)2&o70rDpn0I`9OhUgg5BgF5-~SOrnUEmIx>F z_QY^g8BX4LwHEw{i=$wQE#8}$1zq#*(`1H||M_S>z8VP&m$e`*7d=>g^AR}uuNzJJ z^P6mJHU%9rEcbOvBzQbysqlS*D0i{pwhEmPHyzvRE6{2sV@{H37hAb9_>XlhugyXFuUGSNS*<&!xuT z@4E%yo}uUlEx)e|tT0!@jf&SuiL4_CUSo)jwrN2cm@Hf#oP$bs$kN9HZq)6JH9mEO z^(*~ZKut(D+MK{LUg|OT$RHiJd;JAxYaaqllPHv}B2II+RD$4ANxYzCG;x|S9*ncl zz)HM{@bb;4!dK2sNXnh%?Rc%ES=}tR5GBH%=^=FCZf*RM>2u`@PjjPESzZA@0akXG zgNAX5DEdq$88yBWggsKh?XM4m-RHgeW7I{MDHH}0z02qDsa{puoK`}3Udbqcbuk1b z`ElbUR0YdtD7tWM@3%d8;Kw^7O5MF5)__t0Cui0JWgkz@`o>wievJin0cDHN@JEyMK8eq6sX^AV^l0q*D{^|Y9a(=RkYe!4Dn z)9FQpeh$KmbHrc`%aQO`-wNBs^?~DOS?sb|o<8e5M^;X`i9Nhc;i_eRRPDli+^wic z?_Kxc`q+*|YEd0b`{6{#y%O$HmFr&ww6h0DpaIRQX(FpaM_~toP+E8$b7S!2bXJZKWsJYXJ4@KN^ zLY5qy^sNfL`;8+tc{_(DfBQvt9JK|`mD>2rzF|PNdZn;n>p@hI9t7vM zRgrn`N8*aBJQ_I8kkkCh@`w&c!>tGVh=x%ldVNru)@_-+wT2v4mL;ir9$G}kxGafn-fiRcjCGRz;! zrjTAjsOxSw%-^j@qaXBv!zp>lQTsR1y!{GvY7E0RmxTNs7UslK8R1WZO!xRinhP1} zIJAenrgxp(dMx6WJ;#hWxAa_mP>J;;=^x?d$G*eh*Z^D+qz}t_*k?5UBnemf0%k_3 z;oxjpcvnfB9%Qr9f4aw{ijg$SvJ;))v%dS)9$XIFv7F#p!6REPlTr)0p?sd05Pdkc z?>q87Y)WJsyMWv_mMs=I9=?$p$e*Q#N86&|f$EV~(QJk|Z^X4-7+8L%v zXr^Fe{VuSR@y!2p;B|I$K&^odmig#Rjwpu{xvBZc*j<(`H@{4iSl->{j4W6ceUFau z)5jX4dGuMZ5LVS9cw$#ZjF9&!_*4Yb!p&P4iR8Pz%1dFL=k@e`Z$7` zUz(0xMk&x@2SaW=)8FRjltH{;B<=Z>g7lc~PV)wzEA>vrdxlw%$G;Tdafy1g>4qO% zz9AXhno)`-HC`oQrsF}Tk_LYEtO|J7g$oBlL^Jr?G%wmdE(w>PP^Z3|cq~J>3CGxX zLd^_w`o59P<66vnVhg#nqBJ}H$)nk=$%1shA%@S<%KpiaUWVeYynWbDJb zh9BLf#T%pqljFDZ>4^n2=btrR?wknMzV)X$te4!Dz0a*QqPbBw#07HW5}=u6H83f> zjB@MKNQLGg^AxM%x6Vhw$`et1|J$N`v&vA8jM^{4QoHZI+#Fd|!Fql!IaQ_3#jyOk z%&=VOb@x4(wjdQb-;E@dp@TsExhme9Q3UFetNBt6mr!4(4E5F9O`;xW9gc+IE z?~4Y%4W}UwOIR1lO>A*Pl`bRaXwqxZoNgYzijul#$hk*`=5;7RpPEYaGjU`3b-=lJ-+4fI#CfChA4c)R`)Bn=Hg&XnkIwjif zpa##Uyg_}-eu3}@SHXxS98!Awi-hoZgK4?!{j01F4myq&c3wV+CKd+41!oFKPuocR zDS>4KwQ6xsnU`n5-e`F8M;95jE)r3eH&q?P=e$$W@#I6|bjI8&rZ^MfYW&t_kThEo zhmMvJn)l=gD_s?EtuK$tr2V3k)!^`73;3iLfT~5M6xvi|UMV6wHs~ z;KB3pi zE)Y*IxuNU}ThlSn`xL{mX{O}VrN3a2ml}3DF&=IkuK~m}-=O_0FY&O4GZBiP!|~5g z0paei47DnAp{>$M7_V2SUVesj#N#KZJW+=F`AyT zdF1VUxCoY^+U6GycUzQ$T4Axn!S0g*NMG^8_E z{`!OJUD?Pwqm}4psm0K~Mh)9knZx<3vp}g4hsLJ;B0{eyFp}vRz8R|n)LfS@7A@L& z?pS$`ME)L$BX9Ajv%v>qG5i7ESi^QN!yCcw2_nqoDR%(pHZi6?Uj(Dr%hGhs z7EMkVD?C3 zJZ||-qUi5Pc5O^RCl<(1&+8{>0>jLYJG`JE)Q`%J?;D!ySNX4iEs<(CNsI$A5hp=A z!_4!2GBnrx5-7f9jnnozlf$>&$T+428W_WFN!LzL-wn3-*u^Z^?3qee#^~cJX&#NX z(}g1**P^1~8t~1q0w7rY5`E_Ch{??maMxc8o865B0l#+V%j^?j=8dHH#5sIA9?Nn= zXQxQgKFe#!;2O(d`~o;7qX*b8%Yi6f(1+vW>d|o{e>gU-0FU|DI1;~7r(RXrvQ(iKIKf0#dv>6h7zx?!JD+pC>Dt<-b;J6rN_>(q*hP4L+Df4(BDK z>1=Ol>=wY?V4kVg>{kSjQsQiKMVJ{oegJ%3nTF1!Mv<1^s_;v=HqHom1y&zrx>*|$ z|9t54lFUz{=$Y`60tX8yv~)O}+rnz}@W?k!+BWv^;cN3K6VJV_aj(b2?**S&%x8Z3pwAI!l@ zd(@$3t2{|B6y1hubhGKp7dNqrrW*ZI9Z8o;us(Wi2&0@9&`UDrTPLjz~bw}fAPasXIOQThD=GEQ&;e3u!8O@bxC$ApFX z2X>0)df8veMB=N6f1WUWOG4L2qB*Ce>6=+hzf^i3PjFxwvu`a-E>LnpiEw_p$fwiYlTJI&yWzziigbP5 zR<4m{Q+JJf3@fU;L7I3n%CmS)GP4xnX$e)P2dm{@Og0u?DPc9;0ZP<$ayb>7=qT`s z=U`{ZN%EpW#5s8yD%{^sIoM{VI!!a$%E8+#qt$5u&VQl<7eA^*F1EQNz?5aPc-dBX5caF{FGMSEa^7rx3`^iai*i~*Q zhg`8!7cNSxL1)^PiNX01aN-{|tU1#P4y&07_RMHNk5@CyNp=+aORvVuUM&T-Z3eW; zP#vdF<4-Q zUZdxa>JNFk6AtOas^U5n^jHJh{eA&-6RXfnk9Xww>u_*qwk95VE&_D?fce|mZT-Ld z(fh!6+%SV>eTNRC4e%P;cb91ZW<3Y4?<&x@-D#xmdN`P(s)>!K)qwPGf%zu8 zo@cawvbYq}4oiLZ-B$A=Zk*m1!`xW@k=sDoU>%HK`7lWbfpyU~n zFd||m}e%Z%@)i>3#uD>0$^uIMl zb59eRbcoHWk|DI$M@q0EZacr_-2^&ol+Do2^UM}6D&NI+S(8}qdYC5{vAqd5c!$HM zCu%_Xu1MrR?*d73d;_dL)u59~4&eHu3jUT>k*;!P$nNNW$!V2N61@BSfz0CbxN_Fh8n!wY?z9w#A4a92JIA8P#qI_W5mSfaN1q0RkM+P6 zb|?BzV_Exe#ngS5!m-=SF!Cqp38@Seam%2^k(}k{NrGP0KoEAWocdSH#ba9<;Fc4{ zaE$@m&$}B7O`pF9zO$N;+Fv6$|Kd^5F8qnI<_{8;=>}6(%3SaOeg<447E_xU3$P3G zk?r0;og1$tA$T#a4yFfN&}^Snbeqi!5@w^}la3m+%h8{Ie4-9~J4O?09)1NMv7Roa zk+OLIiAv)7M{jDb#cbRWqYD4D4hk=S5$P}!Q!{DQ0P7&LSEJWULg@Md8$4DFLNBIe z>NYJJ(w{3tn!^<{-XU%GXJEzH>tKH)>pa>%NU|=Jfp*p_p>XMSzN*oWDM5z1c)0Un zShRB!SuYgL?3%Xb-08EXg7gD(;LQg%#IEz>P~W|&c_%&mbtC44N;GZb7}mx9n$0Oc z!DRgcFdI{pnlL~f`ox39&vaP-jwHz4IBm*Tau8Y62EiYtXNZEDGPa^T`o_kbTgsmQ zyCNIbIn|K(4UyeqdtH2S} z2vqErL$r}5T!Yl`MyuESoxe4vHVP2t>nqWm1$p#4y!t}iP zT6c;3Fq@(I{lU_1Vw2X18a-JKkNI@&F2lX`E#slmj3_cSUk;VC{d3JCW0+Z4jjpU$ zCMQp6z}YdXSdcjm-W=`@wpBHtoLn9qYdmghs`)CsX8 z^+FwdW``y$OI9ZjHzlBC)`9*jI*?u-W{YjDykO4Wz4YPHJ~VfgENwVD7IvG|qV~>k zu=8^wkgLCdLiw_^EvU>XvQ!HvbxvgmENkNKn~%y4GHvRqKuTBI;&h)Z7{4H%dNR-H zfAjl~ohGpJaRpkLpaOm4@Y}Jl$KFc9SG(0|)t3=8GVcj8^<{mUyB2UVYb$W^H5U-teH1+VYA~eL zbYQyM+attq!Gjaz(S?WL$bCa>{YncS7@y_zwK4};Tw@xQXfrzXzBQiW;R#*jZ0O1_ zU(tdQa&(>U8txkNBbfV`z)&~FgKq_+4SD@!Nt7&Ho%j!h)$0*f6aXv^XyU9ad-yuD z(rIF36I#MN{xgS}Q>*c!Io(61xIX;GX zyL<#6Ue}_Cj}GA3i%`NqgmW0?Ac(YTCqGBtqN^Kh z@UXeNpkbR7oTwq*AULt$U*SLIuN}0`<%9obj9upESE3O4E}MgLCek>3m@G53aZlHp)+TUV1-c> zXuI+gWltI;*{cBm%iwHWv#$`0?(faZ`X%x?{*|3Yxqt;YIY5zedVqV$lMv{r*TH%9 zW9a=z5$D_&q72`P=OEcx>-gihj)6y$wDG>~O1Lib0=Vuw94|aqM*3|b-@4faXR!j) zfQDw_ygm_@PBl)UL0akf!7MfE^3b1NZMDIvbpX29PNy#RMMFE!n|bDN*XdfMe2N19 zhw0$TkpvVw?I+o+-UiAFXW?GIx_rSe75-7C8^18@FbtP*CG)%9BM;`$^IBoc&3QXn z5R&H(gMBT?(^aBbp7;Dcy{EScdp=j9!l&l&LmcDGBlEBxthR=45~TAOiP;U|vW7u{Tl19W2AYE#@UDI3=3pKWnvsXL%>kpQ>hJoFNBw z8^o|gj-*iR_CwHEVu%AK?}KODr1-PU!JlB|K0l)MS%i~D z#WLK~F}WD7W%t<$w`dvb+!QmJ4wVwjpq51q`VexM*ht8Nf+Zsb)-THP{_cz?-eYZW zti@XBaj1n5>CcFqm7{+<_*~3KaRJvl9aPfA!y`&EX?`M0PbK~JtWf3;k9lZgX>n@;5c2|mC zvV)%ztBE)4o&tN)bjXA4`DlP?a^A0UnC{JXn)E=Fm0?_zM0W0; zfz>W6(0OrPBz*rhR7#mQaD)rDF0mXRnYEZ$jhz6~y5FEyg#f5@w+gJy%|~j{7f4u4 zE||PT6DQrS0ozk0_#Vk|=r)`0*2_xLiET;PPFI6&@!?U|0>(x6u>3bu7j7QQUW=US z0@AJrfCzsB6gFl!UA1fkq~HFc{Te4ocw{En_>G5;8A(BjEOY*f)*J-yu$pVF+a^peHI#XP5W-Nd^CNzM_Q-YEI?>2(e6zP-O!;$%5r;F`W`zv69Z2po7n@>+Lr9 z7up3m6KQy{fMvq>g^}L2uV5CfLIv^Bpl%HUDRQD5w$a%#pttQTJ}Y;Ya8{XQd5H)o zw@IXOqp7#xb;1qseOe*)vUbJN>W%QIm^v(OdVrQD^MoFOgJ62wJ5*I<1oLWRf!5rg zsPgk4Qu_1(zfxfaHoNi|O#WAsXXG9VZtVLjl%DEDm3A$_){OH!&SLrsrrll9S_>n- z7}D)*Hs5Z_{1@&vP$;NFnMMJ8lV4WQeX9;Wp;!(7#%1%>M$E!qg(~o8`cq+WiD;jB z|IsB%SEpnBBWhGF{16?*G{!rc0bG{^sl#Fs&lLM%4Gn26a(d1z+1~d-v10=A`}~8P z9-9e3GRrQmkI6q=7{x!gNgI#;upcJJ*pYCZHuSw-mJa?g<#fJG7DyB@Y;-jtysl3} z-tft8Z|RRIn{Y>|5|wMUfgj%0p^S4sz_sfQ;P|`8=$G*zkrdAap#eO+b7U94*SpQ> zTjN1w^f3tT58X(#oRsnYcRY40EF|i2B5cgg5pd%op5s09G-x@ z@YSM!C@*N3aIbPE2t38Z4%-*Q`O*IT>(+|6aJf81Ij89l6VaV$*RGpFqsRGhp99Ok zmApictX_%7Q$>0->mav=Wf`S-HNn_5^*!S&Lzygk<0g zlk8!ik!6G&4M<>_HlM`>fp5mc(f5MLS_YQgYzLLHbTWLGX^dZN1JF5}Ww~D|M=CcZ zY2m&{{35eCc!c+Ku#n|~36`m2vt>LAV_Bv*!)JWzJoH${qlpYlU$73)8R-+@sUwXj zKh7G&n9Ku*d+dkyoKD3Vplm4*x9vYofAJqv6zjh87GQ5W|~aM3cbN`JjtwEN|YIgn_q?@E^R+K@-zi*Lj{Ajbpf) zDDZ?DkBsTYxjm@Qnsq&x?BYH!kC>_{fS*V!D6?nzS91L%c7Z0mXD)_MuhA#o?3oSh znYNau&`|FpfAMnBF7(DEb*cVI7HH%{cr(!2%#CaBRK#cOoI7aQzl zvkMvz`wkplM5AM^JK6v9FR1=njk5Qh1ZBAk!Dt21EPrc(3()v>7FTJWB{tiV$7uggdYUW$p?-zdARUMO#a(1<@{sJAAP)QAMDlAAxg8_Q1CZ4e1u-wDX ze3?*le*YU0-j)xWPVTKz##O&~^m~(#{J1W{+v4^qob<9{y!xU#eUsJ$TDF`(Mu(b7 z{Rs&e{NN3mzNIDKJ2@Y$VZSe_&5L2zp2vL2y^45koIIT*lOQat675B^|DC1a{7QVk zp5?B)?c%y?#0AS%us%D7cVJmW02+HNi=1#D2A^v;qUzrX{O>2a`N7Am@VlSl^tk*6 z;%XFvB1)yH)5SmZpHVJupQcWaNM56QjORaXaE4>6Ccp>1l_)^Nmwa`$hem6)aNTYN zI5%Sl8Nqnz0>icN?5HAgMqk8BpDnZInwjqRdewM%E5(l_c8F&7+dN(9rm}zWQMCc9zK&t#pYRaTRO!B zUqa7Azd6#h_2)@sXCy=Q%njk_t{l{}Tott4UJI7S*&`dF6g_SK3^*F{@Wq*@$yt_X zcT8IcZ=IqE??2~+Q+-8Py1a7>)iANaH(qUpd)BU}k<0qg4yMOYQn&}ewbMwaa2Pez zC<4!Ic{njuhe#HPfd_}R@WRNc(Bn^w@W{h_G%rq;Miv`$O-Zu_9c%f37;a;n&lW#f zodvP=X&NtUfTIm~bVJ2dsAljQWdcp8KlLR@V}3f~e2chQ6@%if3`25{0U0^W=b$K? zXkeok(P6xF#yJH#eDWJ|J?9!4-6BKhweq2f$s1Ib;SclUTENV_hv?_4Gelmk1o$4~ z;e%-fpy^i#Kess!$(>++C>M^LO}vVI?`qQUL@~-!DL{wMF-_xu7xz$CLZEQz5TG|B zfyy2O)WmkMcPsUw@>VfC(LS2kdz1nk&%A{#fk^ z8`c0<6?%{i_5T ze%A)a6#2kWJ5`{fWhyHA6iGgw8V*hPb?A)ZX>feBCzzojx)W*STp;p&6ur}vrN-&8 zEdSG6;Ct!@$eU{f8x3;MuzdXfS7W*JigBxRn z-17V(uaIBc30ib_CBE6BNZ*-m<2EqPwr*1sRQ7KL3#cF3W0660o@>C>o!`*PtGD?{ zY&oJk)e3tQiBr|mCB%3{2vWH(O%HbT(#!d|IQ)S+6=QRKcpl5nigSjpT{^I_{x-7c zSwNDSC1FrVHG2N109-SiNnBXZ>3{S1pUzye-du!xW97}b_1~FS==pd!@%JGz!GVWd z83#U8XbjK4%tcd1ijmwY^00MTGg@Cg3?6Sk1qRj>qA<(fB;%eOSgWmtUzVwYSIS?= zQI>W2ABTJ-ZN~lj%5n(;&%*$RVf5C&lPFGGhHld~fpkwc(wU+Hbd9!xC)6JKHA~Ta zel2kHW`2z;r%CX3GtfTH5Np}#K})$SLc^E@G=C%OBu!gOlRjGGi#xW$(Qa<^(Tx9d z$TDN(mh%A1F7SeW8yEqDTS&&>1bG_$5pYs!nCMpki%~cE5=6Am+_V1@i404| zM=~^M%8GvCWLAJoSq8=GG=HvFRaNjqHyUhsdlGC_H9$5!QgrhUJ;tBfWnVBB<$@NJ^_{M=uGMXnrBbmnUznjtY#p+b)ln5Iqg?ez+ zPs9b66acLB=>TORe&}sd7infqzYd6Y1%czLzBz@s`IUey=?XXC?AXi>M{MkTNc>-?IzD>S)`H;_gSCK5sqxdIznYJ?@*$cT{Fs4%tdZeWw z?Z$Aj`KCPN&!|JA^iPB90ee9y%N_bJpUwPd6xlAtp&O%RY1Y3poJWPXpg-gWn53l- zb4#<(e2?M6fnsG?nbnLkCXI%kb{sgY%{&)Reve0)`f|7m>$aoaKf8f@?l zxlHKl*M`JL%2BRThPx{5I5eBr9vDgbAB!}cDnCo;%IAxK97m;XvwlqC{&z94zd5&Y2YtnV@ zgCOy51k$Z&Bx_m~;h|e^P^f=PK8WiDWdbdn;=Tp$Y0(E4PAcG?ghy?HLdd*x%t!w$ z8AMEo5dKA?yHESgP?~XNB`zsZq!|xAxOR4@<|a46aZ5jdh@hir-={Q^VQL7c75+e9 zj@{!2&&I%8+7dsm`b#ojPA5iVLXgK(#uXhu((;&GoE@P~E2S>e*ZoWfTjC6_j4*_M z25zI5<_k%xiX6MuRiOhPo`5aU2IRwJ8%(U%Lg!~0q;T42w21kDf`o?L4u+X`gyW&+ zuHD43R&FT!*IQr#yZHIYtVEoAJE;uEE^kJk-VTFTsxE`mCWR>a%P*4VYXR<7Y2Z~c zDnNC4BQZZ9y6>zehMX?*P)s>`9x4?7B~`Ac(2`{g_o7T-N%sR(EUOHz$9n^{bkPp; z;;8{}EL9heFHIo{$L+zw^M=g-s|PRcIVH@FNpWeF(mfOP+6qpDpf#b<-ozZueirc11amX1VUkohsxmH3RGCs$`2#9(GIiwY#E6v5^+VHY(LJdUqzsBHHP^4^#fuPiZuO< zV9JqJ@Vz+`UCoaq(?)&Q~FE5fQnzxmoNBCaU2AdIBg6yuZg zvxwEoujI;W5pU#|DA7^Bd(a0q$6uemid)Duv^w$tN~wMZecunG8HOK;=91BHxpgmE ze^;GcIrj&gW_Z5;wk_O$MH8HgYex4SSr6%k5aPMM5Vy{>;Ya)Tl6kC~Y2wTzxa5}u zeVn3$pE8f$nq{jvOQtu|D~X49cZtEQ#4xn$Tnr(TlvqYgB}!752>3_GgTeQ65q2C- z<5p|~&VA$X7NvC3-M5Ae%3npP?JSqFDTaPyx~UxVo$$tiQ7}67IvRE%lDt{J685GV zVtK!Mu+uXDoR$@FNO*Y%*vxV`H|krHo#p}Lqa-)PCv~10!*jk_DAZ=SF!z=Qym8_k zQhjIy_XIov=kI(#QYM|m-E}TlL^ZJd#ILj3-{B7GL6 z%~`OHp|gdxuw$(fP5v#y$%n_x;mTVN(8Bkt`2m|2!Jq8b>|9a}Ps(M2qpM2M%lIoK z$Z9SKNYlVOe!T^bvKGRP7k$yel;PA{!i&DWmVvvEsZ+P-~hw-I7r> zlwb6)XAo4$ha&T!-9UVK9eBJg9zFlsPt10{2I(`!@O~~Vf77sKK(9*=ADMUz`rW!L zv^v{{s3FV+3rwMl1E^#$g941Rsr40=IcW#%ujT75ERyjpn=7gfco+8 zV6MeI0Th_+cgf(yd6lPp#r^vCfF5( z8qR#Fw{%~5F1~nMo$B_TqbE9T@Ti;4usL@$?Do5bMhDI($Lf{fSMe(J>h=>b&uRx~ zVSdbQRev5S|Lqa#&a}ana4nPwOdtspKchb8J+HC%A}=QJhB7^@5(dGT<`9JUYP8NeNegvbM+vCB%S_*D!hNBjbpX`>^0xov` zLmB2ur1kxJuq#asZ*G|c$Go2*-0>qHV>Ny?hXT9%X=qTiK4qSPZTK z!6@ix9#9N@1@fh15N^3lOdk$|da5FxiE1+V4cA2YIk}=#xUg;pR(Z|(1y&H^`uQ62 z?UtcuB=>T?YN`T!GlnE&{R1!af>7WseVF&+JD77Z6HPl8N!+q}_@Tvd==(7l`Y^nS zd|z3B#$+&ER_-27&0JNWsu2yGUtR=?-}Hz0^xtG)Svhe!Zfr_a_V^SwIcks zTNwO9iDeqXElDtW zsWs~))4_!G`JR?u!s#+yM4d1m8qJe{DFGqq)ABQ9wv-w)Y_34bJ$69wWHMMDE8>$Q zB|=Jn1-$&fKvO ze_)=zsmzCea8(*|VV=LzwtxAIwrnAh0aK9Z)b`--|*HVsjt!TJBd(qDl{LFWQ6bm#ze*(oUObS;7P zpMVz2epl3J;CC23<_+(#^7~ur2$aH;i4vZDupEKfe{+^YlV9zQ&Q=9h%VI zvksX)isQd1&?9F)rQ>9KA@zvp#%T?&vyaEuvGy+Ux9Txv#qvz8k;Vx$zEInl{RNi!kG_CoJ zMkUM9RbM>Fi5?Npl+zZ2zb6Huk4+DR%j52V-?yHk*j>NKXsLaGH)0ev%+>&d&5y{8 ztLnIz&0Mm_zL44OB0Nksmw-De0?`haD*lSCfk5)Q=#I1ERv&P5W7sWt@GYWpoz{5Iw5`xeV>;a;{R6$MVg2vT;?QVWAiA~M0^HwP z1l;?=kiNrD@_y$}u&ZDg&f23ws#p2}KGWXw_Dq5^I@|IUoAS}Gdu(_83R9J-w%Gnx zCKO&jPTR5#@WB8ctsEl`r8fsKK~pve7^nb0*c~b&@d8<6R057Yt45FQrh#n1Grp6b zDC6jZ_7-7c^9UCoNTnz53_eWLpM!|}2GEkxX z5$c_Op6vgq1t+-};WaZ*mo~?)M^IlSaS~On=*}uLLiSFa@;eDy2|7)@7k%0+N3UI*%N10L3zEC}aI4){@HAx?n#%f&P6=(H0{n*D z_Gpkx?0ss{sfIt-On{jgE@0cd7IZn2N9_s{g-#c5;@8Wx_%|Pv5J{G8CB7^PmVPp& zzlM*(GuZxW)FYtFZwn$&(KP?{g^|QZSf`zXstt5FpB2D|%mCf|Vv=jKCttQ&? zMI2_p0QBZlQGPDVCXn~4MZ?~Yf}>3fL7v}BBzL-k;Lb3xov(%GwZwoI6S_%w)a$;rSh3Lck?i)CfHhdo*a~kLf2~99xv07 z3o?FzpKsEnbyr(~U*86#`ahPg!=LK!58GQvHf2Srgm&?HpL3+4y{CqT))j40Aw?po zjEYqHQW}zoxc3}Vk_u%tv{Ra*NY?Mv{rv-8UiY5+ocDR&&sdvHKgO7$#4Xi$?eseF zl;Otce6~3m^^R(bxQQkQmb`0j6j<&&Z9=D1s*& zvLGgAA`#nZ=a)I#O4?RC61$aLUu3_Z9_2Xs_ie89Y%x_3NjXfDE*bP~N-#!0uSve1 zF-5Wcs&LZvHfWkChL>Y+BS7Z0su`vAB1HqYRdi?F&dHC5y@_E}t zvc9Van;e%(pS_ZDl~Z@`EokCi70=vM>Xq3E%~pZXl%j)!~qG{HJT>X*zc3zF>5JU}*ib<=tNk7-vhpDiUEOI-sB3Q-@|=Xu9rRQ_4G zRwkV-15B+@5yx|%JKi+*kO5jcn)_s}dLWChV_;9dl&f4;w;*3JJe*wO{9j({b$Xq1 zm4>5MqDMblXq-V4J}OdUk_F=m-t!$|D&I9N9`zZ#x>w^bP)U<)xyHM?3QroWNQaj8 zMeTwW@q6KlvdmV2)2280VKIM?cQ44l$~C>?SgXr(qdqLD)r8D?zDT%Oe z^hxZ`=lQQL4~NnZyE20 z`<8zsKT>LFX~s;VXsN~0MY3$}rVE%QtFXL}awzUlApSDXR7eP|hO{w{@j{YJuk1Pj z_pcg~)se5@bEI3I2>kJl4xTUV?!>-1Tp{~Ea{cYgVeFQ>6Va&S`F`0(OvR-HPvyDy zHhd0wk+KJe7_5Sut3JZ^N%6R=&leiuDTk7l%aFT24v1&&s({5B)5znADTrlW&&w)* zkH@&Ev8*5oJ7_-I^;V%LD*y3K((Ww9(%p})vcTP5WJatObFGy{YD#yfC0P9f-ZhhX&G4&;T30hvL zuquk~mWli~XU0{T6wFt+PbRt=GQ-IqV2Je!Y=y7W1)Y|tR^!ceTxQ42+3wLMJBNNsCWyjgPkwsgK_TaUUE;-_0g$&`k46%+W#a^>gMPGB`XPf==aP z^}m_4*6V~V=fa8hNnaX2<_tZ|J;;lNl}LV11D!ss=^uxgq7DV|wX&`Qss$wL^aZpo zEXON+%IJl0{n3q|RruBvMQWwP`Y4c0f7#U5{5+5|dL(1{5wNxQ z8Z+x{7znewC3y~vce2bR4TH6q75B!NUATaE6mfqmKZhgo{P7hlBcb^GONh8ujOA31lK)=M40pnmc5s%}-dU=B8YzxUB?_o1?s{=>XzVG!x$PrzbA5S%fZW9_6unpF>o?Kk?2?6rf;1335gElNssP_AbY1p zA~PoxKd)0})2gqt(=mBu#{dJ?Coh;qU3Vl7{oGK&EP1r4aVNg8vlrc-Y=>em*Wl>6 zJQsH38!+5Ik(AkL=RdnGE9j>i5xe~uJt?0@bV;8F^uZl?l1*6oQ6I z4p7-%2ITlNbyhW?noc_`-3R&JQ9ygA`r)}j#lpLwqtG})svY{w`ID*2kFnseg!(2G z!jN=JGV699G~MdGi|+qtQ5a~=DmomT9tc}6?%?pkw*^L+t# zY!Bc&img=Qu7dOy{lbfvsnV1U*8pwqMMnA!M~PHj(D^@p1`O=W`kizlUq_{*cMYq# z*2032T6LCnS03#x*@kyUU53q9K7sk>!x*{7Qv=orzin&r=6&N}jItUuCQ7?;e;OPV z+EYi6-wWl~8lw}`)+!a3^F43xZSu(Y*;Xu3)8+iL2Fgyk#5F$$DZKm&GOAVh_Oe*$ zGz1vSbCCY(*w?0Br^63O`An_2i?I1bAN=gCB2&{CjJnTA=ghat{ZWrsdSt|-9!Qd~ z3Qllc!E&bE)~edjRjQB;!Z5+48?^VG%9%>Q363t#O)IltcEg-VzYIWHyz8s?66wsTucUxXPHe^dCoYDDH4R|neF$G{e@?#! zwnD&`XZU!-da-7}B_Ijv+p+25&@44*5-&x#)B*p1g-WK_Nu z3)m-*UZ!oqp9V$1*DZDMp6e1p@hY9OtqpV>>+lVfFZ@_&4C`M?=gb9j_6QmudXmQN z8m#X}TlVXH1=lusp;4xR^r3+iKVy@%3#M+oPt;8p%2Tyx+GjmgkMHGD^w zk()1ee((oOm%qR!q5aW&`7@9`OOCv~DZ_@9WC-_;OeSfqOQGhSfn@t@X^)S6!~~}J zQi`8X`5BYrXRPq;OVro!3;a302&=Xqp_`8ABez>OFgD*WnBF-JnHF*+>@}m!C$0#! z4HHPny>b{or&f|TLdtU{oJwPg4SA$+wE>&b;?G8FJCW91ZiuW^K=CuT;pB21T9Pyz z&3OF++vq%mMBx&Iaoyl*|Khx)(h%X%14H7m9wFBaE;O$63-0C_ardXX(K$ZS9Z>iq zexHusiZ7fxFLC_ji2hhS!8xb8_&It74r7aPPFe?5_2MMWL3Oe?M;Ss)`MKR;LZbXb z5Q+4qGVR>UT)_QMs~*yK&!e%%F%{-?P9Dj=+k&6T6bYLT#=z9z;aIIrkzG&JK?BTW ziOJ7Us=DeDoH?LQ0@YPf{bhCGbgp#%^gM0O!aq2WFS_f{fPlellge*w2WsrsJ2@l- zZpO-Q&49M>dp|7FYI+)|E&2rYvQapoAeNpr>4%Q;9?bX; zVK7sh>zNlx=g%IO6NP5)VPtHv3>)|~j$U&~#T9&Z@;5nO@biSo_34A}R5nr;t&;J@ zKW((pp{44`+b|73wK+f!nl!?t_mwzjVk~IhAs|VS?$bwKxJF4)5iYOf`k6oJV6|P! zbM~7)1PzINjDLo0pig9+P~Cjqe?3(TZH(CosqMKq?hWrXJL?MPE*&FP5kYis@MfCL zdE>uWx_Z|`I&4W39?iWxe*zo|n%>H~UcD;?Z-t5B+ck ztoRdyEmkYAz0Y{IJJ++tNz`am)P132iwT*!#0)(gtw^2YrL*Y0=z#^Lk?yX6avXd2 zDRP|LI@GQQNUZ-lrhN zOxNQI$ZNU}wq*xk%$wKX0sC-V(q)>oLl!k>J;ja=H-*7k{UB_+AHMpKcj*Qc2shPq zNuQHkOSxT}d3>oL7G_@Pv6l}`)R(@^{maw}$jtlybVsB5{D9Sa7UI&gmudgrCMaI^ z2F~s+7Mpv?qseV`_#Nqwa+jn)+^-g#+1gC+4lfa2HW(7Ob+!Ntuz&7+98hmDfJOG5kL;x%mrY%WRsi zuLw&fxD(Hjk6_x0o02K(L-D|G%Iwsh(=5|7pUf*TU}w5~S(A|y+2ZGhy!t4jy{^7^ z+1nm;hsj7ZVAvBZyuS-+=klOvEbn}oT%31teTksm(}>(DM5xx-iiXI3#W%mJv7aF> z)Y4yynd(&vi01oXQNn+cW6>kgUiJig`E&4PKxU1*PWNK@CEy&3!) zU+22(v=K_^(Kl~wu4w{=xgX&6(S6vWppja-TcFoZVA1b zK=u;cw^5aSv(sTD!HIPDPe&PQb6D*T3)0!hdqvX}k$#E@+f7P^_UTO!xaA=3Wpb3d z&5=V*$N64nkt-BOS%G1sbmsI)&;zY8!^paGGE7$#N@op`&YT(B5(>7Yi(JDBzf+}$ ziYPu_gj=0^pt3eyRIZ+e{|q@mxAa#;HaWF8y2o*#+daXSzu*6Q&reF8j_uxZnC=CCSizA+^ zvdZpB^iz`q5zShO{+JigU1yu{i_>b%V08b2V_Y*lxL810R~zB=soA(+-Yxp5%p6@k zaRbj&eJ?p$G7?qE>X9G6oY2<)j)CgUQr!4oJJrsZOj9CwpU9#!s8OMfYKTmUE#Dm^ zP3d27gmd`Cu}NrjrZT!qH)7MwV7hX4Dk@M1qBiy%zYlkVH*a`6rKrSQ%}Ze=_ZN8F zJ3!qdhr@y1(};OuZ&ZC&EZMW`9F7~nv*>?$F-?6Z;uYD+)lmT3!%FExT!&q93BI+iLtDTVH<>g4u8o{xe(grxuL zFo$a1qiaYyc~fk_mTWx1|hC$}*cQE8aFdjG~jV`RzM-php?=8xNSw+Jjr?(%Tcy1pW@kAE# zX6lmNuQk|{wjcD~TPcT`AGeHl^oqnzOqt!fqfqeXRViV=4cKU(pRniKJnVSoBK1tL zMNJ+QCsf@Qw}+}DL*>^v_3Qvny<7*M)vcKM{G?HXl)%~9khEU5fl$w*`nY5}k|Ub4Ac>yk*HD3Su*K#_&4s5wTZzXK@ks9Q=eQzPwB~ zR1Jq^KGR5WYz;`NPf9Kg4E@&`RCXnXP1VdNFAd>CnfaUK!oE1 zH0aYcrC_yEosgj7yz|;h;L9_qc+3;JctnLdeEotKzgA;#a~KWWC&k8etc2b;iSSvR zEP3?88Qn^*!Rvc;!us-Bu&%m-Z{Dw?qh6IlBk#p9{h|!n6O{PuWk`yvgOHkuJ$#j0I}sLZON6uE&Vt-fsiyttWox9?B|`!~hf-$n5oYc- zAceKP&?KAx1eq77@iE@#^<=FQ8~MwDSgEc|7+(EY@vkq^TU~&)1Ba2!lQL|LTLAs&o{DYMRGHqRn1a0$k?Rijolfefik60p z@R4yn(1|?*QD`T{?X4$hx4t^+*j|e}KgUB#?=5hH@76!=P+85+gvw`oyLkHE}d4*FI zlu?hiBrrNtitk3Z)4{j4gFaqHnm62a`L5QNPCn{L#w^tijRK%*2(?i1PyX}ji zFoJud9vh-vf8r&xywylE&-;JUd90J^Z3qkijvt zrt2{1SE!=EU=a?Vlr8RzD+RS4iMVw6X)4Vv!azQ>dip&C+oBZxwbeP8G%V5#e{C+CuH7R`^;IhU;fIqus0({CiV8tNth* zwBQpY+31mJfzO~QEnKitl+KwG-pI3sTx&G^B%p`O+i6Z_36`6q%1kuW(D08UeBs(0 z@Tu&EojW73O2IQaNlObYz408^ZxM-eS9J;7NIh=cug0D_XHhkoTg1=rE0nCcEHRn) z>0f7%{?o(Eee)W!utkgQ%uq#2lSR17HVnSj*2AP(d+>0-6xwfu2I`nqi#L%RVYj0z zm~7jDcTU@fRBbKb(sLbha~JPKQ@%yFS67hO&edpwcseani^S1ad2i0%E><)AKIt4} z$Y#hkL-WcR_}k$W`ZA(7%3GX{n-^t?SI6pbZ`&)pamfI*+&vSzc>nM5{jcff3;iJd zydhDvwFPgltK!uAVicyK%m!y!v6|5y#578ay;HO-xFI9w>QMR;;EGm^sKsd(cVT~I8QeEiAg2t)dB+m^!pHY| zGXL;d;kB6pdw0Nz^y!g~ z_HLZW7M!*q_DUM8J6{#OT*`m5LsMax(I3#A7LF5JqpAE|6?BU8u}A-4Nb?v12d7JQ zN|x)!L3->EGVga6%_!MUM~G7KW9~`mKUfVVS$pG@lpbin^1U`FBq=7>x(f{Gp`XEtNJWMANoAT=#y9@5nxhp)RM-KQB3ZYmGis zU&Uj7y3r$83wc&P#tOae!RW&$`I?OPber&e`@J!+z-&2*a2QLi8`>n7dG7jOkK|SD z6#D8;6Lw5fW8beD7sPVhb1D$fr2|c1{bv%cZ^@%0-dUk1Md{dY<1Q>x`HaJo*|i=cs^K1GyO5&i5$!Vv}s-=o!C@@G4IPW znxu)6&x`P}m^o0TEr&kt;(KtO2Rp=DAKCf5z*WmOimRjB!D*`=89%`XIocY*iuiim znXks?U7bm%jEo^4va{e$z-h^%B;fl|EH>i-6QMr^|U zhn=GF)jg31_YM#5$`Slir-SF0?f8uPKJ-=gAf54{hzyd zWbiVs;hgmwj@C}cx+7BPE*mSfwCxJMrJN;BR@X)YyDPD3q$SF1&x0$AU*gVN&*{8- z6G75oz%xB;pr2%)c<3hST$-O?!0!C#L5d&p`TvG-fhWhLR@ExCXs|$v+Zdl=5ZR0@8QAXto`a%ln0c4+POpBNfDg zOvw8hLzFw{v#_>Y`mWbV+(<|ISCDrl3Dj<2Jzf9Jfeie%78O6zV$S)$aU$>BeC(rz z%nyt3gO$e6Bl;`AQ$MUMdQBT_2BG_t+VJ|@>QuZ$9*yR>5ves2Z8p*X_r6l>z2QJ; zi_K*+(eJFVe)|W?GXDSG&l$}WpYd**{u=C5wicp!94k(w!t#0YDCO$`yge50!|(Lj$-{42(Q%7phqSGmS=T~Y}&j!S|^-5J=fhXVWT5C*TgC*8xqm_94N zA^}y$fBDA0rW~hpWSa4SJG^Tzz6m1z#$)vH2KAaEi@x36kH5`1FS))^4|zvdV%v~z zSaKl?s^m-Yrusj$WKbBCb1kt%;grjf#px0;@3H+m#~$*(P519LC1qwB%!lU~2Hf9( z=T8ixiBDzFxEcHL2J}G)o^lve#!55gR%X11`1vwq;+WmEblN)jt!GG%wtocWgO-wz zlhWCB?qqkC{L_)d5Aj8(G_=vfw;Qm^vGLT|pLgnf-G}qjhCxI#}ewb6NN5l(T+ z7I!$vpe?8OVKV#{Otr0mTLs7PtFAbj`9}c>3B5@8KJH7NQXvUynMIy|(PA6d7SNqm zQjDFpQX463;q%WcZK36N2lzhOi)Y0RL#q!dqqav3_nI0*%Tv`6?rBQmir#~*Pl0gQ z)c;?1hMKV%tu{;|-*2h1c*WPWd#+R$I{Ef{Ip19JUQB6y@LN|ZgNd-)V!Z#MEzJ_)uoWCH@-nX{!6nL61G z(Z1TqQd5LaU(%pCd%M6PH3Xl%wH2Ppd;s-cvSdz8PF}gN8YXShBTrnMQT)DjyrcFj zzU8FOS|p#?SKcf47h^qs^rpiq)bXY9$}HJX8y#)k@DF2=LKm==A^5+DlQ8E$-f!4; z1P3JEq|cf@0PnRS4bwY>g{Qn=$6S5#!#WVjnZ-z|WDUqHF@IAZ3Sq;|9+5qsThOE5 z|4~bsBmXe=kGLn&yvjL;I}%}YR|eFmOZE1%8jX@ow z*xK))-n<2S7}jw+jy1Fw)0j`HEa^kNq{8eX z85eb0nC$(Srl&fQp2q3OrNoh4>9io%1r4TQql+$-if~hYDr~zUhgMA8hZSohsA?}G zbaM4$Y_^lY*R(kh-cyRPfxQbQeR(f~o1zHqJnu%m%TjT$mnzFSql+}Bc;n#a9%%AD zIi&F^1Z!8$rDyJ#qG|fIcx_2MPlEMD zp5xbLL?5mPiHQ=&L!RMjcyYG%`ktL4x< zseDqUdf`kJ$rHZ?l(fwiWsn(IT@EnD>8p^2YjqoAW^A%>64ZWF(-wv zJ=aFYgaLDOcKqkrY#FDEzMS2Fi+7BtoA=A2EbG18GwulL9{0hd;2=I~)Jmsp{spl* zvLqrxhVD>01Vqk)WU5*5Y^VzHlb_tb$@5{>-cDeCb5vY^Xu9(5Ze5hgvHI^E>!!eS zl}`ub>;?%;7FWT3yCc|cRSdmoS<1T*s_;$c84&oq*?IHmaPV)Dp>Fe6NtPMTCI<4_ ztVTVDhEGky^@^&j@vbf^;<$ADr?w!GkwF$Gg0SZiCv>Y(6MeBL#C{&J^j?ZFubZ|c z;k&8&-=O3@c%i)=T_(=@9OxnGEf}K47O9o<*FJBzbo3C>c?b34SU2 zC6SKOJ(R=X0Cs)RT5@8YHXHv=7iA=g{_(4E?eD?**&1vv7f;!;-e_oIEiO#U5zeQq zgVV*^@MgYK4su%$or@Gnfq6GIY|oYS?Yc;sr@0_4KTBHe9*MWVfU6JPvAazewKI}MJ+g!GO$>thygQH- zSB@o;6Li|I{V<{1kc4O^LDQ@w;@vZ)SxE{r7O>qN`D8>NuFLX9>?YsWUmxg(dM4_k z34=sf^RWgE{M-FkAB3M5`9OKuPdJswb9Fp(@?3)Ug1Vj_xp{vKn!QX$qVD?@JM>p) z11$|`-4iL6hWhKG6&y?d@&mT5-B5ol2ydDe4>r%s!M*Yj?p~8cmmYlp2}5e}!(ERA zh4mrOv$sCa>D`0YF1C_%^)w*c?(^?X@f3YK>In9_ro!Am=%TQ5Qv4i0_BuQY8IHXt zDKQ;uQ}iQ}; z1!rX`ziPZcM>6ccG*WMNT39fCFz>^*Bt~mB*xo<7X#FiIPM$O6{)OCN{GUZQt?I`! z`G;3xdly&udT~BT!b$^-SSM>LqF;(-fQS=Z8DX!~k!oU6or zL($x4IxrZIT|bk)E;U2(6*YM3$#{U47>LbI!~;10oM4&?4>!4xs)BTyKPgu7x-*reyXC#831xih=#Ha6eL-(u)@aI!0e%-r+UcX-gmsBSa>-||S zb*Il#$23#2euM`5E*VfT=CrNrn1}}`;fp?c%->VrqJrrCEIHKiUm!kzrB0Z=|0F1L z9^i1JB6}Auk4`4bk=s5&bldDAs0ni;I&%zAOuy~<4d>3`qH$as?>U@x$U2dze!eLA zm_9lmB*oHY2f4l?AQ0Dh+k^Y!O88K95PzN7N{3j;qJDx5X$b0;Ov*h2({EUkxDsph z=umXN*;na|YP3I+9pqU0mlH^9*GD_7MA&;}w%EB<7Co!ngD)!QfvxK&_>50r-y4b4 z@xK~SwX4RD?#}?-Nop>WtPetuN?987&Q#o6c?OC5s>##>uh0$C)9|8h-o-|E*33~6 zwlLKZt~tx1v{k$D$hm{jyuHTgXFw@Fe<6|1IQay!Ol$G-zDeL2-zJF6rP_PVKGVcQ z+YXTW#&7gCDx(S$q*z)x-2gdX;P3P=b09hJBiyZ8iQD9_(Y2nI=;qTZ9Jp|`xMcLj*+_4vJJ{$sPhPbDJQVdSwb{rY-SD7m0)8qRO8v&jq1Zuz`1P4Ff?6=o(oYV= zrm>)-VnFsNC4!IPr2Gr+(p-_#&STjYH8FYE*N`a&4rk*yCosa%4YjrKEDTf5?L60@ z_m|6}YgcyTh2|UJ*-$z3WtuEuC^xS*`zSm=)r%B3k3ri!uI0y`{fa-isk3q!Et+&h zsw4I9X@I7U7hzF;vLpq`qD`XR_)1(11h1`vL7@@&e>&xnC_ z3Hs#C>OfSX`!;{|SOfB+O`Vk%#87j7zyIZ3W!4#?Bb49Q%2arikPnZK4##3|C1z95 zm-DVwIC=hZYGP-C^3C*!YHCmPB-sugRi4IsE~+pK(*l==Vd139V;Z%2#rutT27Yw& zTJ*ty=g#mBZp$p*VYkf)&5sh{ugS*X)YSkV96j;TdH3mCGaFQqScOXpze@~#`l0t5 zEy(j5<4{YxJHT`aK5V4MDiof&>^&1s5_E$Fd1TJc540p3=V`EAnMP z1tj}@5ARe8r6Cd<)Kj$@S1P%|(*fR~c3}mc^+%C;#vFm&H&jTCeIdPL*zEG)K{#35 z#{+S~jSf1UiYrH|GPm)@Xyznu+{m?BIvxsW_Ru}pZ~avII>Qz<)>Y#jit#XH-hZH( zl!(m}RM?{Q0{EOYgydG}U4Hg8B_6LV(FRp#I#la6w&A|WA+@h^?lfTB!l;Nq~e@Qzv&*+mtg@|TK@Yx< zz7y3(M{6IU=Om`2$2bi(&c+z!aV$M{CWyND%A+M30r(brB1|571~PS|@BNv(RnRVp z3>jj-hbq2HhmWuO5KWn1u=n`_mr>$#xbGsKJ6b-FReW+JYdd_W(>{GO0NI)LL07!);f$9F)c4?f7__$*AM;Cs%MNPLFv_3vGs>(^cZ5*0F`OKb ze5Z1eMfCN;dsvNUC&r&KMoUXXxZ7qfl)m^3g?&A7Yj-*=S>6xX52?nP_g9Ncr+$W_ zraByc$O-MW*#QrE*YJW{%IxYe6=7%B6yjOE6ZH2kl-%1T-C>pVUcuPowdCeGZFW4} z7=3sl!nU=|!3{y6(Q_+qI<*)59(n|}@pr`8 zDP45dMr9%3(PT1i(`!)4m8b0sBk_a}+#_FH%t9|eAi4TRjE7{yNn;nh`B5wlc`S#% z)$PRNx`M>xWBQ`3m~$1lo(aYK?|7n^-)|sSuNsrLr|5gv z3w$m#B8BZq@bQzA%c1{cscEw#+u9-_w=Wwp@y~(Gna`+}`h15q-57=Oy*r)guR$U6mmBLlJ*83Cm=~IW#EUgg=ukx-6j-?CN z1)?oBcU^AIHz4;kG*}kbZwDGl-}p(-Op(_E5k6{91-VTH5G4%97eI;4svUqrk~o&` zT}~@ntWaw(@4V2}<=LUm5K5&yYW~4o!DVR-IUKi?x|zk(3+j&K*YCCHuzCX>GrkRX zp5@-g=ccGLf@_d+jG^f=-?5f1#zPMk(}8yeqL$UwxH`8{VzbK;d3sxrcLn3nk{Qb& zcA*5X?#uJOWXHhhnL4hji&S9xGy|qMm-kU_)?l}-%~0D75w7{gxziv;)WCNN_18lv z{5J@#HQ}8Fy~e?6C4b1xlg_K6&8NWPu_AFZlJIP?VnKIj47p|QjjTRvQiDZO-PFmO zW@yuVZ+vUG7AoR;HvLLJtZC;?r}wi*z8*Drs3;zy?p%Va^AqrT-V39JUqM!|Gm-sq zg(hB{D;(`GA$eJrXsWRdP2%tUzCUa=|4U}V0h252$TcBC43Q11HQpDVg$k5K`SX# zLe(;IVEGC|a`j*X{8Ew;CS5v*qo$}bweOZ}H`kX2^yHqGwe&k$3unf?gq3El_1= zPMD!azE>I^n=Rg$$mitrt+?=ZCM0)%gwNVhc-+z>^yAa-5Ww%amSZ#F#Kjn)E*KHG zA;%6houunMrL*X$KW69_=dU)*(-968$)Q`uTd?oSe#rG+A9Q+j5q@tK&ok3_F0@+} zwl+_MjFEx(quX7M88U%n4^g&;{lp>z)w@p}%7 zDqc&XW3<^N+1{v)?*jf}=0dIS;BUSZUwRTv7hKarepNSc{Hp}PXeggwm9}7HuotaW zPX^ggB@&n`!yYcVDuh4vB*QY>z_RdzWZ+b(cYbd`K8yVRfN+%>g9oj!Wc_G7sOT6K zvgOg|x~!~+84bVRRk7y({cRg%e3FR3lMr&o!DC&!GMdpE(PDE zI{b(IvT2+764F;yo7wQp}wW^UvGflSP)$T)u=Q>YeZ2dm|+gysewHu*P zlluh!OQPwsFF<*=I_Y$ehO^rqxwtP3#hF$7PSH1E&|6GY?G4$-KbCBpjuSD~bVDi3 zjAvzvaA1E;+RicAee)JPuf`M1Zfl{P_hiVY*qpov9EV?@S10bBgOP6LNWnV#E1v7j z{f|mA^!F?2-v3gn8H(cCwoi4*5|d|g=-JpUcsh-OPYEx;>uMMl-@Qz2BEG}7*lL`p zRUrf{ya31Z)CrsBjaJ@WCk*b=C*is3%!lsd?<*;0&gJK-k)Nv=3o2+$x&=SRN#FH> zuLq$WysyD`({k!C-4>mEtw%0w)Q}8hF?Su9&LE=5#Fw%XvDkHA_|C_kX=u-5N{sI7oxJ8TCf~FGcvb!Fjly$+g5! zw&IIg!L%}O2=dQ)j%&wG0zrE>Jd2agpG!&-V1S1#`LE~(^>b6D!&jzae|fISkLr!) zMtfsN4=v<1O&&FwZN;~ijH9{Rc>e#+8jM5Yq3z5C*#9dIdy3^*f$as5@csh2KZpjG zZW1Q_f9AY<$AZd@yN#{6Mt#AmQ3ZXY++7<#6vATVC*a8E&zL((?9U`6bbr_uT&t!^ zooz=W()1jwIy{CAmA9a`aw^U;`At6u<$%*tbuv${Su*Bio-o(Nh+N2WLy_|bQs0@< z`P0^`8>Z?y;~B3n(?Q=Ak!Iv(JXjPj$$mc!8NIK;8{1@&-Qh1V_;v~YmfS}DVsjvu z=dV6nx#*f&wAJt5sgUF$St(>0~|`SY4N zT5)Lu-q<{zezsOb*lZKe7qW&?``^Rp;bHh*{~uI7TLY=8G~#m;zDv-(9H`>j_|fY$ zk?A>+P+?MtD|t>=wVDO0;G9@^Ubc9~K?U?f(HH0XUWI3N-$D2uiRX`vruB0>;M1rY ztkO9X+T4e`{J3@iu7%3brPZH=s0tuOAjhVKAEE0Hrr}T{Rkk$P0@c;=Jye*Euw)V6 zd)9g5j;Gehuh1GjkGzHdT#Tc8SO;_*<#%P>DUcav16K_Fv5%rMoBRAS?LAMrZ*q*b zKpD*GF?Y{+|p)BYb{V%jtJlQ6b5Y{8^J+s5jKM;I<3tV^`Cwd zf7eJ7Xz(FuH`N_O|2?_*@=|efb=_G*kiI?()I2JN?8t^21TKN-dUm?2CGe@4}Da7x5|I z3v@&{|E^c56D_eJd@AvB(U~pH9!VabNbNM2kkM^g%%Afu%hm$ES`tX_aozipNMC$I z)lulz>m_t~hTzy>4|H{JJKWw^jmNtu(RYzK;Ic-Ytoy5ryWUrrw?K-YYpj)-%6$nr z9%965RE*d}p3m?XKQG(xGccEbCeE7lREsCz^DhHfTsS_g`Z=`W4SExI0Kz8uHl09j?*gLN2jqlow zWGDF3jFCtFd74IKTcLyeZauJ(3Nkb9LsiCbyeLbFZJILzMeyttwLiF4nbd0 zg(N3jx}!fEX^oalmtv-JlM-6G)(1biNocm#7<70PzkmB42VFkjoVa)tAL%8-#@s4` zo5R&f+2|lT=-YQ8;|k|MM)OSRbw4FdTW@1OzV|Ov?OX6T+1>T+r$U%eRR>>M`{1wb zN^J8`Wwhn|Mw}d}M8^(C=tTZ={DXJ@ZhLbdItqEGd~quskyi{`Ox4Nwv?j@m!gj$o zMV~BMM$n&0I#l~`GcJ)+XJy}I(8yn-aIn%PnpdcVUcKZPVf6~?=-X%8YodD6m{UN>*7( z15t=FqL8#GS&8)Ar;HFyO_4o9MkST;yM3PT?;kiXp3ZsS*ZscU!)B9nz&;t$#r0u# z?O0HsHI_;%nDC#sstE@+T7Wv!F#q|wgL=P^2cO9z)U12R^*?%v7#n)wl*tN$`nJAs z;;$4x?fG^p%(_R0?os9AT58DWi_x6cgH*ifr!17T^b#sR4d*94Sp(zDEMRlKKThf6 zPD|V5q4ydQJ_|7==JoGL@BUG^@cu_CKgSSur*xt9r=MaU&wHeQm@1z=TOGX3Qn=m9 z#YhU21y!z${%tzX2aM?C5|S)f#xa{e6|S*ZKc-`U&UhQg9MV3zohXlu!IVS$DMZMD zTV5UZkMbebGUJ^)Ss&oPywK@``jh)vgfAW_BPgmw)6K`TP`kgfaH81)V%fbr|DYB} z$11>yFCttsf&Ct9hrx=|4^Z79iQdqVhxWvJyp(y83^TANGoNk#&mVg7*g*1dksE(F z<2-FWogPkb>uIk@{QYk>IDQ(jZ7=8q|OI$+Lqy^~NZC`%r=H4F zf>;=?CFxrwnRpK2j`SSU?UcM<3CEUDdiYQmp1-al3^5r5OXEa%T*jDOxbc+;XQyJ{ zqC#4J#02s>a?$DiUGbHf&LB)<`NL8U0CoGw+3cGb%knGYJ$#ACa53*XWE$5}`;$(o zGvoJ`s|j_>2SEe7<7^$DL6ROTLWQS4TFu%_kFOs9p`q9Dyp%PW>VJSd_F94-@8pG% z?H9?e;Vt;vFO6<0@g!;%p8Nwvw)44hPW*YjM8iM0mnG<~4#1NU8jv?#37nq$qc)3O zZXwsmq*wc~GOLST+4Y!IO;_c6=Ix*#FB=l6-HZd*=?gJl_r&U(Bv@)tXjt_0lBY}Q z*J6^{^n$eP?}y~Ng0Pcm_&0p>$5jUM^p;aCSg=z^ynV$Ta$jW_AJ8_3Ka4Q`etAlJtWd-I2q+Dv{u4 zd6taOyI8?xR8j_=-A`Uv%Q`HgOoHHA(ja(U?T?SW-DypfG7M)sL8ZHHP7)`N$uR!u0b%B z>8>-huN7LZRE8w>UX9SpAqA^@NO|>MG;r8Y)m@Ze2+O33RGUJEo|)xr-L>~WJ^zwp z?!<4kGfz)T3E3A*=~(S5-mEekBDJhQ#G*DU4cejM(+w8qc)8bm|l%fCB0K9v~ z0+L6V!1Kl&+?>CQo(?C_!+giv%bt*I2KRFpZ$`Tu1>tAv401fjli#}Y0*&xFLJN0D zIMPisEn#+}2v_INAZgy6Wcb7BIQ1&~PT!iqgwq%BW2AH8us)}W+th-ClWu;{hY=m$-X{JQC`?BZ^v(XJq{Az z4}#0iBHTS&ogP@E3|k{5So$ki9gG~B(B*4VftxGSvU*zZWBN^o`siO=-NsfN!Sc<1 z&MBo8`IUUn5j8kcS|P5wBH1g6dj!{&BjuyUD1hT6d7r0aq+vE`PjqU5jhn0lbJZt(uPr`rtW#6Cy z6ny-UOapLKDS$-Z_T@c3dvm={woxY;bH4eznsCb15@L!)_;gAJ>12MWn#cYa{GD}0 zEj&o88<&V*$6K7zHXRus8BH>zpRrzd1gM`1ecQ4YdI+;+=XX{JULhLN4n&2pq)xAUff6SiBkpvbj{F?IHJhx|jg-incMH z_F9$}D3b=PjGsww%~ycSEvEcuub;%VcQrSa>7D+0pwc&-pmI5t{OlnSbk>Uw`m=U8 zpPIP_ykxDxwag!N1Kepsuo?`J5#hs`Y%cx$k@Q*>ioklu>by(=lVrn@@KC$tDq= z(lFY8FPp>n(b_1Akv)AF?dEd4fUsMsRk()^I0>X-IOl zxUi|}&=eGa-^wlEt{Z+hD~#0dKo{J?Q48frC_|79p-M|N2h10!K0ZXEQ{M% zIL)kw4EEcF=ckqvzlcXf500VhgCq2CKPjkLYQ(Fd6?t-{&AC`!{9pg3r?24x=~9)L>MC2(y>iaDwe8^6FwJdiYESe?L`N@}V3p!V_ux>K|m@ zCLO+Udm=Gjlg%9+E79%mar!}94eWT?@8jU`T5It26XE`7b$Y8_4a}Km{N0avMzFi`W|%iJ_9(qZa3k0eI-coN+O}sS8-*qtZ@BmC`n)(LLbwCTw3O1s;Mr)SgUb1P{+<|-_Q(F zl*Ia9=KJHT?9DW?RtkDo@50-sx;c%CB(m3LDIVRfAUK~dB1PuU@W$IDdg|;v(#w+J zLBB=*7*|B7)deZ2 z+OP}fm;ecXa+|~`?!!+BKj_Wpig16nF`wstfIhsifP}MM%&$LvLC4=$d`Wx<%O)rb zE?ll4J5kBSRV9Lytb9!ds2O8sZ&^V*MgwfZ{n7Zh9DR6B3QAIUVxPBRWbnCH1}{UlU;zNifi*)H2bMd}UcZKiMpo87rz6=Pbt2;G7Z3LTdH6C$$Y;Ti$ zo?a+@OhL#@)rV5`1{AHINu3(xz^_x6_m_W5^j>vxcub<3QZb)Py^d7!U40^`Q`k!y zNSHR*CI~LZ*nrhfe;jkko$j{Ngmv*uH&|&(9?7*5bFED{wx)@mQy&V_mpgHleW%#4 zK^bgM81qR*Ch%yeHc9JWjH{}Yg~oDw8usNpFEzfCllx=?hc=1u&dO_r%f~Y<{be@a z&d(w0F|5b)@*XT7x{s8u;hgnw_!Ka|C5gpyC+ITv zzU|4_iRJ!Ug%uxtU|*I#@9MuE91mV2dmPL0eohx%erg4=e`LtVPajMEyx&lG!A`;z zY}eEk?j^0_)4MeV85>)$s%AR>DbeHs{Xw$FPe2po0MQ!j+mZ{T1vtSnV&*4oqXu&El!P&#TW%8p>z6Q67M|}|J>X|O^#}S z;$aCtuwcq>GB!FAOQcJQrfW0V{NN;3PD!RRPh}yek>$LNGAB|&y*TN?60Tsi@Iibz zZXrMMv!;;Csl%uuf}u0mKEg^9;-i@FJJ5!6Sp1b_?%9Gf?|6gdFbzm)dx+U{j#Att z%la90_?f|pq;F3tR~NJkr!jt5Yw=5Zagc;7P*Smlsf-`6yQNN-xoJWboA;D0=9BS9 zjKTZLGxm+2ELg+5qH>pv`5|-1LC+?8Qh)vnerJ1`#)(FBVEiH8pz#g~>AEPk(NOzO z+Ybu1Ff2)g^=YZ%<~5pN)g!{lWig~;$t%+EO@z*|N9fOQ2GHEnh#%r=xMi|(AgjPK z>gR{Tow&)QrdpYwIPfp^^|qrAVzc;gM_0Joe+<2~NrK6Vp~GPfuw7-Z#!z^_w6WI^?Y=4GbW1o<@?&OH%^ zpJKhZ1GT{}*&mB^w$Lf;nFqC^aL(Bdu7c_3rM#B1jyaa)TUe1jr?s&2 zMmlb1Guxi+cChMj0A7Bj!Q7A9uy==qH_%CyhQAS!xJ}N94Do+R0t;f%VZaZ%a(g?e zm?O*gsH~^;%eIo~WxD*qDShCPw32vpI>X*E%!?{>TF9BCx`VhV>+$;*?S?bKPU3*YCcJQ8O-PDbC-j(C@h+KR;Lz6& z?pld(1%%U)Ok)o|3>)1Zap4{hNJG3ATGuNGku7~-+`Bq7TQq~NIBx*o_09N}b3aL^ zUoX;?Ezwy8>2`^`q$+sTzTvd~cp2UAVfUZM>h#~?pdu~8K2O}~>P@}j!V(F$FmUL1 zQrdSTs!VC5iE*~Dg!T9JwfZJr8mA7Cti!8kg#jG+Hi#737vud`%EGya6=KEtIsB+e zUEE1`I~co|@w6MS72ZDF8$KVDVDGO1>=NT1h1)OerYl+vp{2AMLqAO>#|P|ijy93- zwBu%vr(Y*z{g>Bgk-^@F7fdJcSBrCh(;KE}1z^*43(#1{Jf{aE+3Y%rW)-l%cUs+l zn$-s=Q^O_t|3-yKu|3P%|JUCnZtVs0r*NpUE{q1J^oAlfvkf|F!(E!yP8R!w zpxWRm?6ot1-Zv^)@5ynxX8nD#gJm@zOj|&5m$z`1yLREjUhFr}Ju80wB$^kMKBcA6 zW%L)zXE?0H@}k$-f%0(?uB=t38a2IPM5hS7Lgy2Gd-mRbszu_KSWvmP7c@HQ^Vjci zkn(vVS=ROGzZ|Lu7cPng)~j;l(_PYvDPlP}wg0+Ag97c~Bb(c;3sc4OKlTPA;{Z(E z8$;aYz9p%~tFX*Efx106fz^%;__3#&E8)~YhGjJ`9T5uYAR?oOD)R}QEF1Q=6}=HE z!QS|KJ9uvzfc|y@7k#XeqE?*#UYXzCB?EolohAXV&*9MGE~=h-o{T@^#+xh| z%k8r+q+^`T`4M{Rf;;Q-c>PC&@?{w$U%fYY=lP@R=q+@Cjugxo9F89+f8{n>FzwK> zr6`mtF#l{7dF=e z49AT-97uq485wY0g1tFWo#gT|S^l=^dOE-+oWw=z@wqxC5P17jVfVE=XwG!JjkhkNrBlQd|`N;e%`4EQ6?fZ zdJ-?5XD9>77sIf`=QvpzRYwN0oWq^Y7wL2(rX4Mi=A9?|Ih+59Bg%92_|X@3!^!n? z3ylL!_#3Qy`ODmqP{_3R>fYh>)@7Ejy;Ov1L60~$QbB_Ldg0O`ib6w%DfHf5i5ot|Q1LY9efM<}Kbihy58H)#Gmm`w(xSq`n|t`egG1?u$O0-g(C$BtYqirz(ClG3 zQ7pIW1AG2r_Wa&WrbPAOJEAvX86FHNrPgOn!7ic}14q}2i=B00{7+qeo+0baiFG0} z!z6ecwZ5pZ-@QFN72V|)j|5A$7x;(0 zy+-N7(%}K9_|^ghXIW^d+JV~7JScb16bdiaV)xc$l6rg-Ib6N@KV3n=;3Bg7t1GWE z^E~xEGP|(QpbzhVW)PTeo=z>wC3Ej#lTpy#UxLH4Iy%U~e8jW`N2tzz8PFWK1A~sJ z7A{HZ2dgTpSqAc8Sb3t1BqvLFi3KcQVnmN2zvA#%Qd@6+bD*w7dl0y!lb%#q&7+-` zp!9kqT&`iW-}Y#-bdog446YU4Bu6s~ z@#5vH^wNQYr28AoL2^hVKW5#z*?uq<=QDhhWnQQE>&y7wA%?;NRapq1ZH zJ$S)z_#ZDJ4v~VtgG2FDWik1<={*_2{2FDSj?xe2b>!Z#dYoYXnUfpiz^yKj_**|t z)BtVYvFM?{jrM=92Pteutu40UdaddtErshbhx3Av%)XExTZP+_PEZRk*3-x4Nrl13 zN%wqN@{4I)|LL_ly@bMw_GrHC`%~(iHWJ=3E?4fkI(1Uihtzi>oE1BtBruJ~h?Pt$ z+i|QQ@X8Y+Q__U*$E!kC&oa{Qi6q-9U{z7!OV%-wE_;JSZagGbF_6r?R-Z<~G`4S@ zta?@)W~UDitOL*~BZh1~`GIUQT!HCR4$&zS%piMV9rop_xSb}?NS_hS_-j80=`*5; z*jt%*arr|l7ws=xknhFk=zSsEz=&GyJ%|ZKN`k7N0|c^nY{@!-OCQ4W2b_kYhnbX+ zF;oub`-S0^Uy8Kg9Lr`md5W^KjpUMU8oB%T6b3P$;ITv11=h_!APXlcGIY&^6bSA5woE_1ek zZ_6H|YA;z3t-MGUM4ZFg30>4GB%QP!@5hg>)8)1dIY~?AoAb-8)rAX79N;VCzW!lv z$T3`x{+%J+D4NLKvoT8AU!@3cRn_1S}Nm|~XNxt?q#8r)~d_!#<91A}`>-Jk=dP4Iu2IKYpJI)MmCU6b}r={_E{Y$D=1?%!ybu)Bi#B zMyi5;qdYJDAcQ`9olHK|>hh-+^#SGIn$8|C?qJAbWuahlgpkC%MLvoVF}ef3CO&QbZ)P1Ly@_v;JQKzF5k7leA#0(_qiclV!nWXJGCBtS$H^pD@rrJUSEZ$ zWX*zDJU0FUwbD_7=C#tiN#hFVK9^I-QeKb0abh>D{dms#;1v`8qqe#ru5f@qgBkbb zA5LZEjKGAK;INIjiYVXpMA^Rbf_UH{xKvex4(q1TPqwcJ^sUGAdgiO(?1({9D$be4 zJf!;iT=TI#yzPpi^lYsI9Atd5nY#x);$;LI7$@LtWk&p~-jh9YzWDO_UHWYLAn5K@ zi&txE#PwDt5Vu2@Ka;5sj!*9r}p z4!r2J1bcH*S*HMQNBA2~mkqH5KhruinC?SP{y9X%*-CtR-gPSS(dU9H_V8Cq7dF$LtKxK=cn4Aqqq4?XX|msyd53Lx-~dz^hPoRw{CTWABq9E_ux$8 zda;u%zsI4MWdb#Hk%hZQx8jO}N`+zl21478$GCpEHB@Y@C$C!`p|#6TdZj9Z^lvfd zAN+78vx2uf^_eB{!0w*+llWOUJClpQe4T8IWpifLb~yK_h%B9#k9#w7Y30~6K6A+5fj$(Q9zaX@Aq z9n5?{i$B)l(Px!h@vM(z>WgMPV@p7MGM?<^mHB-`{?Hrw&CY&~Ui`?2RuXbvnNFT@ z@V_k9Hzi}CRX+e1g$dkF-RI=hpuu>)v4<+Dv3=tHEoeMWo?Zm>L8HjC=Km2eJ)>0@Cy`}eQEYD^So z{3fR@0grFVp)qlCVCTIVIh9zkj)^sNZLh)f5?L5!P(Y5yox_=dU9|6>>txKse*6$+ zJ?{CJ7}{&OIp1odE|^F=u|5S6dTM7f&kpP1I_HmfW46$qIyo4!V>1qmddDSKUn2)P zmZHC@qL6;LgKRzh95c&K(s$_vWLJHEUd~<$R!x2A{H;$0M($S@8s0gJK{n zi2!5pnb75Ypq}v$^Vq$(zn{?NBbkBC%HI>SG;O?b{3q@7FoF4+B7Aa0o;n_p1MB%A zc+@6<$TR*yl)DeRf*;dKriyS^vmN_b*NCSLyhL*Q>GBhI0_+O4dvI#M^K@8H zFQ`kA;{Dbwcb=$tnMgJ1@?9>w;k3sRE~d+b?=w|h2y%5|=Q7ha>NbEZ~Z( z4nJ|79%$(Lkyqo2vAtVaSl?aC&03wn+o#rWmSIj{u~~$p-(D+J5u3ndwj;P&l0!1C z$iw4xn=$xE82!1}1~yKvL-Pb5(wrXeJcsNgzEVBnK;=`!{f9gsqMAp?x~fx~Rat0Q z&w91QPSC`7t^6_CoV`L{=shF=?X(9#OmBHmbKQh1yOFBhwSfos>o9u7Nur{^mlTfP zf@3Er3fpvEki~w?z>H_;!K(|o2Bwuw{WTEshgs5&7Z0%dma^cW;S7sx0uZ0fB&7}A z#7xB*bzU5z?(TBnbw3zqD=8FiX|w@3hFzJqHgN9gQ<6OI9{x`LM(;kpK@^wv;eF#c zVs*~a`QgSE@UB%58s%@%ZnBzJpQOcdS)IUu-8YYBN0VM@GO+c-I6O3U2c5(C*uPT2 z7`Weuvq}+2BhzI5n}IX4nB@OYHd@_Iqqn}~k&UK?{Kc#cvN*NW*=>)6``t6$T6l22 zjNfyN;qXOy7#d)SsY7?ssY6U4hvh#^y}hyU;2{|pcVs=w2QDD0(?5{Kst0i6+kJH8 z-A{y6*Wl^27Ov{pBJOwHO(H@r?fv4G^oYFatq0b5>w*8dKYeG=fxA-B<_9K z9Dd533sfiD2?{TxMR*ZM)?KAIByuZ*fipiJ0}WeZ5|Bs+8K8F@bE}I zoNT$#fX|owr561TacU70`9*rs1Jax$mBP< zDdsSHOg7y-N)}e%+ki*H_K07P90~waqfnZ{P+j zIr@?teeXJ%v}hS>E@e5g&_?#2e}YpyPtd4WY2?r)rlY?6j7+)t&3S@c21aaA7S`lD zL!4|NR<6^88@47;#k^7fFxhUq3>XEi$IIzM$<4vfNd3TQ>|WDKqh2UN+v*NXw^&N! zOVY@&Q5xn3S#ZeNE9r&bcp`>iBt?LG{#eN68y(1pW`rTD*7pNn6t$|K`Xs`Ae6_VCbl zAD7+GhI*E&!m2|cxDf@H(4FI8kfSslZtjOKv*M}t)&Ah1$MDl2L0tG#4(=tbWp}!R zgb#Z~CS2QvPZnj+(*Dxm#Pa0NzHoJp+L%Xdn2$zAHWZ{M=5x=K`tst1>O%K!0>6Iv zqjhLFy(n)AmTZnv{_=>cNT?;VZ@J+16e(fa3nRFCKOct`jHYwu{UXZm>(O9$8nJen zNji&D(PW#l@WR`M9N3b;J1UH&IwuGu_hNUMAP-uoX$tGvj$^W?8F}0Ek)#coi7ED! zI;D(+fmiEsPD;J_sKQVF zVXSI?VVayNoZKtI<^sk`cq@Rc?gos%zlA#9aexu)n13X17RlRi%K2PN^naN!Yer{~ ztAZ3i=XVZ$wdW%@rQ3r~Hy#8hgm!UJvcyMbH4Y%|nFwLAHg_-86qUYDag1GmGHMF#w%kuQk4#X%zDumwAO6ou`^c_d;n%Yi=}L{;`*;l@8U;xD>0 zd`{M)Jqo4xr$JdzJ_GRGhw%ffr(k6FFY-2V46fEVNDmvz!?lLBc->#N@S9UB*?0RP zKKb*5MmXk?t(#Q&#obn<%RJh7#Q*kjYpXNpP807k%;(pl$Q2!`1M^57>pI~RjuE?N3+{ri zBp>GUCmrE_N;$9WWhC5iQiN$!2H`m0o%BFjf2foavFwQ8!n>Zb;2s-@Tb^Absjtl#PadZcV57~3K7%-y2ypGwK#h8LNfB;Fp@t&G8@1C z@t2#nZ7v@jmrG}{cq-SUA`BVTiyrqe1tZ48{KMq+w~YYP^Kt);$byLnq@YgfDISkd zg^=19Vsx|)D?a|BcU>=WF3ko!-!_qa_V5tfd8^@r4Xh)Z9Su>hn2vYpS@FIYQ|LD> z0A>HgkdMQ@5k=*Bn7%%SI{!8R^WAwUT5yR=y)6x|wVUztVGhifr<3shQhc-bXZmT! zcW!*!Wd2g_HRbAn9i!gbx~ zucImyoaMos-TMsw8k1RLq@nD|SoAB&qTV8=^MAbtw>;S;9<1U3?;{z9vqKKf9e6}W ze8|G-i9c!D4}oP0sPeu~Ww;S4&wxR6-Jc@wN+65|W7&o{}6LKb-Lkq)a`x>A_UGi{wOWbD?Q9O$ziKQy$t zlFteZgR!|hJUGtIsU_hwWS<3uGLA@bWEq#Rw4Tge1=#n`FFM!V0*aCfv2UUiEpU>9 z#0CjIujyGyvO7}o+<9ezYP&#WZ>A$U=0P1pEMU$t5zg^7BOkGqYUI&ho zN~h9~29gWqlXy*bZ)>S46K6b-_$hupZ~;-92=7H}b7}(yfCAGoX6_vTqGknfcoK;E zkH=7)eT;A+Tkz0!MWJcY9inWh%D-_8qOo_{IUTV+pWI~zPi%jP6(*MAR0S15WIYa2 z{Mc?{!7P$c_nSPMGa3gZ?x#{p3Sc}h0FU&NE|fc4O?K_h#)k_lX>m!V8?cl+^grEN8`A<+nhn65{75?1 z%mVteeT3YE;KFfXtV4(SRt`P2I`)FO}@( zCT!D(G-C%Gv|tl8y=VakK8o=0R9nu9^+D{t6@YIO-JvGh01`EFvECwrUh|QKZFB2T zajh>|^_mb{k6kGDR#8|wc^HvSoWn0{xqHN@8;Bu%GsC`s`i@SGT}`*Y=o5Qkty9&&El3iL+N+ zz?JD?zHUA%{-Zwttil5D+|XF^YIQqFoG}{*JlaEJ=JbR4pRZx^!^_;nyCdO_iZ1Uc z4uzdI=gEPR?^yc$Ic?PY!P)LN;7?4wNS1BAC_Z*TvX84??Fu7S1faWB5m&nI9dT*5 zK=mW-bn^~H7^Ne^lQBJFhd%&AOdIjLZyi}U=^8ozISzf#{G=08%ZU%`0a4Ga5Fby{ zAQi9m`22Zpuy(CHof6oMFEvz!ll@#_9=rQw^zB1t-IIp*4;}EHVFqp5qX_B^{x~!> zN_^y%Gx)pJqK%&%TvV(hHjlC}EBq(TI9WkD8FmSuWVmJ!?gg^V>7=&IKLf76g z=S?=L3)*K~p@wOD?9(!d)S7{?Qt-!C-K}(;j}nO4-xNkRaho$A5Z!4@aq@cw;q}{k za{S#n9D8p)&F`or*928w>BTb=k#>gr^Eds!d3gC0H<-{6fQ@G~;rW$;Fp=rW*M9+e z)lLaiR*10eg(dku;sbeW8G#S^*Ys$&K7`HxiVqSO(uPY_WDfJNe14||3fi~0t{yfI zZ(^DGH*)EYQRjHG?G~i=@HgTFnpmOPL21As;MksS;T?H;R8WFT! z6N_`Dt7+hQBPb2|j@sX<#Yw(z$yc@qv|Pi3t->$ver`MdI;$#-ip!*}SI_a~(|ZW8 z`^yqH6I2gANIUlqf}`vksrF0|>&PmDY%2R6nFria>jepl+kz28Pf%E-4t1xW;))zs zXL75WDEq4L#>HDeXJR>h(^AQwUmpgE5w6gx!Srbb;dJ}sLEy}GABuy@xL<5fkf7y^ z&ewj@fwGpcue1Q~H;ti#>QvxHS_6(7o=zZkE9%0A}!-sh4!!d<} z8YZDa(P5G5%tn*@Cqxdwp?1?Mf4q;reM}A@32j&k-kznt!B}%ZIk zz}Xrlu%FI$cI^&Su@<2&qaIbpoFYd~oFerlTkz9mMd5`-4KZ<3Mr zAp1cr{s|olZ}Xm!NpU&&CA*5w6u%?E0TTb(M91&W?}kXQ_x@==didaKUT%|?;27Zs z!!Q6#9rh3#b0sj&0^fmhD5%J<1VJfV#NR@VZ&HCXnb#iB{HG(+@V3R-IDqAw*?n|Z%~5s^F-J) zKaT`={vy+SnUB~nhI))*ol?7MusFPho2?VaO-hvP-{%Eu|*+kWhEa5!U%lWRf<;pK9L;2$X{8H==>XCimhfpR!r*KC1>zF?1`otPrX!d4Ap;upd5^GMvN-2}_z>eLDzcP>8>Mb= z`$z!7{37nytM??R)B?L#v{U6QC5Tg&;B&}Qgb!A%BO|zmBm*s6n6COlNg?DeE`76w27he3l+ZOjg4Vx0$M>7-4eA>`LFo+(on4tm9s z3Bil_znaVk+U^1GRM>uyX%h0;GrzHCh8!^?fv(?)r?MCR2+m`^G&6Wba@pN5R}A&8 zaK%lRpMP2(a#=?3D9s!AYOI`4@+F3(yzu1>9-iXLr+I?fR^~Ae%r7jNZw;^69%s?O z3&goa6_P5MRylJWedIL=ZjHZ+Q&!j!x!4QNFCRpZ@bf>!rsr>wGajv|CzC>}I8U;5 zjw!z)l6hg*go|79vT&`MvXFDc6ZSk{`FrWw+;Ht7V3HnyA07<=S!Ff2B+odLG6!nk z-~l@?H=^{T({)U+Zz@~&msJxSX1V3akqx_hbN&22g8d3bVb%tF`eukfA62U*w5v@3TXw&0nZJj) z-cW<(HZJ&cTNwQ?Kn;>cv23)16S(Z$CuEjV0DAg`fzrgMq{J)@Z?8B><+Iz!`h~22 zbJrOnY`@4&WV`IYCM;XkS^=hQF~L>g+h}g{Prm*Bf4u&~|(E z{l&iPwSCAhrrqk{Y_RN7GW8qR3r;XC*(s(+)?D?M=x^MGIeS>Ijns28cE%YTb^kLh z>3KoCr^)h1%6>RU?VnB_hv@UoOXHzcsYGnWX6b|t>ca9&FK}n?TVqEic`|<}SiE7n zh}f-kq_hUa6p9eXHF1tUWn{|EIaohhTKF^nA5YtW^P3W>)@*4Q+NjIF)nfhdJ*}LJ zbq4M{qb#WZ+C&%at>iP$dDGGjlVF;9AbNLe!i1QiP{w!+-Qh^-U=8qPcfboCR;>5o zGr66-1zr0;p*|xmVd|uIEL*;We%>qt_2>2Yi_1)4$}M%`*&&&$>$=_Ouj(xRb{`9p zyt|9!c4?r+k9K;^+XfPpMEJW$o?3p_fLw;#6Rs|0x%Y2Lr}J90ynKb;(j5+cP5z=m zzh<$28Ou@pVa%IEdceFzBZ+5H2R08^6Lu`>Pg}j?`A@nHxy&;XOg3$JF0^O8p1l!7=;hsh}XE)hi(DR1ndrvzA z`&aw0JFNyEt}7)pX*p60%X9qo^;5y2#0!EqNN{`BJsa4W!MNh+GHzGM3t~294E~(i zK{rg6h8JIUVcP;l+K{*q>NQPyhohY&zWxBI>wgyIm`-@_?r?Ikco<(d;;Gmum5N)& z4(IQj3WUK6y=I}A zPlmxOb@>-%`k`FKWd(EpznK0 z!MkMEuQA?@oP3o-+}pO`-eyH1!dMA*4Q9TB{X6N_^9#v>Abno?f*F)m&J|CcAi?k@ zt0sZKG*NYFv&b~&TQ}c64Eb$)sQoex5Hk(ozd2mS{tsD~6opj^_2fzKax%gy0WF!H z|L`ms&}Lel!qMz~2_DK_c_Yy(ce5-Ezc2p0mzTCsjmJMX$-@4*?Y2&M<1&& znz2CxzOX&TKMWu0_LAf`i?DoQ7_#5>zR04l>cGr{HM%OH|fn$9b|1Sg=dcDzrAjToDdYeaD8l_-9 z^Hpi2?xZOx#t<~>Ii6VjgX>jumOG&?$>+IrW))F=)|a0xS4Q1gkMkd0do0?po>s}( zLQyx%a?iEp-W}G2_Vxgj>Fogr2S~w&Yt0i3 zZB>BKS(CZ6^zR#i0_`1%;8Pp zQ(!aWKU8XfBo(~pytVOX6mzsleX@#?Qk zvfoO$=$&=_sg*}1e{F>~HMlSpWWEJptE?96_%sZ9GrlNqEzb0UhriyK>%g`VW!;-YVv{8HYW zJU07HvZ-VaKYn>QTpuCA9aai7-@G?;*02oB+e^u-H!KsI?Rtu`FVYWkHt>HeU3WZ{ z@B6p1BYQ;2EJ|omJlAzS4Jm0V?V(h1juJux5v7up_R=D>m&mz~)~CIcRZ?lvL@JTr z-PiAbuk$+R@jUP6y5HA(4B`0Sd4_ztYc`O;S3f=+n<2~oBx~0M1YaifR6Q7?ya?QY( z&Y102P7e)4uUmndXvh1_1Lq{;%C1Ym>#~k$7T(4xhrE=f=jVujYRBO4KVwibSwe@M z6Brq|;k>h)t2}#OD5-x7oytAva780aoS}pX-fKwVKNXg|U@oSHbP?b0YJmKMJ3+VG z5qj`ZL;lVu1Da*+c;0$qfoz7At7sP!il1+d!I|A86y`O84ODZ(NqpwtcHbI0gf_t= zM{n9HInDNrP{Qtg)=+Zr8ktYHCFU-wq}8oe(8>J}e3hJ}?qR=KQ$Pkhc<3S?eam+a zK4USSa{?CC`9<+P+|cw9*Ly^t1dZGJs5n$YzO%xaiiRQv)+W&XFN)B0(_OEMR~sSi znF=!xlEZ`B_v!qR4Q$fU3|Q2YcNS;rBU61<Kompu*u=gUgCbhR^`R$j**Rp?{F46bvy zsZbQJqJX+DSJUznCD0mQ0=Z|?iTa*q^OoNN-PCe&(pQ0L%HBfO-a3@5SCd!z@0Rsk z6(Xjn>dX5*7>ix`8Gr1C6o~9%fL&$}p|MNi*>>KW=F9)r0q;f%OY1+t0Xr$3Nsr@R z;CGN)wV$5H>||GmX<`G<4B!9!5csHm6+Bn9>phO=Y2u++OEUkslBHd6#oPgWR#b^9 zN;T#^7ko$gxc&k(aR1bTBZ>6=Z363jr!zjcET{LWpM|$ZrvzuQeI{={e@*5n%MexK z;!x+dC5rv}(ETM#*|i~VxZ(%T#JkyBux#Mo5W7$+^7rB0H41p7D1knt4`JI(R)9P@ znWVkd<;zE9fcsS!ah+Exd(<#OwrZ8RSbNeDTV{;K9FE)9D|A@R0yjL%f8+S_84$Km z0m(ao_L+JW=Jqwi&q+_nc8V%)nj(k!vitN?R?jwkhy$&CrsA7iUwF~qz3A;gZPK2k zCjXi^7O(N|rlWmSmdxDv{zb|&C^kZ-S{v^-^rJ`b64F<5A@N}kMk$)EwTa2|3ZP`YO2{22m7x-gtzz7Xi-xWJ6H4@eEX}4$)2}l9rvt& zue__G>)xSw^{lO|R^Ckc?ppGR1!FPTjr+SVTR_i?EpRxeI~_0D$vo=y@drQ47ebP( zNB_Sd`5sRl?j3;XD{A57p@X#U`6rg)Sr4yzDT(XPHF||#UJ2QKj71;EEjV)VBw2Br zji{N$G5qsb91|iXnR5;tU*n3wT$7OWcm>;{YJktV|6LsaTsU>(9_*MgjtXjjF`pi0 zXtV4IEm^pocfM$0-8Ca|^4~A;rm!OnzSrJW5vTQ3=H2U{*iFlZ9ojq&zuSk>G)F!B znc<4vwc9Z~lb@|x-g13HLJzp`vj(I(3+b}X9aiJX=iam5sYZwA%%^GL7X{8mbAMRZ z1m3kV?gm*Gam`iXOIeU^jgQ%~YVO}Y5UBcEfQZ*9mVt0zYdr0d3oREq|L`fwXTU#HC7q zW%-}B7Tp`=DwbUcMf)KWP_*Xz!JrXr!@7Q$$UPv(o2?;l_ix_UJd~EQldR()Wt=j5 zHK`q4En9uW5|x)drf$EV!p6Wn$SOWTD^q?k_bFGPsLx2z-G4LJN>9K5{(f1aa;a$Y z@_zV8EnR*U7-1*n|SMEFAOMiEZQ-z9jn89{LyKc zln!c72A`+OxcG2S@;#KyjK^~g;wr9Xty3t{byY;!lsICiAHaWHBfV)=8vWURf*siX zlxO>tlY@y0wDg}XP*fd`iB^**jq=A!9G|;qr@(~Kov;tj^HKJVX6uI38xK zM&*BngN{Q3HPGAA&Y3(M^}eX&)H<FdTTg{aF#g8cAgS+u`wQD>J`oujuJcQOvRJhzHoopqRVrg+Px}O4HIw^=jZ2GAC-kz^+(fq zDQOUIZtwngNQKJUfoQ#xEBRb+p0PCo0I*Zy?5gDS*P*B6@a`ci-^b zGg9EYjP#Sxwyf#$!;9%Ond?G#ub+go#dh4z*w6~@Z8qdx-@t}>n&M+szJGCOkwqR< z!dvfGQCYtgAUv*uz;$Uf_fQi9T@_3;R}_tp6w87=c7eb(w^t2@VNH)r&*^dPI*_bg zlW2$lkl6nlwybGKv4JqRO7RE zQwPquHJBpX!}&4JfsZM90ug$n>9*SsHa^xCYcihFpOHIQ7Vpb&UScGsZu$aW(wyN0 z$L+FNJg4z!ikCx5isqyQ^@J_UU9+ux5M#GLJeD>yAtVb&kc^%)AA`b7~ z0gkvRVWFum8K^cgw#*&%40vDX5LNc$nHj2aocV{_(#&t5lDL4j<{W4JM%$ytpQlte zu28n^ZY|t%e?{xJ>tXVEW#QJ*6w&_oxHX;QcGZ0$rSvPv2Yb-ysf~=Lah>*^SbEU0 zO?HlFMK%_d5-)~=(Iv;AGfO~c$#p$Cr3oE4oII@P%+oLZP729~A^*8Q|yn7N}&oIM#Jby2H zbU0h4t&A?>N_w38TeziH;-z~l8FC{3%A`ikp!NDI`Fb2;`QEu;G0{q#a!Ca%z}hSC z|L5(z^8vVypJ7K&HW0cq53Ib%b1=N^@$4cq+{HQYb$vY8^lwU7qqUM`NrRxOTQM}P zjH2Dvs&X!T#B*K>;;GabY=v|`oD_`2RWq#c&{6bC|9=c0_m*Gtc~T1Sp9}{&s^F9h zJ*Y8c4Lg``hT$vt8M#%VDDtTy_V^e>%_etXq0MvHvu`7f>y^uLCe*+Sol1(=>Hq2dUG=6c%0BZHp4fZ^OV|Ngz&w5pFU+3+1ajSCr!9_silbE@)tNtmD-;3TJMF*xkuAbC$aN zR((0R8jlpsA`Y<@wRA7{UgqKfe@FD4AHeT12`O3Xvi_5K|8!p|ZF8FmMN^b8zjiql zZtqu^66}B(^UG+zsE);hD`Ee%NA%~@50>P86fR_S7Ju9t1IHgHdirrM%)gmDbV&fN z<=9?5n9t-#J+RLXDLLNQ2p#9~+~)V*l&lxWa=nyr{h8&YmmMiwcj$qkhbyR?|3G|I zn-5JhPt(EWhnZUV0Z8OC?YLtnK<$I3S5j6w^}NNqc)Cx;yxH7urFunpsjP@4k8P-^ zvVr}*-5KZdGv>b37TL{}JgYyOcfNF62Kf`;!fu;1a@J~MTtk4l6WeI(IwmXFnFAI{ zM&gI8p;$XmMVND|naE2^{#kP>e(oftj6W98U0)HW%512267Pytu|SKd66!TINwzIQ z8OIKertF2gVC{t(=vS3WLGX|%uG2!j76oy|u6nPd$tOYE)J*)PxeaxP_7ggOv=!$s z){%FNo{BFgNonq?94P%T5btnr)I5)sOeMwwmG1B}@}1|xiI)|SG2D-)&u(Pf4mqOp z<)?Hwdk|BpWYyZ-yJ0ym;Zq~E2g5~LO$mw zC9r2RJkg0`zLL=c!EVwISh>K1l20}=GwTj`b72f!y!Tsnbz3jIlT=1^FOI+}zvGa^ z_L5ntvOMYj7~$+iQ}J`OAD#`GiVMba4a3V3EPatD_PfOMd|Yjy>_Qua0nyqedCZu1 zjx6mRLmr=FWS{eUVZYO5R1o?M#@oxm_uUEF^6VFj>v9=n3%ZIa26KgbpQd62|Gi=1 zmx|_Y^2GW4naZy@3Ay(ya8p|dWyFWGtPU!8Wn2`s)HVv4A1b`6h9!gP&Q@90uHWG1 zRztfF>|+15$soR>o9Ows17=8SyyXc0=qIrbDCvGU?nCHtV?Aic`T&;#9Pc>0%=ZWkrcl-x^G8E0VtZ<%*mLNpjq2(5u z^4=cP(2(;d|M0y0nkuHLJ5tB%YnZ==CCVnZ<9W#=-Y23PN%7);FvY7H47R0E^5!fy zc;-i_T=axW4l2T^^(jK--F7~F!s2vcci)NPuE8pD*Qjae87-ybe^S87r8AzrGx&dg znPHtR@mY8~o?qwMr^)ZNoeE4|1 zBH^WXir6Lk9=m;A7Z)dVrh}uFvx}adXu{7CL+(cvt)F0t!Ti}g>~j&S(^YWJv}hXd z6U8QcH^h#g^XX&s9YJ#IfuL&L&ZVej?SUMbiWuELk4^itPPqQmN38183wz$N!I@63 zv_n|JDjs{{YMvK2e3FYWwr>|aWEn~ikNDu6GG)B{XBqVtJ($Qd`W}Ur(Q&2Ou(p0H z1a4`^a|O-uLe6A!ad@&LUeue0ftpe}GEtX}srE!q-fMPEIula8lrg9>l5ADo3bUv5 zLMP8Ma_ggx%XjmR@4pYJ|HdDz08c_zyrCHG;SCcXf!BW{+I53k7SnK(k(4Tuj>^Pt zUbuK4-&4Qd2otWU;m|SUPRZ}ptc0982nG;oo~Z4pc>fC1`BlJ zc=8X!*ZU};L^p!Q>l61#GC~R;-zD9*)!WCaGB>wzxwNr@4!ij zjBTIK56zi|b^IN1ZlERa#85zwBx_PxvXz}OwZsN~{)&+#$$l9sVM<;&jo7{&GXA`Q z+xDrXGw1=^W%2{cjH~I*!$)4?yd%7KTwB~WeI0%@pDm0&WGhbYt0V6mGY$QgODX9< z4$Ry(2t9cB#J~Bxiepqde`ZI2d@i`-Gg#>6N8|h&+3=DcxW4i+JzuzusqhS?|DvqL zn->)^ZO1TJ;ge14?r6xrU%Ml$QO^)VpBS;7#?vv~Hk6*k>EUdSfipPQOOs3IWir57;BP>(DL?0u2vQ{$cp`+g5nGiti=I%!A}xjc{$iEV{8j zi>bx*!LcLDXyES4G84X!3x82X-m7%c&S(?p##Yf2u9yCRrv^^po?^MzpYo(ItA>1 z;038X8iC__@g4beb)Kcr$X@k%Etr`P7h7L8!rIcw*#GN%{`qn2O)2oRA@@7L1EIs@ zW_aJzgBGo6s(kcR&Ua z6lfADTllgMTHh$6&O4t$YT+%|dFBLVXZ~V=Q_jJz9o#cj>@6H!G!yT??R)Qat}X@2MJ1M>r-tS&wRG<1e)e&| zIjCK!C9Y_D2f=A16b;NJ>j(|G&i0wuL6`3$;|zqQ*@#JJ_$;@|9!(6b@B-Im^*|5y z`agbtfu%HG+85RjyTQ#r{0ttWAisXRBhQ2SL1AkCY@2uvoRhS~z$PO+)H+Z2v9ulA zU+B-m@^mTR?@Wf{5;e}{I*^@NBD3T(LoMIU^{`SbddIPAdGZp9IB^vQsy>J0p9$1& z|9&?8L?blTl#ptGBD7|07udCSY)^J-5Y}5v60=KGX@dvj7)*}5N~a_|Y=IvNadJNm=# z3GKN|C+#i3-a18`D&AuagYXtfU^%%`urhAP_R!^rVgLTWbhGyn7F1s=j4K^2Zl3CfF7F(0 z+f_HR-n*13_d!(U~uix8aA4P_dk)Z?rVu8^tV`(8_FWN|-c=ogQ67QFLO_aOLh z-vb7GRzJB|UH(w*9Pdig68p@U#Z2xT7eaVy!R2Q?&}#Key!?yrm=@}?S#gNfaZ*yh zH4~-{R>1(@Fv7>qgXXEt|cDoJO~2A_IYVK zw(~H%cF)A;22z@seN=XRHIJiD;2hnjjbMIH6N~&uQO~mp?4_*=#u|pv`K1y8>SD2B zm6@0qpMX1$7Q@Fgyh|u!H|y$l4nn!Fs$k$jQ21ddJh-1uUB0Tzr$x-cEyty#mvKcX zz1#s){*b@z`4{itVG@x_D<(U!H+^^W+q`I3Po;=wQqghX&&H z-%`rjtA|quhCnellWT*mL8Qr{i>|S%@+4pNT@P& z9vqw91ed>0rM{~VGd-?9+?#fZChtEe8~v*T&Kz1rg|@nQCwe#3tg0dh^;TxM{kx#& zXeO5Qngt=&nt1JQC-OL%%>0Z8;}eO5YeBck)ce}vaDJAINk{`di{H>^_6+h*NnvAd zsN%kz{5qG9K>Z7+U@QAWV}f5X)gE2oZpv_RkmLtA9+`vBxALrj(ge1s-(WnmMM4Ur z9tep&+u*}PcXD%WWIEiR5`A|ue~*8Y$^8=W`D9b^V{R=Zy*UR*=VVapqu)#(bQS*g z))H@wIw4D+`%Pf;O+_O;Kb#Uf2R-=rRPr0iB#DEuvVp%ZGHl=`_kQkn8ARPYvzY3C zs<@eF$hV{~k>#oj*mdP|lEu7)Lo-X@aOw&Au<94PnST`|+}~G`->kyoCgYTyKOzwNi1|zsOW6cf^wqRoiJhX)0 zlZ`G=Hu)xOj#xmZgZ?o6YAgI&!Dr5bAQr1|4OZ{f5-p63Q77(zFlF@}N^{VZdz}r$ zrjvZ0?DClRu$}*#8I!H-E5ZI zU-(q_h#vJ+fV^vmg^z{p7+!zK97Mw*VoLXV7P%-83+D1Og(JuC8C`ME4?+huyxyu}vK?J3>lQjd*l6Y=V~JR4N{^jydpt&zmPoX~XXj2$T$i|0cEfNnJhJ z7s|}%iDx`=*bTmS8}-(Vo|#6oWjzPu-L+hg-6y)pZKy5UHF6H~z(w#Fp^CCAp_JSx zWd(f3jyHNnVV>Uw%|361zTWK`@=all6vsm5bFGBaJCZhfz2Xxm9#BQp5=1|3AA>HIkb}M|u3cUN$B&$#0^fUVz)f$g!gJ$x&IG-4I-vFQsU^RCt%u5$E@B$8aiEL0it(mG4|299@}+qb`|=w(RzP%{4!n zTcGdXmvGiKmU7$**yh8UIN??m^}77fOL^@xaJ4WLlifGt+voEz!9_|M_j4eoc?f!J z3!$eWD_PQMd)&e2&k1%_LaDS4sy+QE@pvPfH?K2x{(X{c#x7?^M~%SWVckTnzY2I_ zd<@LR|HtjJAUxb5l#H(Fp+fRd{G`#2)mM3D#Jo=uvNv;tN$e{G6^|u^i|o|^dkp_v zNNXnbW-p%)!Wy2BcR9fV7k@~H@}g^GFH@IyvYQH>ljn%j4^;@({I_hh)TO9rjjSMg z7#0TbjLLheEV0M|EjsX7u4o=O-~G;ek;l>bHGA0tp3(i_QvoHtJS6+IMhgo(o>N%7 z4jzclg6+yxv|~*ROLo)3^`~^{ad8qWPaTFWe2(fnf17O29tR9A<+(T8(_rzpR(Pm4 zoyu;nVNbB-utkUC1-_-|?YB>OewGR(@@O7GVH zV(Uywpjy-tlR{3&?!Pt#4P6s4jeK#@mwBi&MM8rYj%0gFhv9?&+OgU!UlF(Kxzp$M zhgpW8jxPrA?>|H;+c#Up#F>?3y6^=Uy?PGU#-5-B9y||WbqUWr)Dlw*y#@D_Abibr zXcJp673B-w=*MTsx$C&*w~GVn+wwdplL+>de@~-6eCGG56*_x=_Ubo$4cxVEmidk5 z{(1aNu{$!EzTp#y{-`Bhzxtl*1&#|H7PoULz264mtpF))_-r5q7kXm|_kVpVwMR7O z`g0Qr&jRvbVXxFNbbLE*XH2^To{@8DgyK(@1EzR!^f#Juc?`R}=oM64Fcf#ybj8a$ z_XVFFcc{0!ro4au`6$Wb?-$=G;9acApC3E=^k_9ppW%RWI7eaRt5`ISe}5N#ohzow zVf*Q7I6i7QwVCc$ykt+CTvc;Ed4IrClo?yv7xV1@#skGs~HU_I&)sF)b!w zJ*aDU#XfEV??YV94lQxOB|9Z_>#?uE{;K2BB<^Ffj>j(kec94R+6mh|;-Y2aO!Iwb=-BADNT)y%^TKeHeb=-2RUV(M5(Q9I)?K z2@Sh+5lU{VVOekpO)FZ&Hukf@xG5KD+^<_gaoty;CZGsot<~g1dduMI*Jg4rKggW* zM#JIlzT%c`y-_;d5x+n0P2+VJGxh%7Smz<7r59X;Pf^`bLpPLae(>4bQXPfAA=Ea? zl_~VfgBP!oDfqU!yaG$WYKE4$A!-)8-NOue`kRQU{T|oeH~DdE)V&PiXT(Rcw*ogl6Y`M1W9MV%oBVuKb46&a zR>#B>?O5&4?-Ol)pFAGfDx1Gw9mDuJRH0%K7|neLZx-_XyK@!0Hrxz*)PJY#N6yRo z8np?<>MbO%=lJ|C2o0w2+`pZc;Nz-{A75Kgr=7gVEye+}k8sZOW|GWxn>sGw-0!=M zTi|h970e8ZrdzG&+1^Sm^k>hh|BVM;Th7PR z{9Jj$G8g=J3`Mt*A%xxeu7qRM8jevD2UiJ3*`L5x)sKS08`(`;3tS$2l8&s8VSiqX z#F)2Mystq4J9UkP4}RH{Qq40-KF`O^yl-)$8rKpA4a4pvA+r#Xxt?)AO|BREH&+M8 ze}d(2Mp13eS$0y}3;((qi3=?)uzbNL80KC?9}|`3MnOT){YapA`$DBq-CY}t;&uMF z)0|P}gBtvO9a*Z%(mFfgbbb$8-!Gh zMw;Vv(6Qnyyy2Pl|L}RY)gZXC)I{8LW;$$&)52Y)9cjAt8n(RI2S?50^WO4pvew^@ zc%19FN)Duf`mAPXI5~k*4<@qz9GuW-S^+IM;NWGh(h1FvRghcwFf=V31b4ofh}V8z zf^Cl%V#{T|)3i%u$%9AyFE8}(HWnAVQ*x`-#nm{cOgmQM&kMn3-Njc&%QoBl4+0S zejLt`8eFgeyX&p+YOxC~EZNIU-e}?H9G=xyDwRbS4aY6%m9&*-$UHh#3(b>HQ}dn{ z_P6Q@Jio3a+PM!Bw6+ccmq#X|Mph=*P%p%%ocH!HE-2cye+15UkkY`6QxLSq5jS>` zP?mcHGb_}>;rv?l+F2{4`X~s^C)Pu-l`@+*)ROnReWu{=ne10}GtBC0F7}+<22Wp? z2nSZ?QioF-@>#=!QO0*((w_!G+xU?<{|}$NbsTWT1xI`^M?zMb1KIoz+W*U}=$7vS z?+!hL?4E&i{rnI1(ylAsO8!PJEn}GFhDI3V$@PRAyWxs;e*}|^cH9oW6^!+KXL>1V z3ap)|iof4jlC48DYk1^{3hQ_uO^{;I*aj`U!_Sg;>*Sz+`ZY{?5=n2uGT6atEu0d> z=RkW!Fv(y-@!WPj;j8WwVC)4a@u=|=o{JKUJ63Q#VfcEe(&&O7at|ujk7RxBJK`-q z&!2heE96VHF>D+E8_#%r!uw~<)izN^_By7lsD}X#�eP7~HZC0++e%8LGn%nBsQl z&UAFwa&}#L1iJGX>|kVcQHZk>Zqty`>)MOp!sm*-6(Mx<^CD(FxChSh&FB3fcZ4GU zW$H{z@J(RTd8x zj%UYp2SU|0WAROpJ*tbr=*u&^F2B=dRh>p+9LLx-(pm5+LJNy|Ufe(2{xrK8nn$mt zZM>IWEWHEH8oTH}r}NB%D&iTu7#)_qmRnRdP?@5ei(flUY6b z4v$g|#RD(%;LN!5f^~5_AHG^wf(uXcTsz~dg3@e$PVCvvhb!y#!Z(}vjGfsk>()sJ z-|gW%>di%9@$Cy#b&RF)W|hpq!v*8FDT?RwuE<_Bs^HV<7Gm;qKTIcQs0?f&w;tN^ z)V(3-q9>&fhb-ajS-!jcVM=#S;f($Ol>52jA#vx<{~d<;l1h|dOFCg#Fie_vc~ z!Fj4_t5}~iy)coV%ck$G5=`s)S&w7*zj?bO&$Za)c#?Wfk74o+)A(m~6EnLgqN_$4 zT;qIr-*+1FCsU%JvDHOf)O=btthW>uMugI}Ui!FZsxS8Z7VN}dOJe# z`vy1yBPm{Xn$3CF3s2w9r_&obA3kC%o@z7|-&tAVgw{P^U2=i42L5G6{xR^Le}1H1 zj&N#%4!%j#A=8PRGl?06+oha4>ZrzGvooslbH@#yzuRBh2boj8VBi`rOu7PXV)bLSQ z#&rU%JGaT)0-X^GBoufq4R$_J#Mx6Okkp*Qa?Hynn4 zYR|xho}Uk3@Jb23c*VJt zK?OyN6#Vcc#~IzsQ&6nyjB$K-@M3)g+cjAiJ^5K+uvwi@zCm5E^h^Vva5XkA(TI1t zl~drQEzF=q8F#0ch=aQPfw{`f!hO!GRAgw#ZSF|$Vs9xK8W{?|kNM&5d+j)XU)33X z`Fs2y&XV<7eu{&Jd>7GoLIN8dYKHw!nNjt;Xm)J>cAQ`6atPfU$QB5v}z6I--%3@y31m>hP9qx1Q;kiHu%)KT-FU}jJDtBTF;{C9Y?p^viukdg-ZzEfy zCO`C5g5DE2j}gRie!m}v6!V#Xc`8iotB>V=-qhPZjt%Db`D1>c4=rCPT)zGX;(jI4 zUN_zumGc5R%+I8}4;icj*UEaWF%q|`oq#+j6>gTMlkZ=3x&O7rIO~~|>gQe+)~wXP zg?5%a*SeOS+RSqfxej6fyH=UYY(2cQq8;ZCjsF38F006UX$9M9>5SFyeo)4heA!;5 zj<{!AXHlHQFh2)5#I9lz6;}+n*N*d#_O(E#XQOC2f8IN4Dq-oQBwEa6 zi%xO=IFFx+x;cJ>8Ie0-C&&5fPa5*blbc{%wu{&)`?Rd%wk2r8dA3;t^wIh6Xw@nf~flhcprt?3JC8K-{jvgc7o;Wp@+tm#dtggN*hTeHW=SFtIv-%7+O}kIVAM2RS;#hdf{lfFa z8IZ?)d4b#8XLu`zvABtUXQNl!WSMeT{KIj;NtOm-x7y(Bz|o{JBc4TdRKn=lYe>`X zo9ETb76{`i$-I|0?k+0=Qol!&E?#6On_}T^S5xt|djWKKx)?j3;r;AW64~5|V{u3| ze`b3=6ttNFmUih$qgrcN(=dGuP~jR&`_Hno4-~Ph^%^n`8U;6>K7nrox6nh z+yTtiU4qSZ5}G6_C~8X?i&}gKI`82r*uBUV$GGzT&^-}sF!%f%+s5~C8g+uQsVUD+ zFQF45Y3x{~CcbGh63=Y>1s|O{f$NN1n!86sKErPbzTh}e;ASX%Hy?+4Wm0mtb-=V3 z{+UC0E^hCE?5C9hZk@-^-NRj>@yT<@TRw-J9e=RFA6(Ju!B3jJcoJLYtckUrM&g_l zD{P2x0{#1UC~>Z)+)6nNhdr0lE{&-Wl%$E`0!xax62%6dbj5uB98F7CEK-o^;ye8RHJa?~<$&;2~ z;%q5hJh&b%9kE3#lR@;wJ&FzA?}|Z@?Kpqa(SUc#wBx*8r6QL0TtimFR2A0A4l*N(s&F8Vl^YnWqJ zxw1vw6;PS?E)CtO0VVee!SL>ClHXF6JMH`oDt-!LziWQXIyMR1UUU`9Pq<*!q$Mcy zky3MyPE7U9SnS7ns;u3!;C>4K&S4UYD|RaUq1guScqh2-ha;e?QwkEp4B8NOl0`V* zgc`SUn%F}Rbek6mH9|XQ9+9vFhtA-;mGmsxrcUGVA%Ay|O-+T5o+cRYGJ@KSc#j_U zWZmXCZ}DrPP}bouC=BKuD~GFL#H-iPQF$L}-%n?4E3d<(kxyxuUlhzR|0$e)*3QE$ z=^cj3>Y-G-0HvPI=5{*B&9zd-hLwe10Vb z>sPRWGn~=B1*!*{9xN=4*X*S&Q z+QI*S12l}p*#pus`dl=m&o>k=dnm~FmoLHb{F=BQ&4v7?F__A)v(wL2Oi#lNOZaRs zr=m*u(A)|?ua2U{$&IWuKml_z6L^2FCyV!(fvVTdMUxFbVf>`sF!*{FIdkt`Y57+8 z@X1Bg`*K>gB`pkJ%@3vE`TAThIR-PMB>edr%d}G{I+c9#dcc=WsFa2=D1RLyM|^vG3cHq1maM_~+FwVZEOL{vEDM z|1x8zteSuh@%()4tHur<>W4N1xwkGk2*wQj4NE2srR@6O@qo+zO)gMFE( z?T=TxN-1cJEyxEbU`~(jwC=(-wy(_y(>VVBXA&yAU8{(yG4XWVI1%>QeS@*z4$$nd zx9r^dzu>Y*QLH=WA-oMpg~3yd#B+N4G3#nL{xFo1Vtzr9Zy)}y=Q^|?lhd&DS6|#e znZLWgMzEGn#@Oj7-`RQ83HduTg%GP0(0QWBuDDuZ>4j2iSd`Avzv!cXrjcmc@fYkJ zZUe<*+h_RS#o;)fYZX=wGZeC~`D4{*zUK;ZK##9|am^@x{rv~BfOXub!}pJCXSqV_ z?;7abH;|M&HnC2YR%o`nl-_3!WDgSb@I!AyapjV(D7z;@Yv5hFeNR&^-x-1Z-b(5E z;Hgk+%Y9sY2Yn$=u_(yh7+1WJ(8>wL(8*322c2C_bE5XK=`P*SM7x}9EmUB(_B)|w zXf3X9R+T?FngWNT^~A7(v&_yj0()@%c~Iqg*h%*2QsO}xmm^ufUj6XlKCY3TK1v8b zYK+&@rPL=h9^XAxLjSp|X~yW~?Dh49cr(XB%yT&oV7(p!PHiN|5Ow*!kYZTzeS}z8 zwvB0DvgGHGc5Js{qQuuRu+Ew(0bGe`*Ys=AGRBx;GP<$LlgXQQfx&ibu^>YW^@sGw-XmP8XJr_>Rmf@2!Y#ERH&rse(>`4C=ea((BC%^4yJoz{XfX z>>lCA%DSY&6iXv9T|hMq3#j| zOjnGftfdDb@^d*9&Du~dLer&7=~uOyEsedxJvjj*OKAbil4-2= z$Dl*pBcGWH22G|IxOX@$>K@Omy^Qe>fA{?`2^Nm#x53HERdn-3B^((35lScSA!Fao z>{aSRm>T$m=8Ref;teer!1d?Ouya?vwE0_k!Hj3omB$N%x$B6 z9dzWyIm_@U=k(+gyTB%i22OfzLX2nWw5}b1(Ww$zZksIIA8d--_+G~J_7)gA>>GT2 z5KLt!a#{9buJI@+rHMhez5G*Og6o@SWc6SYme1b-2d^85EkSL}R5uDkIM=kYHW#LT znTVT4bL@4DWwZYd!14TCAEf$1uz9PD<7SWgpLS8BP8oL<#Zji<&c52&bk*lL zq*Q0aj*o|F#sD?>oe_^=|J@OyyycDzUoOM#d>2;Gs)wbzlW@#nt~s$8%(OeZob%#T+U-xZB)?jzc>;ee3Jzp>xO5>KPC!#4r6a$gvqUEcz*A1c6Q-W z2;1LPbPm}mlt_*6{V-h`*uRObF$v%vD~@R~Y78wra4Nq)Cte5w+5A87<0!A0>X^>L zj8srvC5}|S&XTPt>V@Oyy`%*aJ@hc1 zK_b)i3cz5F?f!1tWlb;KF{+;PHeEM^W33tvTsDrTu1#QVP0FZoFO~{p-gzob?~ch! zE2wof-*IVQh8Nw>Q@42sSxHGIG&h-u4>}dV)rw{K`4IQoZ%Sl-D*~{E&)C0m9tvvb zmGH=*?xbl`%?9Xj50_Fq&W{aO#)1c{Ncr**u&aLqSh0l?&irJHGE{Kx(l&bB?SL%O z@c^XE=Y3caBeC(+GQ7*rk8UBp%xq@>9_75p$`!U?I7JbSSK5>5m<;xFD4$FDetDHz zsH|(H5j8S7hPg5BsK%dDU$;nBx84j(ukm@6Yh5Bf>j>+U+O>=2A$Hg)`zhtI%`DNc2m0|& z(w{ubR((-__`-cg|M;29%c5{D|IAzQhQhF+ld$9-N; z#z`qH#1&EkK0)FY$QF@oE%QfZK ztfDcZik~$?r$X00y7)HAl15`RyOHINi}^dZ@_}N}u?RDq!Ov)82Nr{>>Q`8NY(DA6 zZ(!NO?Xl@0{_jZu-z;G{hY!^`MHCn=0k-U5RTY@~p>>hjf(%3ws! z2vH|%8;hIV6%}ro(yAR%EZjW+XY%t!)z+9IT^A3m;QP3*hx6g_4^v#gwWI&AJz^Kv zOZQkw|6N)y)Xvg})jI7vQ=x`uMy+llhi(U$!TcOptYRfP%+*gp-;9QC{t`np00l1xG`%jhGusqxhQ#hBn z(x7MIpBaky@p=s9y6p$ob27>K~%(Kq`i%lvM1#^K4FdwjA54wrw2IX~yor~%o`ahfAWZYm}3 z(YL*>t@^~ZxX)-s>?CY-+5=tosEboDtOOg1x1(C$=tg2z?<}hmd3sS6|-V!7=4D! z9Dgw#{Q~%}cQ^6k_g%t=J%;!_Mw_-A_|B}7rebg!-(zl2W40$f`Flu8`YQ9Gp`sPc zc=V;ilr+|?-T?!D#?bDJX|n0|+>@s9gc>6?@ZjYt*qwcw_B?sddaXDIqi30kXZFv6 zD>{5eeWy)5%lVvKFctUQlFTG8TCTc4V7~*%$cEbkK5a;rzye9f@oi_u%ws z_ORwlFOBrW@5nNOKk4ty+P{H8PXnLQEV8VM{FV&@zMbcLm_e~qE zA1a7z)@I7eBqw3EA@`b{^5NX}G`!h`pT*K`;ou}C+;WQNyxrZxdS0-=z@T>iJm`ip zR&I+T%cm>h6}^Rb<*9Vx_8qq9mNo|GDTpQW-G%?cPQq4GBhmHgKK#i&Uv~Ulvw7TU zSao_3PIKViRlP{&`@sUoo#DA6>o_J4=Q)9&QXuoR67yQ+gip?M%zV0;)z-OTeUgpX zc{kTs*^hv?w{j`vFV9-BoQ@}bLaDjd0hhlYgz1a;9`?jQR?jokayX_P-{T5~$9TSv zPCE`y3^zs7mLk&gw`224yWype24bjtR}6wBV55AG>_sj4!bk%=wY4in-d@2@xO4B- z~gzgTaBcInZ{m`CR|EiQWuTX}4ehSdCwic^h)Z|No z_rrxKHF5cZEM~XFfHG!kiK8yr;JBwfaNz9$v|&*=%j5l1IU9K9PsS+Wr^FH;@|o)J z+ISqZMFm65Vn~0`5>|h@C;Iej$Kg+{yFfjABQ-Bom&<~?@q9m1Dp?i9GP0)P{&U>x zdLgFBZm%bH9xJ7yqWu3O>AC~C?7q0YzIHZcE2}|6#dFVjL<7;#(k?`1(V)oI9zuH$ z?X)EMUM)>crBbwaQ9?p~=l%Kb{mZMzz2~0uIiJDuCYpg2`82B3NAMY|jWhwzaLao|o_mZ^V@)ohMO&$G>ZwYxT~ zdn7L^=Z@ufUmj=fg8;lUmToD2FJ_6ZIcD)K5`q& zP<_hmwq@etoE`j+#dr3l_$lt%ro+ND_6rSSr{`hQ=gE+y6OF^Vu4ReZ-C%vuP_($T zjL&H@gHzYZ6JS8NfaKvY-9Dc9OAlG^2|w8E)QxD=bp`j=`NT?$E73=9A=`4>iG^2f zz{MK0x4o?cCFNboTmBng=jaZbE)nj%;h$7|ZU&mP*9e{%!G`uA%-?PTM)xe{dqNFh zU{nciYh5Mnp4-5F?ySMu*h_R{{*pYM8-E4m(nz_rf+L~MVa^g#UOhcaZRm5S!EjO&4UMH z>6KO7SE>kIR2N{`gbC70gFc|K`Z119QiI6+M{Hxrc^vcaAs=aSnuU^vW&c87hLk&e zxxXsr(K{>oITbb^rVNxx`O>4O80^)K!UeO}vt3=)X*cSRSzS|kw;hV`sv;g$kG^yt zPiaE=&Ck%k+fY!veT|t-KZ+;wxA3c;r&-Z?iP)pt5%y?B4IIn4hbKEea_wo;;4NVk zjp`4C{gutk`K>WV&Ah|oD$K#U7kP0!`z~GCTMf3YX5+nCBCR^P^Z!_>;2Ki2`drKXsb zynxq6F!)_e`&I?H(v2f6;N}mSB~M;ro6{PZ^P?FUYOtKoNpXet1yAu+vI6V9S&7Zx z@&#H&%6Tk5&NjKJh(|P2WIL^nX zV>5-Fi_Dn8$&0YQNvUjGlosgA{KcY0dw7KAX=c4vBATD8VekTLDgT`rQzeXa~QGTiAb2ThYlNAdBxAV1!r@>TuH*IhR3p2EUPupk@B081C ztI0!2Ud-D9Wu%KrrcCG(i1q-7)@b7@W ze2)Hf@P0#la;neSXUt()pf`4TpUlU(T0l@a=~c&v3qgD3;N<8Sv_Eo}B?f$B{g$l3 zz%}XI>2d=zjjqH+nG2b$lRIlZ)X7CTe#8*VUDQP?IBdfyL&|}&z*9r&`HqbU2~?jI z&i<2TjJ1M{eUw|bIfBL8e`Biofws+UF6@ZXh4m$Smo%IaUx!eW_<#4of-n zgFV+tY2c0GE?BgIV?;;uczNv{Lp=*QzsDUo&uwl(}^h7o4pQWujZ z`#|~l8E`z3X5o*?{Okk~f-H%{bEHPN`lOBBIqrrhwO(-lRZ0+EHV+ejI`ikbsnCD5 zvAE)2BRh5a3~Tt9k7~nOc+WH`n?*gwFkzKcY4HqLIwKO@&k$a{Mg(8yC@gn&WSZnf zQ0nE5>svW`4eO@C?eN3?#h0U_A>V4WPq2KQwy3jDK3L1R1?zF?-uH_apX$!FkAY)Fxl{ zlNYMl_ciBm?A5*8H1aY#OZggY#fMoz%4?Vtdym%XpLjy;Ob8{8Yh(WhLcB#AgX^7j z`^+@bfKU(VKIn(kut^cJ?P92B9?0(h_`uE|%*4Z$uX(`?T{!LDfbF@Pr2gA3vsGyl zQNO|+v2WVru+j>YM%+8+(|q6#fAlXD1t|}6{c!$;3bQ#p?E#j)x*)!DU%do z3h{n5#>O%KMKx^xdGb$lDdwTq2n*Wz0(Urc6Xg3}Aq^C1aLjXI^i(x`vHl-6O&=!R z`+O#hp*iAXN+DajRfLJNX?Jj70nb@w4QA9o%)0qixY|WqSZ0&L`uA^;{?xUky>kg_ zcrW7(TLl<4rJJ~FmOM1~i)QDS96^^`s%4)obnyK$Me*8)1Hy=}vtVieXzXp(0}iB% z5JLQx|1x)`YuSLy+|GKg@u-#Mou7fT-u>ohR#-y+Sr^GO&4$mZcLA#-dg39{j9xcc z&A$5ILZmGFVlzXOlaq+X8Zz)%)Pp@+O|jp*1$>%Rg!_aU{#WO}9kGVP-Iy~Nan zHkN2K6Q_<^&J~|_1MX3br>frwPh&OMA(c-4$qvGAzsISF%|{Bj-w;C#x08r@m#twW z>jjg348S8DaU8CTu#e{A-=F-1`2IHVkFZwxt0^$gTnUcEke13~4*zv49j3o95sjmc zupPCB+1}>Wc>RG&S%%VO=3pcdO<#?qY*riSG1CyG?F)Fs@|j?8h5A6J#8QQ|o-lTG z6i#z4X1$HAAySd%ni-K?&RG#OY0s7-e3eMb}qn7RmgzC&O`Tr>`v>I22Stzj3DutHbMQI(V@; zgXj2o0TvM#Wowqy{=O~zUP`~e_D1&TUmeRCKL(TTZQ)a;R&X)37=uhtc<2vQ2FN2` z$E85Z)h%YR_gj%)c*X->nV?ioL!40S12OMs!}0{mj@Mtt_aE_sb&cfzMs;4fn6xcv z{qSb^Q~s55_wwmmIj?ZwlMFNA&=w;xZ~bq!V)aF~BPbsa%=^Qo$10eQ9@Y6jE2T~P z!7wa|FtJdpex zdXA06V)rNR&!ZV=TRz2rJTEYDf6FwcpTVxrck}FC581UPl+*O)FuN4;4$cXkb-p7Y z1bVAQVZ-PL!hsWVP_)Mk4Fd1;$uI3-brxwY6MslI$*F(>%^+7l4Pd!?Us%0WI=(*n zlApb90>g?M@q4c=Qsb(JtmUgj)S=neMzIUN4p9{4Qa|v=Ng=R~W~*BgTXxfpwDw2M zv4C_3b-stP=8mJe z-#s84PYQ*0jK-jmJz!;<7wq+=S*c|Z-xAdwe8&+N?r9(PQTZRMR-THFWPkE^Z){*r z_X}9$WW_HMrf2j zCf!MavbD+}lGfGX-E1DbP6pT5t{0zOw4kiW(=6Oz4OahADKjZ}z}{I&#Cd;4@)j#Q z2;~Mit@i?+W)uSV?nRQauPl(2xxjt|y&kiKkls)9@!rxUW!#jH4U-fMf%1@F%``$RbN1CkD#fEUFwjS#y zi#(yZmZ|R{KaJToF!7EAkDhAB{8?N0XthwdaFcMb#u;qx2jWO?B%k?M!dND&z}YF3 zx41Q*S<;!DNoO*7Z7zRosQ}lmK0q&t1}oh2NHCbMj^3x0%W|sKXjj&XJuF=KojIZ8 z4-<_RnQNKRdn*X_@We>ZCEUTJJDAoG2csxl7~e+)F6u_%*B^IS?Cy4E zyDIFeq1{vaQs(S7g$3N(fZF=1Wg)Y5QR%UQn4C9>p{fSRUe&=a%GEr7lsDv1omZ4} zNN?5KL0{TQmEMeC>u!Ey`HdrS#@a$2)U5|>t|&#Cru1H|So0oW3z6)@bBP?C+ zEiRqZ#_auVFqmD*xf9Lmx899?HSVUM2Nv4~B#EyG?Nz!jms~!)doDd==!#W*7WnfB*Kz zf24ih`9K-MsCQMFTO(Dv3ea`;Gdwf<9V>tThGm+b!5J_Aa=D5x?C3*Nacp(2Fl4VT zZ1I%G)jQwtE*W7kpWZudeHDH`m@;Lk$1^w)$}$Ga!JmSDn0O|eZ@;Ss3DOAES`r|Q zclCsAYae5Lfg0>tdygGDza7tRJHyQu|6(w@^!E*(gVYQ#Qo7@xuO&{Z;4X9%|91%wsXL)P`vaL#3}xNQ2`a zg&uzj*_18A;VohNzNQQLykrLmp_;j1;5Xr^)JFKYbQQZEp}?2_>H#aBoX1;xmvEKC z>ae=}F($?rvVemt*ag2%-H=MI4xSz*C;l9~SIDrM3u7in`pmv;!is(tI%Y zf93!@APQgC_hCNM8`$TS{%9WZnxFOW0UAXBb=l|uD{K@@m}YnOCu zsnpNc+rxSZX?zMJ`9&iMd?c*9l%)xBUQSGIac4i@de8zk_4tiB6+5`?rk_lcJS1}l z%fPgM?&PClkJD7cctT7#=pQ7%uP7H`f3OdH+7yldZuo$go&$XFAU@1e7k<1u;eq2i z`}rv{wd`}td~A(s;ve6e!#>#tOtc=t%b(S=_#1lS`&=8CHBo{m5?WC1Pd-1G6b@-; zqwq?XnM`()132xZz1v2olJz+f2+@o}=Oy_}Kjt0F`nDK%N9ORn91TdeuR`^6+U!}k zw}P#oI%aQFF1xTo3%e)Dh%%4+@qO*#aD!$*c62TKDD44Lu6v_h+A_YN&;jg?DQDSW zuArGNfu9ZJCrNewM_(m~s@#ArW!e0zl1*^?&0Z+_VZG!e*VteS z&({~?>^qbhp=t>I#?_*_x*nvZmoca9ofv!Ga(yh=svyei6*6;WEua|~r5)5~F7$;P z?Zh{3%90vAcLFt<-FAj=WLxGnkbcA$>yPE~f+h!;*`)~UejfE0SfUU0KVRS~=ZR47 zdz=LZSKz~gh5X!$Zp33%7w6RbP-f=b|7+F9kaxuCQeSv(O8tg)tuV>1gZ&!W3w4G* z;FG>+KrQWMZsj`gymTKJwe=b1rXFV*aTRQvS7$$ecS|+v)hr`gJV}v84T*p$^lxvU zJB0iH_Jxhzqp)?kBl{fN&gz?-QS19AKH6TBxCD{-Nv>9!arGb5?#RMEkJhkVf9qM6 zRw2goCSK4(5zfCc6<;;w3hTaVgR+baruBWv13pB+EyAxHx~cFS%HknS2=0-FvNOb` zIXbB?zPg*m!|gP|??eQSTM;0gy`X~)S(Sz7^iQ%8a*tWvz^%CZZXuuRBnzIN`eMYj zNsJuhLFTaf|8+yUy&~Zfy=x2F^QEtj`hk2e+I_!W&$h18gHz@{=yoTGr|i%KSQtr} zfKS{HHT+{Ay|d73MKhaM^_u<2*@yC1a=7Xi8R)h}Pt@poj{Usz8LF4vMX!?|dB53_ zAkiUh!kGtx!Z`(aa>5u7oV&x*k2ymF)yx|uKcoszG~qba%!ux8%*cp5WO7pRHLK>2 z^c+E$(1LlZwn?E>1xCqs6MNSM!nAfBto-j!=70~rDwlI!jH}5k2>xYYyIL2i$`|Wc@OoTu$azg`tomrKj92>_8do# zTTwh#y$ehm^@KD6h3rq#MrN9S1mk|Hmi<=gg8ge`Md!*rg4*UNxa1v;2e$SAcQrpa zGA|N;P94m>14x%d9E@f?7ghp|Y?`w#Ry=>njpKTN)s<5y_rjF>TL*yKG0J3IY7M^m zJDFqHdAw2lm+$Q8f_mrWMAz(}?5egI%uY4KJHHq4&tv_-mUh|y)piTZo}gk9g_eGo z*&SO6WS$5`hwrP1W7feoF3BSAvID|}GZsv5VCO#cd;s~H{ZN0!9%6B8q0DfyXnHCj>{{KpR# zk_K?ox?(mV${E(%Mv~`tB)2J}pMQclB_sHssSpKU3Zu||hl_B(bR-zg?X2xTcQ}LM9OA7N6Wg$W zw0ksf{@v0d)D*sFW6I{!%+Y%76{cQ}P$+?>|x<*FI~;SLXTr zf>jil-v94Cn#nTnI)lL>@{lQVDv6TU0$SRo#SNNpL4mjyMip$`?f}m!mcwTGWQKFBUMh%{p)@MH^Mq zGWgLFe<Z*d5@W%Y(Dzv|KVGPePuWH(XMSJWgM)U zOZjnrX!yLHC7z9j-)qTZKXVATKNJ9y!YJSTxg%Tp`yacv*%3eg%;TQ1Iso(*oNuU+ zDpt!tWmX1u_gTdzC4693JNMwD!Z-Zg@9!-0oSYc2GEuli-(=~7cG65%^A!hUV853UBN1ESd zs7*LJ>p0iwcb&!ed5VJ;c4Gtl3D3PCLEGeXu2&cXk|*?@nr@QT4HyO4K;D~b8(7E? zQ_yn_z}<&ad5wWC+{uqb%X?4UW7f#P^w@M<5%-HSq&~2|hP&~>(RF-w2ytkLXFK8g zIksfrH*ok+f$Kaza)ss?=uYox{kI3gaN;7A5QbnAexDok>;ulZgcY~_kglJo3q$FA z>W8?oiY@P$Bz-PkynBr=nBNDs#{9t`-SEvhIs+dZ#wBi zr!3?!T@eg`=i0q$9QvjA^TyqgFW2Q z$#vN{O9$KLwc{ztP9aZg9t4v<@gn6m-`*7f;WXE4?ikF!k#=L%eA1A5xiG^Q4b0Hb z8&~93@ey|@2jP4MR(gMyZjCpEm6TgO`Y8F5RUTqT{mpfpif-i|7!lRo4p}hGZN>@MR6O_ z69p0$-Tz*iaQIe#^2X}y=hq)I1dpIfT;aNco4Be$MXSE3^Hm032Mhu8u8vsa5W!Dx zj)hMpQOGM?1jR|Cp>{}Pj(#lSJ?aLE4%i49=_kw z$SXB_LgL8=ymEI4U#YJK#nseDJ+Xz3o$C0@rV;n;%;j#RZ8_0Gd*0%itkkm)^d}5t z>vN})pIP)X{mD1xZaxcID+^i)8Khy{&cB)(!q~NsC{s_9sXNKClf62*h>sODaPgBy zd_24-U#vC{#uIK6{eCTT`eF}>Nr;=)C-4oKec+LV^fKe-3QHI2LVaJ-F-@spGig^? z{W%@q-CW2!>;l21zrMKDX5GL-v=^wk;ZUPBvUPHX4k@p<2&7B{36XrPG;#i*LA4$XmnT5n)?Ec zoJgbAP0HNI-oKj|-+n$S z*9yCz(-0L`_`$UaF>sTx^xkpHI5>_10~hl7jH(qAOt!(mLAFKO-wS2z&^D=SG) zaeWBiK{dI9YI5%nj?B4VJG*ej9;Z*tr&%4x9T% z5o*kO>(C@teSGia!@(v5FfX;3#2s~h=(Uk zVMc|PP-rZ{c`E5#dq^BisioRGWRtYx>{uYNE}Hh(z(NmngB2$OFkCB*pIWC6S%f1M zs#dvs=g7j4Gb!k@@;l{)erKQF?Zoi?Yk5yQT~JLYZNE4I>5NJXEqOx(U;nfdzo&2s7RF3e3@@}yC1^L^rG!`o8UfYy+ z)_kAO+Sq$+3u?M~Nyj$DLGvp5=G#v(`?fJ)5=;H$u7&*Q_r7rCAK^mJz6oRO9fY?7 zvzRcpL%O7^JWxl08rxm@sB7j>?OKIL?w(>fOZTxn^5N7Nr(Cv7rwjV3wPX9Q9m3?y zco<|HjSsH(08h=aFg+s@{fY+jCD0GH5MF0J#f23$G%;@&f_oP|=9fz4KvJ8E&qCfw zo0%Ehh<}J$|K6}C9jBSU?Rgxr@Gm!is*g)P$%u~+{a|uO&A~Fs6wAsN@~3;oLWLvw zDOJgpMp9nX^FdKqQgE3~ZqtJ+w<9pE_d0%Xrz{*QOTp6vcM4s%^kj9;U*Y8=XPw!~Nbug@R#RTe_jQ?V~qY*V3GM7!0o5D@WkxP2Hk&cDD-;ah!xS1+y&y{LnY}ARb7QI)q${x zYW@{hUpPOjFSrh;y~#@#($46^EfqRrp?`(ahVLw}cN89YThINR&A}-230C!U=5F>n zAdsK=`Dr$AR7V{rbkyTvj~s5&GaiOs>8$x*v-^TI?F!%Dbt|HdfQvdOt!Q1^B#YFY)b+6E2q{-uJ#_Pe~xgmK_WTvoRm9ny=h`a=YL z=V1wvY~`_bwyVG!*Hs_p=_};HW_SwL>3K@K7TH6fQ7s-+q8aOYC0kJa0Iwx|<~2VJ z(D%5E=sf8t)4kpWjxNx|_Ube)Z5s!DspdzI&X&${9{}zz2zR==kzMWnmw6rc#OXzA zdDCur&~YI>U}&7j@JZy!y?67s0hPe5LAKc1X0DF>X zUO2dnUyL3P&7`+o^PyHaSt1MHSr2?I+~k7P5b7;yrk>}(mzpcB0Xmp4c6OzaL?ve_TkwA(Ag7-tZoRua%DUOtsrl@{!Z-e zTv_7ncSn9Ihi~m_1ixu!{}0bOQ!WR6JCadrb0!m-RH6T*GkAJKEAQ<^{OuXC;uZbH zLjD^a&@XR>i_#~2-L{2Lb)3AdR;uu!;sh8>HGj>BIqa3QG7L}ZiSrJo@#MosFqTE) z{OO~l>u<@yzHLc3J%2w-{P2t=&0LK`O!x5Y&$aB*WCQ%9OSDx?A$!f*<_Y_1ksaK&J@jkvV(>t^9%~H;n5`OFc`Z4wn%ajh0`^`&w?L?VZrEweE%FEI5XVo_n^!Haso;!6wpGt$@ep-klM#@_|4h`z$D-krGp2Q>xgnz;-kn|txu zskUHp;|UH(KgIO#6tGF7_Tr0a@@2-_2DrNBAGV9Tgu9!@Ljuh^w?7Z&J<8ocF^#-F zR=cnp^C&yx5u&8wA@5co4}WZzVIHrQYS&poQp_VPF@MKyKQCon3X5>i#}>Zylp$_> zC?oFUKiCl~OW1kT1YZ^|;KM(ThepD^x7?L0jmUBXHR^djUB1kYzcGY+DiP>@cP;lK zZk}yG65co6CTMQy%i5-N?qvInP=w`8GUAWCo&3r=EA-b;6Sbqsqjz>+nA5`)lnpdWI~wzoQo($x5$wAWfxAZq^8u^npr0*e4=HG{o^sb%Qb95n zR5tM*D^0_1 zjY~3S-Ol4D3n{-$u?pqxXtRm$w3&DBPE5WZaV7FTe@9Dsdp;+z2dEq#h_5SRcucAr zY^68)@wK@^Zjdo#jwbJg!V32CC4JA!NqGENBoF>#3%dSQ_;*$!EBTer6cuuC)g0Bb znJe_ssJ0c;!UEWU&FV0@ND(i5yUG9joCx=ike`5-3^$lP2xikAOuP`uR`u;*T^4!b zihcz=B1-}6W0#`0FO#a0Uby7qLp(}8a8vi!vS9fK_;Kqe{#`J@^7n1HeEA{vZjV0v z?5BzMrD@zNaT1)>CVVwATk2Rb2)fAA{NB8g4Pb4oydALj!`0j~Q30A{m*R!F(H>WA z9bx0@r`X>r5G*B^*uVPI`1k5o{@kSp7A@2eKVSBPergG@i##aC6X$O<74|@hDlJDPeCg^-)O8U7NOFkQWXup}LE-S83 zPL-}(6$7WpV_~fEU)Ji70IR|~Yj}lS5L_UvCRlW0x|Gc~-r5dJqc-r&O{TyIA3nrt zr4E_$a6UN!y|1RR&*5*G!IZUlKyrikYte+!ISS%*pJX9}@}sL4H^Q)%N?!Rr0qh75 z|F4EC{va(+GW|^t&S6qVRk(7`8BY#M<2?qE=Ob~DjLwacHrU1vTuxT~54^(VcQCgTQcl6i!~Sfyqs` z0l#4Zh^?vo>=ZM2dz!LVhg7+rB>z2!CyP+jdB?gBX=Iw2n^9F^1%F%ck*(fbi7GQw znf|OB@KmM%!^Kiw^HBr%8)FoARPgZigQ1Yl&&V}((&zikK#h9oz*}z2n)33pW>3W& zl@gw8;|N>e34TABDGkwUWT9VPp-iw51hnbmnFURFW55%B!dMGUB1k*4?;<;VKo#=6 z^s)U#CSSQ{Fa%$s^I0DweU)zp0qV31aEW8R?CRM0w3+DWu!na{q%)KD1U0&u2xH8w zq2i>zIP}6!nA@U0>H-6!PR1VQmW@(M6>=T9cO!+}F| zHg38w@!201Wb1(=TPnzxQUUrrPryK8n4Dop5A87y_509 zf+j8{jq0ko^5h}l$rok0f^E71ULLWK7xmUgd*Wo4sOm@~8iSx$7HLmxFR*MF41K*w zr*=Au?-$LWY(-~%{i& zZsB~~zsa!h0C}hH@P%I^2g9QAo%Q+AQZqRBj{48#e}#g_pP6pr6dc><6_4t#2Om}z zV@ZcTf85;?lHPX_2bEjH@mviYJ?A^Fo3NgL9NYz029j_2D$-J{84P&^#3yueF1dHa z40ez{BDXo8IgL^PmxBp}L2cx|yEXyISH-pGma*a0Moc=ilP9C!T^skG`-!jKI&#Ay zU2wz{iTJ^;2PpsU1I;afbxRU>e(PWuMDOgT#<@aw())NVBOkM-3Kn{t^mOwU8A(72f}7|eTihH7u%Su382G-{rs03i|_)Bs+FYocRI8hKU(K^yhnDhsov*WM3?9O`ZCB)Lqw=r6OU zXj&Q4!P#ibgXYjhX!$qXL-TuYFri$AjS7=s#$wLm&Y!@E7Mu9In|Lw(`2EStgFV^7v-(Psn zE_K+hDJve7q)Ojr$3Wqs;kY%qh3%&L`H<@8yopYfZ!QO4N^S6g+j@R>0OdE+JhixY zt-S%nRz8m{LX+j_ulw#f>7|cANwc9ZBbwt!g;;B95W{qXV) z?7gQA1kUuul{=PktrO;ux3053CyrBqyWQe2{8=r_=`I5)O5N>Se~WXCu{N`W1aV>~({0dn3Tyl+If1X+&-i&h-DS zb7LzXe`8-`CgIiFMSSHc6ZoK6g3jJ^rD>Pi*x1c4FegPHF7MIB)a$=+tNSBvTCa~U z$ZveU-W3+j)j(pbhwL-$Wx6w%NV9|3Csx|3W&z`9Hs3Nkj{T*{O0IGe_P)4{r;Rj( z;f?3eHc4L4_|eGv?0bSQ4T531w;nA@@m9J)|lyz+fCc^JU#pjD|}hV4!Uop zIlYBj)J%ms;@KXEbLaMN7|i74tJdPe_89(U+f)YO_0zZb!$d{+I(Pxb+E+<+C^Kc_ zoL8tk{1;PeF2kllcbeJD?)eLzo&c_H(HMI<6%vBX!9$Ps z)HT7}jdWqUo8mC8N}0`6e8m3RCu34(6K_1O3z>>C;^uP#zj4zQHa^zF<{NRmp6+_+ zdj)amEDfpr#%Z9ppK#_`7ufV>0mQAuaq1V%Wk|nMpC5^~uhWEMV|>|!_)h#}$Q)OA zQ%4?F(^m8Fb)@6Is4p&iNSS8A!=UV)Ex!5~%-1yNq02ut@k8T%;oQ#YaG&xo#Mi!X z`MdxV{D^xaxN=J+3oxg@sb9@s;rxNGY}>?%II!yrt~$>cCQuFkq;9}_SUA9dL_N`G zfeo||)xf`>KjZwMwY+AC9`+7W6EBy_!&4;&DKr69@_Ahe){O_-dV#XyU0)Ghlt|_ zFXcX|3{2=P9@Z~HSToB4x^5?2sOMdFJx>9`a^rAX@NAxvy$p)xnu_K5XPHAm0n>KP zLC^iFWtwe9*ke{J%Ebh*4|N()JV73xo+;-R-Dbc^;wt+ukm2f65!9(SZkZIt*6>!= z^Sv9+8nKh#?4|_&Hq6It1vlwra0RW9O4RJ40aI?3GyjzZ=y9loYrWUNBMP7KMbK z#6x$bJ6NjL;<3X)us;7OOK>g1s>8%_Qg*`A_8OvFsUMg%e1IQwAEV_9;$}Ra0p^i( z$CtbkvIfh7;mvN?ll%v^6CgfN6-4*WwTX)Oz5an^W|Df16(1!SYqz*ju(y%Ahh zAk17VRXUsehpGM-^8?;b zpdD_Y1Rn&*h?^egaI1!yV0VoC)?C9_wIG3qV;s=8d>P+fZUsjtke}hhQPQEYig3>{ z2D^uEW8pHdn4)tUDzDAsH!gHAlOd1sZn7D(+;0ybuc_f3&vagVkb3VK9oSXZhJPc? zNUA_SC)+nL`(fQ-z)oM9TbJ>oCM&p0HLYh%m3v=BMHoSz@EdnmvnzMxAf?Y{e0YC3 z&wJIu_RJy=w;!p@+3qHIuiS@W(qbNSTOY6fQWZ@n#<6N&4dRyQ;f30AZrfXgbJ?{2 zmDWk$jk5*`&58e122%g_gT1aBhq^z`aEm`?P+3)k8~sD2&Xw|TguLHRY3RdMHErBd z@D-z31((m($D?Od#hFfJY_zO84DslKE*=?N2oquTUDCpjij@v@wFcE@!VsvoFM9c% zjnf>5Dzi3oZNf|@Y&e5^9?A-*K6kJ|bWUWdW`WlqBfReUmw5i((nrdsXm?Fh+_P~U zglNx%(^BHMmn>Ex0QB5C7+*gSO|sV@zGH@Wgs1*b*1$-D-D!-Odw&&yoLtjw^%IKP=w4 zAD+s%#!sm#fu#_Oaqk~WCrCWVTmL1-Th_6cxewUc8^`hB@9(^5ycQlw`+_-b&sd{< zci8jO80Gse;CqJ6gr_Z}gR_$_{c}--KYgjMbG*VL%DTYfnDMwFF^%wKMd*H&a!Y6A z2z>4^_L4G*{_D?ok>6C}jR&NKOyRc{Yhu39XLJcwgA0}-L|%9KKOd%L#!OgBIBnG> zf59i$6E=E8sqgOASkGJMhX=Wog%nnc$cah1Jm)*r%?f^CBGbzdC=c-U?*$ zXlF;-rNFEJ_WfWdexlae7tEUpuGPl? z&V4+AvLiM5g#IpYZ-<`v`=AZjr)c2Al#dvrw1!`FH$W4r^Utc~K_*ayTZB>6&T}ql z8*L2}X_h%}v576LC;l7hRUhnK!xbNNgA=kB(Bt}Fp|52RHl%-NuiiUN3vb=}g4g}K z^CNi%`2CogxNtXRYWVa5`AKeg@Mtujd`*PGED9|GBZRe^tl+k!VnqEq!3-1!rucFf1sS z<@(9Ot$PE}_eM7LKT0qyo;-j4%^#wkL_T?>>duiB&6A*$(=RC4EHQDCxmr%CJ6!vI$OXVTbkJu|c%6u%5S(+Z|GZ&{a<`EwL->Rp1DL zC)9Ay=ydMAL4q3V+R9idKft$A0}?ewkr2) z8 zH=j8_)_{oDx;WzERsQe37j!QrO^rppRQ|9XI1{(zzdAqM>?dnjJqA}gp5lQAEh!(c z2sa-Ikt);(P0VE5AM54JzO2;lG*j+@eT=GLPCZ)=OFXGcp8% zchm0a*acRU=mm$zk;jNvH2)lB2iFRTCu5KSO4Ti;79v;g_ z#VWyk*C#k@`g!KmF$T_fcVgxv_IAO0rb^<*_M3w2j!+o-A{v!^{ovq!FVJ32oc5!x zFhc&^XmDD;L+U&BeGhE zPH2eg169T8ALYRDvlsMxPFW%4z z-51DNxbO!cUjmhI)}7>d8RX!=X5>IY)?`SV3J~4SbYMhm5#ta;|ql9 zT1_y&A&b%ZSNZX(V7Q@3b$gQxKmFSabm)%%SKEi4{llC#_raeQn|b+AWl#<#j>JM& z>BWe_&@HhN!(BBXC-N4XBko3@?Wg&Lw+V3j)Cin8Nre>~c7>Qznz(y2-AB>^2{fml zsLqxiCx58uP~w=a&Ske~Z+kCuAU1Ex=E0Mdq5uC#y6&)?*D&1PQ@dy?N+}9Seed&p zD3yrp5k*8>rIfT)6p@`x_EuK1jXc`dQ8LV-Mk@V+CBpF%jN;^};H>b?iQ6W>}He=J&04JmJhd zNN)+pLk=%Rag@Uu^~4CH+Ar`w%nGiAhv9mie*8&>JPf)|ePojun_t$#Dh4daSFKO^ zjuplcxY@^XqV2(Ku0UlLpjz zz60y@oBT&8`Q2Xq#G;}3+^X+Fa3THJQNDnU%v6J-iGA_eJJOsVwuWI5Vd&j=ywLnn z2}0`V{#7ev+rR!|%c^oPXxw%_WQ__0%y^6|=k#JDru7Ho-pVNbE`#e>siAJgAH36L z!8dMQ0I%G;u{{NBAtu@zn|)Ha;zMh&Dx#j^^EIy850&5wX>{{NPuQ*Lim>6;2K-r* z#k<@zK%u=J4VALk#VJX!vcDHbouA7s?bMLp|AVxOi=ON~vu!%UI z|FK=k#0Dsb4>$B5%AB5jV-w4Kam?%Ed?00LJfcoOr}Z-h&Dp-7_R3hCoi!P3!jhm) z#m9)dY0Kd1A)YYzEuHNvQNmnV8<71-8D;xo*oBQ> znfJl5*zj!~-_x%*%$QV+nwKO+n^&p8oGFiS)c3itxF!jX6;KAXXjj>KD-#Uct|sod zG6}rLEC4y0XKoYe*U;bzxlyFS@cbkyo1g@Ck3z92)tr|^jiBs1%FR1=nx($E$qu$| z#%n*@`HEvnARFz4dt3jy8TKYW*KO)!s&nNbW?pckEF6WYj%@p|Uu=-BJ?8Y{JT*@V z{GGyZ)!IrS#9<_?D5M-1lV%o9`5`;)i}7w$8|9xT!5aEAEjGHcdguqw78_tnQ!IZS zzX0OtE=!A*E_1l#2`03IcFMZK?jP5OUWX@Q$?7yNxnBunXOs6?ZLP?0z(jW0zMG$M zCQs4o$=}gy_C_Aum_%4UnVhwluQvdAqdHiv)5){V~U#%s>R_uJoY9f}Qy1@_rrN#tKT>6H&#e=vtcY$FF zIyn7xELWYWhJ{x2mh7n@INL9T$fuMMEmO*}Z9Ktl3u$T2MDTH+tl8g5sU$4awPWUND8`varVZ*?V4Gqnc$8|Tq{ zfi559>Isu04aA|;E#}^t1mY83Sm5$gPxqCBCD&YR~`yV4*l8*rjK z;)&-bwsMRTtfjqhlPH(l4YCB4gc6i}`dzf)<`A~kynAl zs)-Ap+QOJ)PVm>$8NL2S@YqIA_^~(~L*9gn3aN)HYA59zufE3)Br3r@9r8$?oyns< zm9TN=R^YJ*lI1#u$#8U5H=gU7tHX}be@OdS&KKPefg$#EPM%5dx_jOrr$)2%hj3Os zwTn&s*&n@RH*&?FDloTza$qhw3eI;&f%>3Y^t-AK>haagd)js^iao*At|h~uKrd{X ztH2V1O=0moHB??n*z!6A!svbHDUl->eei}Jq)A9yvYzRfQorrE!Pq)`Id`FV{T$-+ ze-s9|B?NS_7mnFz;v)z4_g}K1*86d2V?LkMk_>VIUU;&tfSvXH3_+u+aGuvY{&8g} z*sbZt^XReCVA;z6>zdDULw#E)bEV7&vwpn4mnt;VeKFaSF}vYEnexp{%nW(TZ|PdV z!SAgoZ4@oII3$6W{wO^3u!EJ!t6_F^Cq}<~z`cq?L6jSg&ou4Wa_Vq|n}%5UKAU>0 zZQ;RPI_DM*!hl3om`cAN&6No(ePX_CE@6{9K2$_o$sd()OA+Xcxz=(=D(#stl6)K>vyJe!%}4|({INwgG_i&@+*~% zqf9f!0(QQTdT=g!VaVHL?m6BL#&Md9zSX$8%~XS5v|Aas@d=9@s0N#oHsX$`Y;N#O z7o@j5Meq15Ci^rQMxXV>CyVCti_+@o_3k%r*gczBlE=-kNDWWU;XL8cXc)hTI`U?> z3QLaIf&8#=6on0Cz1Oz0wC7{+#k^zuPJksmcQ}EOUuFtHvvk4fRXyJ8uLA?6Qoy9f z6RrFmc+50oERHC@(>zTn z0Gskq7*0I7PWlp_;_Cx?bHlN2!6#841vin-zEt+-Oq2q8T{Zs`?vLd6*3?@U1w2Vju&~M&4)ma(D`Xz`^HhV=H_6*IUWQG|{=m#WCSb#zuiQejFVtUZLuDAk z?IVZ6{DD32&XOp;fcD)xRJ(AsiM%j)FZGmN566^VrL1A^Xn3%dy6xUZ@TUoO@bd@V zNAoj8srs|oODKgS#d78PuPi`s(=nX#ZVu1dHx@Yc63)3K1%E0gQCEvKHXaD!Zv8d! z(@Y7m!?{Z$3K|2`OA%PU$_M`J8x8LCW~q~K;-_P&$Bo`lArm`AHGMxb=Nb>ZeEk*= z>qR<&nqz3ORh9qt)P=W~>v8eXZ!A4A1r}`ZLWzK%fypRHlzc!%p|+eZb9F3XpHc1eK^ zq`SDDn=dps_adF1vbcJLH8hikTwP-zUeFEZ?SVd!wIm$-Yln#p6#IkD1=0*(yT{&B zHdOo7P~4d_laKHE&GfG<$F`HbsPE+*dti`-{aSx>1-n!@sOyElybg#;OVz=vs}qh- z<$Pdt1gs^#F-<{|kFg&MMy=#w>f&6E zXL3(5i&?eIUuz4V6%O;Tg{hD;*$d+{6xiv$y};y%BDRl6;hF0r;5c!=4nuN;&uL?! zjr2c953m2{nJpn-^OojJzQ0rhRNj#v=T?B*?e@PcnEXBl=cM78M-!{=QG`lntNF0w zsqk)(7oPQ9$9$iC0n3Yz(4gflw>OQ1q(bT^4Sgw!rvK)Wj2>>wDWOPqdl=+SGvtVV z{O)@VnD-$Jx1J#e(goWN=;ULH$`BOzFKk3U@kj zj`~BMI4TmBZlDZsX2&ef%0i%>0j6!t;?m#j;TrLTUfK;p)e8+MCY-lBn!uJCx3KIT zvDokOVIFHwIq*?6IO^(H(V0sP}p;wCu~u{)R}EKuQ881h@+qGbc<(LMD`x{xill!gI2v+(WvLf&;w2lPih#Cb~% z+2F(WP*<&hGrQ7wb&3jJa%jVI7REexcO+=IQYTB#0+u($0b(b4qKDryer=BfxNPdi z`G=1+p&w~2k{&)`)j3iCf0yGRk7!XPMXRRMMh*VoJtb%3;%>ZVJNr ziL=?=L#m*JD!6aTMZQAO7lvli`z5MXD6kj+rX#}f@!FxxD5R5B+xy@Et)qOvK}qkF-hw9lHfNVuat0KkFzAcn=V6R~ZqdHg8+^>{U3R7d?gqn6|Jpi6FTRYtJ?=@ZoX zumGeEr@~$G#2H!bDmypJ3_b3th&^Jc$76gXENmfcxw?eIDPO3g?`-{&Polg_?xNR+ zGyi#%ipbL)QPGX_B@ZM(&p8t%6#bdq(I-qRe>46`Z|4qAQ(?gvFT7|iA*ykYgpn`9 zaGS`De{dNGuU^tV>%1d%j{If{4c2(@;CUWss|lUoL;ub2yG~2MZ~aXA+*dO-4!Y-$udYNZbD z`K7GV#25C{4oFQek{i@Hz&F~{?TE|}HC_&4M(L&h@*%r`I#v#6qT;Ilym<9w>NM9A z?_D4Tb!JmR(!3kze_ho?vpIiIuqYQ$689befNFL%uGy~($|mVm8Zndl%{D@>6!0?qSvcp&Ku^Gr>JJLR7EYG;Q~Ricd> zE=h`4dUdcKalYU|I!yQe{Y#z6_tZsq?*BM%pr8rm=eu$K#{daZZ$AH*(OU^1!e4wX(qal|H*gIZfK&5H&%@~ zDB3ha4U9*2K+498e9p5-@TGUbdmBk!^TrnnNh|WbFoHFf{$bn4^~3pp3b^V5@)^;- zPol(8Nb~x`B$LwdYx^;F!?&7ExU(M5{@KTyzNbPck(izByv{lDK=sN*lkj@JtjqzdTskl)CqcMJxu#ZmqsU+O zlgXu14!TntW^BI0`wfo*oqFmuSYpRmyc|4VZh#6cS$tQk18n(A9<*f*!u0**y(P|h zazg^szuv?WFGS*+sRt;F-VmM=Ka*WGPW1DO2COuF0fDMlxcXuh+}!d7l~r>2#@ZOl znGDC13m38%cG_?t$cj3$DZ}KBBdl==!?^+Dh08y*!EH0~!xn|Cu~Hh=hG*b`F`Kw* zZBG!tdxQ!Xj96UeK(Gr|#E|3Z+(A(dKkfdGpIdwJUer(Ynr74~lMC2Xt08dvkk3Ev zU0&n_zlgKCDMF6{hjz7k>YG=>Erfs~9H;)DOq;qhs0VzCYQpVt4E;U&W)drC@_)I=Zx7 zbc?8`?CTwmv5odK2mbWIc}FzFX=&5Ix-l9`+9(%YA%XWXp8$^rlP+cRC(&fTv7*Fl z+5ftY(no2-xb#qz%`@lqmnA`CRvKOon93qAzG72tHlxb-AAIf!ZR#O^gWqk|h*sZ> zhU-sA8$8#IziONSJ9|W6Zz(4hOdP#NNgsT=;4I&}SsTvDbo1@Xv?HvQPs8))a#?yy zD{JJtaZKYgu0C5IH|95EvTHp%v(+AiVS2byEt;Pe$3TZKeRtkTm*LO}aFzb~*Y7LL zW4$TtZt%mDv#GqdoDN(k?t13ZwW8lj3)pgtW+*x?UvAhs2o~LIL)*|z{JNqpZfSpu z?v08t(seXwzp_VRY#3jm5(8#5gLxkF73q~tfCq2L2ii9s6plN>7}C%DkL?;J%c=AUluCJ66Mped8 z?mG3$q?EFzNI$qm+~fb)o;RG%NiA_!X&Iu1s1UZlqVyj>^UhX^Is(#g<1-uHVq^j* ze>_H6JkR8nW`W9)e#8|=@WeJPT>khEt~gRIdbTwd&g_oB#0Nf5u-XrXttEeln-jN6 zbb{?>mCU?9Two6{R|y%x3SS0>ZmsCDGq;< z#e13QQfH2&Sgoj?h=2*;Ih=gBDg8^oZ*YP!#Ce`Pv57h;w4vrF^%}3w<+m*<1LRUF zp71&@inSTby1pp?>!ChmNqHC3pJL&gUi|hUb9}C&B3@@rUFgAL2s-M94F}`+*I5%_ z$Wr=zqr*g_sT=G01=2^URI;x#wIQ`A6dU)?Kd{8aDZH9y&U0=en&u(Pq0xc)JN$9c8lDDSh3``iVA#*IJZe}RoY+Pki`6ehgU`rA zaZWe3hXoIYLo~zpUe=GRZ_)$5^Q2o77@IZu9Xpjj2epe!c_{5uuIzb?gD+1JcKfHp zU77mj-Wko$?n3wZQ@~XJ(+Gl+7 zWd)y-5)a;;;TU#qA={Hqvut1=JT6+suTLEUv4LTD<-mBsIEwlg&XK>>r;s@xpl+ZI zsVHH%o-a4-2QyDT$D<_{?0}LJTp>@{u%L8)?1>7^p`S6N!jP|PiTl^XzGPVei&Sxf z(@pN!T9n9N-W>whJE%i&U9Iat;&0y)PDb~vXW1iUKx$Ab)+;aIDN9ngXIy5==bIvpJ_W8R-U21v(y)1gtjv@`BBcs z^Py~8OBeJ1JrWh|_w&OOq~VlT3X1QW36ZQH1iyU#Z-&p>u8Bvop5c6#%Y1;D9_lQS z5NAy*W}TWQOP}QOIrF4J zaz+Y%kv;Dwa$5i@H}u4x{dU8aCOydDmYYOcD8jiMVPAvU)7n|$d8+GrV=B;1p9DWPMQMW6FdDPd? z|K&1F`jx{5eAdU@15Nn+bRGLPgS_z9bn$rpBCh;1j=1k|T-Z~lEcVM}@XV*Z)szaR zU11ItrQ=ad8rq*J`tX46XxzJ2G%F^8y?y`w-~QB^^#-A$8nbEtb#MY@2s^(;#X?0` zd&~!FYWrhypHRO4WE^CY_NMBauP7vD3j8o74b_}AO}L;KYyo9Ri}E;keW6x9HZ$Hn!M}p{M_4 z{{ZS>Ft<*(mi*P07_ zgG2(1q0g>qq9mXBaw_y0(2d)o=Tguzw-46T(_U|^AynIk;mtZn;oeNr$r~-j>!0?s z1L1W{-Ejq88MuYNFw@7YD;qI)ULl*^s}Bsm)s5RC#{?KczuW(Dd-98^ApM8DmS2c_ zsZ@Zf>i(GLn92?J8A8sYFf6_hK+`n&rq?InnzVLSW-bXop6V#Y69f59PJ4WrKUdMVcQL%p*)5Bnzuul5oJ1x%?6KgR2rXSmT(%GTii9sfuNE^+*xTXG`9DF>n|RnAF9KBN!o46Kf%!foEOc}BYyf1=B+%%-ni?7 z?JNzPyC|JE=}d=2(n*f_xkxZyHVk&s-}&PGSmvPfn|-3R1LnSh|4opAZ#9XyY-5RA z^a&dfdp$;7aS-f0Zj1E~CB@D)V}*NH`{35QD&lVj6Tv|(5lUrg_m`KzpPNi44L9jV zetr^}4D=A`StYS$+ggPTTO&AlA`~A!G3T0v(lD}r0uI08%R(bwGl_~-_)7Sv**JIU1wPDE9c_u1oB!x0ORRGO%j8?Ar(7H?-Aw2AwLuSdxV8rFJf z@2f8MSr`CcgQr0Z&D(F|BDp6UM)*ZpZI?1c&ats9(XpFLdDVmZwtCR#Xw{n+t>_01 zGiq?!x%146RMidNEHO+rm>(*h23IeIVfG;>-WWd&I!Fh2bi!{@sooD3a(oy{J`?z> zV!Fv^CE#R>+kyl6#cHK%(YyLH`>;eC+e9xgSbhb6IzTp>XVHzxCQefDA)UIP-tJ|?s%uzYVitzjZ{#yBE8{MU zhgdas6?-(I56lcu!K`8Fe1O4pP@}!7qTvRX>8k*9T@rWe+xxE|DkICaj8U_fKZ|S*3e9_8ZFks|Eys7h+-`a106GF2XmhJg*8 zu@6lRg6vfza3}6!RqsUBRri*OLZ_qc{>_|s*nnKoW86Jttf*|i2Gn;whCl@O5%D21!z|^q~5XK7+Idc6eo0Ck8Y0iSx`6q8j~9IL}NB1e=ux0B#)2c(s++q+F10q4GqDB|I~JZn&W^n{bKka za>nNoF4eZwx>~I;fyEZx_kmKa9*=Q}7VJNWAdKF6kH5sS8(02PW~>O;`{(eC>9SB!vlzE)o^lIR z7z{OMp5mv$p|CZ`2rIw8#h!XY1-lR%40cu(H+-K6YmWKDHTn*A4gD-?doo$n|LAho zq%T2v$i`5yEtGO)&3VCQ8MqZ0i(2nSGmYwI_GacPRJz{CH^}K@pRX^`^v-J05wRNX z?2-`+{#CryVHUXGrwkd96FXZb0UbrA7^-@L*WEXU7iy%NGQBSpPL_e=KVookX$EsX zR?nvP&%}g^67If19Yf|#}0G3_Ppur zMG7*kXkIfb{X7NvtcTnHMWiED#pwEl+)PprZ;`ft%s4sWR+T<3c%dd9`Dr#>|2`9b zlYe>fxkxU3RRnib!f`-jhDh;v0=uf$jmfVc%YetLSj?+7(VRG&ZTvAugrv9A^ z^0qd3d0;pno<;djFFvA0aIq+9mOt3EQh)I`Cw}=W{XIt#-;(uPS69dNJF4(i zgFbIqrGopvHKA9FDrE1YT>9dn_`7#BANScG)M;+{&?8(l+?|2;G4l3?RkDUcW4Omd z@wcfz51AtkCkIBOcA*;EYVd@q4yD|)ws!ujK^LP=J;#yhF6`M1${vjU2$Nk)cqH8q z--;x~63Tge&i>gDOuN^qJtNtyuQHI(ll+f^R`C(POrd=k`N#E~gs0zSz}0;b&dJ)v zToyO5$jOW&_`)RdA|tI)A!c3B?m7#EQ$b`S1I);bl+C zG!t)NOFt{Y_No0aa8nXD8D$3k;oZ2sHb4fN-bdmDyH6~EuwDE3F5DHG%deyw;pO3t zxc72j$X{?B#@yM1^?9ecVv7#;x~(KWbT*w`?o@_tmfC1{^A!J60I=Gd_M!Ft`1pHf zkV$)-E&#?(eqx^Qr{L4Rr}?~CC)j?u zJk$g`e6++VjgQ&e9Azk4t%afH={#l-!cY3XB#9Vb*@a{{7|<@P+c#&la-Bb#maF5smhqxm;$}5V$z8=3l>%m*TZfMw~X(Bo5t7RvxqXjEJht4eQL&}1x4)ZMI-8dQb&2Ube^pk2z|WB zBbFE~=#3J?Vd7PkoEEdMwA-rGcEf7RY##kr7QX(B!hU;>xy`GyMg1IA@tl2=!0Q2> z_xbf$HtQX~q!kDsCy*aG;j`%Vi&>&X-<*G)p_2sq9I1=M=C?V&q9O~YhDV~=kx|Tl z|5sMNWEI9MyyZ1C=UmWzf-k?V5ExH+Q zkMQlv=3t^q?+(}d!WGgu4gL^;H`LOY<=*FP2W7~M6Hf7pb4GZi8hHqC~~^8%n3?I>*&qj(^BlpK18 zqq<_I=z(Pl+r7A(1NnGE7M5;|LOTOv9`h^}vQqTL67;57`YRY7uzq;xX9Q3BtcySU zw^PPNsmP~@ddeE8XIXg=ms?0ZWpuAqef%x53i!bq2RY&D__I91PZq{qiNt`+E5gip zXE5Dai+_%`vd)R>IOXg^+`TT1x7?41xH512^Km$ns|o-?lVX~Uo$rlj1PrlR$#a&exn$aN(citRh>k5kVoJG|#8>=}+a(TP*u?!4QGV44u6NZE z!duI5pAHD#x74xC@;!CcUEwQf2eF__LHtqi2D^Jr6)x}4!V{y@NrN#0c1loxbl^)N z#KRIU5tpJQB(nZ$t!!?<1l-uXj)!JjQ0GV~e!cD_(k#}5TNRI>=fDfRSVj#G7dN8% zp-i4dUh;Xr6vPu1+NeN!AL=pHkl1r9$RVDG#eD zb5E%jPuLm6QPxPV-K-9Gah0LPdn8A@g8RmlAmi{ zI4a+b7B*fP2`!UpzZ|rf-J#tg$PU9x!g4-cQ65In&bRL1VYm7q9SpUo!<3NzLgL6o za2(`~OK}T(Q`rjo=JlvQ_8nI%4uXAA)FE=~v*?4fC1{)r#T|VuctE=xY}-aTIjh{6 zr|uV)B9((BUe96J{E)nk!#uE_YdCR!Yp5!D9mGGXYoJx&1KboNICgh9pEq3#1NG#@%Em3C z@8{;hl9UKME0Y21T1LPv@|X3!GN13zu!5c+sl(!f47+*lGi%iJ!)pz9cvFEPgq=K& zI8K@u{uv2*uhdatZ3Lf2ev|2~UijW~TG`O=JyGG2npl5i0CY+R!HWyj|1~v=7akl5 zTbxM?XPYUi2~T6{4Hy3DMvRZjL4zUXuDBZUUE`KR@gee3-I0c&KJ($LZeJW)6~gOh zC&FZJZ(NvSC~6%Z1jD;%Rva~mBc0nMI=BC0^51zs*`dd04wa%xR|)F6$;*@?HJC=CImq-X{R5k*q2_vM;eT2=Y z%*<9&r-L1NnvC*zxW7Co(>yS2+AdMd!&o-^bT{uYe7hE9o;}8(9fn+eVj|o{Z+v1G z&s+wN1c-ISi$NiL-n$_9vM(IH*M^G@^mm80TFMo9TFG?hTf(4Up{TjVpKlG2hoULr znE6JT&AZyj9M`2`uxcA$Xs?gU9iHKW+@VamhX(k`y@$U>r#Q?|LaWM7oM)NCuOtV7 z|1j$2UK+`M{+5AL?xq+byOJNW7>4 zk8}HSGsvkui^p4s3MC7#qt%Ce@x0T6aOdd+5OFVj>}{ zY2n+uX}oXhNT`<&$E{H>g=g|su$u1o-VKyvlkthQw2i~IVFi5DBx4Y_pGK{ZcA}p0 zJ)m#>12}r|9M@i%1WR(f(5L-_AVr*~-6BQthaL2D?=gi2mu{?fEf@txt0@B{&rb-< zw}un+|8oCP$aJ?T!gjw-s#1p>LKH^PYo$KlN8?zy8zhOyArn5tiy3;hj{*E%$`P4u>to&Gstj0i8vJZ)+SQ4D#`WnIY5-x_>cS^F|sz zSPsRogiQX|LkWDAQ7^{Y!*152bkU`w2CGll3DM+5k|*zg)$PqJtl}F?ta^gxgWqv` z_XVVNC-0|Ht0?aAcu~cfC9Fc`lW?fGFEH}*=uEWWW40;51KNcxQ}AH2$2!>gmTcVN z_KYhI(8pV6o?y}Ol_CR?8eX6b1f9e?{O9Tgpm3A)*oU0hazPTB4;f&@p|KEFkM72E zRj*MH=1lsZhx7S)^7XuYM|$!u83t-!*j|aT_(uLFpWN9CN;{5Xy|xq|Hrxx|Ow`1F z9*cNM-z0eB;)R2+Of8#r)&$dMtBd>12n4A;!BFv-vVspq@u`-cU`-rXl}Dz?HXxHZ zxpvRkcV+3_twQ=J4^)Fso08wL#~+uW zw$Ep-`r8mqdp<+|CqvnQ5Oqi#|C+wH$N0w=%DD7P2hP8n#W%Qwz;H|A4=+ZtKi=|i zZm}`$+m^#8&FBX|!^lHHzWWRHGy@ZtGF)N@%a!@dmhQ|!ncB_#@kvcwR#u5N@p;T< zqXWb|Q%2AE>0C-i1>5C*qDztnKfXHzUd<+t{Jjlq?)a&u$1C!gR2P^!$^&x{7m=o^3!`x0A&{awX-v&?Wv-9UWBh_$bzbn=FJfiiKT0Xs46L2bNRU z5n*g@*-K%8hb@@UY!K(Zl~?%#7yA*Jg_B56y}CdTQmlv_M|1A{+SyBE$VzY-ErmpKE9f^X`VCZ-@m~S5*T!bK1oZ@L={&{<0_A zvhh>ZQ{Jb{0BsYV;D+Lrq8%=(*kbn!ThnfEkKSP*UG;yDi4&VCCk1lUm0UJ!ANMV^ zg2zq37u9Y>*^?SEe2=85hf| zo~xmcZWk8*%`ID}5eBy9l=~Wgm4!_i0wWhs#NiXt`PKKfAdo-n>Cgg^fAb0!)X?;= zGc1#G!`3}t<$@=Q-nToiW?-PUxl2Avt;dd!Y8-$J>Ibr1B2l@u$_e4xlvmB8GlY;nQtL zz}q?GL*5t6mt-V^&t6Y-@Sj@dzrqyD2dIgo&&&ps-l3pK^WmQ-QQUgnXn571xVx#D zBB!P-Cj7ndPY2k%N)=X(p%XK}n=(>~l$2U;JuQvt+s7ug>tsg z|5PYO{UP4+oGQc?Q2({mF441+G^V_<8{0D||In}g4(|P<#iiG!K+tFM+W5t@yRIH! z81I0=ALsL_YGLrPjLwN>gh*+E4|u3imgCg>EHca%4l~j)o6q7?X|L)2E9@V($LxF0 z>NA(1=J;lQ`;0Dr-(7`4-v%;gNlj4c(T(j|D^-v^{DFqom-CNL!{H$9D|J<)*iS8a zxUtfR_@*rGe!o8)B%EA!#!0B{tpV$39!O~0&fe3$b-zOn`L;H5V-0P*fBimAo3@H2 zk-0Hpcq%8w1KAxRqs)Y<&wz}s!@;oW)iPgMrG znP+Lh2QTtvsJF0hwMJn6dpA~J%i|-$%yE9xn}1wN%l;IQb@3#B;!J*HtOl+#?84t> zQB1B@1uWcYPx|yApMP--#2gI6f}OV9A=w@t(wouy46yZ%o$O-G7@X>Gn448dLf^D3 zRCH1l))wEy<*KX18_y2Jj}ECY@Qdd^Y!5!(6CaN4p4H#Y)uR599{*PZhE2I(yI> zGaTmML3~}fnAiOt3wvk=_#fL>7C3++-KYO!`>OLA5c4GzgBMKVUt=U8gfa@Y&$ncv zk(J=SZw)rS-pAi;NCkauFWebWBC4rYhwTxaK#4b8;#mYtrn%*RY~MfM7n%yXvE5oj z5*khVqwM|ydLL=P*x#Xe_J@w}#ZLlisXM8URSBD&s)=#S?x5$*Vm|F`Dx9Ia>AR9T z>tSpG9&0Jbp3YM1z)09Og|uF?Vg$oczHpPY7K4=Im~E;YjEEbA)5yD|Zrrrm)`P|VUf_h zmcFwqT1A!97m4uvihrG<-nsVh;&CV*$hF{;#hNhx0eu%}Zof-j~gtl%kik?^LA<|Xq%)H5v&p>4XDtgw$?m39Elc*AsdF{}Jf`0m|feaFu0EGT&I}XLqa!y2K0ABw@_;ObmCvA=LaG1F5l^xI#Oc zhexJ@Nv$WUR!uF-NwvTs@72UyGZ2nmjevnIli+)A3io8-9qU$!mQ3+f)e2_rlB=L(!Jn2>A7f zzVDX?@qPZjusMhH5*NBey_)|paa%w1Og+v~T@xw@+Yb^;H{1U&Q=guJHl78nz)}Mb zt-poC$1LU5I%%N%#Ooh7K0zrG#yOBrVY7W{v7aw!CXv79SMYf* znlO*{`2WxCl1aY5kD?M^!$-8+)|G~yY&04tI8g}(YqiYX7Mw0P8{i+{6Du(3;4iZcSU2db0beK z)5TYHkEnZSAiH@+9d;TvfN%X_{xC}gOAfSQp~G@sOP;cs#GQ`viDE;>$wBHB1I#|0 z$(gJJs3nlT?y{5cK2{T|X|~^Px`X+CmVmeWsP`&yJ%1CXi;@c;QD;X!3%0QbjRFPA z)TQ2s{VJH;(1w1sYJ6^NB&^y(Z-3*B%s*2L6kqnm6BiPA?tBM0N}t83o^#ypFVzI| z0hG!1_XE?rApvg7GSSgJm^bEXqx7}=xIW$x&bp<7VvZ*s{5q5GRO~^Y$zMD;lCqnQ zD8b|{ium;4K7MxlSZFv(v-%NRK7X|XL=)!_*A8sTvJSR)p*QxU{*=`R|1$Zs418xt z`}A=)D61n^+@tpZ>=l#>ORjmMQ@b?}C!MPMVo7n>o-(#7q6Y+y(Zrt{Q+bAlFZ7|$ z`iTB3VJdN(H_3~1v2ZC1-u{hghk2l`MlSc9{+Gp0&A^Z95+a=^Js{Wg4$PiW%#%N+ z!KyM(Y<&1Z&>?QNY^0R<)kg`!ehauU*%TA{$MP)73q#W5opYZcq`z|nEiHN@cx`2Y z%d|k}d&oZ?MroB4yo*c6tFJDJ2AVS1TrGo74ySOx(dlqxtQVR!qzfjI7TEDyMQnN1 z9-7SEp;tMgW5r^Aa)TdSB|JZ<`NY-7!U+Zh($5n4l&Or>hS#Lwuc@5GPwkU}()@HB z5&U`t(%2Hylz=?PF@ zOkOb8VQik36a<^w;sW)x{Jys~oTa(l$w^mu?k)+D{nM~x+DRtVX`;);Tev>vG!I;( zi?<}2@G0BNK0oXY%Jyow*DsBi)kMSRsBqLc86!x&_Jfo8jdVWYewUiD4o z1^2bVP?Kh0@e#KTr>N(2b1HVoDZ>C89o#Uv66I#~5v08Iv2=ekRyPl%H^Fa6t*OIJ zPu}tijxq4&b~ujy)hg=scOYcH2t|ow7JShGZD_h5hHET5*pwxtkDZ%=CH9Yb;Aj(E z8}x_Ku)yO5AVTeL-%o zHdNDI^8Z;~QT82sx;q$8neO0ANN>E1zDLu}UuSWHhQr&rx(G@!+@)CypA7hmUt?C4 z-8YPZ<)>*Dy?&J)4RwK{#&I}wVk(z8

^ky7AoL+?xMLy3T-_-zc0G?c3gk3MGX| zMfW}DA{EN4gfdFnp;AU#k`WYDMU$Twov~=-+cPH-TQmbd(Ly7 z!8{Fna2TN9(V2cnx63ql#E@3fw;Bhj|6~yoey~5+8h1|&=SwcCp^@Pqd~@}w@XU}X za4!zWd6~)3R5}e(sAnD$zL?*xv4PXX6Zq?e2%|nR6ER}kvTHo#OE0i(q%5J18{%Uc zQ$Um@z=56Qg;-1+F>xzynDn!#Xqp*$FDZ)(@6CrSuVs+)mAs2Xmhz+V)8Pxvq+1A*!959BeKi4fX3t|Qd@7*N(M_l|xr|?btby<6 zw4lD$Sz))uGLWY4^KU)B_hvd|QJvB2A{>Uav>LG%=&N^zkBZa)Z>r}~bFPcMk|khs zPy()1PiHxgRB*wUa`g9%u6RN(*ZgYH`7MJA#5 znB;ewFC3?iY5RZSt6>rB&pkyLZ{G)v;RrueG7}aQQf5*kZdaTp^y}gQ8U|{L3%4t!+H&_ow}AmK3bcNWeQ^I~@}g)gZt67Bn0^ z&jp(VXrccEzf{EYcfYkUD7cqs@=>fSnLvj2R4J%0i^ulvB4PVwlC7+gMo+po%T5UJy~`8qx~{@&tW5D* zm4awdun*TtS9IWrdiVJ@t8SDqhPBG-EnK4uz|<5Vf|3@V{h`{H4#!E zJR6U>#YXJ;O#x;qmE)abFL|OX)s@FDQSSL<=*9^ln`_H7i z^aLr|#m6rg%`Og+0=bzMn4X=^*Y48>JN=#-zIVDL$Wdm2TH9&zd{xKp*%dfr)&+VG zwJ=Ag1-<7TWcJSoK#pz?_VRtsaySu0Ug*yw#akA5!UL+|2evF{#}xa(;M}2@=DUV} z7^MRbRl;z?tW%CEHN7CgG7eAr^?|qYS{OB{8ihpz#D`|kxWO4iIYU#a2rn@D54(HKXU@RLEcb{ zZZ5#~q|3a0wI=S^P=!wKl7w4Ml;JDfCGyIjg+8c)S>Hcnf^jLIZXW~6EF1?M8_Dv> zlW^rP;#ZA2!XMwa1t;PX_;}Tcb8K|LfabpPhy*r9tBozTTZs2o@8iL_y7+b6Jq)L8 zit8K4!^Qy81kQ})%ZBM<-=&fw#oJqpMm8@8tv6H;`aJZ9PSbgiv`g8Ni_J;?(EF|rQAZv6L5GK#++Cy z>`S?3SCV?_`J0#8AVvT0+zx&Il{B!m8gW=(HJknTT?OX*)9_?lIX~1#8*lz$r}?87+TgK?W{srl;`#^M6h%WK1UZdLTW>(REIqas-Hs_6XVaG8~I8XI_*bu7c#?~;v ze$CPoE%Ud@p;SR+QxcGe{e_SIEg{C_AIW?I_ zn%YAR-H$tTMv6VCC(bh@&V$DRHsc-nL>*s)F(zAh)k z^!qzkqv+IE$MFYMpVl(BVTtvBqnAYU)<$76K* zj|Qc9!V?}oVOxjjLoZ*N_Xm3N5;UX-?IW-=pC58;lLBNPy)X&P}52r5|)|RKRmERXsJb>#%GHPFIflSum8^>OY_Ns+$JwjyQAF|bN&GCG;8=C=zRz~C3n1;@4v zDSU{nU)}bP$6~l%8WzT_BJT)8-abSX*GAt&{`Ng9dFu}j(nIjrm=L~(Jcox}>cSg) zp9}jung#x0H2=O`%zITjzzj9ggD1Wp(i+M<2L(;&$#d&fPVv|5~{1d1w`uJl$@Q4-Am--pU#-+S%uQ%i&{k_#|g-rvt zF@^D0Ayu(=aX7iUG_EAipI`bss8$l{Y-921IZrmW;ugH#l!_yzuJdWNnz(oQb8JgE zCA?p(fF>2vq5(d4cx#Yzfp4;_e|ohNvki$3Krk~eR4@;E6xkx%)h zh>gA9VNzdt-chKA!$TBAd78uEa=s3H4I6;Dr!y3mLTrSnZD|IyS;;Bx2LLMwHEES=8s0>cN zp2O?iyrG=#YrC;S_=O)1FmYlSmW3dD5c`!K;-gXe#6Er{M-mzuV{p62?;_FlTX;Jq zRg@fMiD@n>XmsQOdW^rs4<;+%o2~75cKRu%e?}KdWYjQiM@^@dMV$WxRzi=(O? zAd31)Lv_lGnE9KjcM+^nx{ez!l7wj?F&KFMqodg!RhVa03QoPw@DXYPoILG6?DAj9 zBkPsXQ2!k+S@?!6k~4>GbB#zlu#{i8I2StZ(acpoL;S!{2#&-JuwS#E&E|&i$B6u# z_oZ@GBN@8b`j0=XYo}U1IV8WeXJfU1LRb%WOlFWvb9%=?3=( z_0(sfj1P>bJNkCY<1uoVgmC@{`Jwf1WR1DRXLyo<)i%XFAYniftW zJn*;MYwq${4}%g~@y|ndHhi-RM7qC+&$0*kdoLf5PYOew)Y0s^iwuNR48X`*^5!Bf zjKKuTKV7LMek+iMN8clHmd-II-=&HTOG~k0^BJCbRvBwV^=N!&Cu`Yc0X18cFnbVr zm~58Eu{FI!Y`YBKx6}uAWDyTpDu$hyp#X!ttx#p*D*jN-7)fB5T^$SGzD&ha zrxUorEFlEa-5vO1yKv=b@3Q=j(`=Xsvna->7eYnH3wMXj6UxBs3!T@nD(23X?D z>B0O|XS1$6Dz0#oZ zJqq>wu85cHoCS@3YX5v?N9mI`>RKy?4D2jQO0&Re=}Mv#4f9~(1Rt=A2t!lp6rr#E z4i;N@6=tvKU2J~M2>kbuPIG_(U%Xoi+;k%G#_Z`V{%Hj)i%Z3IR@ZsLW#a9M8*u9M zTw#cg5)K+FEpjZ{k&$qkS;vi$3X?ln^-ZX+Y$3k(}-Rt7u1SvT2 zZW%uQwvIJ43Q+As33^LKax?O>@NvJ79-Y-}N2)Taua^;7?Ymi+ALj#GP7;50(q2|t zHylQn`r@{0Yx(tV^1~s_R;egQ_`7olW0Yh5w?4B>E$li`fg?QCxl)QDE}GenXNC#D zE0nbJHN$cGh!9@ARs$2v6hz(M6qu^1FMOI4j@IFItUB5e?6k;#qrjIxd1nN-NDuY5 zPyRK(jpeQNM4SIA__il1a4N7K9^5#@CDoPjz`NII;2+N|EH!a#oV+NgL=lcpQG`Xm zHE>T?0`ctuzHB5u+k%ne=aK#35Akp7PaR;h@5zGZ(Z7b!HIKIWq*K$1guqKYUFE5&$ITYGf>O;miQ=D8M#n)~IXrsO1!kY^n z!@NnSLwnD^^?CLwSx9w?!gc@6J1>yik%O z{F!tg6ua6F&AJ1=;EaoosTj9a^jG;n6y>;M}$h z$0mI*>hrV$Q)aFcX?qVwt95FKoe%KGhf6$PT?O0wzajtF)9k5+AxukEMVq;aTqS=V zlv4lmzPefL@E?H1Bhnq1u4Xrqdx6<5Ar7}o;k#vI!7FMRN@%`yY&xe7COM@rHRlYU zb%yG5X+3Ujisc?b%6KvQHSU&fWAV%aW=%B2f`BFb*4X(_OS7Ac#7yzGa|l6-G*evI z&!i{!1I0OX(cDYrZKQ<^30+FstKc@bP$(NmwpfA)hsub%pRS3wrEU@7i7 zsL4h_B@F()4l^qD^IPd!cr>^XtzJ%G$F0fdeC}Hq@+_Oz2FhdHjc(l5D~TW0S^z7F z3sLuUH2Zo`2KGCeQh&RV>-Fjn9~Oq<$HQ9UNhOpk@irV&3J-T z;>LlVFd@$%fV{< zA=Fnr!!NzoLd!4(QH5O^d;5k2^?H<*;9|<3ZS4>0cC@c~KY=OQeq`~=vrwt^EY~Hk zeyd#-n6N%k80nyb&+fEigJ%&ROZe~P^IG=yf;?O&-I1^;hu5t{(4#r-wb5Pi z>jcWD?i+@^E+?=(k3X=cLNCl+o54r5=wjuIN|fJR!b(LG;cKKOZauP$Z;LWV`Br(6 z#g%pV~zRB{RKZz=7X0OlqfeArRgsVE{K^yg-3j+grw;16B z%_BFi%CMsGKiJXMk?8Dkp7&0Yfv3((@ZI-(aW$U>D?bYmZY|>t>kQC)SS#i>{48>q z`4u*vXvW0SS3K?3e2@vF8fcs%Y=m8G#>;|#+;0=5{;-wqtiQEddZ{$5oE?rYyxrNU z=t>CIPsK~kn80n8k;aN}p036mp+@5#Hla^Xt**Hxz;z|X z_{`kvguJI$8tR)Q)hEvkn%ypF3r z*2ATTE75V^CKmk65qc-c<44OR{<2#MmzT7nbAv2DdqN+dMJS6V%^L}y34b2jY=|kb z!CaNzw`$^C9q8xh*zb`kC{bPNd*CgT+S(f)9FIWuW-6aXJuGi3#^@3iu++T+;erfY zGvF`}c(M}Ok|!aklnU=YQ-+a8C9zHY0FSF!2tI`IzD*s%6H~@P{md{_ypQZ<{x251 zX(alT?&QN>%EAfraBQjlR8$*&2g96GL??t6c=VJ2IqCbVZsqYf>y=>ea3Y=@uEnZv z8H1su8mhM^@|8>c;N&>+vbKLA9uqVUN(t)-i(Sp^38PzkYz%Jxkj(9$%fg5Uv>&|u z%5hteDyVGbaDMg)9ydjRPQwh;`XKG}Cy&95j}d(O2!HrGJq$O?H;ie|ro1HTQB6Y{S;Gu7 z7(0&qc_KWyZ=NjNn@ahf$JN-;|FrPr#WE~f+QP%{si8{jeVp|P7zPWVt?o4#PdUIt z%M?hj(}i>PC-U4q{xF^9$3U4e%(kpIWPdQh${ibd2WbuY`*89#D-IRG%svH(!(}PQ2%$0>IAl~d(b&ftp*gK~dZ-o3|0VjgV6Mit>P#jer$gkRu2SYlimG@=XpnboX(S{Lt!0;TmwUdQCD?%`E*?F26o2hYbMBBw7%TO*NULcD$Z1YQ-<%w_W6%#sHEqV4Wv}?{S){|FKH;?} zML0KnFFUlnr{Dgu*bI#4hoamt1ODf$EPSKB>zB40dr5rnMeCBWQ{@^rTTI-E(~nWq zc1#HA0_?sfC5oS3!MnHkgEQ@6{f)bYv3?TpPDUS{pJwse3^P#3rd?$360znDS#YB7 zzcVJ8t+7|dz$qMO8bt8&bB5S9t_9!!X<|RM)KIyfj3{f~&BAfT{t(kb9+G)`+2znN z(4Dvtl?JEsS#krwc>-zKj1LMAH)paSEd@-?=v^$#QALeM9EU$p;M@HKxZ*<{zFXA` z)CbQ6CU1kUB}2J&1NCWEk|M3)QY@|8ADjk;aR2D>zG{4KOcBonwocPy-!=ZYDbA>#Ue`nb_YNi<9_0{UoC)@{@PoH0Fy ze{mTP7e|Jn5BNDslCDsRFs}ca-m>FPvY?z1g3lJXaVvoVp50Z2f{D6dKdlm0r)H2> z$zk4LvJ#RePsBl=N`w!|J6&#IFZ}76$sbqxflnKG51t&tt=z^#E!7RFTgY_Vf3kVg zZE#0N245N`3j-d9;HNboix#I<;|irzQDLejZcU?kYVcj$G(L|nIzV`AGkLAA)ns!G zjUlI7fT#N;@EdwDzt*7@kl8}c;Yua)6ofX+2WP(qk+OKBt9R5%C*vrtsu z?8z5N%7d>>Pd)#ot&3l_m!n)sD?d)&1MssRy{`i6qb-22uvR!{naPi7Dxi#NC(fT4 z&s}E+!nYr!iJIhA#%HNqxn>aT@(v}h5-qWspFB7=5WjTgK^Ejjm~Ee8 zjCDWB^^XW}-p3le4jF9d7HjC5N8Y=u68H-fCA7Hl2d90I19Y+ikbPK>$ z!4h9(#Bz(V=J1&A))UpI90N&Pp)i#AFh&w!T}?ciVbY>lO;2%@U0+-`qZLO#84ABV zR>RS4lmXPoi_4oR$?aiNi~PdbVtma?9A?; z`plXFreb5`alS8~`08oJxUe!txPI|1bW}I| z-eWQiaxlY^dYu9LxvHfz3`?R+$su>evGdG9nP!KV%?WJp!Y|~pI}IHK>0FvP7&>-0 zuy11l+yBZ1cJ)<7mqDR?mE&p{8|R7(6JA_Xy<>zn#mXW(;%FO}0u%&{$1%~7y#HBe zxM&oH_U0MFqFaYq`}tR(GqZQ`M=l3u*F(^*K%MuREWkv=YnWB@lC64v3x@cmlMhB2 zzb9A?Y2L1Qu**j1KV&gf-3Y}}nIN9g=nS>gBQ+|>vg+V2=FvDDD|epZUr)$^CV9eW z9X>Cv&GdyE*H!WC?I`|vj24#BJR9HDUX;0MHLRyxu=La%RvPpRe5IRFdebZZ^UY%T zogb0~CeBH}Q5W)~s2hw)+SX>Qf2r`f8S&7P`)SO1d`1=#Sya?L>U)a|M5 zc~)ZpU3##T2~*ACyej>68V7}Ee&w)7HVXgp8miw3u>Xf^xU5x)cqRhEem2P+6`Y(3YmS?F(EIWJ1uktCE}3$x;#=mzIib8TTi)ZI@v60s3Lr^ApdIpwft$Z z058of#6Bu?F64wj!G@?o{Ir3AaS)&9Lb=-^;^ZJB9ILJ*>i63Q@)z_6+Xsyvvv~S-X;w&YJn%oAWm!cZ!%xZDqi*sB(eGQDAOS-BsO{SaN4~`sG zL0yFe?!Pt|0_d5W54{kdoi-6-h!>P!y_(%BlY#X*_V{jRB6q){2<;=NH<;V%s2iyc z$z#OuBl|c%o2`oSGBvneB9eEg$HN-RxkwbdusN2)V3V04raxQ47u^ho{r`nxN&HN4 z=AubZOS{zk8}!p_l?;ImljpO$CMCly?iQ;AV= zvb<0w9v)6{#Zh{3%=G(AI9Kk7u9KJXIP(z5ARTVW^oB9&r0bbMJc@Jo8kvrRC9If5 z{^Ykjx!yD-u+ZqK?N^T(V3vLbMs>gDW^GzHI^{o{;v-^fwaDXrR0{}`_w(megEM4) zQYPIRZvHU@{zy?S`Ia%PdSh>B(Kf;#)hS%b%@Te`QbzeVEpa31ZjSDwn(2R#Id4_N z7urQQqCJ-f*s0@T=Q?ci+rf@^(vD=OBJRDLz}sglV%hH>c!M$l?bAZQI-9g|k7L-@ z{pt{DL3eUTELWnuq*vdmPPU$MEG2D)UomOuT8Wz}t4A0{8J0imCmsy_G5%;PZk;v^ z{@X-(PmM14GSQPKgev3c+~1foEuIa_P8B}6yZ#^Fd&2aIaLSCbV@{j$F7kyC(2TG< z%bBt>ezLq@Q!s4*aW45|1aP3r}tqjjVOU%7^rP(y_)QnDC3r`q;2e zPL$l|E_-lW9_IE^#D{ zF{`BncT^X!j|!A0bVUpEc1QE9`)eSH{Qu8PdU0*=$^NMBED(jBAl^FZURCCd$Bndu zvmZPOHWIFAHX%c3bTF44_HTp6d%cUZrc$1iI-Toobzc5j6>qU?C~|ILX9RcP#msaJ z#xfq2y9OS7A`kX@8(~CNFu0u!MFq1UzBg$SWRvdc1In_{hZ2yIJ`8V$p61ULlwfvN z2!>ocFTSTa4-BbK`s;g$3MjRkKPnnjEjdel)dt|Z{Pdr4-6AN$KuXbo)#Vg zm`K?x2`NI;J_nfBsvhh`)!h>2NB7kBfGwnDTR}S%IX5+wN3{ z+3GpMRxd>i{r&?jHgmq7G&nm?khXDcx6me~7c{79W0>MT?(T01ayv*vG`d9W{6GmZ zK9jd$OES|NsE$J(6=6qP7;hP&iE;Y%Xj4_q_HHI_{GVQ;6}s08&pr$Rx3^)~)VY_X zq&mW0mASYfKAHC`w}b~YAJvaMC=BU1!d!+ap!D6|#R^5Ls3v<2j|a=~AtzPwi+T-? zl9Pa+H|N3?D{Gt+xR@(Ps-abDFHv6$>f4C8)#UP{`91uHHbO7yNdE3)E}Pb``PkRua4| z9EwY>Z{x!L0_a#redD^0BHIafut70VrS4#yUgc6CuEYuB=d_MPM}J!w6!{!ZTDiRAfTdse8GJQ*x)r7$5Po=>Jd!h!lq zJXj&iYwsq2H=U!26>&^W+XMP77>$R>t81bERNb8u_J7?-hAp!7avuNXG5rqkB& zazQ92eDUOMN~(ZINu#8#&NTYz;(zOI;G=WR{Qh|jJgHEJp@$sVdR0}B3U3C@ioM)8 zKn+VxBt)OelX(5j2slP~b>inStRhPujD8s5+}w5Cy4o7HY$h&^v9|az>25OLhGK5s zK~|rwM!BPfC|q%jFg*<%J+2PFr|)1#Vr}4zYER!@7N>x{hkn7atA309=0`yNYvO+U z#XTHyD?5>+R!d9yJ5uj(k-?+vqo-G%_3j_p#%Y2{0JsY?PZsd7Ps(J!t^*Y`)GWM$FgFQH(iGY)E6L^zpp=Nm7&!w#Fj zoSzI~UGhmLzVYfGKk&~c0Vt54K@7RbeX4 z!m(;=+4=x=TxE9+)vQB_f3ATkq$~MYb%%AG)xgsxlA@Nx>xJ4r5wNM1^6qu_u~}IF zZ(h#%SI=MR4uxmb*Zr;M6CdZY$5Z8TsC@6@OOw?wyY?z77xdv0*bk zEQE$D!%$Kogclr9#Xn!VQ2CJrbAK8Eor}V8*zCJ3ri$tz@v_eDpU2w`hr+~8!bJ}% zGT-J8tUO^Ho(d@7j$Ru0Ah-w<=k{Y3^HjiN>uuO;zn^z(O#nS1_3A25#UrgWalkf7 z(fV;z&x17JXremGTPJWcZ+8f&2t|(pwqlobdbcx33pO^JeI6|UC$|t>dpVh}RZ&36 zt>@8LJBrQNi_l-Y4_;ZEz;DJUz(l$)&KQP@fA#B!qx&d{CYX=_o zd3P9LMf<(W&hcUagvmcEMoxCldjd(VxJroE(^ULk6#DFT044Ygrgam&*j zZmgUL@4H>mdeRNy&`L!(x%?X}OWDc&Bf`OrzK5-Yt$6Sacj!mEfN72*HeO!>w(AYS z4+`mg!g&G2EBEy3&F3pnGcZBqU1o~QzfrbVQCX&zLM}XrI+HdVs{wj*i+BzgJfZM&Pa3<#`Cd-0(fH7Q_pQo)!;_{73d}| z*(-llw6m;0{ydDIY0$#AC)@Bxd>cEjG7>HZ7~q0YbRJ(Xh0=E7+I^ZS9_BP1%3a7C zXGtc@S~VOtZVADDzU#T)2n~1(ZYC69-)*}(ywPIV54Oqz)-dufYR6ExstA?0Tgmi~378Xo<81z(&v!W;Gb;R)$y zD0I(eQ`gx7ln}ROd?HsIu8i-Fe?|9kUE4u?(-D$_W_cVaq%Wx?9ZI^A-#wF_s+l(?0*Cl9Tb8`(U+4Tk4--*yy#ucZTd-0F7 zuetB^8`m$0XN$k32*uXP>_l{z_`-r|VB=&^T`C}r9tw7i=LJ4#*f@?H}@#!w4&PxTT7hL$nCZUuO6 zD2H2AcJpOxra^Wf@tM=_iX9tmpmhQHhK)^RZYw%j|JBauB3{p59aX`JTP|W%`e}B7 zPk~weRPnBS7#A%~f|Z4?v@?2nZ9|tS`J5?>Tx`QY{LBebZj12Cqb2;K`*bLqLB9Rj z8A9#eXIab7S5R`jck%I`>hP*L1hwTgI8Rrjo~Qr|$27Ceo)w^SdK2!tc%85&eKdal z0f%V)Ck#Bl6k;zBmbfj5-`PAJPV6H*GeMR$?k0Yh)(|XkI?ltstHVsvI+YvdiR)zi z;JuCjcl}z%hhNt~#Rt`x(fqvV?GFu{bE5^DPK^RA?}gg7&oE?uE3ewU4D@M_8GJiM zsGNP6<((?{r^l?DV*}@}5T0C1JeK1cAS7%#D9?>OKUD?UKNB!AqJZxy)xffbYJ9W* zfY4T`gvX`7V3hGS9{p(-whauW9f95M60r{HVoFWO zGthJ`Q~INd&PiABcKu==U#5-j^7pWMd^Hnf(LOp)T2zvBv+(zbNYJnj$3MaQ*uE}+ z$0ui@%SrN=%e8^Sv?DGIIVgM)aGC{F%KyXFqf6BA_NoFj{@9zJyQ+cRRn_Q8xsK!F z$P?`6P}G?z^+HTo`-kDmsvK{Ol6&gZ2WHtP$MfIg`NEGg;63454MJOSxSuU$4Nz^|lFjU%X+q875b~T%=Cd{`p)mVA zF5^+`%*t_aeM@iju}a{v^iB>cXu$JEy|`$FDf(AXMj_SnQ7VJTx4b`QsuABcaVFR* z(_Q)6&rx%bEjSVeuCVzXGZJV~PDcpdx#`9?i!||&Z6R95DZ+|mO|%|SjfbUMc?M-E zjLUAphqLBVHmefsG5tioz#07H)+o3`_3)U#6|d9ufarMAXy=L8Aj(o*@W2A^P2bF= z)3spW*AO%w*->PvQHjeQtPw4BHX&{rd7oasjVp~#QP!;vD*Cpe*WgpkfA>I;aZuJd*x=|6Cu`FSa zK6D?l#FmjOiHA7~3aLN0n|<1`dAtrBawF|Slmr|(t%1@~SMk9>9r0sJs`GDa&~8~@ z2tHN~rK>VgJwKPf6RG3Oe!sBo$r?83Q;N`kd?K4C@k@NHaVA`&+TJqIjDI>Z3c~J^ zM#;v79Sr%({1pHX8}8?8&gvp}D#n>rvBHkcx6x?-2GQ^{F8Fb(D!y3Vh%+c>r)mgk z+>|6l(gRA_6s`b2U&*4ocn3dAbCdA~!nhvX6?;04f&kYrbeNRL!hii?c|}fWo|Vc& zrBu;2^di1EeVWN%bqB@A%J^_k5O3YDP1wdO9O|D~^hA0fc_b){e8+}CCh=jU?8Xr< zbQxFNL3u*7_j$iFLwI#|9-G_o>L2z}VWbVU@gaEZxjOHgq>7!2mr(L(6JuJHFmBc+ zJQshR7cJGm2vIXSnO6wy#zli2^~r*|Ab!5X10+{bj?xBMmM

U3%uYV)YSzZ@f0N z74_8ib)Ab~$Z7$)|BmE}k2Fz3w;G#gKQGdZ(MHq8R_wT82f-dUA$)8u=Bb|M7W0Yd2j5@}0*7ekOUDZ+0D4;AbGeaIC(19P+r^Qvfv7!yt@Wdto@9(<8rOEUB zdrLL?KRh6G+@^>Ju6)3h?kl`y@p35nkLuwt2`2SG7Gm~kVtMNxKJczBNb*o5Cr$AY za~)Vh``?|mYndw&2H1HCuZ{}fW%)GI1>D1%FREEcwg!4c{Xx&W*9x<*Er*@7(|oXD zA4?*Si^H#`V#CN)JXvEDOrh`jeBwc2)r9k`?n+N>mtUfav%X!#!5d`w^iwMMYwt}A zbNb3^y#_ZJrL z&#q5P42-YVv| zw*mf+Q3dw!XCC3Yjqg})Uh1E;Q7ii~8@rw9a@SOO5=}+U>CU-el|JoXZpT_W$>UvQ6JmlY=)H*;N)~8>B zt>+H$nLh;>K-2gBV}blpx*l5n*M`?^UbEaZI~eS(k8?C5_*k_Su=ZCd4)FI77mf9X zAnMPrp37veG@tiPChxFzJlK-@s(`o1a!=w!DnkD%?6J2ya z*NXWmgo_ODhO0TFFvd58=Wbd7-Q+#;x1OK4=nZ#n_SADtWe1qNqNkn*Sm=W%;W>Zn zdE8Moe3o+&>mu)Q#eDK`maoG2OXLl%CV+{(AAxRD2Ip$Z*k=6!r(BEX#x07_RHus; z+miTxc?W1B9$MgBZLy`7KKK(3R@rord4{RuqCJ-|Q2H=eCw^ex=~c+wwlnpa_7F~< zLVtIoRoj)&+WS2QjrcBZ5g0*pdJnF0ai;^E9Yp6e?zE%p4Skps684Xa_~Wt`-adI1 zueIrj*R0n#SK2 zO?BJR#f-1L?*LC?Xy+yG!a8<;V`hb8P?)%fdmJSWMLA(C)hmQ`S8rqc==GvM?XKh=MER(gxz^KW#mcL(%%aj`}ANeo|Jp?ZCfiUi4u#nbS%)tN=5Yb zPB`3cp91shoN&eD<=j2k8!{uQo_x#@$}PUgyf(i2=OsR+SPwo?|GaLv2LJL_4F~+Z zNaw4G4P9OfziQKPPuUIr?v^IT9(;~>@81@_PmTqdzr4ZgK|E`THzd#;DmWs`#%M@E zF728YJ~+g~FX+LT$`EuB<%#!oEe3Cwp1S=uNf(2gXb*MfWs#wkF4pi?{M>8@a{lG8 z@ZmA+Uw4X&^NzEYu?7D;ujUMMfSJVoKHh1-9q8RyN$*Bvu^XEytcHgXYj9lQC9Zl% z3!i?j#AzF|g!kK(@%+Az$e$MQmY_Zm_g(`(P2a;u4W)PN2=Ux1OT^mi^kF2`|4g=) z!6j9k9+Qt}=KArYeg;@^s~%S;)H2^AhsQQ9sJs-2+Q8e^Jnz}tWvs(#;?9GVQ~;R)(*u> zhl06Lh#nde_U?IGimh5c3qq*h{#&27CObf?D(!85C^AE>Z%o>A40?8*=Lg?tB;ERirV&y%Haxz`>pE>^)An;xP=ZaDW;R>C#0@9?70XVyGNpL|r*QR{vJ-}!qM zT%%eMTVN}096cK1euYt$;7gubnlt?!(*>i!zBCN2C%}xe>!ans>j)!M;k6ar*LhVqqOOJi$s_K%Y%8`Z`LJU#iV(N@EyO=f z=iQIx@aIq|(f&=v{Ovk#c)XqXRG&r6hVtKTR|BI%7eIAl4tEl%BBtEHt*-<4K-!6C`QOK3zwWb- zukGPsvL41Og!61AA6U1Gc*QbVtjc;ceBT~K9x|ysBFP9&29w6q^qf$WvI=tdNMQ)| zpSFJLsOMjXo9v|cuki*r<6Il2d{u+;eUyKcVv9z@f_cC~A2|P+v`BB8nEMq+I8M92 zLrq>>`@9h-oFg1#i8}kJqCp-B7qR5{J+5!BgVL>)7oNVyq`Prn>w=EO^BI*?CUYzO&t zNgbT9zY@3o+Qup-jE3sap4!{DMF~GQz9B9A7jeF%I*#v<6Q#!sU=n2wJDjt?fYKN) zPx_`7A$eGxKJDnCZ45){p8CrP*O$=59~UlRN0X*_;aVL$KdB1k?i+z5onQINdhEaQ zC3iljg4U1TW7XqjY^3B|7)JQ>yNzc2QlJnzv&gg5&4uj~{b0}E*yB3)T|8f8h)?T@ z5A3i~*z0};?oLb)_R}~*Z9>yD=WY(wVz@lUgG)Rr)C+8UA zME7>AUz=Q1;V=Z{I#omm=P!ZvOQu11^my$3FpA&ooD1WUs3+9fA?z(neyokJKdyTuDr!?`GhiBXDsD&?-2K9PAygiy)3GW(ZyBC zFY%%KC@|eCgTFPJ(6IF-zZ8rfpqA^}?&=l2}=dijc zIVjIlM^~%e+^gCVoSuZ@PyHKW%^D;4LI3{SCr=))hI+Fvp#Fq~e90Ge6b>xMU5jq8 z@(%{+8!jm_;U$GpgLLupMHP`8y@Lg^5{{FgPq|I9(5ntlOO&X)g| zHLTF2hJIT47_wfP8$Q;?fr~0pVonzek`0FFpH}!TDvuu&9ytl0qz#K+)YvBpf>^* zjvfq_`o{S3cNq5?O}pudgr%JKcU({p@SCtQh0yox;DWxe^mqvBO?T(nu7(KV9Notg z_FSrsJ8~;XYtzg-lSzLutO;x0dob-hWtjQB9R`j_=l}Uqy&Nwk>g+7$tk?(MIoV~0R1x~qq?spYT_OD0ZH<|3uO-o>d zdU|8ME%RU>al$`(tYI-PiF0|!67N+;^4dZDz<4s%H~UwPZ(gc_pGO`@%+BUn1JqFG za0v!j1n}}b23SJ+#J+*A*uw*(A^Z=$(<{Qb>6ZE6upyE4W{o)PnJ#I^b z5+d0u>OSXO85PQ=j1rL+MbVBj3RzhpC9BX-qPq79g*3_D(oVLo&F}p5pMScq>)y|O zKj(R$_kink_sKt~!z_#iD5p?_^F12*+Bt^kIi`m8n`7CPB6Wz@xC17EJNdzr>Nsj( zC;q1v!e9N-!EGNDMTNpg?B_yFcz3}7KQ>Y}{u_Yg)xBwG5t;mtJ}U=c=~As%bfR7awpacgrsMfaL$rCdJu#(1BiAz zGq({x*swrbWQ$UXzcsqO6U3F0AJXMkOU2ya)0aF;{mi^-sTNS9RMi8WI z#a}ghV+!lRYfQV}NH ze5N_15jR^o%#EGbu7Q)TIwQmH+vZJXduf10&cOfqHbWT40{2;>z%+^6^+X|c<^O?Aml~8k!`aoa$^0}00|6v&st!sdIiQ6 z?c)Y{q|;eOc{RB!dGfRf*mm6&jYdsp^X$yPLslDqZ;9jbBYhyfEfA+^*h&UZbOM=M zW}?$nLM=-yZvbJ824$!}wR$U`Kdm454{49YoPdL1AdE2V`b-U;K>Iy zv>@Gu#8L$Va{r**!!>-L%~IIuO>^4WST=_6;*#=k^!gjY9a8#%BHejS=C?VHJFNo? zHU_6Si+3G9N+msfc`}Y~UFrlQ3EzBk^(87PmJlKi#9n=mv(7U*=(8aocl15Ro2u1t z;gb^5V{c-k_6s58oHC9vi03&jkx-oHiu&C%B@R>cahyO|WcfxD8dq7s9=k!<95 zTrvUvo+gc}{dq?=q(7w7bJG8<6qGdSVD9yNY+%|Fm&>%HpMM3P{18AoWy{FCr@Zcr zE*}3Q0>r_txTRl%P&;dva7R}HE7&Z>*QhOpC8Vz|d1T4kyeGgmdj0BjXXg3k7n_kj z8oPe&;fhoHVxP7vnBWmDe01s-4&R(8`pXW&t8xD7J$aMmUZRFkm9Wf03iVq$Fu19WYw0e77Sag}Q&eD6 z4@<#}_}K=QqSw0}9IMc=cU>mD`6*v{9udb};X`4a)tsk3Q% zzZu;BX@3lGHV~b8YR#Ue=>clM19QPch+Ld6uC6mNXAS!eOu5;9U@j z&l?MQSZ{q?(dPylWgQY;NTi;WA-hC=!Lb-x9s%dU6)QKI@ORRNcp*zgq!mWl2nQ8u zE>g$V#@#%$&I!iTygh2&HHpd_+f#%sP_wd=*n}2zWrvQR!J=HFsB}?1wrUD;J8r7^9uXfsEmE3 z6w6hUb#WQLhC9c7W?v{Xe8AVic<}c!zA-NXu8t&+O!hRPrNdH?Eeyo@qnGd!>cdJw z%4G0XWA<*OLv^#o_sQpo3(|tdGaOtCQuz_`3eB0*h)T2@((;Xfm0w+OW2ifOeZUOd zPHSP^_&Ba}W+{YO(%yfHtt9cl1lZR}vupnhwp7{@ls*Qa!ZYUo25n5((xm}PM2676$6d>vmTOn|$zTSr|_4PqQR@m1wZQCkvyy!Z7lzlBa&c5brQ0H4Ij_S9W-J8ImElmmgV;o=S8Vy+Ef^Y3-N~-VZqhp?; z=)nOE=+~zoJe)fa;lH&!=FDV>qZv}g=Dg#kFe@84sJu4}-q z_-t-+CmPi4T!||-W-p!8s6+e@IN#sSD-Bk_G0GLp7<^Z9Ks*_I5(p<>ZD9X#Iq2*{*R1yW|o-Vk=I-Bi$=MK@m z9dP!um3-dn6%avlh1ZHy;TDB!Y-nj4_}eI!4_-SEG^Bg5cgW5txHp3`x(C^_wzgUz zQVdJnO8AG7niv;dkNHt0!skZPXtS;zqw`z&y3H%VI-bsbBL()0${VUTk#?tYA1@9W z2#0@DmjvOkw}T&iyseDmGz0l;8AB}Fd;?D&dLn-MpBb{jt>`ty9wsD3!LH#h*sV34 zZz5mtfo^HhvveKiu29I1pX!;7#d9aa0u}0=%r)WumR6wfo%o^^Zfs|^F{V$c!TryV z3dd4T>dnU~BGJldZ01oAx4;EM{}}Tn@@jPV{f&n2wy?wfl%OG76&Fm|#gEOI49d!+ zV>x?GLYq^t>qGxOn8;?nk0f4BfL9(!BrC|jSy^=zyI*j&^Hvn7EOWt;d-Y2_BYWej zpDH4s_hTSw;0(}7nTrwRq1&=+GAO#!@6qwN(0W`Y8!YL;;mIeWVA*2gfTk>xJlm>? z|3#KzWn>qtPp$%4sa>dNb(LS~7Y(9wE~w}^P5AinaxiTOLQ5(~m8}NSk3VypY2Gk>6aOF&Q z7Prd+)PIl{s639JnYj{P|D_&>)wYt~BVFNKIqf^fWw80%2Z8t90Q5PO$crk-=Os(I zmUC_kQ|Gxu_Y-++PK@Ulc4*)ux}RpHew3_^h=sUX>KRGhz@7~!T}^`-?vXx#)ZALp&e6YGx$B(#y8XVCM*7dr|(_j3H16VA>=(jGM=Svk_X3ICTJy_ zz-ROx403%)$LsJ>+*(qDE)AqB5!rs3NgNVoyqSS(!b|6;HdC4>MI!u2Z=Y{ zdohl$aaYCo58qLvd=<}}LGPb58`F*ASix8w=t#20fj`#pg5<#<9UF-95852pQ%8CD znDY=e`v^}@rp_EQF)D8K=6y^k({j*VyiswFJw7LbZ{H2^!MI?4txg4>E&hgKcV0?< zQ8&5XnIMclaFmr=kAsXf5ArF*@@*n(ShAJ$GpF)|IhBhbbeb%hNmIrhovRr?O7Xv+ z-z5sfc}mT#$4Qi#)cqs|WcN7Zz@QEMQ=|^=kd_sl7#HgJW_18$HU}X)`hr=fyF&ll zwAHm z@LtvhM{T$*Ie$wF^W&sNe--Q4q^mmc#+kG=W8-+Fvnyx^lJBfZU$S`?b%kX1V0egU z40zG=c_2%He>p|jR=FjVnY@X~n$c%ss7&2A{qHO4SxEJ63;vkDO^Xn?=h0N6-+Uf4_a&mwAe@%hs63UYOWrRl^o}%H*2=P|gI5-mPf^8AmOq4YjmThDBYiTe)XF(n);=ydQQiVSj zUT3Q3+h8*&mRq+Ch9&fyQY+WxmS-7z*o|#y@R_ zoT3rlzj+-$={ynJXZFR|A1(N6kv%MKje&`2&M3%t=Q0VJn7Bwv)ci+_UDGONe~I6i zzEh!G=aMTp&@7#E*@WMxp48`edNAB%OEfeD3-Is!xxDb5F76mzjxIT=!W*M*l2&(z z$ahR6#u~?hF6G{r78&ycH`FoV)Ng#)xrH_8E5Wdh%J^q^3eT=^g%7_d3*yE#$=G6R zm^_GbMG6zyl5x?HN}4crp+ustu1{THS82~%&Q>mo1@GU^sIgkV^l5_$ezs8+ZSb~* z;9rg){h6Uu)pEW=Y6`p-Q5MR~P}p9{|bM3CKg&plTW$#G@;@Yf4ERe9De!|{*b(H=3D5uS+2&WNdB_+ znZxj8zf=76xmXx^SAbPx;)SxF+R$E93d79y@P!Ap@YBs&ygzXnKleEfq&B+X;XUrm zSEV2PB)?L^xLB^66A1C-5w_V!c)orbm=^_M*z^p>-VA|pQsm3Kk;wg@#KP>S0*v*) zE!=W#Iy?-K$7I)dPNA?k<7YLhlzfonFO7!;9arpV*}(Su+rZibh8VejIUl_)2vUxa zhUdDkOT;jvF-|35+XH(XnZwK!st&4@9 z8t|^ZE6Z}H{z}g#xR{X47gniZ$F}ddukR&3XLArNq2IXo?eVPsk0SguHpK+51Rfn} z10P)}7d_>p*nM;z*34Wj(k0zn%|vayF})OjPs!k4ymT>e;cW!J!z}E_NU+iD*#p|1 zQ$-SxqREaRemW-z{KH5aGcu0JGJR8>4;Ibg>MvE%uFqF|*ZM*t?;Q-s==J}P z=aJ{9L7yc0E-oeU&*UNUnH7l7)AEFS{k%Y4Qx=^+#`B|;tB{&sf>8&)NkSB~@$>## z%59T@!&9giEMqd-Qm*4f+VS2wFD*JHwc2q_Suhk4M}4pK1#`VS4fYk$F7NPsu5oH8 zoTuH^y$&7Lt0)#a<_Iu;(NNw_coqDi6d%M`Q|6uqtf;O6@e0Zw@r(xt7ZON(x+{SquE0tmiUkfLC4u=yEqtIDL}gd z1+J^DhSHM@F>?X+&3cZ9{)tK$7ZJzv65}B;*#)at&XgF%nPQHdim2Z#Z4kFn#)1>w zx95cNHKfU}xIlg%>Upi|_zaBjA*sx1DRus#0lfFu%cL#y*=|JqgxIb^pBTYWN{xL%rW}Za)iZ4U( zw)74@&?OFL(7ZA7M1`Zz8ZGR&S%VSjr+DbCcu=7`Y-5@+tNl#*16MzRrp*>UM5r8`-;BC8&-aixb6hyz^5Wq^0ZOniE>=tj`K4jMl~bMq%7K z*Z>m_-^UQ!HR7q{dzvZhitqGun7iM6*qSfI8{2}okvJGU=nkvcnJQeks)}W7?7?%v zV#+$4OJ}safU6geAs^m7e11n3woa76Sy5D^bFz)MRB7X-Gj%w8Scx!Et{2)LXhV6Y zR(|1iFw}jco|gj(?3RoyjNGk?OfEP<$cd_n#(5<-kjLTQD;V~@bJ)^c(iMqXyAi&m?T49 zIf*msKQ`tGPFi^V?jKA(zm=7bP=Xa_6>+%VcHRrz{^c9H=~YPH^&bY}W%SH+C9+>@ z<6xsI>8=yFr2V-XUYlBkpm~8cOpS+rqg+t+ntrL^Ss$EgpeC~7b};e>^&?o#Li>^Q zeFeFJ>vG~kla31u`qeTex|fl z_w_1&m=X`ZY2@)QnI(u-=AaKBJD2&4PvwJJ5%Yqm6mD-J~pRE#cp4=z0F(g6jRIGpia)unHhAePA3v*ee)z z7!hAxVk`OH;RcsK6SuQDgQ@Mdfm_(aT}P4MbIqjl*m*LPy&pFN(q_x!X9v=RWN2Wa z?JYch`JE(kzb+nF*p79L0toOJ4N6+n3(^tHn@WU zM&wHoU{{_5i&z#HPBTM8=a;zl;3+nua}8;mqitj(YG5H5_-8{2*7KlNUG?E~ir;`h%lv!BKZOQ{(@y3%;;p1Wb>n z`^$qoVW(sX_zslC2!{>)+XNl#b}qrfW#1&1V(C1(QHL=}vY@$wI+)^|F(Z2e@6ghr zJn28g9|kz;&IpAUk7?KQ^##k^G6Ncj51c0J!8NT$LIBO`ty;S5lQ!i`965(dLu<>eFS=F)tByT zQ)Ynn1)9m74J6yFM}q2o@;e+lPB}UP{51O*7|Q+SXTopdEB=q?an$qjbaN28 zjg*Eyb^=U4b{2CVs!M()=wRl-5^PD(g8orPIML(*PRwfO%I!M1IH?)!9<5})ThfH9 zGB>e|d>QUGD+I2-BF)Cx{yf`bCXAuG%)^x~EOo6kI6fSVYKyn=_j~)}g^T5QWn#3@ zYyT~b=o=^cx!eKUzEd8uQ#JbTJIRxZ1Q<564d><;FcmWmkh}R6uI^0Yfonrx0`1qF za_&mB)n-EcHsV``ZDbz9l;K>EEk0fm&CfdHn~g)V&G8;iL$OW5;GoSl}It~(k zVf?NwEYd|8#N`TToVtx47SDiuIxp@!R!Fq=j0B5Cq+S1=$fVy1aM+r27<73de;1{J z)^SBBh`+$9T6OV{PAi7JJX|l~k4ZiAdCn=yas8fyTju|j%%ff8;)NwRx3YsR^tuImTDReAPch%ML6>~DEx2=e zr_iZa2n^jr9V<_k@J;t-z-8J+PHa?TYexKLy;TR|!I*SzKTHpQ=A6Y_3k0mco;HN< zDu(b0J9(Op4pz;p##McMcrEF9M^H=j9A3pfX8fcTE``{Z}$*SYC zp^p5UTMEcynmP)Mt_0w{hD1Jd4Rx!voW=2TLfG!?Szx|Rje$XyET_ zUr@cUh+n$07CsQ3=S_5CO{+%30J`r_lldfGccm7s?E*xFq|5&Axen@VzKm5Pj&Y_= z+{XmGT-s}c20`m6 z19mj5OD0{%ESkwv1fb~EgW-LrY2(LX#b`3qlOI`PfXkb1V{f?2{(8E=fLJ3eqMfWI z-Ic!AeZzCFUPldm~(oY}qCL&@i}q$@hYz3-~w?0xxoy&{hN)R+iTzKUo^T2`GK)a9M@1gS_v zGVg@}9yux_(!Qny(}~N<|7Q7bCO6$X2mFa!kh^oSy+!_6fulb{gDJiX(IXsXxk3AtgGh{mp8mhzxpIi%~ zoE{8czh@3yAl~M>n+u!qM+ROU8iaA7$vjEh8Yfy;;*)Ff!e47^u%C3CXj-HLW|A&w z%#=&VD27 zvswc@ZjVJ7I{U64GsVz~B5ZKUW4Y@C!S}2#Zqp0r>xq|&j;X`)UH;<0W7Kc*w*~i2 z6oJAQZy;GOI!Tj;=TaD`(mlGh_dcO@Ydy0W*fXC8JB)!wn$JD$1>8N+3}@ZCi22mv zlAllyR$cM<&Z&quQ1uX>z5wN&`0rV_1t?H84~XXDZ{74SmwG%j3mif?>L-84^v zFsM?2^?D}{ixu>+?ZzJ7=htY^q6~BCX%{4^&sw0oU?ZL#*TmDW8DoTV1?e0fi492G zc4b=)21ia^gP&Th`~3~+Inj7ZX;%MP5Au!oU7cphy--)}#{2YXYV^lA(| zwF$yiX6~$@MG5U>k7C-TX8wb?z-JMZd$4!6u$G>g`s61#LN|vWcGba^ML+Sa(-!9Y zRt3&2QNYJDw{hPgb6~Uu@zV1uB!W+4pm0JEqWmVdlTqgUptES_w}3mAkq7Sk1KR}s8>%N+Pln4r>hTsZ32UG^(q zneO9r&J(vkP@OG|_|2ASTB3KwVLnf{KTb6lqs3zjmVQJVj(c5%{##S{3+jwk zExe8o>=yBFFa+wlL=?kP`>;f_F9$C1Lmy?L{)GW7~!d@@qFqhJJ^#Dh{K#di47OmVNmW$k>wA4bPu7t8uMbD;Bk}})%V6b z{4TmBrL*lX?TM4@!S=ZW)bMrLTXcQl%N;z|g9+`13U60oChF?#2y1uGfilU;f0~m?P2?Xr+=J~}%Y9+e)gEl0?xc%& zvl#8fUnEhPdU(O17DqPAK*F*Wl#M(Tb3XcT_hFVebdHLs;#s`oqmA?7GtJ~io*rD+ zaV*4>r$8e>m#rIWfcMJI;(*F({+M#zW7;oa^U6VNy1W*A++PV6@>_Y|URrqX;bXk> z!-r?fsp2u)H#p;T8LO8u0W-?H+e5ypE3@W9@HNWx*l8dsk{%0(E2ty&`f+y5Rv#0N z=iqDG!+g>@9h_Tz5!*`=nDgGruro^$*Y~3{)JhY(cRWJPXRjs04SHkb9T}04sWN;# zFc?zLSm43ItN0vU4^SXHANb|GW8;Cba5ItSjYZPXn4^dHd*$HTk7|->p1N4xTuk>G z4X~SNOgS8P|8-6FNzg}`)6FTvCKfAJ)p-l(e3iN$RbAaKQUa2Y-xt=_ERHuDO6WJD4ae+m&L=TE|S-1EK z^S^lsY}ysd4bII6UBc~0^Gtcc)Um)xQ;{&voeh~&3wm09IRE`=UV6>~#Z9*`>mltx zNxN0y@dRh|$>Br0RdIx*o4lfNtb4yYbo^Dobp7o-tz6-LEjmzWIlE zhO`lWtUXWMpgybGt_7a{g^-}RgKsg{LLW&bu4W7Q`g}t)`Ot<&HSd_nb`V_Nqk(3N zV)&2!9-wL&j17vJY?_NbSW{-y=s$`4Rx#n{+;fC;q3rVEIj~7a?q5f6>U~Y@m{W;5 zcRM8&n~C==Xu}t60vNHx4peDhHO$4I+YIu6H}u^8AD?}8+LNv(5M!^p^JiC#u;1xi ztgMxT4ZfsF3@^gvqiT6q8}(wR)neZ>lUc-NT}W8{5*9v6;!oF-rn=WhjI_GIB~K|c z&`Mc!X6tJv-mD6L#D?U%i{~3}*n@pU4?bVLQ-fWRD@0lc^)SLo8|#S&i)%Q{59am8 zcC))!Z=B8!Z?gv@8C8rhiRCjw)p3FQd#qf&f`9&I3ff&mu<}wkuO$rMMjUwao_5Fm zf2h}f^C_qfKEM~QqYOsL1?;Mw%U7!OMFpKlm?fa*TbHSD+qh?^xi(uJO*6W&d&onH z3-PoD)6_(jnGT>_>;Yq<{c-N+t$dHKBUBYoub*eW@Pfz>=2}ojcf$t$dgxsrh4!n)X7rb zpEA<->ar)relTj8EG9Vi=9{k5-Ff##d>1#6O;po{q-Pb-nZJeGhHK%tUk~y8)Fph} zNL9R?*nyfCN?4Pj8Pp%{!Q@GQ7l7y^&2@DKl7V|1p{z3yCBKiehE)bQV0jK+5FX}p z^tI7v63sKjd+Y6Sfx1nKSU-aFPUPJitN#G^B)yWT=TN@L)K0WM_Lbdm83HO_%;_8n z=F?LbLfsz9Lo>*A6zK>dp7`YObA}jF)7zz@kbQ+qT`r za_Uq)KH3O}EA-6RE%t|m<5tJ98uK5Lh9b(#_mUNjOS{CsC@+F=?O=3Pb7jvq%0Xkw z06fxvE1!8n8)LI8QFJtu%hhP0RP22$8-J30o*{r?m%ja*rJdF(qs_06?7;1|)snPsoqY-`+oX5fiXV?<=m9T^QFm@aX=AmwSD4li-n=UUG ze|c?;ALTo#BXS~?#x8-D3H#+ z7w38H=2hGQ!e5c!Hspe&FuV?;`mew!nVWor{6HKuq7EDDo5gKANPqH^eBZAIfWNyQ z=Gwl*K`T1=KqnLQ{w^b0UL;_m#%nCrvS(%vw_XSx=9KTZ&XfmsJAypv>#n4@vsABo z%DMH!zm!k%V3q}L48DnL`yUa$T&;<|VGppk^JzXrhPn?%zC|;8>e*bb4h9`^xJxaW zFQM#fN#7uJI8`B0GZaGQZt6z#+QbU~>f?{LY}8rr$?eF$5ZkK&RciCt*82l7{;;Y@ z=D8g>Tg`+eyC&jxy60Zqx)2r+&-TV5OBiADjP)v4#`P37e0-%oE`)5H@%gu8Ymp%y zIaY?sY2B>4s|qyqw&2Zu#auB(A3th0;fInoVNumW7*j*{zP0MiTlp`mRqBK3BMt&33qX!m13p zf0<4VCEB=SS_NvGbV{sG7-P+iHXJO{gLD6l1?@RTIHb*w_dTY8qa|`8!*|j`DGe`} zN#~A@%6r!A$N-54%V==ta?K_<%Q+7}pO6RJi@MlqUW5g6YIz}fANtI#qr6;a*1Mk( zocZwjA9r28LmdTUx^Tkk^IT`N4j%ofC_41z6?59ia&{8 z7S~~WzOQKd69JwasDsZ2T);q&G=6`(DW`dayv<94<_;MvLofd6Fu?y&c5W+-Y|l`9%PCl}@PXvzb^{z4t|odc?+9wC9*!BpbP=6^MinD?hu3eDbcMrE;FTSHu!lZ|I@r*RAV-It6nL{q1YtooWO z%zvTqkL&n*Qv=oI?xJn#bIGwy>iF5elX}O58b`@$j8YlXun)qhJkXVWb5(%fSNdc2zAfB7W(b<%6}-JY zR+#p@8rKzuiyro~#g-Z!R5z|f%f*>IAVLeR6Yk@)^(UDx(}T%oU%{v{iLY^1MHT%X zeBL&)1-$j~mrfxW{atkB$@r7&RcIDGijpBFDNL5q)Cq;;`lYuIBJKfMixol`7V*#mIN zBM`?X33z;^C9+eOuo#`N42p>>@mmY&?fk830R`bwJ5WrY$Q=`Og{v;ptDdd1rp^~baQZsEDi zmtuEILzHr?!PCzzK_VeuqV6d^>C?))nklz4MpiT;OpooXyv|1dl1)k<}>^1S@m~ND7jAN^lHNekU4vjsM_~I%rILC;q?5L2ezDesw`uutNCZ^(T zfD_8jpo^OaS2Hn0fl>*I6fQH*zh)@i-GvwR3rc@vh#tDDelNxQIR{W{2-I|VoXDPm2drP1p6JG_^ufM(r0H@>A0T|kFr0{E^o!)Pj8vU zl%a6qk2>W@$MC)ODk#s)O>>3Uz$UgAD)s2gCDYcWo;PUrr8$v1bq8k1HXWTQ7QsA*Th z&DUeO>R&ZnG`0dc)RT9p6^NfaXk+gKc2;hy)eh{H}~<>`p2yL`*d(oGsN?S!MtypCZ1^S#EyRV zCFO;^anA~M(avxo+`Q=n2}OY@7nRIcEOUZyJ_fZ({@C_!4VOdg;Ye$45Yh$Q3hGBo0X*eZYYBZi5><_}>aA zxClYi#jeZ#%lC(3H5s(BFycr18el*9V(eUQ#ikz;z+b;gSQ)&Pw_Ml681+V+m9>CZ zQwPV6JFeJkss)>1Zcd(J>QSqAkaQqoY0%d*!UC0SG^}uo3stBg^e5bMo85Ke$u%0zdU>Dfo5Mc`@FVNnKKas#*PTeZeNK zYGi{8&CAhveT=Z}5S^I=!bFjxG5FO&8@(Quqn}nfFCc%@yT1*%z$cRhoYjXzi~j?+ z*d%`7feJ>~{3UZRX-uIo z;`dEB<9Hm?+>div+G~e3D2T>JElJv-R*UWepuW*UbB^i2$vYt~f;6PpGJ0#WFjK!TF>@`9$)e zC=)OJ^{Od<{@w}httGwLM|ZYS${%WTs0ZYk17CBY3a{xViVoJ3zWgNR7ttR7uignR zO`egKWv-Yz;F<77nHD6w$YE|y61N?<6y90WJxjJya#3>vEImvakNY;U)ZvDhsBs4C zZ_ek&c}6ITCmtp+yVScY0y=KFVlZrC^OktP!_rCUQxw9Ba+boZ%pk0Y%o6@5YGM5- zi|@+~Iv)=ip!15;_~-Xe$$jGnD0AD2!jj8e<+lO(g1xzzC3{_trJHi0vql z!HL@MFnMkZ=X@zR7E?BCmO7Jnmjf7PC>a89`DV%`Z7yGzI zrv+vx-^ZcPAF;YkGXX;k{^fqSB}c)~11|Wp#ZI!wqBk!4sv-*a9tZBrmqRw`G)`nE z^N(*P!NZrt`Mk&%dTOnPXSZZ=vVHh|D$rcH+RvuKYXL%lq9!_ee>Ij+9k%!jimD54oOYhtpnzZG@H z`BcKDgIl>|2X$uF-NwELJ-PnyXc%JRir3oB*^Sc{5OGQeYhq*h&K=7^`UmZ`M;S^! zs!awHMe=q9WU;wcMtCgcG+y*R#Gh72!*6SSyjAy9xRdY})+k`IPb|OkSQ9I6HK5C- zCz1(j(XdL&6`RJ*W!g@o;m1}BeA~Q=&v#h?e@lp;%*u6KoiQ2G=y~4xKpNJIjqt$m zGjtD9lgQ;oLFY#D{Z<69q5#t0mR3@K!2{l)ri-4-@8Pxk3)svtD%fwtPfY)n#|=-e z02jkxJiXVIU2N^PxgQVqV(2^Fo*9fggGx;Sjw6>K`4 z&Rc$KqW|v(jM$UOp2-?QP}~>L9+o^I%(+E#99x{@aN?QEc?$2j>p$S z(zaBzaX8F9r$#}PFL_K1RtVLrs@aey#lXrG$}MZDUwABa)peV4VIcXZ$otUWcse_l z=m)!I{{^9NERQRWg2h`%ccVDoRdTQcNoU0bT(!PV8XR`R9<|qh%;X?fv zPlf$NIuP=t*T4DMsAf5UJ!ypODkb~2PljKlt*Xo4#PSXh7WK`>^BX*Q;GIZ#LmE8U zbmC!7nBbAIuhHXuPU$M$Xc#W!f=cbJ~7N+IK}lG-*C%_BygkgBsY2iRd3$$ag7eB0Ex#9lP!ci%p^- zQ_U3zI25sd-(}Ik{4GYFY36%Iu7Lf=soSMko!JUyp!lm1suob*&Qdcha6E@HPWmjx zLl)ds4c=a7@v3SD9I*)|l+@AS)^+HuVt??5zC?jQX zAAg9L6pVw)Gg)TVWQwcm;i4a#48adtWrRP8?6{E^?AzN5dwq`Mp0qc7^`#8eNlnr4 zQ41GeYC!oK1(-W)JaEt6Lfc>v& zB?aOY_YOxFMSX}qb{sz4P36mIA2fGJ1-|-pgN1g@fpb=ds1!yysIIYa+sy?FAJ|Er zyPM!q1y#|<6XW1#tsfksO!#Z2q&fF+h5NK$2>+Td^t!$Zh6T#t=C>Po#;<6YbVq;> zZ#YZTUTNZ4`%;Wr@}BhSw?N-!Cu$^>@nxi+@4VuIe}0J_hUxgj?QenTFu{{oWVph- z0X?{Ve1a+Ztjob;FRHoj!)Pd`&*!96vT#v|0XRxm!n%a5yd<4+K6lh(DeXE1`lMwg zZE&Ns1uHVNgs3mtI4(JcA9(-&%mmWYGDAsFfh*jj-{y?-S!~NY%KUk93gdnr5R4mlf`88H~E;DQ#4S^5)Vr51U zuafw~=98pxD$8}eX+4EJkJNqnLmIlndZQ%pGCO@tbQ|^l%wvg8$Alu;7XO8d z302WL=R4X{pNP)L0084)+zkmVI;l6jZ6A%c$x%G`unFp1$;SKEr&##W5XdyqKyA{v z9wJT9pHnw5Z09m@MTG^f_wT^_yC%XTml%jmaK?}^G5kiYCPp_)iA>}z*u}cn%x2XHNMBd4t44o z`Mg}n57)7}_TqoL!e>GLkUpDoIn2$tfI52S5nnxY&~)~vKokF5J52qsEqsh=4Cu8A z&@|wUV@6XIdWCEd9h0oUUNzL`V`3ofvj8n?1nlWkJzOFG0QK84OZ(lA zg)3qgJn$%yMS1yxn&woRo!0Yc^63i>1!0yrOSs^8J8M%?#04Vxa_MVEcsu(PKF<9q zaXcLZ8*J%woFQaUA8KGsKmuAHxWK1*YhmZ;dNf{nPk3lh9E6&?;;#52Rv0Ufdsn@~ zmlmx&veh3h)&*hFdv(_KLKeo2qgmgGJT*s#VAuB&%uBRjb=L);wLceLEKBB!#D&H_ zE<@F(S-fkGF7|7?joy)unfT0TsJg3;;i)nFdaf!uyL`jB{jNv`T@Qj9?_f0ekLHab zQ{gjxr*Eh?YIdj@inDUC$T5`7QS$+H1v!k|8_xybv~kLgGMuX2BPMap4-B-!@;#7xSsd8*feg z$Z)VdIO%%ff+$C>HPjSGC+DG7jTF4u5&|!etK)_vLwFHsFRKQUhNo*htE<%q?*Y$Y z&AYvPFb{=sH)Xql2a z22Pg{?q8$;?M{}k&D|0w{oceYKH0-2`bHET?65hcuL<1~6JcE45x#gx2z;ggMq%bf zkv8$1hq_(GjOEwZhfj-O-$<>$-broAFnB(|4!vt9h+Mr4@g&uDm%Ec;d?#gf6T{?B zTnvwtp9>lqFIpG|Y*;&MPSs z%J7*wWsJrMhW^q7_mx+{?Rg}huC9!?LvCX6p@saqR~Xc0+WqaxwY@DsMNt*IzXkKo zbKWqU_S;7SwM7%G=fdqNqycM8X5vzt;o0(j=)=22d(A_kk@Q$%iysTNeszMe9RqL= z>0MteqPy^x8)$#-p2*cF45pG_xYu2WW*HAc+a@nQVJd0k&rvV;{JhPQthsRL z261)N#G&FVy{F!3xM;SVNH|CzuO2H#kK5$eC-1GZMkT6_xyy?xXkYZG0W*&-WXtCy z3uY#UvQJNciH3ZV#|D=ls68-`J74jEPX<2d`FS>bG+Y`YMEZFDXc%uBItFl|Mg`X4I0V7?Q(EbTF|B2!eTjlVL=qoy#E+gNf58N5x zgGNrfnf@d#kd(E?eIxz&a1C=@I42+f+|OleOhX_@o;X}ncJjsAy2zGa!Ma#?74puKPn_#q58zeLtw+5PvbDd!jKj3wy(sym}3LS_f8?Z*_qDb;P!n(BN@r zi8uMF0RP+cl2v(xK=>$ioHo;mS9GW&EB{y9qX*SsrtE&<%{2*V)DsHNx@O_(^LD(E zxNRdx^-^9#ENjV>1-m)2ct(6LS6$-(QM5}`_Pr>w7T$)qx|JC6xr*z!g~Gv~>VNz5 z5s!?BVN9INpB7L@nv-O>jj}dRxq@>Tdcu)+czojZ(4f28aA@q%2 zX~<1zMsq(vOo?De=DD6YIlA$9X4@-n+ZYO;Lo{&Yy-SnCZHM{A~ayNqITI%7Cq%_p{vzW{OP{)Cj z&ZDROc{a#g3%B{-!>H`U(k|U_*jYLoZPOyy4AZqx*MBz3ZQRC1<9wjxh&LX6mMrMj z?PT*#48Rc|`d8$P*2ORJspud6Q)GTrABPa=Yy8;`w!N=EGObL!`-k!xHmP8)X9G4p zx+8dN6Hd(k+4!GV5nEO-h3^kgUeE3}E*k0sSEIdg)EfnMRL~zPm9)^!>=4hl7>uXl z3UT=x17^{v4yw}Up;#)0CsH=zkeemwm+8bk&#R+fZ!<2s_?X%L7z;hy|MlcL%5qpP z_Z4Y9AllZCvgnri;7hS2wnD-IWM5If)$s^E{}r(~4rdZiX*0VSz8Y-Q24HGNIFG-g zjAJ*J;OCRiMTSRJ$dlKA3dsW?jGo2ovU>RPgct8e8C%h6{e+zlf7xuj?gLV!KZ)G& zkxifK0K10~10>mzH!ur)5L1B4Dl*WyBLsYzI$jVA;U_dG6UOcm4zL@`ipJ@J+x15v z>lDSK6~kb>rXBA2PlK;~uZoA?_Y*)7NK8r*-SseM`0xsMd!D<_)LEXiF^;{alV2FnurVpqV9T;JN zi$2N-qt0tU%TG(#6lIAMg`4^AOb3{fOl;e;9X3nTHDUR>b8vs!5q`tn1$wf6!Thzy zMS7pq@zvXMjMu!%V$+tu(qJtd(dWbEHibjK_p|=)Roq(!;pg>oLZ7H9z^}}PhpT7O zoqhvXba#SUZEu|KlP?I`;zwGbew39H&TpitmOV{a|_ z2lrtpyTq5D3J0}Oc3Akle9Ez5z7Rvt`G5D9@^|x{V7UChdT!?F3#Oi6(H6}<>))oLZu|*;rb+|P?a#%P(xFV9GBTnb4Zx?< zL-_aGO4ur1hXaEJQp@<`hG zWxl_Sg(YKP+URg-kDWzXpTXSWA!RNI#DxC4joE|qoos#6Ye?)FSmE^15w?)#(;77R zw;|T})~f`y-*qtYoz38z>xV19XYpGN8t5az(QXoZ!c1 z(v0nMWZi};_;U9tOzmmqp&QIGDZ2u#JdO)?>DHlhUx;w!&sF$)sWP6asKe&av%Ghs zDi%zBg&sCLm}t8OlYU%Ao8ra6$vGcb!G<&(j*eoHYZ};L$ulT}?3i^8* zr3kFDJK3F^{qY7$RJ^fRd)ercfMq5UnJ2ZGXo=wU-LxLa$L-~ zi8XU>3)0=BQOmv?R|d85>OJJWitxsA2}QPHq!gSX{nHu?Vx)f@hBu@ykxq0F`|pc7 z7({17Klf-pDTx@im6!2Rk0bw5td8eh8nMXb0o#3b0=(#u$IGEXe8dTP6vci<`+Mc0 zUpxGv!NLdqG?G}$2xr*8VjiNA9tVr@GK_P7^zHLU}>NeDEiR-v4X3yF(*3$}AP8 zr72?QWDVSKDjTo-rYx0Ed3;uV0fS2;*pJ5Ppy4Zx4fTOs@wX8!7%3yXXRHCwcMOA# z$(A_2ZZkj7IUhzf6Vp|{(`MR9P1xRc7QBcvaHBvS6SA_fZ_+$IKbti6gGG4t)KzAe zwiI6M(Zt_Zy}2E6Q}5vu%zaZUy7$@~OJ6An&E)~IE4IKd0cDCc#_(>+Kv|~ajdq9g z1*Z0XFvmd*`NlAQ)tS7=qy@b;xBc&p!^=Lg}Vi($)NVq2sgKT@rOsZLY1Ts=4{KealN|`?hYf}X@EEwcIac)zEsQ> zlM}gZGs0MjOPF#@8L~goGXv!qv$ByVWvgRxNCW1TFJxCuas^^z_WbolI=@!Hp?P0$ zu38RXUcD9Wj`qRA<#SlvIxDokUx+2wd<9ZU^?1l)gRpjuHQJ`C;M}Lh$a9bL$B9~a z^Jp`coJnT)mGmIyN;mXkZRjS<)@?$68B z2V?Dme9YT)p4kW9fRl?oagSdWUot}vKfkZUBcoTAzZt5AZ#Uk=X)(jW-l73M=AFhX zN3ZjW2rU#pCN6YNGh>+LN}5}c!(DexB7;7`-N!X1>sQz)m7BFR@cZABZOQl*OfCHru@(jiu6 zq6p8p4Dq|7`IM0hK%2BH|F7Y8J1LWL`%mZ^yM#X_pWVRdY>f80Qoit*F;+defrDDj zVfG*ue0{1G^U`kf1;jZRY1D@5pCy=R?mbo;@UIWg8MGBFkCJD<*pN$+|HaFf=C~q9 zb|=UWeykNkgUBg-kMtngSzW?+)Bh7(wy#6Sto)sWd;&xlHaeQaOzwtZFDc#3hSsRS>~e1GA#!}=`l@AX^-VMl`Qem z#5~;bOovU|Pv5B{Sy0s+#eFD)(n_-kA89%8MWlOlnRE+N_C90|p_8EJkUSO)3*xKq z%H!!f4kML(P|_-iZB-y1PRB-6c^Sc79gHwpA{_s`q=v85PSJ$fSgNV|W*uzE~39{_?W_Mlwwub$Ul(8Q@1#e^|+zijpdEP_oVh)u2T z#OECxid#zxF!;6%d_JLx{ZD73<;7|~e4P@GJYRqpH;iOo+O%N8lqML~M7^lK63&c% zgyPOgJXS{wJHCkti$>jJ+otP-Ta(7$K3q>?G3=!p?)~9Q`J(BR=c&0wXl1L2s*^QQ zS1%i(?ihEcUh?3;BHU)Nm%Z|u1&_EijyWI1FYHpnHu1;!`}qQ{t54n&+EvaSCI_Fx ztigM@CAKc!%%7}X3?rzXAD+``6R|-PMovEii=Q9jg+fi@sbryd$vi%~Qxzp>-j_5j zV=B3B0JfTcIj$L>l+csz^7jmDMHh>#aLx~9;eO(wZgScVLub%FzbA&**t@`B8OlM< z$`^EIJb-iCS7OBNSA0T*25E3IF)QtjXuXjZ!Y$fs@y{&E_7?324q#+e2`}HEji0{0 z!5HTyHWJZ0;63>Yqqn>ARm)vqi~hfQ?xSjqM?Evpx2%qzw9-PQ$Jwa6aS;2as}Jk{ zT!jHoqPR6_*}i?OMzL-4c!`@fR=#{gTKQ6@N4eMwFA_7sJ&5NR?*MZJZ=BbqEt(eZ z0>-zc5oO#=qd8xmyo6h{ zaaVuJ&2;<5g0m*V;dgpyG-n+*9=;O_lmLc9w8{zfxt?sYzw?w&)^8?buVA~wxc9u+=!tKyfZHn=RyuUzwOg-+^^c2br8jj-{Rj_7U5$Z+6@z~`?IO6#uyge_AHTxRC z=h*i!;7}yrMP85lhm5Jf(6{FWpQCF~ z|3Q@S?&x?lrTuHvhz@Ld(8--X(=80UY0nbH9$6`YOQkgJhogAmgT>HEy|-5XLQz1* zE!d&E1T7bccn#3a^dr5G)>q3bZfFy4OoR!+dhnRo3qyX_;DhP6`Sb6ZIPMyGId}AD zmM0!CPo?6&`oODcJ7C^^%0Rzo$VZmCfJC@AmUTO_&;5Mh*zF(SesMexTW5kzr!V7W zI4o$La|5O42MW~}ti%PR$9DZ$jk8SSd0nX{KJjeBC)xpQ&PNT{Z}tZ!hwtHnV>{q* zpf^66b4|3l(FI0P-5xh0lG#3`JEnLFcAQ(tKXsYmubpM6w62_`kv`thx4@i-?!z@Gn*dxb*pb>`Qpb_^L^e zN!i90?kLA#|tZ@K;BXlbqccZKxq}fS*L_|3JY*-_(--Y%LsC&KZYG9(L6+zbU}9? zqSV7gelk=BXBl+jk8M}kgl>J%A&=-4+Ynx$>;j8xh!s4lr+oar$G9YLwXnUO7^PP< z$+w%0n^fYs7ikN(|0?`jlXdscf}SX8%vln|o70uBs`wGwBrV|LEjsA$8e zF$@%J%yIfjZ+>-&3%F}}qwT3qn;AZuu;gVtoVpXs-RT+5a?HY0n~AS-O9@p!UcjlR zi`XQ|Ww7fd?WeA9@a_m3i8x^X6PabJtJ?9{;}P373-(Zj6zn!x7jepHMq;eY(~ z@P1PV{&04+8Q)8u7ur9cNK|LXX{J-$nSu|NUgKX{v@m`k?L*!eF~`aJuyynmaHxyq zZz|MK>wXOmuXX0uJ-WC^xdUxSma!vaheOpe;>Icj@y1~?s4z@iSP_ygIwFdwZY5dK>dgNuW?;yM+4l2wiV|22thC+gtG z9pw8E|H@WmGN^rTh}Xru_^Ea`(4l?B{7d36&S(={x%!>h;*RB}^#3(WJ`Z`ZEJ)<2 zp(f3_KS>ulrj>kxD)ksyzkp4M&k$_f9>gZu{t!8vC}M0&H?}!taQ)v3aNI%%Wfg;Y zb>v7??JUNdZd(Pf?dq{qY_0Gb@#}A{piCd_LR4)$#)m{{qGufCi!DxI?xT(1@VfV~ zBQcUIK9ywn8O;IZhYl_w*C?Pc~)W ztUt1M<6GhR2&sxaYhB^XDK8vyN`ns`V1ivO>1gx)4$G{hjDV_hxX`_gdr$_J+t3O$ zHpvsrGq1(Ox=7*7(Wfw=lGurk&v2~e3;txe0=mR^VRm>FEBdAkJ9kN=a|zYtRj%;v zxEEHBDHMfxZiW`kpKv;U2`{(T#;VY4Ozpi=K5djb-f=F*rf?0|eNGLFvup6;xZ7Ow zi8khUx1sB${w&MxF`L&{^!Hww6(WOHJH>@nq|5bFbb~*n-~NA1{`p)D11Futyiu*( zBzr98(M%CX8Mt~5H&I14Ko}FU0w*t3!I+cPC?^-sKTnazUgg_ZW4D$$+|z+=WBTFZ zrICE0gAC@+78hE*q)esdZtyUbc8T*N+5KJv^u3sj4#yXA6(tLt)LV+{Mwhd<%mIq6HY)X{Bf9lkl!Bv}7Q4?EU&;;95D$XP|+*wjy$y1J7` zTvkI*JvpJ}j&$ZjI{6i!Rq$*6KECd>F(w41Q7*PB6Pjy7?~E*XNLj9LH&G_kghEWa zV9!mL8ly(uLwqd$isk4}hO1RFD95++5PG)1cD=()Jzo-+KH19K zf{6)m_ZfETFX72T@`I3e>xQxzq`8fNQ*%t|JG+tZIW()-ep?ityIH`SmrLTwhHp6OU>o0h(jCSu@y7Fa)LHB%BYawxj9CrU z-1V(4sx;=HYLhXuzhDG1A(emifgdRUt|#Rx_U^Igc8`@%=l5M?zq486+z~K-260jb z2l2KQGPv-7n6ThLs_1#VJ5-r{$VOnSpwg*YF0%%6?;KWrgsi)ev>9y?E6Z(xPMx5EgmN5R7+N z0bjLz@JEF>EE{8pqqisFd|esQ%QAiJcketNt(1k&Th-D0ULo$&so|F1#98`s6A$z( zV7>Mi1)qlP`K!%#>yk&?R~@*!Cxu^GsfJ4)N(dB=j|m0?MQ4sLuA%$InZpjBfU z&bL}2uq}IxYd>uf^8Mqng}yKO2KkiHc7zAgElz214UV30njJJ51l6+Lu!(w@o8}7m zPS}ZmemHZxr)p?DTSmCMUK>Q7X7D!J8q@D>;RSgnI7c-dmkv*5Yc-qTwVEehGO6Zr z_boAMT|LH`dY3z!>7og1#NNb_FiYqK0n8eMk1XRp5h^IR{Ue4ZYO||dAK4rJ0}zP3a%!0%|P#3x(`GM zmwh{d=ijKKqu*1!9rK*aJ(0(<>m3;47r{2oRD<>kX*AM`=IJfV!930jXSfuK?ic!k z>$o3(_aT!fYU9=VOf+?`C=Vnp^zxBq_~x<>%($n4SwXcp#pMpakgS7K{a*duX^-!H z%8qsv{k=;r+9ZodqWcLCbmZ{v9Cvu??TzopII+xrH2V%Xi7qo+IomY>8*}TiIwwgW zB>#lw*KI;Ox#j3c@4oxsO3ZLP$*pfG;DR5`=>IC~3I zvt;08)GB!GFopKfYq%A?yMDp)!b+cMj9GWHrpjJWO!&!nelozAF-h3w`Hh&IM)=Gl zAGK6pu}`n1QLZ|Ttc7jd&qD)ezN$gj?Y9Jv3#&o4BN0bLpXR5oYha#=obck&boR$s z8Wf`FF1RIz4+=8I6)h<^evb+}bXyyiZ^{I-eNo)uq$-ZykdF!tc6@B-AlzGjk9?6Y zS%DQm@hdsZeH6$iWhr9HeabefFBTaP17l^6oNz%8K;I+se@!EuhG!(7G1LSXhNa^4 zx!$b*p-rGVP7;rO3gfU<1{KK^}#=XDXA^Xo;t*A>l{ES(1f`=tN+)>X5V@OI^GY>Sx7 zmq;pN=Hd?WPyJ@+Ka7P7mKNB)kF+I59?(ZOxZ&DwZ4S@Yg77~lVfT@P{J4TP%1LLS z*IWmFNJL=i>jj$czp}Y#G*!X@{M0MaUiU59r5nJAXU=fL zK!_?StGPqD2gHA&OkUXnfvU$AVm^EaiMT-iem?Er7G|Jv*lUsT7d>=PF2^l~J?vvp z0}P-Vt|NVs4|}YS(lM{m_=<~-MP>jL)y+ZstgFmrqZID7{Eh;h*E~UP6$H;9Z$i5| z+j-Im2X9HD%5!au3g?F#8ZA3|*XrlaIym8Y6ui z7)4sv>7gt^dpT4tAAlwrp?sV!-K_Pmpwf(b(V{W5t1@fCoT}&Sm)KM=qfDR~DI2(L zrxGS#>o3%-nI?GKv zD|vRe0v>u>hM7BU*{GEj0=d9_>_&hLm!`~XuiG8?L?e~!DQn^(PZ^=l>Mqv2m9jGj zYU8?3$710;DQ_1`QRZ&82P>em-TZmZ`-1Wq8klZ5-<`*+J1w`*o&kAXyfa1cfymt z*_hB3Ch%YUi3Q0%1Ao{475U*Fu)Np{rQd1rsr4qfvoIA8d}wARV>iI#m;ErOd;)*y zH5^wOG!x_Hir`&V4bD5WTj=pU4mVv?#q45Y3-o`)J(lc*fXlP7>PV+xg^C7Pg-YY& z?@`=!g$KmYj!P}1 zD;h1AVD&mLnP^xs^jkQvBF4;$7ck9T?^zuFginjU^Y&W?xIOV49`frE{jwj1 z`&M(jrqRPjmfnIbo5-&^G@Ew?Yoe7+4L(=8C9u=J0Rgrt=-79bm(^)vvZ}1mJ|>NM zz8wgaij+YzI+~9p7V!_WWb9T^W_47@jsU8rE)pFC8UJ&V5-sNwpLl{n)> zJuCUbK+j4Jg_!}=|L=gt8ME=OrJ+c&RtL+PV`?z}c6w>Gwx+=^@70Ad`aj z3pcVUjhkT8kN$u6*gL#PE9jAj&llen&HAK zeKxwa&#+Oo^MG-IsR4&Qdbqjj_KQt)85HOvI88r5-$Q834B54h1n-j+8#<+U-y2ps1m+;Lw9 z4@}TTkMaNNcHjgDFq}0Ij}8pvoBI^;nq4#Y4szh*_Ur%&x!G6{>&8Y2$3Uv38735a z@%B0oxGny#R>!Al!4Q>`u=C3SK4gpz&S^}?sKpLkjB;KUnrh;I)w)ckpC>%qqJ^t# zHuH<5*S$Qh375XE5DkeA1W)bRxN}rAdvxCg%q49xX_hB1!nNRQ;*HAA1%m0h0noqy zZ&*DtjH}jZqvg_coUp4+)XD?k&;+{WOHtO(y_;Yr6@kXG7x>u0dbsQCORRHQU~@<- z2+H@-@9z8+CbXa)O5;1;5xnLj{MN$ih2+;$(qQ8k>;R9HUoifdCZ9?DgQr+7Du$Y{ zy3`4BV=DSG=S20@3fzJ*j)_Tn?th35sJBr5;ubbYP`XK(mLl*B3>c!Z^ zB$1~-WzEptb83AG8?$sL)aUfV?&qDNv!4xdkj{CuITyy1j=94Si2;8ZtsYNQaGG@m zUX8gavJ6tj@nf1X%JL&qTK8Bb)0`v!Dp}g3+v2m1+wJXNuj%;@c;=}HO2^E z=AFZ8MQPEL7!!OrumGQm6d-Oo@l5K=@ccC5U~X{P1i#v(;KA+71oO)8W31IiVSL0${3Xyr$H~{RlgG0Sb*8XRvm0_< zBYD>M02rNOhyE4CqOxu+TtAO`Y&{*2TsIj0^Bsd_}q@(VbGA%*Z9 z56o46~sucqh0R)lx%9pi7QUbW4>gZKPAnY5%KBwYUkiEAQw zCuIfRy6_9V6`gqhA8TRE3vaww8_D8a4N>iW0;-;I;$|9p*!?UML$77CC&aHlbnF&h z|1JZ5cLJej!E6kU+rej29+AI;r0|31L}qIAiRH}y0YPWK@&4BgaVMU`x6^w>em9Nr z_xOAiJNSytDi4AvV#w+x&E+p-wQ$q-YdB84Q4p79f_>ZH;m=76z*0L97H~UM**=Zu zkJZNGu`45waryov^!ud5T>bT6B4+-*Gq#pcu2V-P9`Dz{ zB!*4}r?0ZuT^+!EOM@VJlO2k#8Hl_l=;1{n=p{-D6DAx;PnM z@7>5Yt=R(Vo&B*=aTi}690)E+wL)rvfj2?pC( zJ8ZR{VYBJOI?!6=g?*~d{Nr9zT>mQ>uk8|ptWl&zQO&`$>(}`K%3%@Pp@D0YjtVSx znnS0>19&AF#lLJ&q1?zO^vgfZ&DI6O#}Yf-XET@$9BK~ERph6x4&=3GJfZ24*WbRn z&)^nz9-Sv#WG#bY{xruuNJG!jNBAerAo%`(vRc&I1YZ5;1NcxS>7TQhGH~L9$ z8XnHF=Rsk?@P+20w28XRYTX8y>`k`~C0~B&w-V)IHKNfZE}EAc4BO}1Vdm{9c4j;= z&6?=EP`sL-J+dA=-;-9BYIV-UAn07&2bYMC*A_xKcbVzv;_zBjz=EJ5MIB!r5;Daz z4e-8p5B~g`$9Gy9pwyR_IO^R3o1be!VAvZwoHg?bD=(43Lx;ZMkKQ&OaBn?~8%16- z9Sx>>cL%h6{sG!|G`MZfP?Q{Bg4fWR$p;(4o1ii{ZnKB48?K7tr$p!^YsVj5Qo(Jf zo6uDulXbWfGxmiNn%M^NG%Y#oC;k(AJrhM^G^u~{^Ty5nQ`v!Q9+2MB3Y{bGh(g1L zVvJM?7JZ0jo6SAo+Qff5lgJe+c>Yj1dJe1;t#Kn}mrfJjf)~u7a5@w}(Z|nk*YoT$ z4LlSwKv+;XLvSTw1GxX89*k=BUY$X>VfZ=hdpb~5LG{*%dg&3(@~}822*R6*S9{cq z|DeBP*4a|rl{k&flr9joUk_msrM)7gES^9WJ50Q%$SENZAFPlNE~w1`Jel7Y1LnMBU0D@TWYi&sM)gZ77G)NriY&`yjJCO?ita z-@&Nd2rfA_7$*Ojh1PDxqW4jB&%7=p%)71w$94<_moDnVNXvc6)C{#Irl7~jWTqOu z0Y(S>feqR&d^-k%k$^IH-shIt64!r~<5hGYYXMik)V$!Do7B z!#_$3M*G#G>*jFb!>32_M20G^>mkl$(OsIqLSXe-I}C5=5G)DTg5_!h@or-z_gb(X z=AI{B_wzzg^@N>}yyzzkbads?i*)f!a5}Ec6qT3j2E!c-4V3!6jSZSg{>$T6@lH!U zm$X#ICih0viT)rM{*gT6IYl5%c|FF<pC%e%k$nQ5o#DhoXM5|;Io z=GNIau&VY{>Dobb>!fTct+_I=$}Jd%t5F?u+|K>I)KF$qf8mCe6PTFOS5|fZ$KQT? z#9H#4M)bnkl_2UHW{$CN5d)&%Fm3V`=FmOz^b>nNRgdlqjU4T6Ul;s#G{Ye4f3-b6 zKNwmTQBAO$#(&lL=%tQ1$1+7q^QnLMREhT;8`!cKTbQp&{Iz+3eC?AE(9W8Ls}>uGq^24WYg|@% za~Qz6$s6If9kH4#Bl&wT6Fj;r5vA)q+2Hg>u&ZBA|AtR_;>>?pJfFJ8ic&I_v1LXn z;_a_Y?a~rhEvbvIyuG>K(opz1-VRNbXV@G)xDgbopHErh%*U9Up`JxDp4SwEyRo{s z?`RsHthmCT>V<+DvC`J%9~B%pWe&ZX_h4>&1b2`iPs-BL`d@QGlq@Km%k&I#7VUavGfp>l)^0z<&HUL6;? zvD%}Jo;-igBoL;X;+F(3?y}blWL3TK zP|;hPg)Lfe?OYs4TJPtt=jr0F?o_;4IERRqq0p>L8FoW-*|K-u;6c2bO#yyfH$e#( z&8IAf$7Q1Tn(X2ynCWKgz!14i(ynVGdR8I89p8NtqmPZgQpZ5#;C@1uk zlrD}*NF{znt7s18%gmt60}aoqY}b71<&N#b#96sqESKiE)x?wZKl%{c%ktQZNfY3|<4S+;n6jO6=sxH>u3d6Y)U?+d zQkD^WQzw8RPS330QT1 zps0bH;%=1-_$W~x29BsjU3k8>l zv;Nlk7Tw&=j7 ztJcK&vqt|qe?I)W86Mk^jJtA^*npZ_(7M_kqkoI|GT#sg2~x)uj=5#Vf7H<7yNDR1 zrm$xEOszWTxz$KMC}Hn9qq#ojQ^ikPKwn%rszeWyB; zah|A&EpAprV^otIG$~$e?w_6I=tc>I#MP9ITFEQ=k7K(nKzXLL#oY4FGWxgkGBh;??4aq~4 z%Ec=6@lMJm{FbK$E*8XC>tBh!@eSPXC3#nOH)3|*2Z8P4cBbZ91gb*@R=hc-j1NYM z2}`T9`PZA?AWES3OWm1WSicsw?P&w8up#_X@mB12tiN#Dk~@N_^*3?JMIT|~v&HC7 zyycc(WjJl(F+Q_g1>enU#3NCw*sdmHczom!?Ls2>{eyBC6aEd`zdP`p6+YlH)&~{F zMX~i`1L3&oPx$7NEJ{=vjxRM!@lkC#yNNWbc~{}C(qpA>gH&+sw+4)yBm>*CLSgvN zSvYe0c3wn&q9`db;e?H&*juL`titpM{Cx6_s}Bi=!Rr6&d_n1OjH@rjRS6&2F9B`^Nt*>DWR+p`$#_F zh6&dAC8F#+B{tby52oEo1BIcH{6L%nKD=6ll93f`!)#k*-fEZP`*N{;Ko0p3fN?2KTSp;j_#cHVgZ_fV^~gu-uu)4mU@` z=43pPB?e{3bWwUz8opeAg)g9exYncsoD(~W-G6NX9;5F=erhE5NTD6_QqsLYIl(Pv zhJo=1J8VuF%mNz*gD6xT3l;=(l~vx*J>DA+Jo{Qc=~yFvZ?P8+JUk~x58@P+ zALG`PL1r)_7mHTxVJc1wLC57^-(I$#@_laAVa)Cs{1W|q$&YsA^IgVb=TC+W-KIEG z#haUL@rFLyCr9?YwXwXQ1zE<&AYOVOpF_J5b^EU{a9W%w(VEyQcpkOA3)$Yj+puL@ z1a=wR<7bHj(3M_?68lO;&uhcM;E^3p2#jW%PAq|h_ckCAnePNd~y^q}mf`WQ~ z(9Qb@(@eMVIqG^SX_Jb>OIk&{&51+%umB%KcQVU~1JUnRHVz-##^1T>W5dhGcpz_{ zO-hyu9)Iy0*Rn2tEXWrwR(qpHsRmo8WrkPgC;r`mTRt$uZHamK>$*9M-(w1&i$w5t zTqKtv4dd_E9H;!4&7Y1_Ctcqyls%Ne);^yEwr@$V*&f7qnaiR4zR%bic}Db5;0xW6 zq%m+!WfPbgcJ564d*3uBzQ|^$bS&}S$>xczgAdyV;OMSUzMtmhfVCyW!@Mra&(cQO z%lA;};cF%VcA)t{4-L9J`9>p644x|?{Np-RaN?~mNRj8|h^qu(kuf&)o<;2i14TtM z%<$~MJd}`@hx_Zp=*Fmlc5}?RJ>6$DA6-Iip^!C~To$ak8umBa-B3Cl2A`jW{G}pS zn@oGYjDEsJ@SI7Q>Vjk??Ng+K_$=ZuH_@%iz13B4>ObloBwU42^qi&~QAerOIoOwW zh)=E}zp{QI#;6`-T{DJ2dUqErua4xuhlj(Pj#)T8zgRR|%LtuyWQC7?b)n+v5RhV) z=$NsATUODot}hX@V-lH?^IaG<#skapukeI8D{NJ+!KM_?@~gv*@Z{JVsI$--KK0fD z80<&8c^CPsE8$RHZ--Y)!vvinUs(R8J8%qsbCXk>p@eoX*Y|7k1@abXhsl_2+r*v` z4|9v~EXIFtF-E|lCFLpwW>dQQ7vpx>UOZ&TfS&?FZHgAft z++GV3N2sD)NeKpMU*ipLR8YgV9v|d%3mVEhS-4CQ=&22?hzO_b;PxKMi%Q`VzP>QG zgmS)?IHS{o_vQZ81do-fe>s9R8 zT~j!i{s(r~MDX1o74X2C@0j{-F5lNq&kQm2OdTmJ$J-bMMQ5?Uz==yu7=oi_7h=+w zOYC>EE)L4A#u2aMN=<}_(gN;5i#L4x6#buKrida z{r-3NGJpF{D4qTlv}a8b#lISgnX1KT+WnTzh--$)23zo~aXNSDR>OezWw>TpwczU5 za9I6i7T$E3#^0ML~a8+l3r)@+c&p+=E>J$>IpH4{;4y%O`jU?N)PQUhhS>5oD$01Exd_)wU12e9v*1~-EGCW#>M}p*qvbznBxZK$Jz<5>2APGiV=PRr0qd zkNwXLDo<^$~;SvuQVas*WYlA*!PEW<_QHOc!VGaB;J_kjAcC#*- zMKEc$6i&Vsz)NN;Bd}ULv|&20BZgSj=1%N6DhBHgjfdcS`nXlFio1kvflBhHOqG0R z^Yg4Wq+K}*@4I7o)M|Y^V3bPt={fu&Wuu&xJC7+rg{*1KW+*tMiIej-la^8$Yx-*N z(3BF9C23-PDZ|26#sEYWE8*}~A#$s=Ji^N#x~Qjm{NAH<>cxxw-|`Kg z{o!dY-5DD-Ske?T^jAHH_q{54u8jo-?asrWAI+Jziy6FpP!7rUv^O|RFi^!yxT}3C zpLA3UHD5NP_oXbR5;_I$_$mF>b&pY3z?lV~F|_WC=;SMZ;=p)g=iyX#F~S_jFG$35 zJ#qX#v9>O6NJpvPJJ|!hjj)Plp9ITr-aejui_b2h@7-!qVz)X@8Q)0Q+2?G9;T$-z zQ4hDodh%l)syMv97jxMZL96dpI7HsA-CHGK^P3&8J^nK+_&T>-;(#UYd~*S7suZAx z_A|>=a&a|fG42pIrJg~V_9}1BA7rz441s~C-U5%0;M;_XsDJ1& zX8)SOCw?+QaVZ($ptU;io$|B7ZHHsF;}*U>#)9&_lQ3~;5)0_^0vV%UaC7rQZf~uF zsZtm4mi*juKe{pbC*44k&(?5s)eVr@zYn8s74Wq-lowk13f%%#SW0#eyO`Gu#h$%< z%v^s6QzR}yohEmaw?ygYB%H3<#5z~{LGWfVJTQ0y|1sAJJMUNHWK_ z@f^^33^4?h>acrjJ%3oBhUeQ`(dzv!ro4f4q+(L|%p{U`KHLK5$@`Nrr%3epS|GT2 zeubmrOSsn@eN-5bijj3?<$LBD;UuL?Se2;-U0$kaW_%ePbE~*N%~NBkS621u7W^94 z&06*p!Rxqz6=U_~>E8PZYd0qGZk;8 z6AU?W6Mwg^7j{}KAlP{{v2w{zMaL$FHXGuuoZ@y7h%MT%dFX1595es9V#DJ`aFqz z%HH*OF-96T->-)|<)=|4=qhifEE0d~e!|(S$FK#eV({h2cbFpjM%n1ZEGlgU#|^_p z0ZN1L=${O1^LfmMmfe6qZ#{A5(sMkN?h%?Yr5KxDDX6-shR+pVq1mse{Ps9a^q|~W z>%Mq)PemD4*UI6E6Omlmav1I)cF^S}btXN;0QP-NfeaSGUsG0*eq$Cs89;TLes^y@ ziqQ6c1*@J${H0nMjBek_+liO;R^>5qSF%O7kCB@!g^I?D(8V@UUkU-eax&3fA@gEBPbN|)t$O=^)6;p>#Bu{Xi-+I^-+>OJ3UuS>541*jI%~Ue97y7vkQk6-o z@A$2JSnD(Fsa+&=Bwyo%o%*OLnS#j~|M4r|w9wo>7w->@pq%ZcXbUF2##nVl9_+8V#+V4|p+hG*x2`5Z@XVWa93%1Qip+~Tfe>c#_ z=PooC@3rHz%uG@7d(%DyBLT+_y%Z`(0vq5=45 zEC$&Rq1c&M zJl&CYUz;D`jgR&=$zf`E$@dpJMRoF9J9dC_nm1Z?X|N}`<~T+B9KLR-uBAu{#_az*qXUl)MXk$()@q6EAGQ}Pn81_^VbrJ)4%uofK zaOneX7C$ZO^0UB#`{(H9636}XjBvGjI{tdIlTDqv5&B#PVC$GLK6IKYswo%a&tX-f z+X`Cv`DG(oD!yR833L8O(s_sF+`eI4N@(v=X_tmVMo7?|Gf)`JvI@4bhUah(Deq?((+nr0q4B zq;y*#^M`rlah@_>2_5>sf}TnVJHFABLU$Tqi{%!+p;I8G`?pdLon*JRp5?HO zn<%Y2ZGi#T_3>ED>K?21ahZlbbW8G~cMOe2BDd!+GsW zOH7`wB<=a$ko*pde%ibCkjr1iPoK5Js6X+jw@6^Nf6A%acM_UM=I{d1Ega^RfkP9$ z3v9Kt@lxzg@jXmvqQ-4H61hwCYF^+qUG*{jc_SRJYO%n%EsPFTQcs&7eD^>0cgLn8hYKXNovwcaO;Dgv@UEP672*p zV|NLb46NWao%FHmMkAgb3}KTiOv%f$BSwg9(bSAhH1D}!ww}ExlNVi)QqQk~xj2PK z=9^$;=OkP-DJXcp#SjzDXW-=*P3pKx8&ii|LfDV1JW0H6JN$3s{-ckQ-?<;y{L%kr z_3sI)h#&bL?RhL$7a24pD@jkZd}TL>E)gEkr?g|9EieAz1dUFYaB9SU$w+Cr_zW+R zPPQM9ec~O|8JK35j8=M_Ep<`%Q$eNh{^ni(6uui zVYR@AA57N(Sw29`#dKNyL|dE*R+HWsIheZZZ=y=kPgU15f-B@&Bi11XJ8mvwWpf^o z_2vcee)5d3St$4;s%Z$iTqz3^eJOvm^6+443w!H2hp45?-}`2m@KzZtYR1v%7jAuu zHc_9SVn_8E&zD`Y#Wan0__q9EQ%y|JenBGYB!&D@u0Hhkqzj$4JIi%&pb^D2)GH&5 zhboBoZd!@hCy(%+=Ty-WTZa>6vNU@UFgs9}(HW z%8fTMYi5pY%?Kkn2EN23QxlqVZ8447B}L1XMLgztAh{{El4;u(KI5PX1~2+Iljm&j ziZgy$SQz}0DF|+eT)zPP`I5porxW%J3mnyv-V;kDbC`xr02`*aBzO zlhMn|kFCpHLF)ytB(g1#|N5YfA(|I4ckVUW;dTZXbf6qd9zJ5$okmfqn9n}%7jf^O z#;ETnFEy)nml*h4VMp{yj8^U_`})fU4@}OWdA>3^9XCMg+cc>AaK29TSRYz&4z6R| z*x7De(q-^J-6Qp+CamS|W1jj6?tN4ldg8sy3Ax24?J}bK5jUBJnu`cuYC<^|N@$hNc5JN9;N}N(L>}QWo))XI;{RHiL$BM^mj8_# zZcv7MguHa1QZj!v(E+x-62!k#&1%1`r|B)fC^fwwH=oo8QQb@N;o@b|wljWF z9g1;lv-r_k6Ff*s!0pHR1rNU)Au2ZmZ=AL0h+u+`ethx&Sq5$)*eG>ow-A2im1OPm z&+NF%MS3W>559xcz;C>T{gW83^Pli6C3cebJ@ttN*$2|8_^+f~;=-FASi|;H8XQhU zO16(E$2ZSK(&5|3LTkMiwhTHix)k>ExhsVpWmtme&9hj@Bzwy4@Nbvy`%OjU>|f*I zLl5p>t&J~Bm8E)9geRqsHD-@Kg~0GJe8UAxgj`BNllK{ReMm3y40<0;laurBz0pU6 zZ#fpe?M#*f%LN1ADE8JDh}*XbzLqLTCDj9%)((04Z1!)LK7MgFJ)U@%48yEt#uqKo zGbaUoZ$DtAB4;DNClON(pYz39M&jNgL$!0U#8|fr1}NReSc5?{EI}RNDtE>6VHKY! z{3ZvNyhX#GJ#5S^EqW-pL}3R*`GR*&cq#mxUK4d$S%x|FJ)J~Hq~YAs)c|%IQlX(Y zn6F%=DR{zJc(LO$i**`JFUysoxQWPLX+P^uR+?O=&+ijIt!QqCYzZ zo8lKU*Y^$d_`*VDUwO_~+!V94Aq7|O-j=Cb7zkEEE_(77w)wyLq!9COKF=NPh=7iX zXm~G2uRfT<_(B3|+86R)8ir_|nvRLB-C5^ejm2(&s3(1C7JjeQzWnof6)YShFYT5dA^X(R6eSPiamO@@pAIqF8o(dV6B_c@tMFmR+Aqn5q&AlgPA;V{)|)Uk<0hY6q=WT3MVRWCD_gck6{p5l z;Zm3yna*5F3j}(!XX-+sTZ-I)i;8q;zS9aD#AFkcHzjgo(Ie~ku?)4_+}-*Z-onO;15){1HGE&MgH5Vm1+(Wl zFW;eucJeCH)}>j@QhOCS**~Mk-Aa6%_OxWo6c62tS;IH>@*BikL>u?Uc zrZRq8_$&r=DaV-P(=6d2(dR%lSl4Xk^ArW&;qqI|op)RoD|!h$bX2ADgFMKgC4lbt z{Y-Yvjk0YXcKG^MWPA|Bf?QV9C{;!59kY#xztzG4#dCN%zfd;xvNjAdZouGFEwjGv zP5<9rHd)N)k4D=f{*{t+Z^S5xzNNM3Mm>SHGm5g0Kg`i-brM#)DUzag7mU1@3iX{b zzExx>PF3e%*jRCg^)8pJo3@=L7Ixx~0|eK5++9?RJ;vJ|RmG>g=D+*%_KgtW3N229zj z&I0e?CE7}1GTJe8%>2Vjkz~SRb%scvwS6u9mMYa{V zR?H=yC8bz0YLj$S-5%5n?%w5`YdBb3#OGX7NA#5%JagK}-c7Tl$#)e0-WHcwDx-Cw zoOHe6P~LslQhM>|F}Y$0ztGMU)wAPapOaTWYR0haepY06H7T-G7oS2dq9yk#A0DZP zhpTSk<+9h3tASscbIJv36DeHpW>PYg0<9BMf%+8JKHF38K3MAq1E&$ z&zvsUWa4>Wb4R%3XQuEPUCxH7_8#6tu#K*cEXD1}IZQjeJM|m)hyI_nS-4gWW#+FD z73;yz3m;C|PGxCrqA886nM=XpcWL&s-7-rROUNQlWA%(Q=CaulTC?w9#>DviWxvH9 zl64(ldn-_G=udilUwEr}H1XI-!T4+Zh;>WtnD#RT>hIV}MIBoC`c`W^$UcddC!b^? zQ!U_HorM3E-DA0@m(q<-?QwcbUmg@`g3gXtFynoR#8h~grPdYL73NCEMQ&PkbR7)F zSMdxJHJm*B3ht|SvzasXh~HDjFO6_Mttgmu)xOj9pjnayPL>pPA&FeJhx50i4McBx zG9IQ&xs%A3t>j|g8+e0RKN>@;)+j?!YYW#GcbNs9>mYMUk?lS&*xAEgV|{=HrI zTagcqUf#^_TynzIPKh}Fdlh@#ZavvLe5ZsxoA^d=15A37jP{=^WSVwHxXSYp8vdP) ztY1h*BfI?V1GHgX;ZgqrOR5{)Jd%CsI~#%PPF1X{=%|18xSe!K`U}2;_rRO?iK5rN zJ;kpv!_MpRNOj}<_FyBF>HeGHcNaTS@4PBn?-9zScSPUj%d1Gcv!7SJ(nM#2I+3k9 z&)zHaCYPC_KVtJ{uD3`TCq}lDTBU}{UZqqb_T6BqcUJ}6&@sa>p&woo+Lz}-WBkAw zT)rR5&Q*#$+S87}&8azMH z@6Q|gm;Hjl9Ttae!B1p^=9t3TH50K%n%H5H_3%$l!^Gjwc}%~qxMW?4_IHN3y}w@! zvv*NabA46p5xUu%J)f}T>wo;9(4QN>C`;u+ve>7gXIBzW2&=*$T$&r_6L zTV#c=t54(H(2mrmV~BuRskl8x#_NO!WNdQ|rewRbk4=K*x3Lz3yC3EDv;1hoe_k-lNNB%tgzYU0L8?R%TUR{U08o|=LVGxl&@q48=h zJcseQyIF1rXUfce{nz7tTCf}(a)xpz*BbEV_!xLz8tDxF53)oV%kZ_SwG_iJ6&Nq=Qbt| zxFShRt3=O2KdF~e6n1pghH24N$aIQ$N}G)>BhFz@ye@^C3x?pfEF>ir@ZQOK z2-#SK;^obfYn{I_^|k+IxO|Zs{>Wb9dBsWou37X$E?1IP3=&-j)%R%r@DZ50BwlkoX`m?UUjIaYL^C+)Lp6ui>3ai?20HdgNDdo+b^HsO}=7|deR+IJ_9429ew9C&1haa3k?u^mAFxnay&L(4LZ8|IaB5o)@ z3Nd8j!F-wE>uId|H_!JyDxt#*4|e{wEknu-+4Z&ljuzL zctXaCjp&{3=v{0Lv#eZ~s`M_VPf^9%%6UHR|L@ua6Co_fTiceEB8+sTTqsGp`;P2qgM zjo?O2O2LMH?z}){Gnt6YYPOphJGg!w+ztlV=}IoiGAC2F>Oo{ z9awB7w>xTtyu@cXpZC=5Q@_om_|Xe$?<<+{8Np#Zry#95`j%JE=qY$RNzk>FC+o(I zB)91&&GFUd)*p=UVtG1d&UR!k2KFG0#doOlyfD6BbZx&LUxImNZb%frK@*ZaDa9>yj`#Ue#imbsjXN(zC>KF5yq>06@ z9i)qrLnIrkjOj*j6#3aj^0Bvl>13~;q~UWy=451yQiU{Z&CX`kn$>t@Ugxy5ho z(ME@HS1@VBd0BpU4Xoc)iIJiM{CUXBq6TP6hLBdaa2rk== z&eHnkv&0u{DyuGlE7l0Vddnu2U`BTzHFDx8&#LaiJ4Ll={ zu3* zYoZ&?8zo-T;cNJq_KxsOh(*D-IJV)JKZP&)L$f|l-t<)2` zm89037&0^1)=lly@o#Xg}U)^CA z6N@1|Dp}_bzLYrjCpoR?$Hx{qpl{F1kc-ZcxFl4=J;6`v(=!SQ!v8o^>pCW;74zX9 z!aH>E4&oMXU}SGjt};2y-xI_Qo0O4h_Y31K+__$7ML7Fx79P_EKCibKuII(VeN%41 z&dhFNMv0!Ty&&TxPsVNpvb4fsoTBxMvYB{biog;O%9SLnafBJb! zumo#A%9Op;Aur2E$2+6h9(gBnxzt9F;zD`LaDOTjSvGa;G?`Ad(6Rk6Wwty^PY;G=fLesnC7U^nUGQnbl#7yyD##X zdH&?%Eh}S)OL4(%ui&XN|q(Uf6`s1XSbMQCjO?i zw|nvr6@FyBL=Q(cnn;>;wK3&fA^u$HL5(WH>p1uh=HIK}Vc-2ox!x0fAGAoKb{kQi zOhtJ6Be<)71cfC1qK^LaC0FyTY1#CozuI-z3bDf+5WDwXDL)tEPiH>r0%uIwx;_(V z=OrclSmw|B6>H%8i`!U!EkTyLbSq8i@o!eA`aY!$mlDAhZsw3Wpr=+ec#p+w^Xx6; z;QE`c`)}nvYz%Sp)@j&!RLEXo3mp-e0^7mEL>_+yX$yY#zPMF9eTnGfYJQ3*8=tuS z5&rh29Yj8HRweVv)xxkqd1-9zYra+JC%icZi50(Dz)5r5(~HBz_XT{xQWK07`pKeO zj;y=TMzq>h(K6>y-pfG?edS~**|L{!Y0yN8YZYE^&1B|V`_YTN;#orI*nU$~@OV)h z%=-k(Ue#1#>1C_|W}xTn2zJ1E0VUUU{CjikZJ`C{ zhXrs<8N?48iykeXDwxf0VyoYIlJyO9Ojx>%y9>W@e{Ff`-pfIfw$UcE@N5)09*E?Z z)XgzZWJb&<4&%ElyP{82D((kovl`JktgyZSm)~T{`gPU9AHmG>sZ^tOm$uN1tHZ@! zyM_<`ri1A33ew4jo^0sCt@QoeYdUAPo=3@>3r12bTBkS2w2SRU2WKvhEcn7q=5C>J zqQlC+co<(?Bl;6UMAzYkp>FdZ-@>Jtd!@mxO32UKO3iycG4qof*R?am_2ZqTwGC&P zM!GE$hnzs;dCnh*-kX}saiA?mY=DgeZ79m6?Y5yjt8xqFTZsFFQ>^UsC>7B~Z~^k( z2U%9!P!VWqwA?5xT~JVt3MiIMf4-w6kL_YWpXsOuKe$8 zZ!g}LhyFis^<)fxH@*k@uZ_dzxGLsVw~D^Wf1s^3j(onWGom+MflJ+aNspKsv_<+! z3noXwc9!txrd$!-8aMf&b=tVlB(m_YeArAy8@i&XfJ^N{`7R9=OjZ3MIH|;+xpl;& zW1F$a@d>YJ-as`5;%@s+wV>^WB`R-Zp{Y)X>UM3R9&Ng?y=caBL|!2=FZB9>C`h#%w)tW`h4LLoiORfCmyiG)^qXD zX$XiDgeC%9#!*n5wj)ZhFkafL9hc4#Zf z)_J1#Vyet@kCD)1l%#5-P07)z8}2k7L&xxuTs6xQ11save?>CuT_<>a)_MrnXwG}? zqb~I3TrBC>#@3{kP~wNZ829}g-!UM73cm`Do0#oNQYA{d(?ad%w({uJw%D(J0(;MW zl$8n(ty}*@Xs^G^PQTW}K;hw8YthJ47jL27&vo&;n~7wdlE@}};P~y;gWd=(%&6Jb z*fgMmpAg^EO7T5)DsGXC7vAiNb45l}E}V}X*BfCh5#ua$|9WFad`+anm~j4d|601+ z&>oH34$EFuZ6)PmU3eFmva2V?(28%02zu|sw@lZB!;%VU6vxZHuMDK=$(};<*~uol zOeX8`46WCv^DW#7ku5P8KYtnfnBzz1XaAsWn&R#gY>0D-NjU9XE_45~l}_K%#q-ZY z*~s;kbhBF+qOMeO<(ERkTz(%_p7m~amjdbf50TH^Q^`8Wi(cy+^3w6U-tb*hd*aEg zI9x6lUK^R{W~mU}XkxbK*V}?RUc}`(7q<nLHmkbMp2^y&3m#Cq8VtU!=PFYK%lL2`idF>68g^IV?jw?BcWsZOYv)t6$cZ>VD3uk2 z3Vqlt1KFR#S-Jiqa*O{r+k0)(Mng&gX66jyQ4m_KaG- z(V9onfnnmgHIN>C6T5*VR(5c;A*vm2!u4SsQUlfWK-#UShlSlO zWbUGa=;6kE*r$}TD`RJp{GhHFn!lVYsBNQmMIvu&cEoMPf)IM_^_lk0A6wAW*9Hq3 z6L9QR2STF}veQrFb)U;zzi%Lg_Z1ny^k_-h_c}?;o9#?aRf$)Ko2JXRa{L}IZYwQ; zbUD^ja1(m44gKxtk+Lo{Wt+HPUneMP#$eaIX_BckZevJ}w^SpzD*|?}A@`SZ;C~*< zjzt zt>j;loMC5^fJ)OO;pso+rmR!n;<;g(t3D0AF9Qan0=mp-zD%Dy;U*U2v^y<~+B4q3>E z(xKWN0W?JP*DEBM@spGEaHqKt=BfWla>x8&`JJ-J{BVcDFJ}Ttqo>F?Z|}?_Y_;Jb z7+9U%n%KQRW@vu9AGs?V_^~C{xY#8DcUFW-OeJ^G7PLrudC7R3+Z{k(&I?YW_D7lT zT#={Sm51@_qgiN=UKAevgO1M$<=0~ZX_Ar1?wv@Ly*}R+xlKw^*DzD+zcobM>OYe~ zOq@(9%^Go26EJ;f3fuTjWLib%(f{YX#xs(g@Uq9H!!g9(D-Ur#s^Sr<2HtJmF z35C%z4U$GeA4l$|5I^gU}a->r%(R|S&uqJKNQPcH-7uA+#T)@^*`Ge@Bl zL}TZ04Ho~!hEB#NQu>;3e%#dv-mOW{SP1_AuC~ElGZ1w@kGWM%qWTU0cK8pa>X0rd z#ay3QS*PCH$WG1+b1v;<7u2TGNp-@@%o*HxdOx`D7Ji2AKFmgMo!IX_(x%UA___LZ zq-G^Ay3);MGjoiw>f|N7bot6kJ5`h7l`y=zQN@=Dxnt3`PSWx99VIU>ZKID>URb=f zitSl0y5mmBODo5};c@5s;p}6_h}<6zY>*`GFh+51L@QPE!oBfYu&)4<9uXg#kJ+YP5JPo8? zyL3_dVHj6gYJ>-KZop}eo15z55`2oTMmy#Vh!)bZ63VJH~@+Ea5@40U{tTrjgMtGWIva^abWuOP81vp@&cwYFq=>Y$7!3x>G zg+|TSv)#$H6qP#Gw7V7(ck z6P|GIe#C9EfvxBZJc@5Z3-XD#fqG*+&P?n;txjucmWCV(3^n=V$ew7uUxuN2Q(5Xs z;n_5(fz|sXJUB0izJC^-5(|4W{Za=C823+~X&MklmeF6xZ&b3|p>LH44D*)uO6ZC= zxxzc7@{Lj_+>s5*5k9e5*_bRyX^*r9lKt2>qEjG(8}!kDOWrLw1q|T*+67aO*HNw9Klsdtbpl>4ou;sJe?d@M#j%u_<{jiIM@3(T*k)pUP7Pw z8ha9(oXc1p))I4nM|~X}`ExTzRE6bWn$j6b-kvhp&s-t>6%>iN!jJT0dmh3wInQj+ zM)bo9n3b(z?dIB2xZsX`ZVBecZmQsY-WT-j<;IJ*RMUtGhIy{(+*7kEV%%6nFV%(8 zoHMAc*uhiXMd!xVTy)O`bMwRBN8!B3a-i#WvRkuGy1mO z7LWHI#gJXzT(89nH{Ig!alvVJyha}uPMNrCwLO2=A}s`e$VGZ=8yg&5K^38U;qc-d zmx-K|^B+$<`Mg{5ak(lPKm1Canp*h0kz$9RaTL>5zLR;6w?RMQPg|*7$9|3Kf_IC= zoz6?JiK7j0x{J6CEzOsxiq~hpq71x)6V)En#ZFYgIIf&$9neO6*XOw2u!G$^X-ba^ zlu#gU89xjo=;)=Ezqiqu4{fQ&`rmBt;U_xbA0{SxaWikEvjfc7jxqVyY zI$p4~zr1PW924jW23D}hEZD~Uf>PcV$zFRiTE_R%>h0V4up%p@rNv;zwP9Sby#unN z&tpYP0ZSkEl`?+p#JFqExQghszhaq-#mCRc(q4%U+e*}Zl*h(zfg*jy-dHaBbI-<2%A}-n86KgB-V;9xb2PH z-q9GnCSJ$=%0X_g%}NmvzEe8rW=9--5=;X|d!l@@g#WxIm=ral7ien?d$h>`2Cc^s z*^~2q$~Ji16blM5V!hr74fARa`Dur8O`$_H9zBElzOHPpXkB` z=~#a)PZqjf6E`1RMAzO$ELw9Gsf{y)=exz+w?GHnsS(Sg93+wVZQ*_N2>3DRBUMk#9=$gro(=laqfA-;4xn$$iZGW@#a)Qs2S5$%p3!`}T zAblK=e~Hb{Zn0WdC$jR>h1EB~t92TLcN(c^w|S|=Z$OpkD;goKxneAOY`fz52hsC? zVi)&brjN-T&ti(-4)&wxAliQL4H=e3@WgseI9A+(WBCAHBeDZerLRN|QGukLJZOoM z9kM&G;=RW95jU$ivHv78CzoZUH1)ZVc!zLTH507=n1sO^Lkb$SO_3t}hn}itRPjOu zBP_CDJMlR`Br+x)Qp>U0ssr0QxC4z^TShm=wDO&iYG^s|Mfj*sauqmY#{Ls%b}40s zB9C9M{hbV^_T_^`-^hz|m*BW7U6NE*28TJzq;`9@W8`-&L|o6o6>}Ls?4^&F6RXg@ zoe%rg$DYpb{x{F5mkRpr`he*+1G&_7EoC*|r-09c`3nuPYqg8UotR4n^((tUy*^W9 zxO8aG6+K7?pFvDO9+$X^&c-QusMz&Dk`nlXUGqLe-3;Xm^)xh4CwRwa&Kwf`FnXwc z*-pA~%?qX{dUSP{)zQP97JP^3tLd>Z4p;YuNE$?U_m}hO_~pBUPx-8dybI@`&^C%`OMk95qn!D6aMU}BPM+SpYIryFFp0<1 zW1@@umMv!dx`L^L4(Bg()`8u~JjD9`WS9PwP}u67=-WAi|Mu2}kIHj&_cLdD$W?;DjWF(0>jEcAg!3O=woc|i z|Ai<0?Yt_!Am-=sL_AC;o<$b$9-j-@j+<<0vDkUGDE;*up8ldKW^Xa>UWk?*ju5?D z{a&JKjX90pc7x6+CL?O&RW9q`0{is|i2QF2^Lf36#v8TJM?>+fI&~Q>R&1r4wFWYC zTO-t2W?}vIw`};lavIn(5N%$?{Q7niC}r29VNSi9^@A?Rt7tEM75g zZAV@yR=64#jSJGt{E(X^yrgMps&r&MLB-`=63Zwi6N&hSULr;bXFSl+q(ogK+nk&tq zGbkCZl3;eQcm*XM?}%{KK;B2_E%I|N!h1kJ{z3TqRt8jHk@Pv6r|(UZ>x^JkK2K-} zx;Vb#7m99ek(76|pewHXsN3L3t|z*N{AZkkn%fXQe|I0~wJSh>!y@+7xSULbmY}}* zGM_H)Q-6e}E@MC|DZ1Ey+rjMlY?WE2%?#xQ%E*V`B z&qt28_!f6d?5#Zs?I{msLq^+Ro&H(8=+MMkgkNRL!W7K%ZscnPH>2faA^KDfaFdP~ ztiTPC(iNXNAYHIF-kp7fDYq;6Ocw(fziKD#>z}~Jb##E=h@)@{EZ|-G^`xS8|K_%~ z)Bu(f|IO{UQF?eXHy!r9m+*Pu6jh7Sx7bgzmkY>`BfHsum2DxKRuE ztwKGF-qVQ1s@)~_^Hx*jAumLm=!E-xMlgOJ)v`s>v z75V(gTz%wBN{4r+{%k>7mE^~Upuf8MUx)pjaWC&;q>AtFYO!)=9=kWDC;bvT z`Tu9Q&-+kPH2gsA?k2je5;qEVaJaN%cO%r+cSV+KBHSdq_{c{Fc%XO|zF9k%cMd2< z=Og(a+QD;nh~1%25%d#W_}Tr2SUv3(76&O1@8L=vBTS&Ocs3vJ(HH5WTj0jrME0?R zxMA)8O0TC+;L_VmC|vf1ZZF?=`Mu}^)E|_AFL7OHo2we;%4K1LU?U!q30~^wGQ`&_ zu!vC|>AZD0ZD03|m+w?Xmuv44H0>CFVc;Y(zbAyBzJ$GevyeVZ8px*3g0l)M%nTOn zl2L+{@IySqcFV!rYXy9Nr7nV1$`LzkH7nI}AcG7!Omhw9)nOuYk@Fr`vIlUDO;&jF z=M?0>UMhHGX@l06XYhHC7Fkcx$JY_*_)w6`$5#no;+i}x`Tjssd;JI7bs~*U{FEyk zW~hO#oA2YYskmiKQ$lC)n(WD_Vs=HAC@71}a|nAcZ{p1;3MB_no=yJHsr)1r^~ z1up~x-GZt0)ub<9z7h{?<%6c$;YsOXoNjs}dlzgEk9!IDxb+^Z6fC^6T5?c++lN~Q z8Y2B!2A-YElY|9o!)5O!L`2!r`kvzUr&o-vxN2+YW($$XMYu3tvBCrX+x0gy|Q8Cpz|ao#zYW#=s?mqNwAew7T-A^d0f1%&kI%j>V|BKLb44#hlU&40!adYNMG z)y3RQFnbbK{()kBfFyIDIYq_qAx(wt+%JAB8R>i>C*`BEqtTXlz*8{R^c*|#yn^nH zT_RX21$=3ZHddKm#DDH-vMaB;VCbSsG>lZIm1}R2@B2dtJaU0Mn%m&dOC{-yUgO!T zu6|U^8ffQ+C0u)@HE!)Yg$p+y$riTj1|*i1_C3gA6Nw)c2gDwg{6=eZ)=K5zB~%zJi_MQM$uRgYA#Zqa5wptCmW zCp^TB5&LAmy}Bb@_b6OFqxj5-Zi2@c1J`%!nD1JV9V-#HU|Fv0wz#z|OTB=b>u<8S zr%NeU-V`gNSMwPSLf_usjK!ULN-R&TC%cFdP#XMRH$Kt)X~d0 zD|g18ucvU_B#s4$+kvTn0=AU77uYviU`w{p8@lP|m@tLMS?ZvhIEYW&2 z1;^`zw@ih3$Q3*h{r8=gox%3`S~RMY0ixE443u#$ z-zNGq6%Po0{gnSC##`H1k~EcC&EyKblr+(Aay=e}9^hlADr1LIGa7O$+0X(jbn%Ho z;hV?&jkv8OS+-DE)GfEmn=4S*ccOIfT@U#C=;N2*L^#Zd@0&K}dW&p+ zQa5tS7T(<-MOZZW20yh^1xrp=V|#~f%tqUWJRT`wN{?{vv?-jvA9+vPCrp*tKkrUW zw-f$)4i%eBF#AP39*t(aMAsAzqp~sT6lV=~b7*`;=fCU*E`B5WPq>NDnWtpUrGle3 z;00P&n$f$?A8B=C5!`E<_=rg!a9(p3NhN_S;_X_&qi>?f-b;B&Hxukti~oN%Rd#x{ z6}$)LK&PUWtiazJ@ z%_)*cb=5)Y$D3HIm%^GZ44|eDoiVn@O1^oU2BK%ZN60KcS;OUO{5Bsby?f{v9W=6m zg4HQZ8@h*QJ~f9{VG=4sgP70URpk1u17??Q;od{F&{mv{NXy>*QM2f599oXyTN|0j zhiT;IVTpJBSMg5=4B^!DN9?$Pl6{U=^zFu8s+lQR$=(a-+q-&N`65ErXPq??OjBW8 zeU63puAD#)^;(3)yfLQS*Vf1)-oEk{xE*8yvQw84A7$0 zCNfZrjqSFPx_qpsJJaX$E!x&t-*^H_wGU){m=!(1*#OZn_LRVavD#*UDKte0(f!Js)TcwU$J z^?+W`JeLfuw-!u)jsq>~pGmvT1NcW(!8G`lio0w8kI@!PkVWV4W8(pKYnI6KK2|_- zfZ*bBP4LFMh}phdmQyWqMq!4J-}B-B#5NHRnYRYg#J%&|w)l&1#^NMNP$)ZOX;^yD=%uNhL`@YpfL0>ulvvo zl`l^qxW0^i@(!dP&puN^q%$uTEUBgs$>{ALE$Jdyn%_$1OWntZp>dHe!Xy{5a=duX zRno`G2_-1GxPsxm6Y1|2Y{#X+T;q*k-cEfbx(EC6O#3RTU(+AOuabC^Qa3bTJ%vtF za|&G2yCHXRIs$HKQXj9mWKj8&Vlq4N0dKovM0_DWy?G`%w@v8FKFQR4{|`S}poNC% z^*D9m03Q>j2G7)cTlz)$W0x3zEJ=Di|=~B}N-4 zQn%?MKWlUti|%-FBYQ`&cPAiADUFTJ7Cy0aGMG<4nBOwe0I!R4(WCAsvz05Oo(U0{ z@->xL4A6sb*kc@6(Um!s>yd}Tcj{==#tka$(RT6>2K{<1TVvvYOL1{HGpmkue_)Ia z!(-8O_dl-B%n&JZaPLmZBy(c*;q)~JITP&Zoal$lnqGv%&DZ(nd{tzBtit=Nf$a5m z8(JOM88`og^2z59BidBtR!lbMa)eYf)qqMK!}tOz@Pq%dch_^wq7zRs~t z-20};!D^JyEY3eC+_NSWMbFO0?^U z5|=-h1BuD>`UORTYh#3&V72Itw=xmDEkU=iA_xy;iusDoxLq1{yaOy=YNPL^ zdze^P#utg4?9T94B8zp1m7H?In6e|d&{n|9H`pWbQp{iPV$5$Ra$lKEzh`aZTfz-6 z_(d}E;lisX>cE+u!_CM8Oiz6xHN96w^k;vrouP%GH+4u<+btWb;)tvss?v;vp){wn zBla&j3_+~mZmQjJub=2E_T0#xZQei+#g3zpn}IkJay#P5i{U{@Jj zW0Ee5N$*7$4EJ5a>$(`>Jf5LG#X&NjZ6=YG#P|u%*p|T#7$*9#y^Q2#OS|^M%b!W; zuiKe0+YF1t;_+p6E^ib2x4vaMmL&IQy>C`a9%OF)+f}${nih`gUq#;Com_vTxYy%3 z)-5h(Mlrp~XP4-Z)!o3mpLD_Z)EM-Y%#x%F4Nu9+Ln@0hfQMjD?3p6EO2+Tx<$0p> zEcq;)?(Jmby%|liYobMq!}#j)nn)4P^?Zsm&oEVo$%QJkZ+*+0Dup)nx*K+h9%jAA z40oTMM%A-4=GYcYryhT!ck`$4Piba2bSEBDQrrtPgdg>RUN+`GFs8fWxzem-Chj>s z=U>k2!Th24{42L-$IO*!*Mm}8CHj|UE>_3?NILJhn!i7e3z3kDqMi0G8bsameqFQd zz4zDNdo;Bqp-7t2E`*eZ>YmDsrkPbj*?Z4^=a>Jf`{>^L{+#oAzh2MRDY=(8q#kVPxCxu&8~E9UCZNVR zSntRynYX$hTwVyagR=&W3)Mi+&c`szpn&)2ZjAbMm!UTLwIun>FZTCo8kJxB!!WKiDwTJk*5$S>Fiexm9U9YiS7_| z7VpPIg;Zw~ujl{#(?mWD`6|Pt%Vb|>pcJPr2!Yc}J|3g^O_zl%m@FWT-d zYCym~9TqXS7tPZANNX2-<`JXB8RN+zB)Y$n$qS~U@`5BdF2BtZX0E5}y}y#qG;6MQ zMjtL8veBiqL^At?DoXvzVK}>#uTcXGZd#UC>uIh__o1go5QDiD5old&e;sSD%#FgJFlf{dzwhE=s!M5Xq8TP z6A?A9Lgv9NpcW{4B6|L1Cr{SUiqAXn@!JJHSnyP=tt-VWuXNqAS-hY62c$91y)oXY z2jot_fRfe?-kR+Q8{q-29@WY|d6?nS-6MFgznBLE8emgiDmrSIvoW8YY2Aw|GR_L% z(_&PiZIX@is=-{W0w4O-YnZrdgn*sF1uZFT4xC@{8CTz ze_xQzey@*d!u!-A$Css@+CXJ<1an37M1)T7iH}{+ATe9)EON!)Ve54aN_feBHczEu z!Jkt5vxFGHOSk8~Be@rmvg;P6*!MXD4K_J! z(NWRqW7-Y|spEOb2*KfWK8^M((qvPZHs*DyLeuWtSZjBR_y^KD@o7=_&(W&Fz`7wqVJ8jtfWn9Va= zx^*R+ZtCyk3%YBfpnWF(9vi@;7kg4kt2(R`e@f&dr%~a??kE-c1&t-be>LeoE*pl+ zq^6!^)Nd3jYxlELldRFaJ`x||!ua!KE7UGc#1a23Y($_Z6%K4A+f#xAFi#VwW@q9| z*FstD2v55IMjg{5j9JgCD+y;cq0?a{-@INO`S0(d=DLw2M|6?Ih@4S}Ymb@xZYvBd zKZJY3JIK7ltq?sm5pvlb1z&zU#YFt3PAhuwO^dYg@W64*nm&*{|8q|g+rgh*Ue%F* zDHZ4Tp&XSzLinI4kqLcy9Ur3#n4<6*4!G76p=-DCkOk4G?<+4oG_z3Rt1kAQ9z&!Z z4)n$;M}5qFoe1glJv_g^4rt2>3?8+I&3NWQ?>jxFj`9AyC_>CzMJ_l9{rG|7f~mV* zoE!i9z@m=|hRirqEW5FqYuO6^$>KO9tUt<(9{W<~zwasS*+g!|`r^#@BxL-MmR$SO z7uyT6apAHy&8n;;gU%k%N>Aqdjr*WVXrzH^Vut_Mjdm~icWzhJ@}!BTqtI*vDd63m4bu1p6DY4(~ zN=W|R)<^%JlE{3EY?P&v1Ak-eNh)@uFtf`_wl3ZZXKx$=J#pvDcUVDQ^ztb7%V2*5 z2RJ(A6oUTjE@~a`LDHG(BFiv_%`2#;JxRN8%-|UJSlb(C=ie850WDUwus2Qo^@(ai zzVg3!tuRdC-}&4!#2S5=*k32zW(Mjz=wx-B(T zCDG4cLHt^>0pvD_Tzo0x^Ezl_g5fdIg`Cd@e_KSm1=n4-U_1XjzNhH_5j(P%(Xy&S z6$}Xzna91V)Kk@q9*lLzxp^!3Y}1jDm7c(|(Z1}t-aGQdT&QV3<`aAA3ufd|9L~5R zTPifnosmK1}*ZR~^2_UUWj@jssl=@L>^7m=PF{ z$v6M7T_)!EW)hED(;{vr{78VxdhePAClJo2^aY?nbzv65aIcc`C(Gmbc(=e?$^ zq$Znt)bEUjZ0%EH%oKC`)2aq`V2&n=D${ZJ`4hgU)r)rQP>27gaF_5U`q((S79H!{ zsa$Bh6~bqq6?%#9-S15!gs1xUCpos_lpXB*MnU;y2@fzCfQl+{hix`ump}HW-y?G< zZ@nK+Owq&-4Us|n?!>i4Z%d8fYrJv!DdFvBkmmDl$h+dfmH!iG+Uzv2lIA`Sa_{_`7S8Cw$2aKWTJ{Mf)H}1Qxs8$`!2#^GX(#S4@?0Ov zO7Nd@2oL@)_=mmg@MmB?>y_Y4x@A4loV<;H&W;h8OL?hPU7^JFVJ&J>giUv~y7(R2 z>EY;~RCw`@EUSkB+$~PS!GE9VOdCQSpFX22&b#=eTOv=iphRR0ZMk!k3T(cL{;$(- z*teK5G%M2(y`C=PnIjyq*Etpg!xGrwd5U=8=8N9n9`Q4A2I%rC3GdjDl3RBSVXS!u zn5#n(6`q2(uZH`3hw!1o+osz4GSZ&NvAZ?h$=l%H3=g;RCa;O^`0~Cz*9nqfch?k* zTziK(WE-LGbQIoJJmR;5wo|v(ALQil##PJ2i!y)w-v_S67f$N|bK`TU51qw24{@Mw zTL1JGqg|p;s#TdX_oxi|^^ z&=iuxVKBb&kYBrFiS`o{Fky|qBwTGhEl}tH^CP!p`j%dl^ji(HtuiIQ7BOlL`QDZZ z-TX=P^D2wnx_*DYBug*{3f-Ywwt{sHwnmo~hj6Rdoqt&=7>Rj_La)hS)92`5Vvpmv z5))Lk#NUhF+Nr~8_!#D4D!z};{h@d&l{;ptBDL3bY&B71yXUKtrNRsPQuK;Ez;N9i0Y_*=HUi6tsJ7#_rb)qQzMiZS#CWf;UB#s$tLX7TIsn!5ZHE z5)=kxvXQ%n(SPpU(E8s-KCY`T?fvV9XPs`9e2THaH{EzxE!)r2iVczQED4hr`m!;R zHB{4XK4$sf;=>O3P`!&fBufv=#*Y#Hhx_HYr*Myz+@444pNKBB7t8sNvA*=m%^i&o zuer`CHX@_5p_IID7aw}a3_9&%p=Ldlzd2`&&(SHkY;}s+46mgvQ|2SdKA(@6CvrVE z#s2bnciCydq^i>_#9_U56#wBGU05H6H+3huf3z?CfIG~_#!B=XzfnT|B$U*vkP}+RhlNS{*eM>i-&B$L@f*)osKVupYZ$r#Op6qL+RRZ7lm%Z`}DIKCe?0K zFLdvbQ){s&=^|fq*Oz?L-0@tiJ?ksyh;=bBV2jImmb*RD#9rQDp+2jg;z&m|a%t#L zf4(nZ1GU7q$M*mB$@b>@P>{&=#PS~!--a1vD%TAOemi(&yIy#kS_i|Pdt~8dzVzMK z9qB3inRA*gygElBxiXATGO$JWPKl_xzlB-Udyt~wraFXd;j2gs-JR2MbyU7gZIKV1 zyRC*14MuF9a~=KK5QLD5N}l~t1K&Q~g|myXBvjU#!*({yN*m`f@mcd=*55RTCzQ!}mv z+QL*>0mV6OF*yL*O{4aAhoObOkP0_{I-b+ z`pOIT^4&PezN7UxH+i|#>;7)xsr06zgKE&+s>QD=h;EuC=b&gZo26}Yr2gU@a^trj zH#YDkmmoKE)QXp74HT^S&l_;z$V0AbAZB=E4Cq#FiN*(04696oVtXa3Z(2u7&&eU$ zqC4Nw*OyeqS@-*^{*pZU!@9_l=)?B!d~cNs)Pk$w_+u}B-snrGM6RlvzY}XX?MLNk zq?{N_{!`4}#dD9MW>0`*$EF&TDvp)byk_tgzPOQk=@=t=x)TJ$&D~lZ9?6-Kf>9!q zW%P{{lmmH&y6Alktb)QsTR!`v$m3Uu&Md8!%qPbhexk#4d!ZZeIMo&rj*0NRoWV9M z)`e-@F{Ew{DtdQS7uP4B!?muh%)OHmh6m^2=Rv`y+tm}hf7XJB_F^-VHK|Il<0g*z z$}3md;L5LvHeDsbz!Ep6$HVx2Ei?I{k8O_>?y2-2GSXxBCDl8*bzUk#bEkKC04M)mf}Yy z(jny_uJ*w|@KzJiFjm529BiSRUkppTO7mnU_Q{-O#!9od?T zCfJ;q1F7^Ao4VJB0^f-)`6a8kykw9z$#b84i&JRyHC1JNnKo+sTj)oL0fXcu-{J3})c#t~QZaFNA9j=03XU}2Jk6LE*X9+EiHbnTdb$s7i zU-~UNm0ljX=6dD3F-0bY((m)T_>V1SI2;!Z<*QPjt7eR-JxRFXp2e8R;7qjpO)p1| z>O&y+%Oz-AD!aG-*-~ncQ;r`V&HBo?IZ`0e_W?`z@?+e*14Eg zV}xLduNdP;4xa9KW89v3IoiQ_+#y(-6>;02LF8uom7G4VmAJlhqC2{|w8md}9*ni| zC?gH`{y6eiGc{o7dJu2<}^}_{~;LbTIm-u|%2s)6DCm@c#W1HoSu^%0@+C>DBhKXXou;Ew~Ej z$IH_P!P@eBlnAS91>7Ue8Xu+=LQiWXTM&IuqT0=yd3G=cNAAjLwG@= zF5JdvLT$xv_9b{I{RhDBc+L;YIx@JjJN z?&j+VhilQ8Q*wk^AM>M+Zf_~Na02gr(g+d8NrKrvq@*Fl7-6SRW9LzAx^~5vIvf}M zLmdRabYpJ>rI#X9`L{$VRhf1sU2WTqp8dF!B=6jy@~b^xvU?y-&51*!o#xO8}CD$&yX z^`za}4pXAL@ln(J;9$3G+>*N?Iq&wD^(s!Jb;G}Lg^7ZDV{;X8rhB+SiXVM#KMG6b z1~5B0V|4Jx6w&A)n)NwND1%eNDrk6H0s6BiTmg;WY@7o{* zc^pH}n`c<p@Z<*89MuJ5dt?}>NP7(v`xOW69GY4}W0}C7r%*D~W=UJbyRkS`oxv*l{z)+1zOCoqPWqFv zI9E8Gt8`T!Vnk+YA$04YU=FM|N5tT0l%JIHC&Nu(Fg^+MW@fQbbJmDC`I}aSkL3y_ zLRXl50=J8kWzOzBp}4sa(+k>BbIx`8{v#Y4bh3H=3(*g9>?xE4GirT*f3iCGfJk(f ztuQi2E-Ui+fEPM2@05<*1P69p<&osl7vDC|xyKq+%$#2! z_9j96g<$8Z+gwNDg93JG5~HMM!58SXjlU5)`chc64F%Bo2e^!;J)WX=htUR$vzdTJ5@o)VuHb<3Xtw03uf$p9%X^sp?n;wd zZ4vkJAo6~@@u|0+@mwhbFA@X;>bUS&-4LId+<>BUTeYy^^BEjJ^@Y8PSH|+*c`!(C z7FqaSs0*(`o|h`SUZqdoufI}{qd&Pyu?-$QK7c##p34kltud@M4sS$Xp3ZVHH%7FB zWV91E%NG8|{Cr5fFG?~}{OQ}S-blC{$}Gl-9sx0Xy-pN}tcutJeyc@TpPg)7iY@Vb zoe(ubhpZ+18_N=k}={>}D0bJ3Ti+JczP8)XZUuA}6G zt#qvJC%QV#0)4tfqoZdimx<4LR!t%XIf&ip&L-Mjy-Ij_AM@|-ePH!H3tzSE_*|ij z?(Lrkt-MN>s=b<;>kV)qc^x;IF7B77pJFGLN@mY6Cl!~y^xunMe)Nes66QxC=R0_Z zax+|;l#EaOBpW}vBjU3{pqlW6tIZeOKH=%D(@T~$#;Bog+d15hk)utYDrwlJP;5&) z#^(-F$C#f_V47yj>^k3|(7(1qPb=bnjuucp_HWL=7y6Q~PAW!+G_a%3S5xVNA0)rc zf)6&c#BJmAs9Yg&RS@}+M$zMys_jNk`>UdS!4*8LlJQ8N-njj&8LzY=*p?4=SQ&m0 z%VmW;qIM`$cAduU5-av@y)&^LIc;b7)ImBZ65_H~xC1vAzL(J=OLBf$I4dw(KwZXn z!yrvh-YPU7_s9yU4i1u~4i$bT)n_o;YDDj^+lsEw1DLmTAAkMS0fAzd6lt}CMcwr# z)3mQNZ}}!Zaib0lyQV_1>a1+cUt`2eOEAGs@E<&DNN(It7+<=`9VV;ewPH0~uW3tW z>Zq#*JGmYL8#I42N zVbRt+7`a&Rj{55O@4R3L4t&KvCeEgh%S>T6dM%$masZm{MPcFUBka*~!7o1H1%tki z_+-uPG+6xuE$|L6p8LlLLq48Bd94NwRMEiMz?1NiHuLTwf?u-e9FFbzENNWWlNPtX z+LjNUs;Z3GB*9HG*vBpE2V$aG44&&%vJsEP?~I6q{lZ2rooXt8ABnImkCFUb`vA*T zmP#A@?H0b7-q<$a1fEyt@Ps2uczQk?f9fW(x?=-rz1AOU-Mo`OJfe(;Tki|zwk6*v zm=MPM?QxhK^vX@Q*iKS5I-{C3hhHKz@pOaY8XAC5__(wu;Oc~^!`Evb)Nf}Pk-1CMpH#b=-ew= zNq<|U7{+5|Lmlh)U@J{|{EoVmTkvJajW8qb1U@||l>BwnfrapoExlqwovnMKczr%r zw&V#7M-AOdDuw^hi*;LTPh_Hirkp@-v(N!=)*oqs{mzRg3lB`!j(K3056F6U?*m(rk-4}_l~P__ zqMWypNZovzm!>=5V`d~GE-hdhXR64>dmwJOmhiwGf-O1V2o`;~Bn!?Gos!!#k(u1W z#=g8pb9|P;NVkAT%4#jhUaAj|5EfR+@1Agh{ml5b z?#@@8Eb&BW5f7~jc-lcznA;{{Hkq-LN@*kUj7jgyZH;DagsKQB19c;&M3=(XZA$f4BuVk{0HT1V(FAUF!t`L#y zRQuSBrw5lwTvnUYciT|PvI*u-uA3vc=VAOgO}wRp1&oZ7(N*vd<@~pivAP`g4xY^O zq#_@A`xvaQCdvAXXKU@ybC{PZM^78-#13&EMyY0THDA$lTHFA)8cQafcvEy%*g~xpFS{uyka1nmNmu5a+6~u~y!ii_VNoKpkm0^d_Tgq9 zR1R*2{d7Z$QCdr?RTs(Ar&MM<+!6i7zDB`lJL`C12Q{EQdKUJOd92n$N8#-sIQcSj z9bQfCg1xcybva+7rjF4**I=fkB{})p7SqDQQDiG8%PzCW(H99Q?;=kp3yd+XlgI)G z$HR+w27NX5g!E|E_|0-D5T>sxZ|2(o6eNd{PjoZHRezD4! z+guM*%e{R2&4I{%8`YK-HS`g8y5>V7OVYsa#raU&$S>qt`_lEp(rQ?*nJQK9;R91e z!N3>n%9&v~TrIl?E{@H{^8*u^{ahDPTh>Z%s{FXRi82Zt>)|=kobP{lldSsM;X%73 z{-38g4qb}G%aZI8&mtSVIi8O5mwE_qi!KTurNA>Lm*3CVMtnPQ?|XSebXLmIc8jCb z?%5YUrMK8ks9i$FyN@u!DbP>KU1&;gtijJMohyS*-*!t`T8_>I#@Dk@C zLHij`6S=vn=~al&Rb|=Es?=-Jefpu-C_LD9xVPW{ytH4)Rts(L6BE55tFJSYlS%FN@kNU@W=aTTvzJ(yXl zJ;@3?q3`AZuIBHAQIbepSl5-g8aU97B?+|pOdub!-WZpf;sv*AFn5jx%?ORpZgaupKRZE%fmAQP45W=O@>iWBR^C z%rG!zCt}5ZxZpz;Yje6lUa@Qp|YnRNtV);e>fmK*o)Kg z?wuoZ9?&9z$j>?K@4$DB7T;5=vl#y>fOi+Yvaasc@HEU5e+Q73VA8Ek+{p9(Itqr; zA^YZtSqK)#$5g>g*~O-v8bL8D8%cMEKTp?C zMV{vw`2RKGr%N@&xuY5b7rkcZ7R{lnx<;5{w32sA9VWJeN$As*!7dCIdge}N?A?>X zC+Y`K#p+*_=N47`v~i$RvU^>PPWZ+HKFMpc`LXsr{7DuoK~X+l~>y4 z`B1?~yf?KTvEM^^ZY%>E9WU}%bK6WDd`_1yj5S)@pq&$J$s>t5g92+JeJEF-sp?$OD+b#xFb2B z(ShchAEgJ9uRML83ZAz=kLS;VxL&Kslz9I;pF6Iy!l2N-c=_l)k00y=zsjS~>>ng~ z9aDp-Npd)x`(jU37pr@GTxyKikw-Lbnxzxkl^D2O)Y z?^kOdHf0M zEjo5YcW{~qt1xmPwnrYlH~RC>83V9QE)t^DiVaP0ptHM=&^ebtzUt&Ey7{G%o_7wE zZJBP2*kPh?rKy00e%MSy%M@Uo?ajl)o%Gq7Gg!MOOr|Tcv^^rlowrnl+INx1vPF&mA&t}tusHS|F2&gFir;7`PSnD_85ihIqGcs?;B`>=oW zys+64=Qc*-NjmXojn*&~9-AzXOj zCU&H%Pt`PO+HP#|N$2*py`dP;fB{{t*s&!6LPxzrQ%^48(jZG%i)U-h;@dK(5-YR_ zKl9W357_1!LxkE0hC@L!pA|C$aQJ|nO{-it9NkX0eyC&P`Uv*3b58`CoX6=s=lBji zWvr9jz?HCI=4-Q>cG#6sRQ_jKf_Ro*>MAd-|LVskFc%7r$)-Q|{CHi>d>Xf|nbxOy z%CtmYGDngH_26(8b9gE3R{1yE%T#;fy2E+Yd-}=xKh(nSjZe|t%8=R%y}ddi9B(J? z;{hHF9i!5*>c>uI*~gdq=6;~_H`ejA%iHP9tG_f#r@QR3;FR&_@|c$MP`X{!1E1dsKh=o= z=ootlx|b(Oeus%{@~DB*0b=G|ax%rb@_6Lt@8+vk^~F0`3Vd${F~7;9NPA%usox3U zhWcWM@+})VG85j*vKO9YT!7E%CXumPNXvg3qeX2E5B@M*%#9>$l+R@2M)}g!gOBKM z)CgX8z*6LQ60vyW(2|e$Z4s~|2kX}AlXTrmI_=pW$DFMA{H5yX_x3D4<-L`Zl3$wwH+fRPu~61iuaBJtLGc?ZpjzH7I4Jk|-=CvA@38ASuyrz~1l) z()Ck@q42OC4nIml^Y|dHY@-EP`x6+_XDIvFc?@Z{|4vWSgSf#{Wh@w1iWTFGd1$N> z?#kDp;O{4PcUyl1%ngUU$w3Oxmr+DL*qL#v6u$8`d7r$;RjEIQ+J!@<|8v>V>kc?L*MTlIpin6s4f2DL+=;%J_A z_$m@M1W60>yJ5@`v2$;^js3b8xc5Ud}L00ZtUmnqM>fk~!T zQcItAG}XWgmop+U-g*xomEK?EAu>=tDTobm*+NNUeotp2SqsHyLF|>vHX7)8g?xAZmAOoeMvb<- z^p?9nTU_W$_CDF9A@48xDR$84+&}c<^&Z)~Q#v?jm4%Nv;Vg6OGBO|7wQWy2Z>}0n zTV24rvHr4_p}KfKvl-G3MxSE;f&8-epz`0Zr(Tn8WY5pR;{N$10K_ex&^#J zd|!r%_w;s1j%>eyF5-@5VXtW!Tj5Ykm*;PXMHLr4r`m$$SOw?dI+9+Q{ZY9n3`O7C z$@V`Qh*^F|p*5uwDQcTx%kX%d^*hV`|LcqILz96X{h39VPm<3Y1KIyOL#^w3qN-Om zn%w<(i^yfy8DGZnQKwn|14Ae|w>wrJTgQJEIwM~r5>f9aOR^KLqxgZ7w0VRwR-2h) zFOFcq5ZnG~9I4KKO1mFLA-Tlyu(7-2xut6OfdP62o*W=w_b8k;U4i zJYorTY8HETV^coR#e;k|tK&=XaLM-DeMr6N3Qg|vjpsjB#?vo#=w`H=w`2`MeM2O+ z?xR*`mvwoOk8 zGNmB~&=f3sr53-U?yLLa?g-(}8To}3C~F{nN*qi$E5yxF&;va>&%}T6ePbYfA;>qh&0B_i8 zipSSuMF+4mZ(L%Gf_Z6Bn3l)(-W1)fv=McKpK#e^Px@dg*pyd4mDo?~g;L)#JZn;* zOUJ9o?%lz*S-oMMGor@?P$eMjTXv&0_Ja-*Fvpx0i~3E*n$` zeKM`}ET1;X2K!Z#+VcJfvPTHcMi$_w)|_{;pt_+TRnq_GL2d`X&S|a+F3+`a|8W*qO`5w3#7ozVsrIsrhvNP}>YYal;zhh9(N`*hv=t$BWM8{H2a{6ZwB*HF4%y zIu^+#%DiWKQ8(d}RGu@DU0h#FDw}uVesZd~!;0P3k6Y+=$CyROtf7jjoMb^`xV*nD z9-AI+^Sa!)ATsq%V(;&MpY0g8okq6*NfooK_}o%k__%Tes=ByJLPY=3?0+-dMO_Uc z7s{|RzmWgXQbFjO8vKw2G4Eh|IDX%cWV3v(TWtK+;Q`)=*F9fHd zPI%o*FYU)D{k?p2cS87*RJaL^!|=;T!qNqJxvGhG-Ov{|n-ekOL5}Q8Cvz-#osZNf zm2B|tUKr8648t3HO5Dy>VA!rOY3Hv7s4=sL$MOAG9Mevg_}U5PA@NYt=|~HPnxTVs z9Jp^TU!!S&?0reFI^2&P>@Gfgsv>J@{!n(^wGT`iE@IE(Q!HVb8$UPINy8XYoE&Js~ zSqbV;3fU`*a978uDd*vR{t>HjTu!^yO!1qoK1y@#dJ!{R^!zIDO`V`a5{e!(|+AMY4KRsM>?1%=HW?ZI< zu3x#KV8}E?)$zObrig)Uk}l(Ajy%;C>uhStNzmez331A^uighTPXcw%Aa;vPgTRp z2xIK|&n#=aJ$R^18_ySPhbMcEV#R4inl*4K*)=?)XN9dYmo!66Ru%fvp4$>%)lPIo zK7ow(f8p(&#hGwAhih{HU*M>VV`m=YLzilnDQAnfQ$uli`F(D3BL;6o&fUGGQL?n> zA{vtSgk0AY%bH6~acH;j`<0Jpu1m*JRqGd8^Er^q&sD*vx5fA?xRK7kRnTNphuIfD zv#zi0p*S)Og?=OWuCop(ON>QeKq|{i*g}!xztOh+7th_PH^S$6Ina#w&Wzf5(N^J^ zGk7538^k_Ed#4O#bqZ|RgkE$w=q4RpCcH{ zQCt4aa4tNYN;B%9ki~h%@>069L<6xKJ=x(-HhBFb0+Zh4a$k4C?U6!{x-^jGm5!v4 zc30ZiTqjnnrb;35ynK>rX?jx6_@8v-+Bn`@?0LcA9C#cZ-(n%QGr%K5qNAf zU-Ux*b=LRLX{{rdDphSxn9zqkgg~Zdns?3`EUb7zHi3In?|%L*a0nR`|)?2*um{_z-kr)ubg%4 z?#0h^(0&1ir8V&b=^o@{`IE97y2^q@HgNKYLd+?uW_}(!Xo_}EjQz5ZcYmygn5&|b zSIl#R2^C0B+$a6mu`l{)*~2DaALMdcOEkw1#NMs(m@4$BvIH|&8O1`OFo&;NVT4!f zld-t5KilN@Ua~l2C!6Um&rvV3&uVHYR(K$LsnZA6$Ic@Oy9(d(D(-AD z2%mH#+H`Vjn;WQJ=^(xNRtZDl50`fj!m*D0jNaO!m#C;w+suzv6z3!@8F#;^3XdW=>PZ)b2Zw6WPeW z*O}wFxPwQXl9cQUauf{eT;bz2AlqnNJZ?RPobw{9(%FaPg|2GlJY4d^QIn3$xrh5Wi$NttyGj(i>? zUEX^unv~a(#Y#D}E>+-Hokb2#^rM{|pCfsfH;mqo|4aX8wtW7mhFrleNLp;lzll3w z_1)68**>|<2IgZ9iJs-`k~l*f7!5dz0ml?+-w)Ai-ysRl|DF*UC2{{1`RHTc8YNA0 zJJZni|IX*0UsX`di}34!A3y)Q7w&7{zz3~THt4r4{1yJq_Qi`_5nYvta=l>5j%AGq z+%racElCQ|`bXo-#oal(R_46O9?C1qaCPq-c6#|lN-_OL0at=}gYa=J>t2lX(FQ!| zrV65xt6|#vBP-tN2&@ik(^VFovB#IdXhg&&v(O)6M=6(#H|zY0`lMLn*?|9%bkPSc6W>233i~;qLfMrD6I(6rGm@_!~j7+Y(*^W?)JMM?|&|r zYpiF^b7Jq`F2(D&?MY2-4;2dj@Biz3eyAeqYs;{FPgf>wP^6w4#ZGz74L;w_7Gn;F zLVsVYZ0$ySjDHY^ez{j!Q)>WO2yOh~3>%J*g1_|T7_x#2CFp91vUhn%)iWX&;S+!8 z{$HIB`Op^{?j_LJzJkq78%%nV|LS~kd!grviA4HTZNLJ!6G- z(~(EG=;Pk7WLzJT&r+#@hVNSdq2K=FRBW5DW_W{4W(+m!I@nBWevSmV#ts&2=F^t*xJyd^SqODml4kAgyL5WkXcfw=rc;R*6$`)s{v-(#Uo zD&NARuJyyij$+SWK9I{L*ul}{n(*(xXDjnZe|JvUR|>lJNveq2A{WjGLycN?$C z20t~2a%Md4r`=-fMi}AOozym_Znw2t$R@QT);;ugu@~7`-wcHx)+>TN)mMbdlv3>O zQpjr*lu+nhkAHOm%vC(+KPH5U?6XsR+g^KQ6~tn!zdCCvAR2rvht3E1@MLjMOcmeR zLno}cyrVXTYi3|qV;Fl=y^e;qc5l-wYJL+;evMMpdhV3Xa#X{NN!Ov?Po3^d2jNWr zFzi$h;ihSWaOjKZCuQy|)$l5Pl`$;aUCyK5>Edft0{mX($wuukMpC;%ydPN2HY$11 z>wiiZ>#&T6SE}IVTMoljijw(bYS17HktR9lh`H7d-R^{nIia0QdRJtiG{s@EeMd4o zY68`Bv5-$J;1^oG>1W4wNS+xi$&tO6jEM7U+6T$U|cLp&(D=u?QDV8N>}N1G5>s&8DsMI7?iEq%jZZ8Ft9lZ ziA(+2>_e03#*YUgN64QyR|_xgRb_m$3z1E%RKT4ZC1@9ZlWje@m_h=y;s0?dmunn} zoni5UO>vy*^b#DQA=`0&hR{nK8wmUOBUt0Z%FZ^KLTB~~tlqCm{l<$qXxK@t-7WYJ zGj(9LuLRefze(&a^rLQ*E|8@67k>Vg$Qd6aYPVp6$T|{c9Erx_+RJQ+WF=YWoTs7! zCBET?KOJ}ZOuIc^yT+`n$JiBPr6n1gk&xy=#j5RbW@K0XPr(RZ=T^e@?h3Zjc_eLn z`ByNreEANcKkNIx8ka|F^WL)CR4()iRW^zIO0@-a3?krGkz2O0mle9DBx3WJ9#o+- z0O6-oaMiYmH#}ZN1HSyE11D7_4&hzt*~55xqwtk?d#Zq`ol2o1@!|P_s<4`K4X<}p zu*tbr@bn3SuHs!j@huSOmWtsA_DiZCv|z&UvC<)Rz~=XQ=qGL^>t_0MRx}XCn@(Y) z=Va!QGL_=yeIpf(z1(%L@bw3k;Jbq^4-O<8*orLCuZ~WJvbs;{bsrN9>sN#;HNRNyelOa-Pg!tUC49+Jp;xq#!Qy*YW)iDN zX}7M>v(HW3DRvMF7K`uHLFF1uM*UTtlnldh&$->~D+1&e{@bmS~$MGriSjd3u{ML)kZ8M9vJGsEU}R8{bYJ`7mLd3T|o8J~&2 zUcs`9ISPXPdj{LjbtJh!k^iW85dP*Td6x_+ezpkx$(t3->-2T<)U^}(x>DXOe3T2D z4kO}yrA)iT7$qZ)Vd=ZaY;nSM8dtLj8?F@b&U1~>cS!|s>bz^Kjseo~b$wjqo46{#NK&sDrwcSQdg${7^l}5}lULZ5y{TBNMI7_WU zI^ton6^>U#V0@Keg%ey@9Q=RMA@pz(LVlD6tDnP!FqR&=?B z#hpH|tHML}tmrWGm>K_45$ z>n1_}Z#FC6yo&BBw$kGx5?)!no@#6V(2=muW$nt;G07kgxjH|X+*CF6{lcM__loZ; z5IHZJSCBbfhvCf~Lf}BOY&*kK##&<8(r}zQeogjpx;Z-EJA%~c8!V$zu*#pOz})sR zcbw!ywPMeqtAx`7CgirtFMHj=c8ht8|Q!r3;(P0 zf5JeojdLh=gb$a9JxHKq0tVc-;_qCA_xVIRo}3J0W&!SWv6?GnI=B6!-+E?c-1wSuPboE3Zk`NlUmeu){?kX)WE8@FVGuwhv!N+z_EbsX%7 ze@|mEps)jtsWQQ$#2BnSp3j4$1oQ1ws^FO0Fox9YH59Rh7O_3>y#k}t>W%9>tU>%e#cwbu7I&}jX zk7|blS*G0hw+|E1~^zP$E#Uu^#>G_I%n^M~_Qg@<%4)cu=zgtH}j&j`mgliaeW(;Ogs zb_~_}eQDe;eZ+{~;898*pPDUxJT?oT8yY3cqq@AdKmHmlr&5K>wbuQo90M1bgd?eYo&8iha)gPW|z1TpBJ7BX)Ga zG#VZAg(gi8;K4=;SS{uz$r5cIu|f&+3PmW};Sa3i=@pbVy_meN?2(h!zB<;a<-vK>Bi_+j5kY|>hwgG`X8lfqMx7N^Trv^JrIvIkQy<24_xsI4IIu54it}?ghrpP%Fi?H1-e9AL#s=4`xst$CQ?8!FA zpvR{$b+kFH$W+0oBUzBw$>Di6y|Cr2$QIl_k10NIq0H6}P_6Oi_re*nRz^a;x+l{g z>rC6u9-*OA{kdHGf#APHJ#Xj4?|vPCTjG7RN3($0{=7*F>lefP+I7DEfim6~ihjT$ zSQhB2jG3=Xu=PVHy1lcOTxxU8;^Odfu$PPq4#;QEI0No+C6ZRroZig zh%{^L+7*HOHT(JTDUR5G;TRgj{Ml{6L8_5`C7*8YJZX~_d?Js*zN;zsuj`LBnMD{| ze}(m5Sx0UjUZ_Eh2+d+$}*vK!)ldLjqT%f7L(b;|JhS^~M|R=zn- z8AF@}^YoTBTl(V$T^MA92Np$q=VVKCn{Y^E3^mEpKbT{J#S!H9zQGK_jPQP8GEQ%O z$nO-aqRtDxQvSV-E{0ousiT$(YMw=~oK!`jbw7sH|iGxXEUYJ0my7k7xq7D4iNf$VkAA;7_$r7jXtGL@@ zDQ&griQ7>^e>E@$Z17&*ccLkjdL4uRoqG*Xe_xz@W z6R*xdQ|%^;TwY82Y=Z^ct%mCwjK;>nN1BAE|~0^j;oteC0{SrT z8Hez_Ag9cHyfr@Ah+Lb4-6?6F0gjJOz_6FOTut!Ao;}P&|I|jwlWX0H1;n>$U3xhy zV7qrQq8{(&dqOnOsna#|I99=oH`svH?#Gp9clf)7_E>0p7-rYJBuZBrFmI=`RESEU zZDEMBiXzv0i9et0uZzkM!Tm5D!Zub;qhlhQ#$0%F4h~X4qVVHy(CyFdE-T}lXB{pk zePE@cAGkLr3>P1b;Pq;bNKA^snlq{FtYGnN?2&}M!QQ1chfLwwy8zQ23CK~ z!CRAuTrx=s=9*`4Hls6}q^d~C7pv*ruzLP>nKwC(tES&d`m%o}K(6@i7u(-upU4t( z1=G8}{xSEC8Gy$d#m^temAt)Vg#Lnq8tytkFv$cbuJt4`k7e-%(Y=xNH4oG4=P`?& zjK)pxDEciQZd4_~wuKRGtN?$V!8C2ke|`JbIVR}b_b?P1?fLLI#yDq`f@$W3?8SsS zdh9;~LA-|hg$RD)^OHEcDOhGbMj5(-Z&MT5iK=D^HvY2;qz`Q6kC*vU^2%B=H#s5+ z9CDqCguZ#e!!x{pkl+vK#K64voGi531SR`Z@omjxHgu7wKR?eyT2te?VWv9r7jfvk z8%5m&Yob*203x}Zn_Vs^voFe+wtpK7h_b>aw{RF67xD%+E@Wi z_jgl=*3VS5Yb@6?><@>%si^LiAX_+88@~(+v9RA?R-CSeq=d7uaemH?7pNdaz7}$Z z+RUza2UYu3&^eRI{G*;V&Yn2bwv*X<+6sRc9L4MYx7f;EJIFKVJ++Em=&6A9blUod z@D6Wvd9lKes7e`jH4&^raORzaH!AW`4xj&4U1(n$+UogevBxlb8G?p=#k|XmLCDmP z!r~Xo?8sM8r?Z)K>Z=#;-p7-cT7RVKKLIkAJ9_xJCLIm$!`Pst&Ghv}cNh-a#r3rm zv978J`zCLe&1kPG{DQUcN>Zea^IXul^dQW}91t0TK#sWOh5g#e?56)Djra5LSmhz# zBs?Hrlm5^X-QKc;GYug7nIZD^%9;D)I@} zA9IZF##3X&9emqKe2m`BckWk!bDtvN8%<*O6voienr_gqT+K7X$KaXXQ8?URC~2{7 zg8y9$>EetYxOmA7(Je99q7}&fl0-gKmt+`7#9h^QCW-ASc@GQVuUs|oc(cguH8tcT zZ>i$`ky31$bDNE-ZlD(#A!4Uf%SX76#%~ktkfi?HkH^UN<4`>$P zQf6~{uxP#uU^ZKi{t8ai?Coi=+~30c7HVTcN+DM7elOYRs6nHHWpruHYrb%YxU*cm zfC%9a>SZ-TFxX;*m#Bd)tFnZ5z(M4UyvIK+iG;S$saou7&s=6|qg3=Z?0ycvx!+9q zIM3nky;W@LopE$}#$U?0>C3~d6;Qb30^TZV@tButko8@IwX2)Cb`LA`t~iKuKeNjc zyW7AZRQPv>cc=bWM7;t9!nuu-54t_c!z-RnMSbO2Ys5ZWuu%HQ ziRVY$b9;ZgDs+tH?9@(MwA;TQTmRhQI&%l%iQt*PE7>ji*R2ulOa@B}MKAx@-4Mp# z;!$5H^65J2VxZW~w$}&qGMYjA=6q`7?na8*a;|+5W+`g%mCNMOZqj-5pZuJ)`{_-s z$1l-WX|Qb5y`k9fCmADja#+0Z+GiX5Z1auo7ya0=izTSo-ht}7>f*FPF&3)^Am$SN$)M-1Ry>U(+6g4hCc8uqU#z7AIsqiNV;@jm&tz(1fgyL*cfE z+`Y3g?sz0&;)7g?qNo+a(uI#H&x}T&QpKLwljs+p#a*ro)_w7R_55R!l;-vAgwSEW zyytp9I=SvL%?lw(?7zWupld93iuC2r!v|v9pJ*sdcHmpSnV@`SGPGI?*p?Izl7Ih$ zG%l>>*Y~Sp-rNjS1qI369;sk~!x>bncOuE|K9E~b0kWD$G$<{JGH zz2l1Wr?{K^Ky=y>4Y_HRGV_-MvED8frs*Pg%yt7^UGbBym5kyuYsJp$vJ4d;&bjt- z?uQ4PWGGlaiq?wv^^Y%AxV5E-A7|(2@-1cP&)CiajICkba8UTp^10J;CRpR?7(UE~ zeK|Cda`Z0J|Jg6$Bl_dR!4#x^_u~8J2w$XUHWc&@3$FW8dL=TV{?GNg60d=3!v^ei znlJMay50VDdeTWtpOVAc)ufqULH6}UvQ9gqa8R$a)PLShcJ976g+Bb&rf-}Rw~69T z{-%zmKC$PzZ_t#K_~I`l|*PqldCwsmCF`i1t{ZE`uJ7(h~I6%_A`WJ%XWztOiC4j*#3;w_OS zI;alGzxeq}vHEnk6pt82XdBt={jxm2-X8)em1Y9bS)4#Pex(y*gL;U{#kxpk3z zKyL?pn-_&3<+ZGb$5u)^C>Y(EZd_a3{a=qciiD%Nvh-1gxUo)TA(e7wJ)oYN`>ha+ zxI&(wrwRAJG92<&l#Hdz(Dw+G{`;qa$)D|U!yp*xu7ArC!(5?oDh}m#ok*5G5TBEx zacEW^Usq&}wDIYve?OSnH2;zexZ}-=qvUwaay8tk%7F8SU3|Ny0_K;B>=;=BYu-DH zG`k1}y4emsR!eBuOv2k(0hRJiP+4RymAlj(dxfrbboOEFp0bx~4K>9ohh!{H4Pd^j zW|O?bL%O{^fUg$}>fx1{P^j1E34`UKmX?Q6npc=Zc?}u&3q*|hd0zD3w%FC%2$pdY zkGf%wt06JCH^{Z@Ql>K&)#XE`rbiE-=%S;zr=PWM;Z?JB(Q;WllS&^Xi^hnZj1?C= zoi}{bAfXTWTnUX$Ui{;|A+YWmh5Oqsv$IF7gva6_E-BvQO3_g`*GcG4s@gN@(R%E! z9VYF&W<9#5Xu~`%6?b1{^KECeG5UKxqKjv+hhry_@s+>Sf0*!t7${@1%O#OT*q{I1 ztS<7GR^x1^X0EZ>21&}qJ z_v$=EcxmwZ3ko>f=f65XUC9A+U4zBmSuoRF$HC$73G@#vVx4z;)8VqOq%-JZ$=Ho1 zICdr*9{!)%YfK`BqTWVeXsTN@7Vltt`O<}DiE(OTSn&+xaOO!3n&3fnqV$j0?EgG;*BFZk zvxaKa0St(B;j8vYFz@+s)Mpkm5KJtLj9NdXIKQt5m?r50%=5Z@ie~OOz zMQe?NBs22bv&7*4diB#Q)rHqG1M5yE=m&BRO)jgpB0+{S7kHk}rlw;ciOsoflU+4TVx|MTa8 zJ^G=CW+t9&(C51+DSURf~nc80sw&2C> z`@H)bbIe$L82b%f%1W*PXH`z2Y19C6*kXh&15OIYQ7gZvW`)2V=U^Y$fo0Vx(Q~Il zs>K7|d4W8RX;olt!)|`kXc(Lyh#GiC+)v%tQSr1&x>TgdyF86XvPx%ZnQ8}i(Wn8b zsY9h&Th>9gK?fUz&P^^fo992%5ZT2i@it-tTc$seTvdP5|G8c-bmUQAU5=3M>b#%O z5=hx9l$^T9AGEi@eeu3{^CG)!R=NW^ze+^alb)oZ?MoxdzR~ch-FbDz0Q3>>=r_gn zlHeY_>0;K=w)?5Oydv&t=i|$@?fkES2JQ)eSv@ahD-=8_I)T#~12vxd(jEhqBN6+1 zmn3^>Blc`{kV0sC*WX$~ZdSLbRKG}e>8>u^*BnFd1&n#g&8EQ4A1TAipRX1Sv|~#P z5UZ`p_bMw1wrCZ)I6PU-~7Y(aXCu|A_&% z1c=OE$!oSDatVDe`$MFm&-*`7#(OJs22Lrk8D7Lxes3W2>EEea-6|f`T^)xXr9-kYNH*kP9mVepgyp{^KH?|vbaOZ~ zZ!Ka?hdQ9{=2R>@)xyW+o8ot9Brdp>%l3>lL)Y`k_&Deh>lflqJA}S{%kJU)$WB8z zh+N&4Ze_0iS=-6eRuwJ|iOgt-0_KgWgls|qeIb5R6Q@+Xu zjyVjrzO!^-WiY$%2I`+#Og^#=+@g;*dL2kc_l;h>-#RT^t;oikjKl2t#ucP`z9$L? zZ|9yO_W&cR(0XICY+d_n7;ma8{ZaUYE_w=&%=UwDY7OMgD;QoBreX8pfBX*WKg-F#KMnXCpjx!WFVJ6FSAC$*)aHqHp-UH zbb)SO3a;orV#9`;Lft0;9s0HKIkSa^*7KOiaW`v9?>lEZ!)FN6aIILA}sFYqT1+k?5JIZz%N zbGGveF*E9)@W*F&NKA6>;o=q>soIu4Ses~pdsWep@4c6=$}+>u$|P*A3}7!Z+{6w1 zK^x1f*jWP~6VmZ#hAt0{zCtrE?nSoac^-0h3Z}{u+VV*&)7R0pb``Wv%aZ4doKcQ2V7unDpK9*{H)1zB-G*KTD z0%OH+V1t9g7bd?cyKI2^Ae1aQiuuajsiyZDs@H9%Im^GvdMk?jYujUp%B_~P|Ja+F z2OTB((l5NXog$v@%f-5HTY20(RoH#M0Mo2uwxqoWNt=quIKMCN6y<=(EfHcLvP&XF z

{ZFJ1o20;}G5(}^{oC~kVK%vs40H=Wa9UI*r3=|=sfpQw*=0H5$%4|1+I#9Z-* zZC|#F%*;963k{G>j3o@M5E&(FPq14XOmXLA0`@KTE`5GnPx$3ik+SF+Tj*wh4ONBs zTk)I+mF=WqLVM8@b0l}ZD3F&~1*LDj$d~lC28-~=(N%Y3#i`B+l|^Gq{|1)zUfdd9 z97c?83lHiPNc{R=@|@RGq8@7n`{(&s+rgAhIB38#E*(wFGx@|nL#cRcdyKR3<`3Tw z#rNCdmh_@0)5~J?+A)?sMf>s9!z|F_q|o(={rM~LY+qlNgpTJ6SjmK4G|l)Qg}(FP zi_WWKiN*;y&)P3r`p=X0%2Z(abq0I>TNMM>UcjsOulNqfp%{j6ELpvnRW`086Qy$c zkTjZWr<=jnArhGp<+4>jtT4VoXsR!?vd^d2laAX5TI(@{SBorzl*KZv-c;r4c;1sb z>{G$vX9;YC$lp{lsDQc9D(H>6M7d1tk;`_n7wUGnefa>;n9t{%$HK*`v()l$Fk9## zdh*G4`<8juN#`Y3j|ZWT$YdSHz5Ho-0vGh=f-s_N#; zhU;F#D+O(-N%kW;WMd1zjt7v|Gmy((jX+{@CVFoVW`D=mbO^;e@~pkRoUQ3SCIjq0weZ_ZH~7>dxca)zij1K z9SxB5A{FNn3|yD@-B0El1P5?M6zjBP5A8dyiYzNdu4~;F55h{}(Yl%CioK0`q92}{ zWb!dv24hpaVAEx(u=wXA=>E)1vM==J*XxaN=y4np`dadt?n0BSoq}J1L2UZOI#Mi| zj~6a=yeQw32KN%au-waK?hgg$e{MN^C-k7qbwX2g#}A2p{Q37tCv18d0o@5}*b=v3 z+A8;vZcp68!Z~m5FEcPk=S@U;Dwd@ncz^Nfrnn8HKgia=B3#GuT~8fZ=*;cD%D3`xqI( z-rM)&au+nPChfnveSOO=%Jmj^DUB{{<|#KiBXqt0XYFQsTI2f@Kf#M5N$A{WEJ?7I zx~TO*rn@OWQ-Q~ef5=8w=LCL2?35mT*w`P*E@>R%CTt*9eJR^geud=W}GZeHx3-9d3 z?6&SS+N|}5K7IA&|CY;x49buhq$0AeZj(ir9y}h#@I^0dustjc{jX(}ZC&k(SL0If zA+!(mSYw3y0der2n$1;532p!P6l4ZolE^&z(%+>=+x9AdYdz_PrV8wgn`Ak|)$mgB z0xHytS*5rW9ZT{77&S9D-rCwLYsS7@`yS?P`SLm8fPibLEA=WtgL41CMGhgw7 zFh%4|3@T4!Q5ROxOtm{?-Z!sgUKhbs6I!X~h0nx(PZMTF87OqW%kzcbp|YyT}$QxV5cJvhddk`q{Sw62EzK4KXj2oezhPX)jii z&1gs07)rkD%j0#;@o}f{@(0@SmE$d;{ynM9msHuZgNnU=Qp~%xJg7ngbCc3A$zs3k zQ^9UZ9HoNRgc&S%fEwCIR^eNpm;8FuWSo!_yHk-{trfk2T4E|lBWElR6&WIpFCyCN zd0{s@cn&*`4(vIbIAbTN-up>@o@01J%O*63b&^WkcawMx-9y&FDwtrD$aWo4K>YAB z44EKqcDdD5Y$8~SmYz(v!WOE_!Z2q?9(UOthYo`C;4m|U$t{^iFaA`~fiPcA%XDGf zISDH>_i%SFT{K_F#^c#B%+YWir7r9#?y}pt_M-miv!)geOXkYls;|RPQ(LMu-4E?hTy^0+2y0c?GLl5+(rK!1%sfs6E_hW<{{(D zpm#)x^}gjp`?pq7m(*z@AIcVUK851Yq(<45L-r^Z`oQrKx7gsz*62`^f|H+Hd3~P& z$ewTv8z&gL?pYW_n!8mnD?f^9t`Heyf}61Lk36sc))#3BBID-YCRV({1|boCF!0Ib z^L{zw?@8gc?4!!6-i@VaLv!fCKtJB`tugi|#No7>rMPD6W0-i~g=Yt`%t;L-d9wiL zPF~^7R=Y`YhqBP#UoIP3(g*kD&cMz>PVm8PFyOc!9+~=cw@=PUI2MVnf7Y^*B1h?O z&K+9TX+EF$(Vs$VzS7dD9x^wf!@uS)a{3a_vMZh|sfWgII$$}BOWJu+q0k5Pdc4wg zwW|#lZt}yPfRAORE#;(pP#qFqUpDKs1;(t6#6R;~9zMn#3WA0Hf1jy&k8UhsO(1)) zpf`W1;ZCs$?eY6pg-kwU4?UhCzO%+%7=q^0p~rpTdvzl<6(lW8c*}6#7-}2`rPc3jmI|&|V1K4P-1@uq7rOlV*wzwZMFQnm_nhv*d-a~mR zD!6QD$=aQ&qr8=VSbe*kzj!+V68~5%4L!ydOxr}=_E(bC2y5QD*%Hh9L}BmJ!DU+& z2cd7nan#OHBmbjIsX6=!DKx9|>2u8RMXdz-B|jvpg{q{sI-eST-RIKx^4QZ-3XLb* zc-GwO=os2x8rNkOSr7N1%^Kx2{hI=Rkr#(oMxCX#A3Ly(m+LWPEt4{jm9UcNV~Te& zIy}naw;WBdtGE~eiEeD+zv*=0?r(|`I?2F2f^j;&6xO4Z`MbUzw9%k|&i^ps=i7pkTcbikJIJJ{LPWJeM`yi z-E=Qa^u9@5uw$r>f4|9YjP46PlcXd1}H)gUewx*bUS^Sw5_LN30H^BV#6tIM+%;;r53=)2JgUz>jHrqo} z)KxGgZMI~~Ck3)FFQWy`=eX%`8$8_Mhn%F_GCgkzjIyKKGLPzNeWe)3EMM2G0{-!kdd!(CJl~Wc94k)Sq=g!DJu) zQAq+zL8o}tvkNQI0X0{}wDsyUr&%CTEfV*a58_+DTfo9936_5f*lk-6s@8l@kL{Ll zl`Z}7_>SO(dhC}S6rW!uKL5yr8LaOtbxdD*9wSU%apMz{U|1K23$r{}^|Fm5Ut2+m za^v_4Godli5E=K!xoq(%TPzC`-f%IqSogR_&B{|SaNa^Y{Y|dl<;#P%z4nJ>52$ zPCuz2{}69px7w2`NBp7*kr!n_u39*8AsxTvBAMaYbu?vhPb@vQo%>jbyll&}aQre_ z_S)$&g6|qjr;YtUy_VZSGbOC8S6_cif=do5n5^f|1~)a(kOhR6v1Q!)&rUji`)Av2 zv{d-NE0-4n3+kEbr(MLSDZ_8_LSE@7^q)J+!Q6&RI&H9{2o-#js)p8{kvTGyFjVhp>mBYAH{5v=P4nd<^gY0UwJ&wJMh1aB;Y*V+r zV%PVT4ECGzsG$-pK3|Gk>MpLQt_0Ifp#f@Dk7oVHdQpJzwPkOY=d)h+z=L7=7&m(r zlZjsaQ@}p-m{-92F=u>yC+4ygWfrh<6lp%nXv>=(wSF)4*!GP=cLvEG5#2xkR@6k2g(Psfs(3y0Wxu3+es+K5h9&-Fw+$bRR!F z*-nzV%Y;Xv-bfmAsS6%#6mvm`2>kK&<2gdhck@6ZCI$pBzh4U|zsvnL)~?12O{{;I z2Ib8<-1VO}KFlq_!MfXQtws}d-W7mk{VG1AbTSmz#$nm3&vjCq{2}t?oAoH{ni)QZWuRx5r#wJrh_6%g@Nm{!Nx0y5UA&x214lLU z)_#Ib>RyVCY1_EZ&g*dBq$OS6bta8E;DFv;4r2I{`@HVs5u7&eES=%lkxlH>fTkW2 z=^)z`XsFi1yW@%YVw=god^Sby^J1KKn#T@@&7{5TH%)rx%NI`+ISXq_u&P>#&yHD7 zM^5EZ2L)qZ&~Xs9b_~P(H(6zAeH`Iyas+d3cB5BOCK&xbwylR>QD=x{i78moa7kji zUV;9d{I9mp_3)x+LcjY{p-GlzsE#__b1->WzydA>(9=f2^`559H|%%Dwt*2aNZBp9 z*yAc@4ziK<&@jUrUlY8)AB(GHK3wOa7fo64mwuW?NIabuP~_8hq}t-gBY!AiTtF5a zpQ-ZpQS$KGa|Zp4?y)+*K*GXm`gAr_rlP>G;!6~?CZ@9R%@zNq2vhe7 z&2#1prjw+FDaTJB)9wzR`Dg$RFRH}q%e|P_KLt`BTS~tygy-U;4G#VCMbH$%yPhv> zITsFN^b4U~4_HM?KQEAbUj@z(Kt>b4(10ghB$F3A!1Y%l>>rs?N*7JRtU8XJz8So- zRuyRtxj2zHp9Lh1rA=-f5FIb-{A?+8t3KT3Khm!kIeJ0iP}H^K2e~y?`zML4xQR@TK`4HX-6asSmHHfpK{mJ7y(x%~@%=ka9Nmc-)i zad)OzaGMkq1|mJZi0>&C9K|)^Xj#u?+n<}EsrOO5u)oJ#DwfgA*^ej{j@)7FHVXUQ z5lwfxx=w%MLm?u^)7dUOUtuL!J2Z<&jI5WL$~;ey_r8Z z8EG%}zM(j~*@c^k+Ut=MgP*U`nX2vvI=lETy^j++mYhA*$>b*$UHV+M>4(rxEIox8 zwH+uWMFktGvvA1t7S9e=#^1QJFyE%c(lon4MK%&wBAWTp7j`&vJp`4p4YJ!p?=kML z&`|BT!DbIJN5P*Xm?Vf3+G59h@52c^*l*%$s~bua@>FndaWp$SPW11~vhciDIzQM+ zaCdL#!KVKzW-V^1jcylcc}9Ew@v<`(JBMQ#l-XR%arC_)lir>8;d76f;AC+OOplmz zW8s6g+M0y@xA(I|dQN8~TM+s05udVB88_!;BB$$W*{>c-Xebt$fET)udqN;p%3Y$G z%4*rR1hGd-7dz5zYgxvI4zM^p2SLJr*XNlrB;8|h<5HIF=psYpiazJ-`%|p(%ylx4 zU4$=bpnFaQd7lJU*ql4PvVze)m*v}xB*3ZH3KW47S)Y~}lpi@U|ZA}G72v9wA@Y@)qz z8he`${^Ja}Md5gLYnS9=bfeJnSxFb3HpTK$rWija7EaziJY<^*LN=0 z_Ks%i`16S(D|o2z5&Ye+$~Cj)QBZOUNwe>;>_N6*R=y(GZ7?6OeiU}RK8nQQne3bs?chDKKK z-C`em&Bqr9``(tB?3bd{?=T*9Zek16>~JYE8b>;`@Yr96P-EU%+T*$+n{VrcYc@qt zUuI6dj8~E0knd#p?~m-^1QlFek%hS9bJ&#C<4Aj7`?g(;$7%-Yh9HEPh-bOjm9+nc zlb)LwFF$XIC6=Nl_p#%$Z#J+UlZ1bri&&myH#xd}qbqi6xXwRK=6#pDX!^}E1k)_(JjdhVt^A?8i{R7lL+Sfz%(YPHG{mm0-ZGzOYFI*g@DT2wmdVT> zn&VvR5nSwjkH!D&jk2CWICtq0uSwrX(R142>V(d&7ytQE*-%wP9ZO>C#qPQ&;xv*o zPICLuD`YBs+dC)iX5+%`Q8qCYyC>xFxwD*5trUk-{)Q}S-waAnt)!3heE7zd25@Og zKs((%JVW?d3bvlad#h*`_`^f=_}w8MeBR-g5{$N%z`l8uY{gZ3yxJIwtyOz@?nQ!z zOOoJ~__0?p{uJf+o~%Ev<=#^agg!9=dVvFYi-{hFrVNY+C$!!~eGcU4n`}q&ndxiAm0z4KW{}2Dbh-a#7ne<8 zq$qZVSF@s7y&!G;y_t!!suTQ#R&NBY$%ERXmF&r;y`*)sir)Tc$A`8bgUWYDp|@3s z{VbGHMpQDrEZf3kdI}$|_anMx>?K=wZ~(f7Ct-+n5PPe1iyn1fjO5ft{(684&PJSs z{lrzW3E!2V_v;L>t_wL&bcI>SJ{(mH;>DYRJfA2eeQ{@z<=4pNgz&M9E#}kS3$N&@ z!^khsl0E5Q1l9J*NZWOq<*0W)5w@e~jxb_xn&3O?k>o}(|bpl6? zzevpHH=0=fih8oz=8c*eWxPf(g(B@eU^$|hKj~^Cz6TMoZg48oJa2;@X^9vdp-6ou z8sVeJ@;jV z@~y}SzTcDPvMxx5#4C}B@qa!17=3kE|INm}GwV4__x(CLQ`_VwI9AH#AcM`+d5thj;&A3&?!nG1M& zhsDFLdlu_!D)#$F<6wVucWFP7vw4`O;`)*othT2v^c>S+l5tmLe+z9%haAlB*^U{m zP$HudXJ|@7Iseqz4#ssp&{=s)mbY~{`mBh>7tI_0Bk8>3a(=%*Zhq|9B&8IhqP^68 zo!1>Adu8uZ$sUpRqDb1M(B9FInci23kQEwaX3O5&@A~!q(?7Q!_x*mK>pJJWUe6cX zUSf(r&GBfn;XWVPB0L@E@?cSWO14hqe|1@xg^I8|zF>el+(HlIY~^xxO<^kiYibwB z%8?f?}G4>Aqy^ zS{6hyf5G~GmdYwO^~IqEk>#zC&t2&nosLsR$2-2veUJsLwnZR&UkU%)$6WaIMYhHK zK|&)vi(Xvdq}S}v7hKTB><0&M_qY%DxI7Tyf|s~>Kr9QnUqes6y5dCN>wMc}Mf4wf z0yBcfNrOC^@o1-x-0J#kG8TI8+XlO#vwu6kmPtsxmx_0tf|=)$I(pw-Xq5X({9>LP zt<7zwo!eGP(R~MD|RpI;5sbDahE6YM)Lp&uxTOp@Xj4};Q@Vr+K* z&0N;2VnIY9PCGPk^DatAHa-p|mp;t;Q4pnANaXWlIv*KohF(L%k=yf{G%L~yXUq4t z*7n9cGi+{2!w2Q3{M6*(*j1FPf}`6-AD(GMO!!1&IA9br+hqbpJf2Wh$@)v z?A|I6EMs*t7Bx?A>Wj$N->>|60S$AZh$R`$7%P%+4 zoT)7@oYWC_65Xidj?)w{?~s%|-3%4`)8J?n%4!cdQ@e({tuvXeXVlSaTqYJ?R_FIe zsN+pb2_`+h&dd*8C8PCz*wnq82c1zvV&FQg(z?fA^)Nz*qG*u`Vo_oI*i`ri(va+| zNbdKy(D&tUNp?W1wP!KbK8V-%U&`p9KM+1_Wh>t(qL|E-4~xvlwnCjZ{BXb1}5)t5_|ePe9r`PJgW%D{i%f& zp8af*nYRyYNH=2h^^jhk2-DkzyyM29s1-ZJWk=7;+>(^&(8c6dZh+|>6_`IRfbsr~ z{Op*%pbKRfHaCaOj<$yK?(K*)zs)C-Oz@4P;h^a&8@cQTj!zgNKfYubVwfJjr6=Nj zQh;DW4n^4YR8-HkVM=12)^m6Z&3hWin{@iYXYN5nu2bNFhcNkCGq+C` zxxHTc4#s&$k_=Uq8iJoN0>uv4ObRt5Le)Vvob0_M+}<9dn&*i21#vk#(_w z51A}9LVMFNTCq&lEl&e_mRWd|n8&wl(ZHj{hjH`SayCS32Dxu-*XloV%o&Y-+Ph)C zp)>n$!)Ri!;#+HYyqzJIkBdT~mobkyVgi?$DX0xT%uFw>rQi5Yiyg04bPCkK%o(NV z{j3eGJT(w1I#sQ6^+nM#WE~I1oso{L`lA=U*e3K>wDV|(Q z0hT{vj>3P_enuNH=bz3m&NIXq|D*V9AlU{!5xS-c$1yT|4C(18qTlr+$dAh7tEF1< zaaYEzY(KW*t_6;WzrR~%F}Jxt2C84vu`PcDJMA-%#zdTMoxRMocBjrY59wB)GU;TE z4l+FQTQx8vTCUQ&C|C3ucb$*yt$=BQC1P~jPWrd&F+4Q2<+YbvXi5hgOdT5uTg{z( z#PZQdIhclhCLyd%jt6~lyF=Bl=kV=!ooRe@69v>cOYx_)ao-^iWkaf%>4mFwaI!0u zb{6wLuQf4e@;S^YohWlzV@XRo2Dh?b-uYT$+5Fw`JUEK~r7?ImC>>Xw%UHLqq4Z?J z2eO_$iHC3)0Q*cTVBmcqP_*MliXp zuON@q>3m$QIW|Aug>QqdNown@uyA!ER5R+>@UH%}(W#mGZq?-Pas(fs-!D>{?_<+< zKs0T-EHclK$jC_*M<3OjulrB%Dv?4&h$p( zNHf%z2Eg0#eZ^6yD*Cro8Ie;0+1c|Zuo7B=|DUTr+B_ERHWeYE?-=&VxEp&_5!}jz zY5Q9ppL%3qaaRw%vs(Bv))k_}WFITI;7Z}{JzMqaW7e7B%fkS)(`2$UPC^q~K1l9+ zw}a>djL}9>c#$p!iyRhnp_xpB>8~B^`6gHLC=`rV;W;|)paH|hA{)X`ogWGtf-vbM zI>tA#bzd)0?%b`=Qa{QKB4;95HxWO7XR@%(1F*7kEtKEgMHdm%>rPV~r&9ot+A5U)@0x$DI1h#)EQ~j$%U5s*R>D8NDF}yEQrX9u_i?w{c zPaW3ZP?fJeEb4@k4F;%1!sYvY{_>T%@S4TL&^1oBWK}JO47QRt|5y&I6Mp1<_Y+xV zw&&6$Z8+`9#b)ivtmVxT^0EA1Z8sUB0JEOr{R-^O3%3N*jjRglJ;0oA_qKp@TsW2l z6;^b6C+-6ilM!d#m7169qQ5TYm{#I%_8#3&SW-46b$k>3>K@P5HD*nZhhwmRbmrfD0;xfmR!rYiV?O)Mqze9 z16S>DiFs$zG2-MA*^ks=I3P5!ei>@CytCNF49dh0(K|1UF~%U-1x&f-%POzWqKxb9 zF#Ku|fBZU-wuPOffz_t6)sc2|Pc@ESn*{QEW=2@w5(&?h#yrB;1T$~%7hJ4T=2jO- zsk+~3zkChvR;+y|o{5KP7J(8+4fRK8MR{ zy*opz%T(yK+~=`1hG@S%5=T)Xy~;2bJwa+KA7*XATACwt;4>Yp`O6!^tK=klx8;)U z7oi~(qHmF5Boka-1)NANg;9Mrx0`&Ex{8|LOWU7$Z?h2W-d#94tB709vA~|%IMlaj zvX{#9Xc* zF}a(aG;!Z!eEO;-cPe>BW$Q;_x)gy|-$OYQ-u7mQE;HVz|*U?zqWa zaGV~{*!yl$V(4HfX5_)4xr+U~=}cai{?W=}IiEF317=E<7#e9Wi(Ft$?kj^S`oMO+ zt=Iy$3wFWso)y3JYzo{3v%;!J1v6GvM&W@Vtla#NH_sZ3;g0)6&zvM3C=*_-uzaLE z{>(1wI?<`kBJ(#{gRefQfFXeSQMs z{;L!II75_H2}W*x6K|;rr04U#(aSE|Yzi!5C}OWN!lov&wV(Q-s-y4|Rpsz`oBLwo zx)OvxTgg6jlwos+9U>37lxHro!`9uR=6_XTS}s#b>1!U1xfsC9@9JUVk$BwQt;ds= z=;3hp^wwSK(;u7YY|_uxnm?+Oc&Gm5!GDySWL+=x|4nCL@VzTo;G`w%^QIoPMuGCxAC!>y!3+<_2B1vmeZ`5s=jlkYGWwhhWJh#Y(;2tZ zWZUvgs<|)DD>2)g(j3P=4eZVW{r*?;SL_v8)uS^oquPVdKdX+HD1uJg6n5dT8%0F* zXyt(I9%v44mjE1lB9q-~a|`24wB%7Q+vE2o6TDB2MpIrexAG)RzmSW?H4$uCvtY0f zy+rWGgeWG@o2lI{ZhG5FMd_-+} zE_;1fnGzFn=-ASm+`of(ztl_d>CyF0z}rJGvr1%EX65t0E4ARFnFW(c4s2by;G+NjO%ErB@R%nG zFg7?0_jbMcrhl7AQ}GaGM-Amc(Uv$qI~-~I3M=*=vlW?BNjTT8E42^M$AU2l==7j~ zuNGX~Z-$xZ>R2P&@JNNuEJ|+G%rwna!@HP5p?TZPU-S~JExl5lU6I8CVuLBlknTT>d0+IPQu$l0)@V)~&~Ij1pSt{a>2-++Z=sQ!R$&`nJrvN|AJJ%BaEM6i@46 zj>>rf=p5G|P0byH%MKzR?N%*oi_*&%IlQ%8^c zhwxzLA69rzFcPbeVvX3F?EAHu9I6k|L&q?g&-ud(gQ4Wt3d=c#_o4{2qE1%5Zi;dU1-7Jky6x(qHNx0+S_=`vm6$xCU~ zM*bAuB3+R&r?@VP#f^JHJ@@(`BjPbvb5anQS)~|hCYPE+Z^5*^ihRV|JJfO2NJK3Q zL7yJ}++()`3JtU1wLX+}Y4M|`GjLDsjAS0j`yViaiU2-m_ z)xF1Xg|n8>-zLtHP1mHB>QV4*C-Sg9)Um(gEk)fGd~B;HJTYxJj`vK3OmUEHrEVdwwNGfe8b15pP{xm;~D!n?*|_Bj)$gVvC~g;PpW#7kjQ>~Xt%vkOWqK}p9d(hCk26T4 zcfdzwC-1618C4m{kgxJ$?a$v8`M}1geS4g1zSBe5{y0=e6i92*^>O}P8eA(+u+%nN z$T>=|UdN2(R{rbo*R_Lu;Oi-}rp=Ic&=ff}%Rb9hC^;gV^qp?->zfs@^mj3essv{~p$-kD%JMH~rqK+iwN!Ad zjPllY=O#lfQQS8U<4?!Rx~J8my}P;mn$J>nyEhaH9{aIqe?EWtT?gUwM1JDJNo+u~ z6KQq&-MUNl3h9ftO+`ov>%q(O4TXj`L}&{$D@qdNP~I+bxPIsYIz90ymOVEy!H^Aew)cReG|I!dwR$czQ|=;{do1;;n0|!il^6YSjwPHbUF7M z_1LwOzZG82b0&HC>7~R|uY1uz4HaCxYs#)=3TE#;e;k@&#h2cmf(OsVOsU^N7WCEt zN9QG=HrBJ;&qiO|-O_Mq=QCE-#*^MA{wAC5gZW|cy)~V`1Q&ZH7J5d3Jm!?pnUyE_ zuwrwVKJ`bB=?&7h{#$8Q!v(5wP~vAt??uw$j`9z_N=&Z6(97m9uJkpal<{6PO7M`M z__XI|E7efsUw~;Z=CQJUvuUbRTYNed$cNALBfoKnscZZQ*$KTdq^urGlivjJo^ws` zZG*VC#~JhO*9~#6=UymmJ;?Td{6UvTxM54lL!SR|AUcZu{(>XhrTa%U5%IhTZ?^qo zky1Z=op%i1s_yc>7lDr*LJ^bU$VQB=qk0`p++AGAedie?C1DR<-8?1DiLk=PJ*kja zKV~2OJ?TQh3p&1q@!NNO=={fjG_mu4wtH;qDPo%NKNk42?Cpk_7!ZuOui1QsftAQ} z5VcX#WM!I5N#(>Ds#gr=GX+ok#;}hR-R-QjL17Sn&l3KKQBkbm`!kA<^2Pz#V_rU| z4!bjy8Q|)C#ksTHcx#Y(`h1%d&K>`N)d$CFL8tGzBv0r~AH~@Wy!Ztq{%5~bj z%M~3gYL|_cX{XtPIycgd`$rX8cD%vVhu)o4MyBF^Tfa4<=-B8WGU>OSPn>FmNsYl6 z6>G#b+c>~My3t-0+s!C8%K? z&x5&I9gkb$O>2KD;i%RcS;+&T*$yhBA;TSb%~KzGX(*;4>c1ml*^xgA2MBKf>%$ovEcJ#{%H9iESr#l&%N)-_-V4rL{sdj_c zbP)WvlwhPJUFGp2H+YZGsph_qkv-U4i=wNh^7Wqm~#0h8%MALvoQ%l;a`^>!K*hhLQa`qPhsZYQp6^2$ zk}|3syR(BLe|%C_8U1IYz-OcwAxI$vQ)ju#YI{6FPL-)VLDvWhs|@g_G!8@6{rS%O zda!o&3so9yP+1$yo@W@tS#$_oN4fKS`#b!(Cr%K{>Y= z^}>;(Bq`9A#3Jh7bd2vX5PDGuf5;o^rAncF?J{Vf{H(!ZD$}-shK68m4SB>1j@zQV zDg#dMj>#r?F$9YKX#G@?hneb3&d;AwQ_5Q@Ur8UGq;lc!UB^bd%%e{i+qN>*SDSg! zbCn{Be>+^3Wqk_lD|&g8?LM!fcs5%%-M)>_?h(=Sp?cSTLyL%!v& z7wLTcMW5?$RD9hv7)!;z)hn(YeRmSt>@+2`TVu*MXU|3p36@LAYWDR@knng`(IL~B zyuY#;F6BicDqE7CUl@yiY5B%*L0ObFy_1at3! z@HsZddvPrb;ZYW|(EqR7VPCJ(U)v>UqjZUPQS+tu&y`SpFr%V+LmhPXDa!Ri&-XpRq?5nNAWe_Nnp#Bo0Pu&$^#$*5ka!zUCD#^SYE$o^f) z{Cl|3d#B%2-4?te(3due=cGJ-pRGZ&HBEXQKwEl-@V&y1kh>=sv-TVDYkuO6-9~W2 zSCukjSpdzOeUHMLY`G-~zUAPLG~my>it)udST#Ho>ps3_RpZnVDR{Onm+Sb7@4jT* zL-ZYc*T`ajZ=)~Xhp6DW9Ur~J7!nW0GLilIuf!IXh6%_!TE`q$8smx3#IBxnhnMtN zMbG$cGMu^4#?>)_oST$!S@^S__8EY{qq#5|m(9=L_9gvaO06|Kc<^@W9&%E6$iGV! zb7dH^b2q#%^kKh$I?|}w1+?p65MO!L0BSYD%eHJdKhQJ+i4)T>$0wX!h}cYq)t`k? z&xy|yo=vr>IhdEWLfW<3kF=*NW6QM#%uaBDa)P&`d;6VytgkzbQ!Anksu8lGM>o^T zy0i3R`vmS~J`#62$3yj0p`;sNhz+&r=(wev?aIDRAAe5~Suk0A>3bst&#T1hKouD( z?g&qizkKaeMclt;fyps`STyimg*^Texe7g~lpVy53vcr7oqMprvyitHxs>x4b(9DE zjc40x+7V4&Ppf|Zu&{lYedR*AVclv4JMC>8_8kEAOYOJHIDLpXS*MmR!Y=P6~ z{V=JUOxD0|q4b8j+@?!A9G`BAU&r=fpkUHQHk+VFmn2xI2C==4t7+1^JG8JSgde%= zN?yHQP}eI#HNMs>c#QRWpuMZh&1<-|2Z>eh=Z63Tq2e)5mi0}P@Y*(-fRbI-V zGkdP_JHiY3W4XvRTz5h8EgXwHjh#4PewvxT3Z~zA=O|@*f6kU#;Utg28iiO{Q0JS_ zK4L1zxFxvepbK@G@C`Kx9n>ciEElulagP_U8D;L|cKI(kKHbiz_wgmu5G6ccwqANw zu7&c4OR%!n9q!Z17>8B_Bl>GbMbF$yat`k&^y;F{dyT+#*EmE~<@07y=YRUAV&eU3 z+1q_;v_ag%W8Qw{L+aJ=dUGy@q^%P?8R7R4{!`!2-PpAaGMp2i`C(xrH(6|qPietu z=;ta+UU~y}3Wv%Qi*#VNWhBOmy42yeKezm>kKa2};23Aa92Z=rq_Rm!`}mBf7>eBU zGdVa@q{!EbJM98H;l*2I%C5%-P;dP*iZ%_DW^I{@UG0)F=4t_(EEwRr-4l?bw5@!? z8)NwO$b!1-Yxdo2Fb)-ELg8xzzp_L0i2)~tPQDA<-&=|NHWrDTyJP%$sRcT@`yt(> zUivue7PKF$%WXd`q|0e0_&$6O49?XF&0#X^mv@xwYACa#pA1mok&2T$)Tmiq2i}Q- zox329Z#z5?&KZT!?Y)py3jb{3{Qu2WmOFZpQ~4pEe{U0&r& zU4?IJQ>H1GUGpNhUPa^`y;Iix$ws<7_Xw@5vEyGnj8S6~f!vsKDVy2hlVJ{uuDxN! zS&I0g5r)&&&HVQLVK_H44`+FaZGMyvLZ6i&`6nZz(Y~aUA@u62y7Q{MMv*J3j4_S@ ztha#;Y<|Y!gV`W9?d?)}>T$Z&XL>McC^Cf(c4CGn@7!MpS+NK;T#Hom7mXWv%r zDi%!9Q)16v@tP?@1DAsHP!mwc17?bR`2^t`vRWfk4DW%yVy+$dtcm~VXaYBlU<5un zC&{)jaqmcgVsJfEnBqodhUcl>;~rdL(01Ck@(ZQC_Ow}eJCROzQ-OBvUXfA0o)+$C z3%iPclHCb^vK8mZo6FU*AOksMZMQ?pEal_F1xsJBZT&~|VMEW&rstXYv}8>XudEW@ z1i|7km^YjcQ4l?~LK+4~hO_$8I`S}>fsHfI@qMCCJXN2K{c~4H3Xe3PZF&N$tUHr- z&1fvRwgZmEyLj^TX*l1Igy5%M%#g3aBx#bj* zqaBlnQ#X@X%7}HO`KKHHgm2;=DVA7r!xwF@+sZ~q-@@*P1LWuSv_-^FGwdI|2T{Tc zGbO|p_J32+ZekcyXjw&HPBoH|;KY`n*TS&-Dag`R<4etTv3q10`t7b`xq@kyzd;Ej z&Mn}ETV`UAn8W*jPGt^e+sRl({Ej)6-29L!vYrU;{W!CVye}4bGg|l&_Vl5P*7~sB zvmZa&H}bQ|LNkyr{GosD$!=8ir|qY+T4yX<7WvZ(@lM(Iy(sM~w8x~&VR*()vk!$K z^l{QTs&?tm&&OKBVNVQ9%wuKkeu}+gT$0dQ!T_&z*wtC*DP77IXs}yobokA8KPlivc_;#4P=V4-fAp{;%F?aFS$9Gu)l3 zs$R72Nq_YkfYW+8aBxxNJFP9SGQJM`mbRg2nI*C&`eJ~sC7hLutctdA)Rou?ul(mF`nt{>s^ z#B-=7ogS>KT;6>RGN zuk9XB1|j5oD$c#j=9=d;aY*dJ;~p+x%U3O;r5SCpF)D}~+Ra9v=P_8_uMe|*Ii7ww z#!_{sARcwt6z5ok$mucS8^!seJSiE^`j#*|hnsX@7NKd;NgkjqGS23t!0B>`B>Cu| z(6$H}<^NdkW`FWq{J+|6Gk-kPChkOT(|mUE&<0YoE~TXc6K0id3Y(!3=so0=6fS(k z9p)wBhl60l4qi|Gg8MNp#*8o1_oH(DlT!Y)x3%;%z}FMU;rqy*{1ybz?>i#H<41R1 zKc^GLbKKnctKvVYtY+e@C`bLT(+>GWyC*`Zv%JjZkW; zuBQ4Ir={U$GMMg(L#KV7%+0qwF7#Q1O5+E7!9!hi4cm(aeuMbFa$U5`&w@+KY39GC zj=J|w()wh!h8PU2p-F$hcE8}iX2v-RB9csLEp zXBSTP!>ObISdMzYzfRGG!ns7e`<@`ROc;vb?-^L`^+tHL*3&S{HfSqpaqWGYunIYW zS#K3sb7oJh4YEUI;$3dHMda`X1R-tZIq9JhiT!FkZkpAzH4_$7DxIP^T{>|^Zv(W5 zS*T^UrfrgT5)D&O5xJmA>{i-J^3wl7ZVSIk>mMn@dfXwbadu^wv*q~b9D-uIQl5TG zCiXeI5LDcoE%2Q~qrT;l*~lQ?QaA!j?PBnA@-RL;$OxA-(lDzjoJnF<+@}09dG>MU zb@>Ajup}D~`>c?(g>P>9>>_yUwxu@9chJYk6O=!LOCArWg9#sf*n2PLaJ`=5vvi@| zshEFUG6FN&$6(XDJjvb27@tpx&wnNKjR)7!%_l9C_<0mxs=txO4s44RJtx{OetHFw zw^qw%ee8no&n@A-&Ii{gyshAOu8?+vGG4C@W?MDP5&bhl@Vg7SwkO~+AOpKxtyuW) z_H-q2Ej14K$0v@|#*OzWt#v-Rd>~$mGkv5+GK)EIgQkt&h^1F=@rlE&;9TQ_kN&o@ zw~Du5@1iDOnBE4H>V!`IyU=mn3gDh=8IqiYmhVLv^E)i`W|6mBv+(?V{K(GjC-qsm zQ7Roi0`0zv>>hESZ*#hqmW_K)CG7|4!Ss?bW^G>Uw1na_6? zKI7vD;acU!+bh{)!rD-jUgqqs@I0EFu4=u{+l?57N1vim_A*9x%db{==nX~Y=>qJW zHw;~m?M3^mIo#xv4k`-Lu(-;eb+BAbM_PW-2hpe4brTs|!wT_caX0?>oX9=tzZem& zx4D{NlzA@-!o#&073D7^vJ^f0In5pHp~#4D&*Si=zJMPP9)*jPhGXFuWoES+^d&c$ z9%g;#?(NhOT#=2wZ`W{rp}*~DQH0F;47N<{Vood%!j$t3++(E)^0ow_tEP)=Psk1Y z89P{huah>OO*DjJdMx5T`0)=J!o#JLj>(IOxkY%=;>6E1zB-Ht>~bM}!Kv0xn!W6gduCgqjlb5wmE`(Re|Hq~Lp!m6pNe!=sgTC~DC1`@2`|++AKc5UlVqoE;n5>C z`EQ*C6!6aqhW|wiFYz6IW2?wXnVf)&-|}U?R)&cDB=kI@zww+a7&!e?(Kt1muge~Y zHM{cg=+ay^Lbiln2MS+OY7l?^Bb+R3E2+7kt!$3NIC}Rtigt_(;OTO67)}>8U)<*l z3M>(NQ~2Fp6|<(f4fNenj;4}Rd}^={wfp^*EYDx7m?r$=3U>}+T=GA*LsbPziw-G!a!Z-v#lu>@S3>?TZTx|nS+AQ`ED;B>fdEP-i?$y&JNGtr15#eSJ>Z6 zc;&ng+J5mH0hQjz@jAesbjPY-tdH>gZq4A;J?@dW&@kMx3S?ssj1u#%P<+05ke{xy zfu%zXE{xS=cTYIckbS&0Q)6EzJ=luhV$ZZ~e72w9NOaA>rhifFi{=|@Znq6KZq0oD z870IQ6yW}N8%e!(I>H1W$#ldFs!e0i-Lb3Hm$c1OhJ}%_aNV($sSUeD!Ffhl{kfDs zNgRePcN390U=WY{rHhP}ndoq%lF5ZG#mP1X^%I)8?a`swq+5yUuH$9Bn(m!iE z4C|UG?$3=Zz$A#CE^DHgqw0KO@(8GD?8mbMnzlRKld0oZWq8^rF+ZW9z3^PHsi$P| zhG)u1jVeU!wiQgL%nm6kA(%C*l+P&ILdt#1$gjp)7SV4GU3AE8oxK}%FvN;sF{s=# zjGx_Of)L?LI=^!_TfD-T9{2l3H;=pU6(U1z_PH$Rq&Z9P#a?F2jUs$L)|NgN?V#%2 z$7xxOB&9Ezj)aebRo-SByMONvxd^7-uj!?{^q(OP{)&OwngZ#9s1;c=(hyL4l0EI! z7a9+QrZk|LcU!iKdgOnnD>p~mX0KJlfYT*V3Y|L<&5XtMS1*2I2PieE3eRVG3Puk+$~+Y{@#z zm$=Np@2WkpPd&g^H)&$f6F1cNZsNHgg@4&I0xu)XDn4|R!^Y-FIsR{19SA6 znutQlr#$AF;4;MuwxRMH79jkWw+^JEX?Z>WWIsqS%JR{{`Hw8TLW#0%3n*%F86PY5 zUw56oVc}CJJ^OwOA$9%bN6qKc-6k3Ki!t#&q#uowtSpB%wNn$7;sUPf=+1>;Bx;zt4}Luq|DK8)$gQr=7?=ijk( ztZOje{>coLrMvM^5RxSBA2)j|8}JFlO^|Phxqr2 z4S_7rWCyv%SJ8d5pVIS@_V}%l48JG3togDNy>sAX@g$IU(f6YG_RUlod`xm!BlvHr z>0l*M%(rR{S?T|xjELoYfP*re?-$@tjE%I)X$F3r5${gK44Rt7Fm2{8WM}N)k%Har z==ZZVZr`$Liwah79PQ=FF~s1F3KNM?Dsg=33@L z_nUPR$;EcE3oorHMeIQxA_DmVc#z%U66(8Toz&lPqR6A)FPI#q?COL_p+S2`c3r1% zos=*N$^JqcXMd?!7CRj3V>97*`7JZB*+OLx+hCcdHn*EH1nr$qA*4i^_0+1T9)jE3 z>w5-&|J)SqcLk#IeU;Q#&mP}f_97&ti7jp%35&ZTpJ?a}enVuk;P5^i2+*|EtlCGh z-<7d0Dv5pEssXad!pj#K{Fcz1WbP3h@0vi?D0ZpF<{{7(=h|l3cqj-h(}K1ttoPJ8 z^hhskE^(~5nF*s?khNvl`LDvNKzX|J|?ipC)1xVq7y zgyDU~2DyPjn` z)?xC;e)4;AeR|nhc!y`jVdrGe@)O|}IC(t-&Kq8{Ea55lJo=A%-P7ge8@1p!Jr~|~ zKV{1VZ*%L<{MOpu!_pd=>%3rVT_;6S9TqkBlmF)|@>Q5Mw!GT|v-(CJebp2({b&j2L1Oy2j|ZpfMR$SH=i&FgN25tjmkWBe5o^CZ)ppy&B6TosClR? zj>h|reb_t?8%hzqvFFQm{Nq+j;j7*ag=!=2{zzmTY}$(feT!M@(9QJW#BJ(jHj@`u z2GOFezsX;_uEJ@jF}!q6K&7e^)d|Lu&xAt3O{(P{>*qneIvQq!-Pyd?K{VF0qSeRr zPSG4+JA`9%%t`6SQG#-p6kK$9!e*xg)Ay|{wDzAJcQy~A-!p#E*LEFk=iOIX zPe|i$4v)vnZ9Aav*}?{d+rp|(DEd7;$R8F5Q|iAO+V*vk?6s;hx%@sw>E{Ck6G;yV z!Uy3rU2uB;8iKFQL#{lLT~544R~2XDh1*#kdsPKeT|UOW8zp(HpMg-(N58)}jXLbx zLMsoI(BdNprToJrv|h1@yu6i_zrIDTq9)2>OL+9-;qVY_hnhuN{9f}gtPs5S$Zl6agu zkk5`6sv%&wKgJEd&qv?hPQ4o5lHTvP6&u#*A?a)eEVjO70fV%V5S@+B`Zsxux*9qT zIfNVj-Po~q4fJwoZ&<#};L!sFFYa6b-dR;iDp^x-XG#k0l|E+m2ZeWja}=6HZ)GL+ zM6u@k1e;IOHsHg4QWdk9>lH~XX|?b~T+I|3WPzL?|*Bm7p026ApBm8Z1aEKl)vCK zH5*RgD(;5xmqnq?r(7vQ68e(~2N2x$IBVGEO6`>H)4-QT+(W|%nX1QdX+v{Zz|4)-XOI*V%Fyx!a6rwpj>e`DpwS6&3+bGD8*y+8htjT zvOP_m=SHqAKltj$zVx5ZCkjY9DP6T4h|v9_?;e-H>bhT}v`wz~Hu^G;`EHGnquUUg zVi4yj&|-x+_oqBmV=4XW z-ask_(GDe4AV)nnT((5Izn0T;|tABHVmtrX5p2f4wZNb##b_K=e81s+4 zEiiRcI5f_iRK$3Ros>Z`G%EVg&`|MxPRc~VUs2nC2GT;?pVaxAp3J|y3T+&`k4E@a z^Kq4`*z8*X#X1-6qhpVG!6CrV3Z}b&;qQPj!Q5=*>0+jYhtU{ZA1m9is}?hZ_2soQ z=U~MHp-VAK#2>93Zdo=IJxo)f)yZDW@UM|tkt2?cc*@NqRpC8Or3CbtV#n924+HM!79EvSUjKG4x;_nbhc)Iwb(y+VoKmuuD8z&QJVj&?GyLh zMD^4`@>ND!Sl(p|VOb5?SQJYek1`Ca&coYe2UgVa2K`AL2RC}m`^dDQRFsYM4~qOu zng()Jg^$Lmfq7rB!Wj)un9eZg4GuH0cR(WU?#*Y(o5eX59g9^vww4EnS)e2=9b3A# zu-=_llZME&{c=HxtJY{^@bo++4*4yX@k;d1DwnLv1^>i(l+c-Yq3l4N9K zy9q9q?L4+M*o9VpZHvZ|VD2sQBu7@oB4)D!+h;JD>N>>G^npQq+M`ievvv=*s+#gT z_sLkOm@Mge3U9j<7@UxRyE23*>$^Mc3RZ-WGmqT5*m*aci5I=p>*!tdm4Im9KVwpKnYe~ zsUWLKc9JnXt@@oTe&|IbZg33FlFRd~lF9hAl#LyZGuBQgX_Sxs;=GlKc* z=Vpjl9DtGaBY9-PXxuM~!!fITHZa1CE>}x5wRkY^CguPuzbB$*;a*9zMGub~(y=M> z4U+C}~`mh@t^1By?7BaX5-r@2yW`c1MfQFA}rNe&#)8znthnp!09yePYOkwdGhz6Mi|^N3QpR({EJ}T)Vk+lgmWxA zd^M1|T>VC0(%iU5#8$E^{7b_|msCU!RL7_@hcID#Te3K9jUCBbvC}tzdu?R6HcVu| z4PV0k<#iSLl`~MZ;y&*tK7VD0D6Hw0C$+mPSONDBV0PCNY}V^~`WQ0-ua;$S&1*K; zwdu6Tr|u`y^}7bki!0>)i~oaJNdPU)Dx}#RbShLI-6WF|p|wj0VMbp^BJO7h)CXtq zh=wu9O-@5FS+VLf?djn*7s__|&O;Sf(DZk=DP=~E}gg3{PN#|6ZfbjxK0O zs^Oi|=i~RtXiSS;Ap14(7T*0)mj4i%Dy@`}m~dQVLS6LWS{`DL`8FLdoWt4vz%4Xm zx5{p*JZqW1p(z5V-|1#mtdjZZ7Cvk@EY;C($77@Q!p`*8z@X6egE zM$W;|czyhrlz?9~**wi`7~0sU!rt4SeXHI;%TIrA)vgC#>xVym3(zpP8`p6hEb7Ms z+%9Y6=Z=|)9KrzfnU`KMcG)?y5IwWv$xt@tl?Ux9xk$rZUrLSp5)dOiVjs^AWlPy0 zx^-wTtsDD|*P0DPwPpqyr@Qm3(}i|Ly$aqz$62PAHD1cLBH+svzDU6w*L(xebl+L_ zEcYfJ>1xSGxoN^NI+$j~HPYA~rzB@BdvtC&gaNwK*vU@ywQUY zWu4$-smQa}&7t?D|3}h!_~rb)Vcgz(MN$e4McVs0_w}^N2qA>1>`k=yP-$uJp=6ej z*>gf=&y*;Vk-hi+ouBVN;N|ssJ)Lu(>%Ok{rHw`BL?6eRi~N@G&j;!xqeJ^WlHYyQ zu-YOAMLUXk!5L+gR2HH8tXZsl=W^=wwmn=0uX0AzY>~TiRQ%Z|9tGuI%bfGcijJZ zkM)Av&=wYsXQ2zRxlH%GBKSC*2YbLBtwS8anPUcOJkwC$ced52;=#VX@vbpmcuycPO>EIo8Bxh)W_KD%h`Vhhub~vE% zY$moE3xBdfC^`PQP4b=Q@x}^G+^-3IFL@*8? z0d@Sai`3;q`0TTSOB^KlbS7iD_h(>myWRMxm&{(3uBYhskH~Z7EDnv4I9*bJs=CFp zExi@-OXC1i?b}mhxfy2n*$T~=Al~66Axtpx&Y)s=vnUD2gnCQo#-WF=v4fD?%xJp-L z42>$pyQ?WI=*V-@st&}WPLH_nFlQ8Pii1j5XGu$4Jpw)rk%oTyMd4#7AXYI9dnBIx z`gLZ<3M-s2u9>m`_( zT90{1<0xDgcgOUayZlif6C7xWM%z`r%IVFP=q}5_-Q$BvVVfDIEiDxL@rS%U8;?c1 z3$eDkRkFY9P&(p~K~?W+`0WovF*ZstyJFqA@gRGo-w%aAh%v9!VEVcE7#S`Zz#~N` zX!`Cj?Cl>Z8B)-KrDP!e4mb3_pasqCq6_s~5ziKTkKQ8RIwQ}P4ZgRT&Xs?ssi(rY zG+>xGLqx~o-|l?L^D&rjIS>0bHF8UPLkuem6b!Y3%9Ojc0o)v?5^fqQVWW)iFV zwT|HYkml|Q~R+$Q@5eMW$>UBHv{& z^N;$NU6P2`i#$)xz9HBS-Se^M(sQ=lP6J>5=HP%z9p9g-f>x2kRpDPGVcCP}-o2ev za^e6l>S&45=0I#@%`(pv(Fbv1i1canY}#onekb~2nBMgwzuVUYUcZy!Zo5}9@{I`$ z+ZW)0h7!31t)vlp_sI3(Q`xTKQ5d3MELh*7Bco(3dGzdr2uTD#C-l0GHnDikdo#DL z)2Odu;y=%fpV(h$283bILUq2{X%fP_?nJy>B|DlINZb3jP~^e6d_b|_qgH03Kqpjo zHDfgDCl=$#h|jEQkTV`t$6`gG2Xj0eNGIbUj9~bNsn=vlh~-lM&##ndg7j zf_h-S;FBh>=zxv1l6IpL!`<{4`}}^OI#VX4TpP0 z@OCe!LHa!lBWgq0;ytU$B9PO?=Tg2~bfC-{oq`v&Be{IQI4Fz!W3OD!0v&znQNkZO z3~ThdxqpX#l)NnqK59=@T{!W3|W~I&3w{DoaQwD z|ITo|Us^b>osUuNUa{`BKIAm;H*GLe<`XWD6by+{*v#$C)MxZZ|4Iog67KTt;@|u( z{>?92&&tkh*F|Yj9IVQ(^T;12(7%?4(SOHSMD#15lO5z>cRZ76wezFAYk$be=a1~c z9|bu3?#0oI9&FfP3#4jph03xL{-RdwRiedv(77*j(Q_utj|H^;t3QtzqmNUs<6%~* z&J$+q;<|nYzIjA4i{*bQ;`eIg>a_B_#;uka^F#de4Yaj-ZMV2zs0AWVww zS8xV2ha^KON0XITb)p-I?sQ=KSH9I)9ojq#i3#iZtXIC;UQ1PJ}rrLX8hn$;@V zaeOGvzL8EtLTh++KY4Vp|L+X9Ew)F0C*d=Hdy0KJ9Y~A957Ud1zFg`5`H|USINBpp zqIt0enmzQTNxDlgG+AU8KBZvxsbcPNcF#rq(nkKFixIX>5gXIb`IQ#F=jrXTAyD45jmjU=|_vR+Sy|k09;P*x;Kxz9P?D(9=yfv-hb1D##M;myH zo)NmO2}I!_cS&%j=$1XLD7|$;FnH?39dR!XCmwk7(Pm=*d#wcPc1~m`7T=-ou@l8E zqm7T_zBD%W4{2t*$vU*DVVGcIPpiMr)_GgO;hi{d^(Fj$xFv4%--fSuGT27pCwVSB zsC^ndPd12sNTu-Y^o@JLXy|I1|Eigk-w)vB-&J5ST6E;?`z%o!GKA*5Dtc*-PQGG$jqj)5&*F zA`Pt$;qyf9!{l}-Y~QMJT`?<;bIE~>9Ti;e?IbtkBmKF&hL742Lci~Sq>*mdD#!F0 zjWZJkb2#M#+i*nej#c+yXou^(oyR=nQXJ&lma^Nk1tyL2-pwtS z9h+={Pg_!9|5N**H zmjaiQTlm<^>uK5B_hd1}g%AHIk8wjvkk{W-c1=<68zTow2QF%+l}m+}`&&8fI#4G2 zl6sStFI2}j*ifsR@LLjA zOHyQ>&-8G|q8MoY$TSZ5($9&%$iJg9Z|ABk{@z8``NdxBOQv94cV{T_Z{nM{9~JE= zql#-?WLFI8QBkERjsM|BRy)?yi`!My#jO|Luc;4H;mc)rlq_~T6jHY*L$LcvCM&P; zrfCa)PzRqMGC9HGSoG#3s%H8zn>jYvXCjytcT0Iql?{rfM8QA4Khrq8fE;fY(b{go z{E=YZ9=#hUd>v|hMx`DSH8YS`6v=YZ+Trl7)wtr&%8!py#>Cb<^c(IfYx7jaZ;it! zRqsN-)>^}W73N6}t$l>0R*KRV)){V6UF4hyMNy$ApXn$;``4++ zsS07w7T43Yu10uO^oZZdQpaP_LG#LO7_aR)2B*&L#Jm?ZtZemiN-F$C-=CTDdBdh5 zAxU`qU!}5H`$nU$wmY&f+~J+wb+PnTD6$hZD}U-$(WEuQuzF?!TcfQDy9TkZymgDK z>>Y<@uROGjzb`Q@A4;|x)2MY=HFqvhfK&Kx9Ln_IZ)zu@;%q3WuZ#u00r z4|mmtuek39)kR2VmEA-Tpm zoD=PP z+#16~j@ac)1AqKM>^|Cy4E_^0Nldp}So&au^oX%|=N;EW=GHhYIOWajN82MQVjpxP zrn0La@6bGVd;GZkgs)oWPf>q=)Ae9CnVs_(-1}4xjf;1fA$-jPE4iT_4Yr`ui+!q^tlY%CFg^b)x4bAq%;CuJgld{ONksGa71KHn;sM#*+l;Pw8pOUE9;YKx-uc-|6vds!E?%3*k3e~~}yX$rN_q<_Ab zzSV+LEqb3HMvtUz(IPt|X67T!g}i3H3a*GdPUGryX0E%I>eh)Y>hDl)l`m)=yx3i zhKAyTW4Y|6g2>Ve&-U>vciDQg;m}hR9p5o6+-#$+=#Jcp$1h4PiZ5ToPtU2+S9nAR z+=nAmy9B*D=kW^`vvJcb25}p|uqCG9)Nt(ttu=oy%bsn4u|H$rmNJ}GN!O9xB~F%Y zp?sm3pI? z0u)e)lAP0Q-|#vrte%ePC561hig5@jJqi6R8_D>mmUM89AC1xorFrAI zMYJPy?`A-D{2=r2P{OHjU!>~Y<3``c;bT{k@ytk;wM*2)ukAb0xA8q2=Q{@HE)>FX z^$lJpI-9B{9Kxji{n*7X1E8%W!TYXFB5!MqYG;4c?>{4}SXz($het@2+PjglwE=8X z1j8Zh1}`wv#mi$cx<015h{rNVlacs!YcHhjm$45y zHdx{nh$e?pUVqURk2^%cFQ-3ivs*+jWkr->8_dlHi{8VcSU6r&<;R4@=Bw*Yj1r#G zk0Wo=xmd!5#}#~Xlrr!z7kA|s$((IQAw#|tdKn!k+0O=7mjvRSMg&hIFPc1VAGK4C zlRW*giIjUBp}y;g@0@3Z42uLzIJ-x7G*u5bucu-DibL#mx*Q5$MIpZU0oM?DpA6q( z1kdR#xxCmK7n}nStopf9v3(Owvy+43`UsY{&J@$m3BJno-CTE|Ih1}R!Ca!nevRlt zM=bt3=P!%Cwz;tx=rMFH*LpDqMTR@E+aQfS9I=}APx?diOkH`flM7ah{Gce8l7yeV zh01ROq_*OzSZ0ng3(*gIB!~?w2qM$0W=iqe#uwifIf&yKq8no< zZyBKmoux&fj^|jPmOgl7oQ^{wPx$J4j zXjbm+f0}N-84AsD3GB)TcWT*vmVO6!8>wNl$%D?d#btTk>ObK zyBLNMOL$uCENl|rEoixTv1dt!sq@((&|MY9;BJ6jrExfYWEX!W%fi4#LO-9U!3OK9P`iR8>iPN|zbX8I4cX$J znz)=l8LWt>LKl^W<*`j-=KT9U0Nqm?`13$xkVkJzh>(H-*;V9<|0?xHUEY=?2Eq>0t} zS)g$f8dY`?ev}sXm{s&e+FCDp+IwACXZiY?4)$+h94i!J?#w1>1+yX|Gzc z*e=KC6`G=|VFyM&-z^DQX#(BaY}|c2oYr`2VAGUL+^;C)KHW#-;oJhadCXu>KCht< zD(x`mUI>3McRo(u+m30zeb}7|)2S*jUNFOh`H$6lIQTIHcIj&Tys;f#U&$67c}H1~ z5A}3K-T)&-_V9BLp>-d6M|-`lRL(f5hVVf}u*>?yf*nU-&#_&wIDCbV?dgs&%XT2) z`C2yFz8^X{+CX}uiFcl)hv`>BaH@Z~>|H5Cx6Y~XIo!k!EDECMAMVnRb;i7(I0JqD zWMhE*Zj0#;u8ZBvWNFdaR=TxuIX$iYMy7LL%Nnju$GF@G=y|x5w7yah1+a&S+N?jp(P2R6Pf{QX2{d;RUsN?1--8GhpWw!dfQWrq@d~ z&=j|ypA~Q3yw5w3wp@vSo2ZLNlf|1+?KJb6xQ?Q=U(pAVWtg*G8zU~BK#hfsEllf#%m{enng4F1zo*?Waky ziVp@TnO7t<3T_mxbc*Yg9bC+}f3mpMU+QckP;~rnek&k|J2K zZv@F#)zXz)pJbo?&Ec<+1eF7t%wu{N`dPD>-dz36TUKkJ`_FVdE?L75DXZddhe8Z= zNo7_0>uI3q<1^YUif#8UL_g7`i0pZiv+@mSyFNfVYU?)|C*~R1;V6{)1aYI|76=-d z44)@K?97x9GA+GF_f|*oz#$qa*qe?w_vQHD0>K#EP>k!j=h=pV{U945d}t@1@S)3` z5tS`|pA)m0G{=XGqxK1A=xDw{MYIB*0_iq81wfmxwA0>(dzq4RJFFAR3aq9r>-@5L>)_nIX#tpA(m zd(RYky2ucijERs;`+O5iZ;X-36^MRg!JpZ;IvLaZ6?2~nItc2P|BvN3(AA5^lz;ly zb1e~^;ng<9I2YE9cN1@4dzyo%R)_&so229EmopM_9!1WZlIZ);_q?}W5M7J@O%l&zvWbeym}R;b>5B_k{wf_SlL_-@7T|PWD>lNq zj`G?QY+p6;Iik-!IPC`wV~b_&4{KtecLnS&-)BMu!@i0BupVT=&r7CbrDi-f4Hq4G ziH1lDibMBt8&4{IHN>3_8FyKFnnq*Qa~o;zw)U749>$-HbcKCe96r75$Bu2A zNrk-<$YV+fuM~`k_Rb+VV5-KaEh6;VEI9KhW!im0$@ua;dS*6{Z;jPJwsksk_MBhk3QCky>whpGQNAJ?KJY#-XS6gKLbD(*4w}rY&3;gq(r8N<6Y2zjFn=CAb zG0WwLOcz3$EP7Zr{$l5%g_hMl9N#7#;6cL}EM24FR430O-)t0FBiX-sUO`<4Jxh}C zb?0VY>86ifZwt_6b`q;|3ZUt)zmfZMH-0E<1Pa97YUThF*~K|?(SJoWRNp(2-mD19 z4Le5O+mFi1|31PmQ&nm4+upQlS_8dZsRpy>d-;5amO?4 zSkrAf;yfKcM(^ZXQ&v)A{5L9747GUv*oq9$AU{{ncHt3D#H#BD=YjXxJ zE0(iK4@Y9@4{yA@+01)bPQc}?9Wc9`EW5941oSV$kBE<~{akgJ))wNH@TJ#fjEBYJ zqv-Z!5KAx^gyX->VfErJS6F3&%5D| zgD71{LHrv9i@tmp{nC|#gF-fYXgnH?r*olvAdkTGL7_Dr?ajBbG)XZcfT6dD1JUt#p zy^o=9+Z=JHStC8h2V-x1sC2z}kGlL2%%Y|U)*!f-T@Od1$CVOZ%{{2@=OHTVdl}wBpPz6!F-%uD7~9^mCRHROWOawLlLotn6l+Duaeh*>#8&~ zz8=Cai~qlSoM3Yuu4N|no9IYkJ2=h|Hq(A{aj07~T>E9SxGYudy|oxAx_5Zl2z{g} zh2Y+fv6YWQt7ypBA>utB$BdV{Q_YAf%1Z6RLrV0JC-y-({;iTO%Z8D)c`|kVUB#z= z8i6kJit%XK5`H^Vh(rM#mC6$BVC*oOD9)J@~0}$ zjK?w5fG7O7hnRWZXUnyKWe&QQ{xm`6%%FYnXS7QL_gq3&9f?DV|_@IE3q1A@3k3@c-DN1K%Ax3pLtv1la3&#w+bSUK4Ekw84v3$79n860k zT}OviepB`SV19AZ68H%o`#DkGy5jE)@|zk@8mEK#w@%`F_6`xVwJKjZ6N0aqg2xw1 z*%$eG+Pg&;-jQWIU#0=McA}5+L$FNUUIPyf?EE*|%QY#XbY2PWzQ4*x7|ui6*=RW0 zxv}0qB1N9=1dW<9mG6D8hwXoZ;S+gKR%S32fw}pD#qpB46|JQ4b86^9nJSmxY>Lo+ zqI+WIVT&(1_pwrKj?}OF8(JDQ0$wkRaIP?i%SJn6@rEdznDm*Mth9uCmoUte+s|hh zOR&p33a4KTV=>FzXsvp=(6P4i!f(syxcpf%wab@1`lAOQ3*jq1w}UAfuA)vCpODqE z8QkgTQu^&E@@O9-DmOo`$E(HNq(%N$=+0^3v0rqEv?9u73zKGGe%B1_OA291c0JJH z*lZYO+~XViXk&gxB8=uJ@-4P{P)idXomEvVe1{*!9r!|<~-+LtDWk{0j zpt>>k73{=qmyc}I7B%RHiwxk-Ydop_D0CRT2h_UQS^sUb;_oCiGcggy(NWHZ9;f-!J&~ry!P^ElHg7de%AI*9ulZ$k!Nz-6@uJ$(o4Yvq~`k zK`qmKCl8$v@!PO#<)(cM5Sf1fH*$JOmJOW%|0_q~{B;gp>}LbxGv2U1_M!6j?fY~n z<-c>j@ubk_7yft7Ckz+v$B@f(zWW-<;L+X4!E`YlwfMrFJ8DAyVcNfQ-px}39X1x? zlwjKL-M^N`YyO~~`xc0^dMX|d3xRcvy`(JRF)TOBOQS@;)~gXQ6z_MDoZeQ-N}n?9 zjY>lJ*C6(*QypEJp^Zxqns}u8Hkx4mnGR3hD08sYK(ciqItSITd1Zo8FzyH4nrzPd zsLg}pi74o(io4ie4T?h-qrTT2?p-T1iriohnh7udmG;`|f) zi{UZ#+&EhwABAV{`KfS;^@KXqY#AlBPMQY)`qgBbSwpA7nq?#U7@>D@A+{}^!ovSF z(t=5j2#9^iHwsT$zwf^&%zc{7)kgzE6K5flZga^W6C7OVgX8=1D%&!y(~*-yVCfdk zWP6NYC1!8iUb}b?u8%UU6kKZM5}mCIRMHwvPJIN+)MSicXysyR#WEfv72QUH?PfEg zn3ee2;!&(G*7())8j%B{V?GF+zeLhOLv$k4Y{&W^Uc7I$@EZ$lVZ&G>W~kOgo-Zx2 z*QS+UUb}?OyEM_7vo^BH(W7ws&>nOhaf98OZi_e0zR22R&I9Jn!4dsL+_l}sZapzT z`K1_W>{@%0eKmsboix$s^niKH)WWL183=oJmA?`_Bk!$?F>KIJiHWZq#gE7#fBoHj z@FZI(PxFQGh$fl4+zeC*oinoCHD*xEVB!;nm+k7g4>7RrN&h@EODCA4c3u`P1P-Uz z{-XQiO&V&(6!3{6w-~c54-LN@S$)^5%5%@7xZ~%g3dhwd@6Z3|@ z`e(Mfvl1S4D#8+vOFY7Bp4ibuL7{Om+dgn0cAvGz>TAv1P4sga*al;b-9cIMttqg! z$VI)$b2hl#lX~2~M0YQ0@zIJCpca#bu8}1c8Q;8Vuto<+Gr!Az^_q!+Az>I${+cC! zFv0zIUN}9ckSAQU#&V@t6cs44KZ1LF=)H`}j)w8_E-NTy(rId4m?!J?)f_$AcH#4; zbk?tS1zr66fV!4U<*8rSk#7BWvRxHjncC8TLW{1_VdpQ?q+AmeF84y&VlSSzaVGN8 z(-8AIm@O~p3BSf!|IYR=^K|fJO(G)CC~}DN!98~u>Wa>@(2vV#o_Y(NuO832)&z)v zKX#vzN*rAl}R$QN%|Nj7*h`CU$K<~H_@dP&xubS!gKsppfF7Ir{{JPJ&c2KX|5Rzjqh@s zOjDd*;El}8)3P9kdJOnERQhi6LNcuozeB+$%Ck|lSQxd3l#JyB%OjiVuOEXFqa2|d z=kj!sdG}BezK$?AmTWo^#(Mt3-(1SKP7WeV-~ANz)>txW?P7ZFQ9!#}1Np@|Lp)s@ zgV%?~@cwpYxa69Fv6fM6M7zyoBe_F&-%sV)+ZI#5qDGQ`omM$;wL0FI9f0eN4&;oe~Ke zxtlK@X^UQ;(=dIlE?ZmHjVk84{?liQ&WuIp6(R@GXBA)CNfVJVh43#;V?C#>r&$Hx z>3+fjUY$1?q2@uDVP-2a>-iWb#J7F2sRKORCHS#D5GKotnrx zT4-cX9`e-*k@RcA2Xa2WPIjZ+SlA~C{kBUD>$7J7E+0$9)N_ydb%j|dObCZSqb>sdYPA+8VYSJAM+lz zN=)Amr$@@k^lbZSo~x~hK|2dYrh5_Z=)DMI2XBXXL9q_iCU|4vg%I}({GpBk581JdsESzxPq>@oEEvsMp^C(W4sD0L{9z`7Q0)#M^62w3CY{IYuh^N zYVe&Z3Mb3H2v$brekY`UY~b1-Ofj#{Tl8z@Reox@K_20PYq2ewm1r8H=hp3*lv&I> z{uaLU+ag~-`m{vROPTJDi=#J>p7X0^s+hby7sUq4xt`M~$bA((o;~u}(r>odINt|K z{p-1#qZ#DIjPx^giR7tzFirk)j@Fh5Ci6=}3>WXyAC^Yq``@F`AC}O*(8|Lmy3*5) zw<$K!QfAp>6cToqK>Fn>`{`nfIT_w~_`r0Cw$FWY5{KVQ5dA9GhW zV23TXJQTC&#WU<@SHgr7+fY337T3KTN~bzrrfW&BEL0C3qnT_d-knTkx3-Q&g1YDz zOUmPG_NbxjoIHHCo6e4pzD5h}XW`ked)&Hg0h;GULAJQj@4xdU3b*AGo7SBXyTs9@P8!LGM1EWq1}53K(^ zCA16JiHbp&xO?3K^mmWO9cOp;)N>%FytMkK$*ANR;Bi3^d~TG? z=L-1KUs6bwqTx|AoGtLaMT6$3;LQC;eAiUrWgVZ0+CCe3`6dZEyxfJcXVclD{SkEg zr`SgXtl@WuZ>0?b{*v>K*vcQ;4H)sHv-FbfB_feS|GIc9O22RA>#j|OsZkP!zVc@W zntI}Hfs@!ZHuI%J_3kgP)5N zP_#KomKCXw+Qu9)v%X|Ed#$F9tq{}zoF7Rp9Qo`UF-;&BXD=ic^-G}|D9IJ=#isfVR&gTjZv3__K$2f z$UKmSP5ww(oxjNRss*3$T@j+%T-lmw_PF8XgLOCd^HS#pXi!Ol_7p|7zuJ}FozJ7c z7XtX0Ya-*hITrIbsdEjnlj{0O^uR7pXZD|O(2i5aaML)*$I=*)SI)wRLoTv&BF{DL z!~rbu=qOeX4v2^iz>fKm{I>FJRLzLP?K$h2-0i;D_`m^?i<^0Wbt6>mi^l8T#j?Yf zCgY~7c+&|NZ_la#QtaAFwTFzjwR|`kul+*>S(7bhuDlNWOHR@$dcVo2mo3%=ZG}za z`^x?n6LH{FIC7jnv7X|6cVby$$ACaql=biMAEfBS~JGrzi`ggWxYH8uNUn+ug zR`IDnHBqfvD12RMEbQwBiZlD~Y)_Xs!Z0TohEMDzhDG(znAJyGH18v&Z?ize&v5iz z9I>KT9{QKWuvOQZ>GU3bbP0LHbw%>6;y?9YX@Fm=gD@glqq2i-4F#?j?EPi&ta7R` zj%yYmSox9Ujrs^OkV~ey4X1hgampCrRD_W#OZb8ZOYvA1kM7wwS;&0xMt0naZmJjf zw&MmEvoZ*$Sh%FURvr5GP?mSnS%hi{P0I~&jl zk&C~th-F_3V0EwyA2)d{9%RoHohuD|(PAlv1qC6>y}0suL>*Dl5b>6bW)&5|q~~&u zTpeD@?p`p)9-UO&{CQdeQl#A$(d6;)5syFYPLrPBp;h~GWuLE(!qRRc`?frf9lmV` zIqr>*qQAhlcpmg-B|`a5sATC_ZPA$?hIL7+_-Hah#M@+CO*dp&^Tl3ZSrcWDA6JQ2 z!=BGMP>JrxR|@`Npj9!3&%Ml6taZRlvjB`}Vm#~WB8JVLo7gQnaBXJSYD@&s`p9z+WvN(~Uk!oJY!0|1O!L&$5^+RokNbQZHzo zy(2pqWs8&VLXr98H2d&abhO>ufwG3Zk`)V%lkr|TgnOnkSK&1^d6R-;6Q8wR;zB{%W{FcuR*%M(PP>tjr!N_I#Fh?j-}2A*X!|ROY(DIzj(gV1 zET>FHowCTn|14o!EJlfZ%@#NaUf=l!T|helx`|0LwQAAvw^;NU32wlpuWIPgUhqi- zhh%Gv3f@{5!ML^y`)DC_0&`PD$=~JHJe+DJ<+L)Yhb(nWJ#OwBA|3f>zR;L_XwWzr z1?2VO?)nC3liz`!OXMwUPZfEyomJtf0aDibXeJC{Ow$a&{Dr$KA*9iviQoe@k#pud@vc4zn;COQ@28<5lJ&wCTp;)j-Qn#=>hF*d*Q%3sV zE%;P56FeLl1Gyi?vP!X&@fng2zaY-u55G;DD$U@Mkj~5WCg3qIf{soX$t5k3ci1yS zI%D`xvi)R>=S^EgC*AwXfJ=5ryBdmDKJQuQGZLuW3CASG629Hg8PnW$;#xkjdw08& zXWc^L>Yw?i04>b?f9@t{C6^Z+>oXDsk4`6peFpfa{N$=kr9+9erw)_+{Iu7C1 z{+jsZn2$|*)vW99wN%^T6J1I&7F?h?2$6>4;p}v#*i8d%X$$|I)sN>G3Px)n>ZfQ_ z#%!r2NBtq_6%x;`4_!+O<qw>iA21`ME7MW?cDj8zmRjKs(X)V zxOcYfmeX7;n;rqzO*JgsRb)r*Z^7JY7x*_A;$A}_bbf?MY}D#tb5%*Y+-@?cMHkA3 z38Ig$kmoyDtra%H|lR2w&RpTt-uFx5}C~8=?Gd5;Ow1vE6n!moPMU--Xr1tz1`d zIdpZ45jy>sWZ617(*Kc8h8acN>aU&1pLwBB?XGOHk{u4u55=vx(`?$PK)SARg!VY~ z;#==cK-Z=)+QtUq!XF(QrCJ828qkQ&{imf2KeL5&p8q7@ z7r}h;wi%EH2BVC1X62{m(uzNE{}^9Y7DhP#JP@sls{GnIp-~)65{9@716gCD|*Ka%4Fx3rsIrqXQ|iNev1{cMzm=_4%U;OK3W6!?j6yteyO5 z=!bg#JHvehQ^I|I0`?3@mR%Hns&^N2kh|j*lWg*%%vG-_V8Af0dq)MINAASx0bSV0 z$0BcCVe;<`-?70KF@gy>Na?aneO&`Gwhob2Sh!Gw$O1$ZghC^$nzw#7K(|DpSE$Qd zyfZSwi<}%_y(-OIv78p2yhG-{nq^1DKGY(l2>C-7vvn&c!c*A`mR9?De}{SE`v?zt zxjgg!x|HVD6p-JDU_NW3(3I@{&vjJf^|cnbelJbvlG|9}v>;mltc6@tX7eE`YG6+@ zv1PK0EcE4QY%nUu;iezV$lM;*`?f$P{HS~X%!ALSc*I6-VoLLZ==ioH)QMT~u7VMC z-{c%+eRy5DbHXIl>@9@V-!n{6bo=yn`R_cBwbsT7f6*(E-AU5#!!@KPIZCJW`%df2 z?Qp2W7P#{Fm7aa=5bqL#{sC{<%Ur^ku@RW@riA~Bw}kEEMA(IEiSE3fLeF0KZ}w)B z#)+I?3O-q{0h`|UT)NLs?JyG??xxZ^SmrIK%I4d|5HOB!DO zo+64Y@ykx+5W58PjviB>)HM@TEs<>Ju6yJWE%I7dTe;sgEsV<&ewg&ZT(?pSZR9U=+dhYX=fL4XZNK@ za*xG6m+P$KJ#)yqY(?Ss3;g9EBRt*`2>VxI66a^S2vms2WbFd3`dxwyF~irWPG_DE z){*AH2ejw!CQkK&9VG7AMd_XS%}Py#Et~;&j|MJRX$||^LI3Y%tlTT^-;aW;rujaG zjc=TQdBTVP$3L6j&N6{&NHPZQs*)JKRiNm55j2Hb_?AL7yj_?jI)gm;W~mCgZ7YP& zt}J${-$dLxxD~2#xA;-rx$v}!L&ND{$=~Eg(M>HUooP878}3ZN)cQ~~%wEOgN0_4F zMKS_ijF^4Q9de&7`nj#{@-F47IO?AXotM3Nub9y=y)9Um5tmthq`lZxZAD$68J~H0 z3YMOTKN#^U-3kMyl%qz=#H{pO19NRb6As-DgUZ}O!H>;BOHxnBN_;?7(Z zj4=_N89(GqzB6P0&EyTMjPP|-AO?qy;bkYL3O29kAzFBpJ?^-X@*B?3jZT()rBrk% zj7ovw%OKeRabH_?D#moh?@Y77i!6P9(B!4V`LQe0@kJ>J3r%M+?Y@IiP%lN}`6j-h zUl@(QbDT`){H;7#b_>hDDN3#0tf2S9Hqhy=XXsqh82&pq1NCD&OSOIaNy4tS;7Y+% zX;SB>l)c28+Q0rmCk;Nxmi}~y*UcC>c>QLVkK4fgRuHCa+{^P$* zBzF0T?oF7rBKVA_t# zjB5>;@7qzDGVuaspR|IGPatMp3gVVkGm-3>gfE$a%y@Gs^=Yah`6E)A@6I<-V4u&_BO%1XWr;l*Pw@OVt2-)Mqgza% zIFt4HoZVK4?zRodGxFHcDVxZ7LWS_8sPOwjqnoIg_%EXre#`{J;&b6O{tY|YrVbr3 z_Z~lUk(-F@jAMEMPW0%^t_c>O!ZMS88q1h?8yNTn30}lSnZ3v-I(UU*`_*dRm}iU! zxjPV)GTh>6im~uP=fL=+Dm5Evz&nU3fv`1}So92Me*UNrhT@B>QG|mrMf8;QQb( z=UqZ+#r#j?AlqNr@9tLgU^*59;B-!!6#mk~tsNz&?_Gy( z^)%_8pl@WGY=?>Zo1vEfuJV}uMD%+ZB6NWFZ2BLDyMno)n!bzctg^#=!J24&qs@BV z?@0^yE~FV17@4pV`Wfiq4=x zeuC{^J(zoM(}wki0=$@5%SsyDDe}Y<@^cx_56p3b&C+1V&L*?o?qgwTu|VXw8+l8X z=xT2bKw-0bWskrMG{9;IV4A?}1skU@D;_BmuJGF4nUFK;ES*(qCcHp`+1)#yWR9n} z)&ga$o|uofM;35{3U_p0CKxguuCjM?CgE*nC?1A2@>5|(*l{`l7jnZSt|bPjV+p9Z zQpnduS>a(*2^RF6%`zuHAom?p;a2&O?{yf7-X?iSAJ&<3Te17gn2tVr4ZP@~==F0C z#68R6%4X43rmH5046p6%w5l%BL?*YPC7atTm>{V`62cU? zsU>`pZHHvLLR4^et@u7onJl?_B04?Tf|512c(BOhXoyVQ)9et*+uTN^y&obCNR$^n z7`iZc9xC{6t9jmC6I5p;p-jb)RSTZ0?|3P)1XJQsq8g42%miKR&G$?mgS93_cq)IH zeMuH<(lwr#deM}h*Pe!(XCvV3oXu`m>R?_>D6BQzPPU6P$D-;KG(B%&k7e#Ocu5U8 z-0941-L=p&O7!s!`zXo#K9rudrBOh;B7XUQB%Oyp*5Cie8?>iNR;5CvLS$9$bFMpk zMnY(4(K1U`_TFV=%SuaI%g23al9sYcTS7}|@89|P{sWE2{eHjR=UlJrdS1^=kW%jp z7vl$_Vv0LojKjA}ct%4AaYaM{xH!qU_{Dzo%cK3OpmrD(*L!ey=ELt?F`r!3+OVqEp^Q_{a!z}Nf0V-PK@WNA;Y~bB$dzYM}QAuI!?=%f;&`rVe8y@VK zKm)b^vT^=x5*ZLW2%2$TxKZ+q$?TDb&+h$DcUvfmUDJXOLkA0wRMycqI}8xcSs&W7 z!r7%@Llj%Zqm_A(qzG@?%XtXqR!i8ZKkD$Al7c_6a;z}j3TXNqB{@U@-np#W_4DhFS z%+AyOA_ex_O%t2nryy}jy68lu5UW0w;jPYh5*4qEvWPsSZ)sqq`JpuHInVyTUM5)g zWHO}fbWm~X0n-dHh3Di5Ox$ow)KqPbp#@1$7BrG0c|O#`@(jI3hA^eeI{4(5kBcuA zxfgg2UU1&m`0xTIu$YOZcZ&G$vWhIpFawd@h2+Mg%p%YMsk0N|=scMOwr-=7?v>D> ztO!=npbj&hNuTg`3KMM7gSMip1&aC~C5HO~0pQsJRLf_#V@Q zGs%4hsv#n#2rpH#NX_FW+VaK*h6k#dt&KUZ4DdtUeF$30o1ttwLbzc-FCF|zpR-qE z@whyU<%U^i}u6I zPMqz$IuCOyt+~&jnO!?=fS>2-b^wc}f1uaM-LoF7;wIdEg1f{IVNf*L# zX)v@D2}CtARM;6o_h&v}4>{{BWn&ILe_YSP(-fgOt`v(;<&*T`=I}kZ3*R0#vB+r_ z_;ibNY>xN{J`~5$uDnY#uY)RA0Ke^?v&HJOanU&kp01K#{jpU{z>3UP!s~bkOZs%Q@llF0D z{xh;?vpW1aw>hZnHgk7~r3y=bQnO)1(BvmYRVMDE(l#YbI@1ERasH@V@ksRb*$OE6 zb03KGP4c&1ACITR!pgIWiE+NcRmVsiUz{s2FlSVBZ88F$a=oQY1(P18qx57Uo4j8I zI!pIMS=N@I+ZGM^p}6BAM%>y~(ZVmul+K7`=W}(Cq#TUEp9<{R9&4O)%;7%sbL98O z7W)0z9IVYe%oMp!z9}dT@rt1$;Q&o|>69Vw@prPEGeRA>M=o!AJ$tZl6{IsbbNkh5 z;=M%@!*8JfO#bDP4vrZIWAUEjqU7IAyl+xY7~bqg@A=O}{(vx4Mm%P_Q?z)05YMZo z9MpR@^%;Hyn+x+dyrkJCO4xt3q~Dh)+_xV4*2kgk+;?)t+6a$Uh9Y_MVRp6A7%B?! z*tJWJJZNsGstwa|@gnC`2QTFL8t(Zq^2wQYpBI|I)hQm4Z#>ECn09Iw&d)S24zjFe zu5|Rqv-G!#v51uGp&)NRHYZ&o6PC;J{*WZZ3!kxrn?){}5eEb4*?2i{&JW4f|uqeZKK{ zcw;MZ-8cd9n@#b=^AS6=QUm{31ort9h-7Lg-1*L3@p~olV$;w!p3m)?Cv5O4Rcz1W zOcJ$0g8izEc+WFyMZ3OGdrebFoc4i!?1$>2Tr1>yN5OZ|7h?99=Q{09QIhyflsQ{~ zJtq<{KvR)Suoz7r?Oxrlw-_wpOhx5%^wn%;f;=6F4Lyjw+ye5pw3&{6Vhz3F)ok-> zbL_Y9#f&i!Fs`@!D<3ZG2z*b)TY2_2CKd+_!kJEz4fY?&!OZYD5;I;EvxlTZyL%$L z%6)68ytDo24myVXuVhXFR(YHJZ`c-?#sHC|lhTB$jB*OiT< z zBmvWQ`m>4ci}AiQjkCzK$Pcw(n#|dqu4w`6Li!xYuFS!*L!()4gA!`nN+310ft>kl z0aI;1oLZ#Ek_;WtC6<6ke~O4xmpX=Si@-(m^;P_JM@+!J{tT(4zACDtxCef~XF*K3 z6t%sZLAU4?vjefF2$;MBN=j{_u!4;!&Ps#TjECfqKR*ZVi@|`|O{|+g&+}^{FzscI zAUi@tPyd;OQn!61<+&v#^7HAKu;~>mSgFZ-8lY8N-E-cQny+eD_|( zzcm>_VN5#D0#c5Na1q-{-X3~PWgkt)f$~G_ySE#?^SqMg%{3O;M-!;`@Lo&n%OqfR zD^02rVs~&3%ga|nRYEZmd{qS>Jj`ic=?*Ft7s=GG8R9k1iawgJ!44#F=B{x%Lhc+R zjW?CBav%^|!GO8=8g~Gh(tn7) z*D_>!_+!V~7-rqP5hr;LZosDi;x>+Vl((7m`%=7k2H}x9{}w10h`f4$>fn9&G43oG za8DkaUPWWm`zOr2Q4I(9tgiJOBrp&&!}gEfXbk*NovQ4DMW<3Axj~HX?G<9c(@1z+ zEN458>%q_>9@jq4B&U{-p_c1c_n)h~0v6!a({!jgZ)Jg;W3Vfw7>h*NWbC@#^xc)O z{a*2yhgMiv<%itpr2=)Q7AV~uCQL1TM;*=?L1B6^DEF z*X@P;w+T%CuO?EBOY#1AJ!x2IgPw#y{5#D(_H*W;xY`L3+gsTvA6=}v69gC8+0_@) zZ`0=mlE}#2O9EeOA(o$ew@kUoZgCdGcD^UQ6x%F_?31Fq$HmiGF_r9U-%QXWh4@># zie1ZDk2fl@7@Aa19@v}1$SoXK5AnRbwJsJE2ch*}q~Pes=NMhBAast!@l|Oc(r?g#N~45>~Sqt}kOD*IdHp4b{V!iZoPxVuAqavJS;<~B(*ts4Qnk9p4KEuDjlH?r_JbQBXG!_N$Sx1uF% zAcq~TpgzM7Y3KCVhei!PyZ$$mr)}Fv-+S@QmE~Yo9FvCBdE&xDlg)|OQz`oXc{=?P zS;XW6ETGh}6Fb&C6m2(ff_!fRTG!kmN4FY6g8XkLfBva~o4OHjFU=8L=6r@FEs_|U zlSSSSQ$xz3G@O+vWVsYb@jiy-S2+JFYB#;s^_7ZwgfS-Nh}7V4^mPs)v1gpA+k-?} zcqp8G;~BsS*MksPs=&HJo8a(4Mp(2~hl(k*&^Ys1+=G3Py?0UL`bruu^n{AO?O1>f zYWp$x^+!_2f4fHh+ey5;&IZq%jL0sE;N*7J&gcBlf*>^gJti7d*aY(-vcl&tH_<_V zXQE~**S?A$v5cX7_kAJ@S~m{pIlq~SVWovo`j^92s<@%&O*|I4{U%z{MtC+gn0p8h zu@(~tyx5k8=Ml3=!p3KucQF(01A3U4suuT0B_sK{2UGFVhRU;SEIE-(o}c%op)&0> zs?VIATf=#@cRy1@+xTjq4=>^LYnagdz#rqv+%RK>AcC`sK(|fJ^kC})X>qVU&pq0 zG{tT${(sEUWE(VW(Up;c)XGETPUtKw@$`n1;X@V?9!9P1*3lCS?^bWBTm&PRT-ZJ8 zA_4@!^a)*;l7iqK-z5|~6fQ{ETLUcqB@;$GM{&g)!$GQ}J z3v4Ehycf0eKpYx;ZnMV!wDH`V`}+JQ>kUXZ!uZJtFn^pHm02tb@&g+0T8*zP?iQ@#`FvO)16G$3KXI&<0PM{4xJe3^P8w z5({6)!8C6hiM=ur*OvcpCa*uckb9!Tabb9Y=t$I3G-T|SJ|XwlkcsCE(Wdf%Kc{QcO_f+$z0t z7XEo}I?8?EloY;HWD4v(Y!9vZuq`K4%Lc~UWs4a*^V2&Gq!ee2h> z<@;>#qbvYR^9%%rq85IaA12%(_KuES7f!>xPtXgxheRJkf@t%_v-J7m5`koI3k~O9 zioUVUtSC_xk0$e+NZJH8OI{u00}4^0e1-IkccoTSpYrZ1Wj3|Y4im&eV6K=>Zhf1F zrD{%)4rpcHXD)(ES0L|KomK5(e3y=`lEkXq?j=!|G%MbLF|7SBo>zvZYxt zxJR1ze8%<9?G?im5yUy_9XYF*qTN)23po*(xs!S?U@KTKDlh;!ZbPJ{`T zecnm6{+^_TTKh#a!y@V6oww+;vB3gYtrps*ua2K*?y@Hd%6P+P%dcajSSaTtx7;tm z(R&R<^_w|f#{1w*%_62a#tw(}a|TX#0WsO?Po+c8&^fJn7ZZj?P<_dVG+k~I8#gqD z&aV4NoA>JqcvB`7_N7y`=S6I=h7}yteeu+!UF5dh8CSCt(B*xHOy%=x$@yrUdU~I& z+p`d{N5fI?oFlLoUZV23yhF1xi)aK0FfQ&e{0FTk<~*l7`RfmwY`{In(;V=}%>jSyEN)gi@6`<+SHD+Go0Ea1|7`NY^I7mw2ZWDo`Z9D5+y9nyT z0V+5>H+>`HjZ84KemCy59^x78We^{l2+{3nWcr2xS|U6{=e`JK z`}jU(ZB!CmwtKK4XLKO-I164#CTRm>Xuk6Y`XJ4PwQp5`X=6U7cdCoju6E*C-B6*! z^LsSL-UPwdc0=iH7+Ys=hoOR0#7x*tPEL%Z>-e5vfx0m}ZmNx`oX7rnz8sSq#aU{D zOCUOSjr&rjpjIXki)KA#A2cH9x=X)!UrwxEk% z^4T~SSA-G=adKEz28Ay)aoh9(>nJpWBn`xWU$2P@J&ZB?L^OsEttXlt1T`<>;AM1& zP5QyTXHAJXI9^h(_p%8(%MXBxEugo@&BHmqH@EA~V^y4YcUg5mw#u&}y(N}-_QD6> zcyF>+kTY0KJXZQmCL6MS=!%mi)VhhY%O+^z;goRfu90KPeBWnwH4Q_0qshm>Cb}hD z6&+)auyuS_eo*&+=W4w%^I+Cc3YitZ$oB!3h@atuk>?`W=G)Gk2Op12aSu`^n8Y*X z#%Pmy#C{O&b=2dTubO<3Vdhev|H#CL%1V;7eG~U{iKt`G6xRCx9Us}e+kKCiKw|V$ z%r03W{Lg3r4Am{UZs`L<t(CgP5T6jVioyq=q|K5ZB3Jjwak{9Wx`~!lG^&RwswJOv&`)jxY=N~Gh z!LoNEbIerd-`N6mMqDOh6J=nTmWBy~UND=fE3sBS6f=!8NC{^XU0mvj0W(_J0nP;b z&U=*ncFd}tQPxQ9xsSTRCXEzK=DZ!=PrA^cfeE5CF@}4d|9^&;v`f>+$71RFjc3@k zuL|%Pz&)rk&P@BZE9N!ud{ce{8R=k!^1yIh`q;{L<}bp6TLEx59VwVC{Q?90W(a@G zw8gF(Ed(D-#7~#~?A!otgz$_>X^@cAXarKVIZx?WXaZ_=yVE&Ai2SXewj7<~~%W zjby8Wl;L7pf-PYUWU;jcrY-lz2>V5B)U6fhO5lFZ(FNpR*Fqfo8wNG^byc%w8}j`W z*HZMKvH$m&x2lT^jl0ds!VgmPPT*d;BA}4jUs{II>wR%s;*n^Cwmr^x#6a~%JsI~( z7w201arfgD7BOEF#cJUgr@O|axoQmWopHoSmB(!Abnbz2*^9A)P|;LJ4b0nJfM=;6h_HA&{lIze@86GR@7}J$ zw`Jkb{^dlXYNb$M{=YeY!E`a!xd$NN=rNJc1)edvE+sS@ypf(9p@c1qgRx5I5j*I% z7y*6R{Y|8qMvmOQ6JFKVzf&ipUl^_{BUkJdXSYeiMgdH3%k$6hyr z>;Zp>Y8S99OEcK=Gr-9yMP#VSZaVDX8M<`aOg5=b3kUNOkhEcssOYf{R73aS+}D>x z@sbJ>|70U}{0-(=Q(R0zhmt~lz1K+#(gaFT=(N*(<&k#X@lHKUrZi* zoIU!!3Nuf}!~XtcGKaH1vcDGh>m-FYHKB7P32p{5&*w9F}=*MctmN3&v1Qop3u>alz;e=Lc!n|jX>o7}C`Z&EFtA1BW)OYg%=1#zLpb4S5O zJVo{pTjAEp|ETK=a}1XAgi>v9bz8hG?%j-pV&zxz(SH#}-Sk7ok^<%v!oLxo3DDiG zME>NCqcT0t{qtOFjXG}6-;3%vH&*!ndZ}1B%%2vJ;00Uh59g;;qu7*n4q1+N%UyUN zqc6a-7Dx$)2&XB$p?ByaG=})$Q=A8LSjAb9{H_s{wu?9q>ZF}-RQl)n7T$?jk-Qfh z4^Cv^=Qw*dARl!;mx#qES==CL{Qmiz(aS4Qp%H=zxeOA_nVgg6tb{@-_g6cH(a4OW z^th4he>r3CQ$~{~3KL`FD^(Ht+5(59 zni-vMgjbz@2)tQRJ^zL&{u;$VK6L%n- z*uP+m@Oj$=m=);ZjUWb3_U~Y=w}Gl*>5zY{O>~=k=yKlmeuQW3YX;4Q@`+3gS~HU6 z+?orAIh?P4u7TvgHb=3dCmw6*GWnhMkSmOaaYg}APv%+s;4o;&t*biOw2c}`UZNAI zI6Jm_9|~Q>g{2p9rY9lTDyV?7T z`?%_^uxGC{(O1nq#(%N}Gm5U#@1G=jM`|{yd$^N&1=dp!*N38g-wklv>llCDHj|}s zUQ}XzCr!WM#WoFbhWfiu4E7pAG)$f8n9?|ERu#&U45BGjJWZQtZ54gcZAR)ODd8_e zEvhRw23IGqM9}I-Y^kI=#QXN(cXx=W{-7oV68q6G;}aRFsf5W3z2VFKjV(1)e%36u-d!8I z%QF$Vs7$Zqm==D1-;X{+O&T{`2~o%Mk^Lr{wS;(Z|4AZZa|Y1G%ovLv1@Lp@K{ler z8jimbP-iGl><07uP>3v+41e11=`|_h9bV_xu|Mk!(ZqAjMyL1j4(LYO)S`p-|L+*J zR)oyJd^o$Pi~cJyNAQIZ9CnIeUh7vvo_C^MTM|Ng?RQbRttY6G?IL#gkrvkSoM6IT z874l#7%#t;Kyqar8CTy-m0gw~b!{e_KSC9HOE{CoP;!h!|A0a`yg{om5uh7&U)5g^8+opKoM5*WXh`ZTl8udR!KK#Jk9=XKFCY z=A1@;2CG(_i^p?|kQpmZifUx=bmBq?wzaY8rp9pLImGanS4H<%awfTR1VScXCFN~g zzdd)FUJ?yuWBx|c&cb?nxW#@+k|FmF`EbAA#5~rntc+Z;AB{s+lS?mMQT#R<@}p~5 z8b9m4X%0dDwo$~#v6Y$@j=|1~ZuTTn3-&r;i1d(S-P0^NT`dpuY*WZi|551m+5oYf zr_9A+F6Y$poNv3msDtMSqI%2VFz_$Y^S0udFfYtbj%2TjR^VJrBy7n>a`zn17Zw>I zQu`5$%g};?ei%~i@pu@xbUTDv%U06LPsM^SG52U)<}{q&ev7@2P)Ee9J-D1Wfz_sHpx|R3 zlILF{Z?xKIVxAc)gYtMT%pHZCL%Xi2m@Gb}0zr)ff?8VGAu&T3C`2H7p<1=zO%t6e zlEi$4bRx&QQ%{XxwDHhz=9{kr-6@$Enb{(E%$Z7UxiQrE#A!BUY$zpaAL*^UgQ93e2fxKHLvK@rP z^XXo>d#!%%)s0!p>W}`14v)eSen;l($D= zr~Y5Ec|Jkj$`}MDmat!kh44&G1Bs~>$c>mn>ADcQfuG?Wd*-4OnfS7GEwiuV{)((p z+<#q2mXG20aXGF-*4}4NBl*2@XaGFsZWajKn&Gfww6NB00$hCrc-tI}u%I36ysSPx zm8ZjFtS&M9{+j+9!@IX8J!gNe&BvOKeGpw5#l|h+J&ct5C(qOqd(L3{FToQxCoEzk z2Csp|%6NFYmk>*N{_K4WMcpZvswHYo*w`j7lqvS6+0T4wS#=#9F=Yfh84=4IWC86Fjj~3w^WP@$Y&QFjF7YB7`B;iCIcsVP*=t0)cw+S)?K#| z4<|)o>8_FF!OQh@^o2y)z-;eVSsVY6_ zUwX)7l=+@+Z#Z7bo)cLIcRo1WADw>VD>x`X-?~yL`^95IP;XgQ(w*|?3sns+j;n0r7rp~>=oK2#f68H z?$YESV=P_4^C0U&cu%n-)=f-BWPLFC!8=*J^eSnV0cBs}b?|jW0)MV#n0KrtZg%i| z?%A7UPZQr)ZeNV9S()raoi2vgRp6SLos3Q2&qO_vxxq$C z@qU@~6Zmhh1UacCiwP_F4o0nwz3VZ?xv*W>TYgpKe!}H7weE8P-~a zB15GE645?xVO)xDNJ)PuP}1cSacVv2;maPQT( z^vxJ641x!O>^@Z2jNS+d$s~{)gK1PU??36=g@Bj>_PNK8y1zR{TVGlWHWrVkZquBo z;@U5)it-D_-4wW9+Q@!eYv71qF02F7iR45v2r7JGo&Suz5!fP(>;y`e3O2t@p!fft ziEoa*$3ko>G>5x zJx2D@yJK}&y!mPza1ZVG1b)+0MN_Lie#EyhgDL~;92ky;3aZuNDJ@j2UJ_3d(@AMz z1Qm_AMvo02%PJCeaQS6A=ioI9vR+72{jE{dO5r4{I;n(5hjJk~+L4{i--6YNF{n&$ zAX|sn@T^l9RJvMO_<(TwzV9$SWqVd{SXmQnJtql!_UNPJj2h1NM&f;87E9#M{HTs} zOuk9UCY3fi!F@5dzrVvGr-agVhP^bj%tZ8iFz=R)H^=P0CT1gJjBjDSkW(nBt_-!s zsdEV!8z@c{w};Y-urt)8{Gn*fyah-yiNX%eE?vNiZKw3;ks57?|Ta2_vQF| zY|MKtxF?4~(k@%j>`_PMZb)LgaSo~L;CI92saP^CpB2{#Flk*G{GYEPechdO-YGly zD0Z-{d9L`{7l{iZ-t&HBBYkrxk?uauyDE&6=(q0kbo=%lqOs9Sah}Cu^N&(8Prj8l zj+~Aw0i_HJ7h+X;D&nO=MB7F$0@<}6GlzX41AMpAea9cttuKeOK`CotBOS(j{hWx5 znhfszKbQ&mU8Rg)TxQOUg$a8j9JOsK=*p$0-VZNpi6W+}ij5k?M4YzsI z@MBTTW3>sUSo&h#6E&uM*Z~W-C&Ad^5K)X&#^A2)5Z!5G$5hmj$MY;X;R&M7r94k} zHWNE(CvlEm0KH?pH!-=M{f*Q?*we!pBQu74JR*yKdAv94ODik?X#(}pJWu`bs%Vm? z8GK435hPJZ)*lL^#CkZpFh?Cd;!&72Zmiy1Lq^w5lg8SSrNm^Q3iQh}5ceR5 zU2NCEebpoQJl>sblkmbR^LTiSy2gI~v&9(waKv(e#v=PRI$nD;s&l*8t1@kr$%W$D zV_6n8*$R$4uQf9ynJm8HP5YcLQPuH;iO*BPkeeCUaNR+q!vDQ#o64|r#$QsFWrK%B zUMLTWV){wTVdugbJ`yhEP0nPfy)nS_-R*pb8$wTS;_OP@ht<`ymtp1BTnx6aCMz>M z>3>-@)PC-CmfV(uKJF!`pw0s2=tk%d6$+n=UegZ=yrca0HlXf(b*-{1R;^9KTMse% zgX^EeR)(RWwTxXUil?8p)Y6uNZh{4`CFt^XPW{?T2sGdl`oB3(wH9)JSq>^~(uwT{ zG2GYs-<*G|zl}3aW3ao&K`@}M1)m%T3-=7}rb>LzGNq7rhJN&C!>$_eTx}eVg!+@j zS%K6us*0Wn^JcDv8c1$Pfz>Su7MHdFdoN^R`}u0J+?{9Q#Qd-NJ0+^l`x?6s;!ntBV)5(bxARk^Ci{T;03?`+Or&bAvID6*?Hkb+FF% z`vU!RX*xnOlFD2>&R+Y^g3RPx?tNUz2H1I^+9D1;t+$EgNK@>Yz6;TJZnM(?T$^2* zg6o>uf(dp_=$bZB_-y%7Jjq&s+HB7D&&py2rxqb>X9oPffLzUgKrQDi#);8)nSSyt ze4dkw*@Ff%9q#$*D>B2(vL-f1*#z^)_(H?7qAc7OQ&+*w#tal4S<5U&s=;tb31M~rE4S@(A0)_BqTw66#ST|Mzj^iV#kMKN|d{Hh6D%eJ69XUaZKRXLroZr#o zVgmSa?tS;y`LHkGSz7Ip%-TW~_IAbnds5pXD-yUgs45}rsMMa0!z`H&c^|H4~rhzqDvSV?x^Z^@35^36z%T(@rkKRSM8`M;OGG6`8 zA<8xyIG>b)jDkG&evS#c2UXxeh8t~|eSl04SZU|}51 z+ZD#r#~DJ_Bn%VA&SgKga<3iN)~be95DT9OT3~vGc9a;iPudGnVUWt1z`>$$1#L`= z;C;9!KM-;M*>D(~hXc>9u&c!mXio9N*%!-6g02h(mU3Of;vxI)$}j|Ko@%#{73n@S=`rs+sGiC;cnGneJQr6N9M!Ygq653!0$e|#L5C~NL25}J7S?97 zhC)x?XC9B+X8%a$22)(+nf<)Of}DX!NS_Xcc{TP6O0|c z3$=YAY@Wmmi0zpm?0Pwfp5fV5m>i=u-nuMdv^wW5M&iiYi7d@bh^Y8n)N$!OcVZY- z9>(vjR_g3?5Z5AZ7hv0(`GP0Zmfq_2qAK-KtWm)fDw#Vmu33$N>qt9>#qzUq2}zwe zm-o7F$C8*f_MloF$3l6wOPC;PpT3EPY`a2NcMW8{i|4~>b|D^RiIGiGawzXwz!_@1 zJ7%s40$g`svi=oO*L{ADt%^oUbpx6DXDK4D#6TwRHgjlFhtr-&EP6Rcuk&OLEt8jq z{Dx8zc1wl({dk_MB8Tmnt^(U%g;4KUP29dOLyxjMs)ih4(@pGg=~_6#uZ|;|M?RoM zXGUSKa~B)6L}sO^ zOA)HCA|TLu%#?KaF7;>*rp+24P+tvJS4c9p6>VUK2RUa_JqOR) z(#Y}lFs^63rv?&^tofKd+#7eodZ~e6H)+8J#X&-;uvc_WkRf&-4aNCm0c?_{5iI}3 zL1In-`Lu5b{m;6RIt|*&Hh3^~xVsg+UT**lMHh45d^KW?rnILNh=UQJ38heLTnXJN-9Vxha zJ6kX)s|mzlf>6lyl8Q--pw$xjkJP@E2G3gR=roj#UW%$Y=Y*``yoFi;`~ zXRHS?oAK({-De8FgeEr2)&xhgb|CC}arKITwLtV9nADD>Up=Dfc;Q8AaN&jMb)hvc~l_S+%R>H2MSOYCvFafq{Ef#(kTN5DJQ ztv0cJVk%e@lMYY65$w~Oxj6DEAD&0Ak)>Og@eJnn{&_CB!X86zhxaoNed`nG&Lh0% ziQhK=rZ+*9IYsz`|5jPGnmjXwT7>qOgIU=#%7p@?5fN z{6ajNoPv2?dF(9jtx)edjPnaOk)6Zu(PexO;nQ=Ijmvb!DI4Ci`FsQ!d1Mp4x-FqU z2Q==85x&-Q*2?U;?9*I(gb6r8ENXw#tYZN2CK44j~>yR~$cc%v37FEhw z;>F)2dGT?wxs`ybp1v2lbL#=75dQ#f39jY{2GM*qJ&=sB+nx zs;@D_x{95cySSV=OjyG^yHj9&L5ZkEJ*OI0vIyAnoE_L2OK*;>r?TEhMTVpF5NDBr z-kL-*p(B)T%zxO=t<6!MjsF6;Prg@GG!m~c&V7(DXX$O4)MySvyIok{5X$TxuR`>v zWQ=SMCXxn|pb^Erq!sPF6Ho)Ul_T+H=0p~lVuUpb`8 zjS>4yXCI8xO9`~0L*?E3xhofHO*t2Q2OKigScmg6{23FC1M7=O(DAu29=;7_>TPV} zIIaVnia=*=yr{RLmTo&N1#7`(vRo;Www-=T!KK=8&QQ8iZYT_{c)m`H6s=+&gBXA~djNb1TBKp*qdtAHu-}_D#rCsUx zd?ttGpI?H(FOHz0&x4pKTVq%8HYEBVW|bNa&~xH5Tr`fvHn&m3@R2w^@)dh|LkCV{ zf+24!%cS|P%G)Og=Le;b&pXB-GJP#}i5@dYRaKldOvi$q_M(z_EpYcYPG}CGejk?O z^;Hij7)G%tt?My)Z5%9}Jjr2kX}svt@1N&a_}w8{F&J^Wc_L^`GCY;T_(LocJBlM;_f+hQ^{l(WpMIr`cqyCb+ z+++X4KNJc1W$cEp3BCu#WBvA7MOY)LT{R8mihEGs@Qi8k@4Pqn z>pC`;lAG_<@Y-ob|2)Siu1&S^j)M*~qDPVBKQdaaAH3J=zWAZ?+i@NAAQzo=Nl) zxWI$=7q~R$3U+tDK*CR1;ff2ESj{_GTqaznsq5|;durkHt(5+=`i4aAA^E-!9ffZNI_8p;cEr-D zXET}Ck>$9z%L8_|ABfKKXU3X8Glf0+^vx6-yi|=rS5g}@>D9qT8jOZ(S%R4sx9F+A zlE}}evWzU-Xfqdu>>QoIFrPM_vw0Pit3{`+4w)3;ZPd^ovS0sy|fMV zjY=FHxIUak+ZbZQK+d2R%wew-S7K>OI?6N7kS7n?`PovQvu(>*_iX-cnv{%(IzghU z^#qNxcz=D)H}X+qK6db&+Vp|f*}52ed@T0H-sEMZV744?ty$c!&zNqpz?u*~TQ*)4 zWs4i*%Z*rEQ@Bf1sWR%P`op35Av4Zg4D0b}xOccj&%tyq5@d4`Hawf9zS)9S)kvN< z`AUv-@q5HiUzBk6Z+h=)L>x*6d#Xt6PQ9cF4szHN(!p$7^k7>-E-Q_v)XYT1- zD^4V4S|h{I2Yn&w~9dg?s97P zX*=EO9?7~-n8BmN2TA2>Yzu$3jYcP6eS0~nsSTvHoF_Zu(iG;`qJhmu5pXDr7k#w7 zL?;fELKkx*WolaCDVRH3{m4FPNIM4r?5_vddR4lVgc)_T~& z>3}=-kBwrvo-XM78V$Gm+sMKQX`Gs>kLyd@*|$brtl>Qu_e}Ccs|uU(^MkDL$8th{ z$<6_6@F~N(4&c% z|5l9p3wS4aLNM~fOIcMZ|5n>_57i`P^1EUpT|a(hzuw+^MH7khlW|LFBU|Xfdt}tI z(Gi+Pmd)~}KdK(mHz$nQ7hkrxWz3s!TbVv_gKJnPx zQO|~KS&SF^_V(*AsVP!4Lnf341Rh~GzR%&TvTUrcbYLT$w`1Y*DEz6sLHxg&asToT z2$XKKj@y>lCliU!+mZz&)%c#? zk2Qvb`7_qnH5<}+;6t{Nn0@-|JxeHx*&xqv(|7 zLOjTcL^g_<{$mZSF^_=DqGN)+XQt4vmA=%|<}RC;yZ|0NYv1!_ExS64bI8XW!q~fI zWL`@QSihi<^7h*)?A-65>b2G=-)CEK8l-6_(=0f*iATaYDalDI=> z%$W=?`8+bUNE316lc75_kKN5AnE7l!mgTM_egc1*IrBNy9qh?oc5T5LetuJyA4R+@ z+~_%p1Zry?$tM3W!bSfOOkA(bK40p+JrIr1S8r`TgIxt;nV* zBeFu;yUu-Ir;;Y^X_wMYdui{9N&`_L%9h=^WmiVDLuU4t@iBk*x8EOddhj^!^LoF= zbv-X69=*>*Z`5!gF&iG9QKB#zeN=LeU*()WGX2~_*v%;I-@}{_v_sK#fApDIl8U)J zEAYDxehRwTOL0E)4vgV@z~iE&^OxdsK^iK5-zMJ_7oaaJ9Gza>Y`vHsE=}NhqYV}M zVxR6n$wWzrzU%bl^o1C`r39gTzi0H>6Q!LAsM6^pQ?e}JF*OvsW>v9hM_1Th$ikLO za^!^BGiuQw1I^Ya%<3C~!c49wmkDGu`EGo~%|h(W%^~JyZM0{KDwgFPV6z6vqkex8 zPIxPdT%(>tCzMa=JXh$Xj}xk&WT3?@oEQ#~gn+Y4o+jL5HO;D6Y>XW#W;dGL}S@bkW%ZN8sM=XUs@T2XD=yIe=M)S)H=Mp!LN_J(WX#ydDED z?^UQRc);W;6fx0i3kJv9iH_e?#&6Ry%q#y!atdsrJI5C#~jp@{>ntrNAg%) z8e`TPz;DDo)~v3BZA+uk_pns-C87<9HPXUj9Ra;wI}d&e36Q^ij~(TllQZKh(R@Qp zkaffwN@Cvq`bNFctD(#pcNqb{NfGzM7IR;@(v?c~?=9!OEXqQ!-2(EqbrO9r-KoEC zUo58qL%x$gztWAp>e9lbzr}DX%qOpuQs~&gkJMOv1xp{~&T|uD(fq|yuu-WOUixCf zvw>geE{mn89lHtcSrN>Cu?wa~=Ht(IKvK-!jUjLYdz6Imh^S99;QBX-8Xk7tS|A!pxCGO|+{75+9@pxMS2lrKTj=O{D}SycD7 z{sFzGC5fqz3&`HB`bcm|hv(JnEbFd5oE*0H>(vc{r_jKf*#6pn`W}DI7Zri3JFpM+ zet5Jn8RMol5v@U%IQb?RTiNo*W_Yx2 zBP3aQT_>-@8$)?Eap_+o^H~U$F-e@`T+W^bsX>k8xOXc>P%@S&r2vWu$7KEqt_nG0Lum*-dlcpN-|*Rey&9s2d6RDW%c>DGj>HU~yO zud=dYb)4sH@b~F&1$S;wrVC!A_3vaJJ-0@ap*KcZcZdR?xI=qi8m3z|6Ku3W>=e#n z{?oyB%+f)@;%Ka0RwOu-+f3W1N}(=jJDJb5XBpMmNd8#L#>=WB;wfhvrkIo8Xs4&X z5ZoSqlNs^8`m~)thD84p+!wB;m5-C@mp`%0cD6a}AMl+_^&++?;~7>?k`^8^(4(Or z66tsY5&ckM$g(GMc3)){1~x>BwqMu8Hmf424tztDM{lAx-Jj5$nPXXkyA8w-c;VJ} zQ{p*l8kC!~`*$)n=EgkZB8qc&kBgRRF2%x+{Qt7%7U>RHh;F$sbja~N{CxxDX>P-@ z5&QMWp6B;yFGXQ~&2>80U?G%qitt`~8+-f54IVO^5FhlO?D4fk^7LScmG5IopO@pv z%|x!tlqU5LpHsC=nf@Mr&73g$dfYMkUwg4gl{3OB5dGG#Q zp@DPFG3H+YLJJj{rJO6|c4Q!sR*{Ww6foz_2FShcV6T6uVd`AY%A1xUI$C*=TECyf z_vGuz>eD{->fTEs|5Ye1*n6rIVzfLAJ zMG5xLH)EK+ooIlN`)=HMrpDQ?WPGe07RCBN_ec_Zan=c!65}A&zLvz@kVfezA*AQs zW48Bo@X9(0Qin@LV>;XLyJ3n@t5~0=B+kc$oAKCCbC0dvqydGtLi~{Utv{IS4XU!r z@ho=j?cCPR0a*rZ~2*#KHK%LEeUF~~2iWKHkmXw-&-bdr&c;7p+; z-Bsk+U)yJ!YvPYmHkK8-F`b2`P?)?AHJf*nyQ;zT1?MTJKQv~Mcf3)uJptQ{Z3W_v zz1XvIxX`oYGi|tMiu|xx78qq4ek5m znElBmxTROgeJHoczTTNwbU&BB-+3;iaU?8w7WTP8dr5?y3Qi|mW8a%rw!&%&j|bvcgA6^v8)C^nKw(K`qy=llV>aF8769Q(1s? zJ+AjNw`b;iU2)Jm7(qYJ65Bn?@Owr`zjnQ8&~n)POu*qk*@DE)tx`Cin>kjmf`i=gnkX=o4wk&cq{@MImPUmraC-q5^(FvLBX9zGE{wb0JT5T z#HRdKLZ0y!{Kwe^M}%B6wx|j(w(TL+u{_w)%^M$F?y^7UZSiGR6juK96D;Na%3te- z3IARl4edCdJ-R6Z4m_i9DZfp4C+6VXDmC)d;|u-FYx`HLN37XM8Jm)};1{Qwnnr13 z-knN3{?JT32iu~w+pE8CKh6DvN44T0$|)g3*6Dy9j>KuJRp;~q@6yu_Qn(=FNkoIS z;3dk2@5HODMnxS%xW2b}?`wgdjT8+IOQHY0%x59|JB(M|!0ULsDD{UsR@bHCd-82! zAvwflAWpTI56lU7xy(QCsKS?X-f!8y#@Opiu=oR0E+Kwy2RY{)d>8OCm#>Hq(y~LKJ zb0+gkEAS_!lmcH|W717T9_}5dZFMVxb)_NI1-O4l}|@`)(;* zX*GrPkbCSg}oKavvHfN@6#r@(h5)06aRY$lMd{F>rng&sMJ>nmZR`wEhNszth3)yQ!lnEgqAv zr;Ea0U!sfdPQsdx>&ee-o@YAdBHeI!Ap8BS5E&9fg>So7k?Z@X<3izLu4Ur2J<%H4 zouP1;(;$+Sb%ZQudY{(3O%&C1aQb989FH&-+N=)0ws_1eAEocDdYOI|mqgmraxxDp zSf#rKi;@`vEq*ORVZVNVzwimffSB1xi9Z(4W zN-l&uVxFoWE{sfJbC#@xk5vLDSFa~;1v0SV?`E%u-K=PW9>!}%A$7oZ(WPH)FuXNc zSbSHHKH__}oWOYOPrt{ilr?ZXv;Yc*KlSU!Y2mebITr8cHJ|HnvKluMj-0Y)9ykUvORcgf8td!HC#syl{$O zQJ#+QNX>)t(Imn$V(FHslXT1~fA&qC=d}LMv;281n`*B8`{dA<~N3saz(IgDQ7tR9&m z8E8D($b6UZF*q+Dzh-v|Hcy>KXY%_~Qwe9Ojo^Nt=0d(7w`VJdtb~CDzrP2aBb2kh z&c=n{-iSNwyZ%!gz9c1-;o66k`Uu+Ubd0twZWh@^8zFk=HvB1BLW*X6p#wtrJtOiF zb6UL+H)Xa#d(1#q@Qdq4<{IO2M+@t7v4G{xfd2iAdHr(87Tg?wy%*oqWD+jdwphuW_D zdSiI44`LqTob#{7{ik~K*_wl#74MRYg`fA3a}^W$Z_^g$Q|_~<6B_8{n$?kyB1Cax zwUKsb8#*7oCU0{Updwz30Ow0gHp>=AA8)`aDKql(&NRFot&N};UCd<(*WS|z#E@g6 zKaUI%5uM02GY!OsXQ-v`J3%Er&0sE8Nz`^#BW>(?qIc`pBmB0R!Kt%=6zf$xdb8*f-yWx%CE#NKLf&D-}lq#H|-;k!Gi%Am2BX41m;aKF^a zMQI5A>CNs{m?HaI2{uM-CBp+$l3<{(W5^jnEb=|D=xH?)d#N)qbZR`nE-8?)x|A1JF@!jm8a2V`mjEvSm z?8tbmm_ADX!htJv=U_?Br>h`;<+!KjHupPBC}#3{#z>=wU|kkME`PJ-{#L#tGd#d9 z*E{3DiA~6e9z(L%KA=Tm;z+*H%M{LY21(^f>ZZO{wB-k|J0>0X+T)0qODApS8GE{) zE7-eoWvCS9A=#uG*~kxepO2@Cgl6r6S^rz&Nz$&}|y zMRl{qP6l|D6pz(B%X^e!JG|~l31^JequLkb@uejW2mW@m7vr^%+fsnPp1<^^JvEW< zxeGog4C(DLwn#eVfvCdwb#JWPQ5=^H58*%Ju3>^#k0ao*q=G%1y^QCaq$62jJ`s-L zjHWz?{@#AeDMd)RBxBVBM;2lZi0pRY2Io<0JZ_;i%e1l5shX{B@<+}f{+tkdLF433 zTrd5FFIS$>CWoa6yBUsDw@_Bu=Zuzxn{jz}GM^lm^z+o zZo}=^?dN_tl$^kQOxMYib=J7~Ef|Z{@38#`mqJ=A0ux(O1^*U5#p+#>!b7U2_{BBY z-Rh~htFenl(r>l#SCE@rNQp}1?G_YAc9)2 zt-P!ZucLYRGS`*;7;6Ce(gTpJs3QBdxmI+d7yP2{vV0?5Ot%e3zAeugH!?sF*D6mR zszf&a*GFq#Ya`e9A@kExMk2|>ti@tX=Bp|!-F9$)%5^dz+7{;&JaJ{O7Q4OJ8M)${ zaQ9y^Nt|tnvm+C5@UiDPQDZCZZk5CkKTk4XdJH`~`2sb&JB-EN(gJv%a?gRc0+%K! zy7OWZy;ZoCx!2laqmL)9*0zgMdOc7)fb(aHZ<9~UOi(c}5<35Qeu0xC=NjfhvGkB& zYHS-lZYzabw|0;(5sI)`l#J#rTiGw(W9x(!;y3T54ZJr|g`^(pI@X`1PjkXTc^@nY z|0@s^deaehY5iHxV{=R}XfA*E@g9EaQdj(N-Hi3WkCB*poXy!`g8^yxIip(>ZJd8N z;d{7f-6TEuEib~+$hYJR*Yt`9RKqWi?>|FqF=mJd4jnZimmf~YVE!9>(AmYF6)wfy z2Vr#AVz)Ix%D{zVo?NCe#22uci01&678oBWrmH-fi4U zGPn=@++Go#wMLT-UAYLs9R)akO+jQ*+X20`uhHFlo;sC!F|H@D3y7>lHxu;#o3lL;&@Xzev3zr?U$qIn(9O z5aBiVt%7NX?daco9(4bNMCSF9^9;xM;pDHy?3$b-RwEhTBrC{DStaD$_vo+Tw>ZnC zypDTzcBG5`I9#I#XG`K}9PbBsZpg`yJQTdFXZzpsyR&!&T#k#AJC9~?{*yv~udX6* ziN8*M*z0ylwA;#)@1JrZbN4=ZC#wga{b4x>3A?4SYQl*I&a6)vnROBRFfQqJnH) z%)OSic{oFgSe_ej_u4*$|K~$qjdH=6!@iJ;IK&pYxMJOHy94Jd*wpzF%g{I#Pbo@!&`ZvO)ek#;`iR8;hEBiKhwk-9Al`{9TC;GULxA`S|1-)7bEaoJ!$?Uho?q4 zysq{z+bB19zvi6zt^%@usTwBvFUOghRu-1S@3v-P7Sa+OfS!xet zvhy_HyT=HH+gezgwIya{_`zaydEK`UHjp`xfXfg5k-X1(SYH>8%y}iu@|gw_4#nX} zON~IBXHrjm=|xM6ud{{Rhc~e^4^H=7xqnR+kA1igJdU{k9ML#62lfKj!w=ZO!Yt z{5M^W-t)J~$7vh!-8m7bO01Yev?orurS$txzlQN_P3w64QT99+Z_-ZvuSmk@l_v=e z;5)`=Jm>4jS+?(~HoRncR$%R0!SOCB>QR?SOV}3nX`vksSa=}9wOzFRyB9vTq+)99 z9pZo21ZwwqA64GSlr{Nn-KUy*Y2MKc(NZ)Lwj$EVjP;`|!{c=L{MsLhd{wolP`O>xSX>`$-ME1JZ1Tiu9&c zqxe+ln(ZUf+v4en=vpdr*JtxGc>d8?-Z%RDi&U06(=}_)(*^aPL>+ZpL&9&FcH-tl zVag0V7SqJn_oZmw9EwQ?kBWxo@!v~T5@rv&Ny^OQ>8?Swbgb=6W^+{;XZbzr zm!MFe+vRA0Sd$yi;N9Bam(oy)JxCPnaQ?TVjYa(593+=NLT)SrJ!$a2(by6f~PG@;jy)w zWyr?S1A5$#Z*4BRwtP8M`$}Q7^AgFJ6GSJ@y+p_Cp23zFmtgbnA;OF!TLo>y9O;)! zp8dS9n19PKt-%jBC6w4Ux(eI&r@`#}K9a{7uy3S15R%@(>i2G<9^FUjj{;GhUvLBc zRVaz`=Qoh*ah#JJn~O_g_3Y=)5-b}xRG6f@hD=&43m=|6X|$`IS=;iQsf$5K_PZ_` z*6xPViCM7B?<9#HHn=&5YlJvgWbSTFjG%D{_$;CSz2rLe>6?VccNHXHqbkna$mO%- zHkP>wyGz)n*Nb zIq(d!!5-w=fvKD&L*OLV&7^p)ba8ef-(yyaV(Bw1_nINR8oY!a9vn!uNjGEi73Ee%)L^W*?hErya5H*RIdwULn1@r2gK!+t3gPjCUY>RWbS1&_(6B@ABTj zLu|lTFYJ_$L4m_^!Q#`s2)sX7m^AYPHBjM<_RKK2XN0noBWw|rm%;h!apeBE&-CF~ zc}(-+Gk#GD{h`%Bmy}tFBtLSUhFTG9t1pnsFSB9uH5-c0dRUaq6Xfptf`{iOP~CTG z7+JdvIa^zqou&!)JBDIn=7PGzlgwek-$#3H45QPJ#L@Knr=p{ z6TC0lJ%E|k^LqZ;5U*oeSm!efet-6XXx#3)z;zxds?0{^gpoAnsSz$NkH`FzyV&^{ zO<2y0Ltkc%ppi+_L}w3rVAxd_zFHMFqFij>=faW=)v!;l6xrX4iOU%Wga>%`@72#; z_J)mJDq5E(2x?V~pwI7v@2vt@!ryf2Sbu@eb_x~v*(Xv9=gaiQSYP(!G-sG=agB7- za2CNeiZX+CKy1f#66|V^v>)r?`ACb&yxV~7OHy$1dIh<$(g+ei})2NfGO7LC18L#Jj7ZhkYY_NwBffbLChO9CX#vmAI5i@Ptt&UdnR}r)I%R*+)lNnu&hr|#)}Nd#<31S9NDN+f znI(kU^BUp-*qT(ry75)s_1J}$PIlyM)~8k-=r z4DVt+d~RC*BndGC3-x0@Gdk(c6z=~$N){C=;PkozMC%l=saD*l-W`OuuV0W2iAZlJFch{k`-^_D7N4}bURoKg@?z0`r9kuPB~>^xmOll$>?x!=+#R(Mr@$dyOOwGYdQaJeK9{uktIi4L#`(lPr`Q)Wj$p$@mjZYYzG_sSrf}f z$AS(>7tzK>`f8&j29NV1SFHl*8YxDLZVzAw*Q;Y@PYHDG29wd(Wid?b|7*L3r5#?) z=l7|s>mo0O^?3I@6OL~?iS8_0Sno>5UXOP6Q>cZln_{8DB=nmnG}62`laRTjl9U*$ z;e-?SK}2q2sRseqr%X?Yl zb0g%s#lgu;mU(AzmWwbAXDj1~m2wbW<8y*Kd#bYwNougk$i?Pawjzc1nwV%`rWhL2aHVuyI1cQHev7aSt(LH!8+|y5sdIFZ?XhI%b zollTQPm`(Afva?n_yTt0vL4P&Da6&pKl($i*}>qv8(eSmyiwif@X;A8yrCLHb2pgb ztYH`wzmzlYYF7+ekc*+Gl*r}hQz&z{>))R{%v=Wd34g2>O1JOw5^sr}mt?xT=RaDX+!vAsewvZz~y~tB&9zOB|cj z%0g>RP^uDwp?Z9mGRgug#gd`aGK`7|QmCKYSvpx_1beVr1u6DPxNCD!P&G%IE}tDj z>r?l#nMW3*Z&m@E{p{Fi{?3=@jP(EM8#BJyW0yn-hAX$QqH~rIvy6h`tPFwrvo_Gn zBZL}Pb@6Xt3RP-8Lw!cy6Af6W50iMF(-f;i?)NIdC^R2?_xuwbb>{cw#XN7xt%Ysy zUxsU8KDfVYcU_mACyr}mBVg1>x_{nM+~G6V&gR|h*L*F`w2tLo{ThK_hzuP&cs>1W ze}!pYR)y}T92CEFW+@43aFQv(2(DZjR^|u|e*gI2&V1j4HBjbrYx0qB!EWz%DBBDY zUi6T_UehI9Bh0;8IRVT=*#ZJ#4o(|t5c!fIy5Q^yy6mJgJ6NC!of|p$eq=bS<~bMk zYj)wS{Y^6dgfsVic_HStE_-*~kUxj9coDq*oH);ag#!{z_n` zFqw{g6Hkv?Zf0L9Y|)mq4x6-FMOt}2n9-gBcfC7A=?2%NoezWlqeiB%%>qShk|DOg zLeRCMo7%fcL1uIrksYXuyXQ0Tskww5dasK}{{noSXF;O=_R-_>t)MsY37c!_1B0Vc zsC*|zvJC>M1=qu$)k|jTH!Zmykl#R~7ckdF*6=u$$~C@KBq3i41`1a2a=*udzNujU zj3m6g=O-%T`ENHJrl7dOpNL;`rT@jBqdnU{iEc?b!fn!e@bGuCKwK7w($%r_ZYLYY z`;(&0!B|R;icWGbLR<*4dU5+? zDAYe;ezgYp^&th)JA7D`Y8z6PP7{uBl%gr(opfU30#rKhVPg(2Mvs0zn*UoQGC$pk z?}g8CbK5zpIm-sKxfba0zgYIE*#=^R_UNQmorUB_3Xca)+k%y-3=d9S1GdN z{Pw+g$|h8{Z71s;AS>->LeFO*{5Q9=iO;zXR(2ysFTXCzT4xKDn`sanYh!KSv_Q9U z|6PfM{)5OSy0&!^;`1s=af>>l!*U_`u#G84b8qH}V!pp{CXu#IaC^O;vtp`Q%U90% z*|Q08>f^}noJaIU(r`?e-OEP(X9R7rSS;r=$f>X;I9Zs63gdWkOzl1;JQvW_tAc41 zsiAyR4(^Y#5jEN9qF^7-A?10X)Xo*!GG2J_B$*8ga{=)U$0V&)r0LBxd@U8=;F~UH z#_!P=4t9! z)pe@gTPYg)MGu;iJoA0%7UF(Aj;@;BO+B5=n9?O5Ow8jPk~PZ(u7}$3d(aoeop?YG zhP$ESaXJo9&0z1A+M{hKXR>+45z)afbnc0H*j?Adu76U2`=vz4zY^zMCW7zQ+aT?J zfkdB5pnts{(B|~TY`~Kk_&-X)nLU+c?iSAKPqW~e2rX=au_+GD2}bH)`8rj;w@lxj zij7qbtXe`9${mRqH2R{z|ME2I`#qex#qDRWCn(~GaXuDR+A^jR3hSl>H2!QNm)|)- z=13?;3fq|4P*?oD#xpM6wg{S>3~^y*D*9^6n5UTlFQ;c=kgpCgys{V*hvws^=ReWF z2byqkF~D=B7Pd3lhO^xKF;Tvov$_4Hi#6*e+O4dwwku-fU&vaYG)bYC&#y^Bfk2xqWr59o@wu#4~4qB0;3 zGLOOqi9PLDP%}_CR7L_r`Y~yL@=REdA+zzt*c^lr= zB0ACQjf})(Xx_a|V!U#JKk%U5pyqDSRYlx#mG)J&BzqC?>543^AXYcJ~L$2@^^iC6R}W< zq{l3)=`TJDhxVxQ`jm)|H3j+$xZdQ9u_Vr=93pO4xnFEVJ_IN7Spu)qm(`e|;yEx1n0Y|b7wT1*iKT{zFve39sFPbXH+?#1EZ=jfPOfsj3!iY?nWvyff3(Bl5w z(B2KiT$g8?)iH?LL{f-V6)JCt%h2CN^l7HgwBlP~*pY?1eY!yw8(RF=-E3U!{)Sx;cpW zR>(fwqlg(!zDC+{ZG;^YT3_?;!Y*8Cj5(!TJS zv{CTPz5~G$pV7?ob_^n%aFcVS*{cM$E9n`$XN?#7*oo11SNiC4?RikF>0xPm_+24pY3uef zF9pu88=eoh)3(f1Hxx0?Io}&iM7GEU4XvRVH?p0n-M2>0iD;zNW(pqHw!!3pm@w&s zHYRT7ni=t<)aS|_QF)9WX9c8V`YBD4HME^pZ<&Xa6Bskd<=Gb1Te$D*k7&?REu824 zjwes=G9wpTOgrZH|Mfh@AIDR3LFbL8m-(IZnDHk3Gc99&8@185j%!38R|~{H%JA%q zb<`s2G8?1Lvqc_fqgmk0MuuwOg=I0`N*0qn6I|h}=7~71R#r{dJSxrwfvJqVG*6 z@O+BTYMK15e}yF^>Y=rGE9$Sk7L=(?ro*qsQnOvTtm3O3BrdE$;`@?Bp-Z0w{Mh!?%Ogl%vcvLJ!!ZbT+FuKN}vnZ zPmz9RoX{gfoo)`A3>VAgc&U4jY3Hb7k9Hzd|M`k0^WAl)q$FO!n^<=%BC38XWZsIH zOolyqkw?zclke7z#BtlEm68Tm|K)fo}m>mf1y0g(-Nz-{G? znEG=+8-3FWgA)_*@|+CG*X*DlcZuVJ;!VaLQ&?P0#QvKe%<7#r#OIaZ&Xs&}+G;$i zW!F>j3thLdg8G|u#<5e_7QVc0Krwp(mTPimPUJmiyharZP8UKsdcNRR zg)4Pb@aW&4j2g*xn=k#~W~0JpaBb4(2hoWCy`7AcSA|mCI+Vn=vydm+kd%wYp71o$ z%LBLR(F#e_jPM~1{3iH}^KhQ8zQ9^esX=^CAx38nAV0RuLXrIf{BJj&`Nsk{dSGrs9*Zm3$AiLt|{15M=Hg(X@C#rB= zTg56b_40egN7S9aF4&OJ0hP>;kh^=I&evOoU3}jddpDU?>~!YOU6y=}D8=`Rp*rABl&}iZb$BRui4; z&HL;8NLMpN{|)5*l6>8rkJiY1my9W$Vw|I~1SBK{S>LZS!u8$(y$P@>tQRz|lA(VC z18MfOJcfeqG8!N7|!GWGAlCyL8a%+!^9zs`D!VmbIcYbP5dL; zzgLTAegR^fJ-BYM4MI_j;VEN$ z=3eXpFIvcYUfY={4Sh8iSw7G85O?0nz1FV<^M6dHe}=`PD4HmJTcsesF=A-W}H1_Z29fL zc0Xy_J_T7p+*`|QyZlZyRQqvFb-1tS^5jc&@H0s$t?(tgpC`~Z)h?QGLxQdDa>iGo zTYs;vAe@Pt3sn*Ry@P96&GGX{AfD755iK6(ija|+=(*lSesSJrzM?;VKI~v--+2yr zc>;Q+3-nKIzDQeqc%K(?m>8_|qjwHnp-Wa@6V)cUK;f|)s>eSd`T|ev_%9B7|JAbn zrj8IF9fz}dQ^;Sgk%;LWj**c~%y4P~jVm}z4W^cgBpPkel~oM88~NmH`UGqr;RXvq z51VSLg61i$eaew~ z=dGb{#S-|vfcuLNZ$Rm1K2tAofLQP*+~2U146WerxSX{Zys(|gdFh}=CJI?3P1LyP z4%Oc;3HhBqWcDjou`0yalmSG^NDf&axH(`QzoGAb*2d;GbA9g~z6%wT(3jC}rf2?}gtO1~5P8moUn`M~ z7S}@N+{%4Y0fjg}#etOFbikk;tC2OciVc)@z=%zLI7-DyrScQ1e`qKy{yb%m#f{-R zEDCAv)7g#j_PDh;4{zhrNzkSw8hBqs(@%rh>T19yFAE2@Scz7j;aOAzi*RJdN77K? zgcT`kL0S@+#C|(`d**{JckRjOlQUp@O|QRiA2rpOXK6(td|8=DLVGFKv!`IjpaaC@ z{$j{Ki^4)){}+4!=4~tBnT~(;gFGKYev^*y-+wRY-!caz`>sa#`nPr8wtGU*$2F@@ zevxYvm!tMe2k|@kJsTTbBAw%mAt)>%-F0!8Z1Uk>Ifs)ixQH_E*_P?v*Iqv&O zT8Jz1L)g#zdgt6G3}yjrw&5~J6=z~ujT&iwl1K%=>!|5u zPj>E?2F}mU#yrd6Z1Xm449YIX7|pBX7vCMJ9$Sq`%^IvpCjuK6WI#BR?_{Pd!Lp7B z)P7udZefrK^bV!+K#*3V!|@FpdNUxee3iL~lBo6d8&t7CPB3rqWa^b3Md!Cw+0n0Ff-##>_H?jC3D`2}S6K)Uq?cl2eL_wQDS4h(x zkM-a%G7TN1m}dl=;msY+NK|nmoo8F=lL1QHN5t3*{Qw+$9gZpL;w0-P-=zm6_iGVL z6)dpMGZ2T?&1F8^$EPze1<&NF$Xh#Ue0yctU*}gEsYCQW9-C(QiUhHj>Ciip7}4NM zEZ!^Qb;uT6S}J0WTn94p)jH0cF(YilOq}6a8Ur0V*h|j4IKp!_*RrFcQvY?hbUX*D zvmTMx{Ilmm{jmIc2Xnrx4p;pIv=1)O&yv1O#X=-8ulF#y@ZF29u&bx{*IyEOJGfxA z^g1|AzE6(LbHr#5KfF6%#aa}c@lqIv21995o!3rB!!dECEBg~@ zk0(XNC{-&UIXV*&wqhMjBzu_NUnTtBvKjV93q_@zVUV*p9Kx;UbSn26&kFIv`Q8|2 z9I^sCI4j79`k=Y8Ks4~$g7IPywT%WUsxMR$7Eq!kdRu;S_G@_iLkuF z83+a%_}x{|-@})2=ASKDOPBW~u%%5l_`Y}pX2>eCy1R}DiQEL;=Q~Ncr5Y5jt-+;X z?Mx~?o=(v|NHfCD*A*n)r4!>NxfaET^#1UnC*5o5u_fO{U-;j@!u9R)Dg#K%Svi>L z$oKc~Vf;OkAmNDu*NdW=wH`40FBO|#w2^~dOA!$lg-Q8W+36#?xbi2mzs`>xf0wE$ zN@8Q`UZQ8Nh3E;{_;jw2Ssm2m{_;Z18{tT%WjN!)qcv#Qv!9K8>j=wMKd!kICv!Bq zsO*Qobh~&r%dRno2hT6~qBfn$P2|jtp*_xS@!{N82O?0D#ra`+_%FPRIjmiZk#8dLa#xv1 zqrn*F1<6qEtRj=9D`KHrB+$b-ma6(FZ{<36`|tY0_C1C`S6k@X`<$M><%lpzUgz82 z)`{v?VVQj>yd6K0U7P`RX;KgdrIxdtgq7%AmWd+E#l(^GMgpH%(~NCj*{9Lz^!txX zG;eje=mY2J{g&8;?D;!M<_UjlfB7=C`>e%24tas@tM5_gd0pVUuM?Nj-eaE4eLB3z z0&(VnxStfvmT{ef-nn!bX2ug2|1P>@?Koa5FEO2U>Zm*z4-6A$2D(NV^s^98_t$eD zhbN?01wf%HpGf3tp_qGmuC%wXlmQkvToTaV!_VWs)Y_OdG-*mu-Jjb0ZW|8yn`fC6 z-`(x_6OSG9>jm8gGSu>fFFnMy^n$xeIL%pM*^jK)(e7ZRPl&;ZzH8)w&q^pg4aQ8n zcDD1cEvEmD;920Ag1+vj*j6=K_^!qPW&H2I<$pgdJfGF&n&DOIW_%AfAi33l=pzLo z61gVFj{9-O^6bmLh5tmqO8NKOLEs>FmpNM5;8c|-6k~VSo&M*B)oW9bh+*`Mv$MGWIpu0TMEK+*^8CFk;y>>i=#vZ8W~blwNRMhhE=`X*#8B%w zxh#61BOHXQkbb;HG<4uf)c6ErSkVRYn!lqTJPN^OlN)T`VpE<05`*4=9fC2+d~f-5 zGgj-$&}Eha^o&Y_c6l*-VPJ%^0o-4|!;0+u`;(sH8onWeAG0X~V^PfaB&&kQk@q_T z>7zl(^qxi{Yg=al{V{=vvYyL&f7@b@Q!-XZ?IZdA(g;hoL=N{z?)Ol~Z9X$9_WFo^ z&Avjvyp)8^3_s#<$eSJvt*2Mge~H)`M>Gsr&2vGPlCa{L@O`7)U+0Gxn?rME0N$$~ z5e+Z0$0(N+IH(#gO<&va%TI1pA^|JC^(N7XR) z9%<~4O_aW!>yH?vFw8q)z~9ojvL<;EvFT$)WtI~ff|5`e6U^kh4@2~B(q&QKXmU>n zE!2apd7vOHF5bnlp_J>C55B;Pp4*<~+&e>A?CU-YWkKulL|#?mFw%uz{OieuB{9Cd zEzw2U7ZQ~z;=8pyHWd5HU+gnQRkOLH~v@;93m(Dzs% zd%S%rYW>r2%&0^t(X(uaP96?Cl3`)`qtSD#YWvRAZjKcOcOnh?=krqI=f3ztyRd}W zwXAE;`B*eP7A38h#GhsQkfr@y)1m>|(~4_&_FM&A{@4x+_#7w) zZosGxc5IiWBNT@HSLc5Q+8`;|A7?LhVPDi5`S#&|c!!aV;`vk~l#ZZ0%97#YVk2?k zwq#>$K?d_%6veOQ6!P@`Glcz}S&%-;zz9{oGAhU4^=Rb=M^OGOt z#q(txyR~xhWZ_Tk*ss<2a%ZAW(@tVzJha2+jV^HP^SW%vN)KE<6on4~pV(PrGvtV{ z_FZaehlOZ9k_ej!6;|0aoF}wdv}+oB_Gg%ow;XX2cX33^0;5Z|!+dH!8)@&yt$Inh zx!epfdDU|~JMtDUWv)o>f2zj?rPtV5d5?$oF~#=LA;5qLu|t-;DpymWyfvCNMo^u% z>xe@2*Vm-Qdl>+oN0NHZDx4G%>3a5cE5XJh;CU($0e8pO7jpt|sm zDEe%PF{Qppb}lHJzt;=D=2DJN620fkMi}%U2J(;d#l3h3Orh)^v&)wxfjYzZUNu)f zo1Yhx_Dn@%P#U1PP?Yutj%jT}p=CZRQFg^`S#QWF-WA^-g<$`Y6eQ**Nxtzm4BOC2 zrzN~U;!F(@({(A191akZkGkN;t+kkMN;x2pm+=$pPm*TEMX1nx#^XRHjzo45XU>z~ z-8c{SBQLTcFYKVT(*?JjW{JNlo_K2!4WA2}X%B9I0#3}e3eVCw(sTZ}LQIkix7dhp z@surJ%&)1-h*)D?oF2X&+b!Qo{5uck6|FIRci%N);U9aPr9R_*%U$VCe_|ZH{Dspa z47jqLHO>@7BTns>s1CKjx;w2D319|6ulL00>{)Pln@AbH0aD}8D*lpqajn;a*r~5keC^xITtT6u z$QnxAr*dcX2{vFIwvNQ;7t`QxSTD>A7hqsIF}hzDO83w#XVm@xjMA?cCNIfTsgi`4 zrR%geJ-x(ZOsHQaJ7ZDjG6H1MnM{s6{?fJk_H?uOoH-rV zx!LGZJwaOC$sZl=2O)c|KL0GS#=1IRoIMyP7Mr=@=JzBdUkYXN4#S~dJ`aP+8^zmM z%Xv%G39i3qp|s!pS`;r)(0S&<`P=W4afJNB|L@_Gj*+J-c0C?nRh7K)apCDlJ=!(u z6-ibYP~wBHZc{||6erTmBw%~59qhv?b=uRpA)u~Sct4tlx$;S8ED&+{{1m z;z$YoU18)oy|IcFStfDy=_TB8zNT1^mBx!bukeWz^2%l}0uC8(#i_XO>>lm=3aVZ4 zYJIXu@U{UiEW#coYu3wD1-lMt!bq)AjPNnUAJ-_9>f}oYoUnmQ>}q&d7O|0wrx8Di zii>4~XpL0E*Q;r;%V^U!OQ?a>iwQbkzSMG$XnPdybH>`{S7kSSJ@EE=BrZ68WH;xT zK}RMOwS#vG?P=zy8cKCCVkC199>GV1Tk?S!--H}#^?%Guhss7*5#hc7XX`g3^3*2w zs34f{+grg;UY{in4|<8Fjc?I)#}!G)*?KHee~H1T8u{{P4ZF7te`cTZES!;1QoBAV|tG}t>sn-XKpqO}M zO{N~>!48(cUIWWxjgaVFBSx&I-BzdI_TB3{XG{EzNXFnxo%xZUbCFXXMHwii!jSsM zQ4uG&t9B>J)~q2sB-@`ayWRJAQz#d0tt5C&E#BYksI%*qI*yOj!on|6SaoxqkiBh)=5WgLek)-k*Vl1rl?ooL zIV)B@CVe&OuFEI?lKSdvqATsnZ+hGj8QRwPl;n$HXA8>mU3~HBK^oo>#~?L>=1-KR zUa)q%2=j8nVyzrxZK#q&Cl2MWW1RROr*h%Ab{ZxThyVX|e&G&%c&6;Yf*%F!iiayS z3q8?oLyZ{S-5*C45>QeTBN;Af!?Rs-IzIRM;hUZbtX1RMwd-BRI%2(lHjF&9nEJna z{EyCH{H!k%hR@>o3);iZ>oG^VcgM5K+C`>i=78fVE--#FODs`y#b~oI1SjS( z^8iEa^o_#le9zL)?gr>Z`@|WAx0sh+GA~L$#m$~|6rztV`rla#yUTARr++E&We=ly zh{kHc|2m+zx+{cYtyJ@AJwAH9#Nme;+{@Yu>q{bW!0m?kwAl*#=cFKH#BRy2qZU|R zmw}f_1Nnzu3>xdwvHjFWVSSc7m6RJ;d}RUK*%HXN&MoH_^%lZZ!vV|uongKCtK>{f z2#@}l#FrZ;i46UPFuM?h!d_#=i!MV^f5Ze$>+gw)6J}$sFY#>#21o-`uJC4>$#+>3 z%<@RDxLQ6NH+|2EXZ!8JF4D|h(|{S(jYQ|yQ=w8>Cz_fTqQpL!n3Bh(jRl@)y0!{$ z0-IUXg&E{`UyM=z>co!F*_gaK5&4tWX?Gfbng1A~0FB~fEJJ<z zH>pNj$j}M)aaayat_VB_w z?l4pV^9%Q}vJ^Ea)}*%A`NU(IFg~%K`YT(uk-U40S2*L0;(qbzf)|tumSE-iKFqhe zjYo8s1AG2NG`}>0S4t=P8DDwwA9Uv1Z*z3R51&ng*Art=i9Y1@~}KLb`uB%Nyc=uIDLR<@Bqv=QDlLq_Y&e zbH1|WX5?Q;4MB+RPEqj990MrxBGG9i(~MBz*I>z;zkd^}y8>fv|yIl7H(u|F5=x>0pD7r+jeYIL&G*+c2@CoX)v{X>{7S_sBKaYkX0nqc@D7dh6I;+gqyD$h(n-^HB@M*KrH*FL5^_oc6My zk#5Lu@@UV+8)o(l)7*Z*^ZQpxymK22t2*i!*!6>wzcG}|mg1sekdQgs0UhLKl6U)o z2&q&9w%zli6aA$IJ;Pd(}n$Zf`7H8-?rhx3I^r4Dkp{ut43j zG^oIs{6v(MHmZgNcmuT>%Tag#yoe_)#^CaGaIb$S8InDe&l?!a6|bxjHLED!d6r9i z-)_=965a}_I6R@68Gd#}@S#MQi+a&N-vJ|jq#>@yeo5bd96BG#|Cq8#m>kuknK@f-tvcQwZ{y-!f(bXVBNgqY+1({I6z(%rJ=cEZ-g_F#<(G8Zxg$-$_A%Qe8B?t zh%V$S$$rA`;qsuD4MppQ^(FhkESxd{2YhNVwP;eU)S z@}Nl&QN-dk*qQ~!F%zWcRshp z|JCyvXUc(%PQ;i`^1`#L9;z-Ayl{BvT~&U@eO>) zJo2)=4q^?e(}~}i3cs!;B9rEXKga_z!mI;Rzc&VBipE0TrcSgO*G)>kCXVd3z|O#}Fq7NL#OQGTKB9t` z`OPL5_%ifdo`|n!93Qobab25oqSd;JgQ>Nco;_SA-)I5Xl}>_t=t_jR-xqp`%b-PlRQHYrZ2M77 zOl+dvMz0#7@pU13kbkXc;`p*{odXcQEen5U$#awr>&NXj~uy71gm>Asc4nEJS{JB>Krl5sRUcy`tH>nsN{x4yh5h{&?ZRu4IJ7 ztd%_Eb@<~ft5euWOo9MCG-@UytaP(@zh*uT=Vik0w1iDH598B56>;TQGojd@boDW7 zaID);XBlK;d%dCqGU>B8@@l2)wxsM7dmyuXzES5;THnMr35c*pgG2q0v$H0lMH^*{jZYR zEE>Y5qkmc|{v~%1)|(ls!!}~~t4r)gnLW1NbHE*Cb&>25g@(ncv=iCOX09|sN1aG? ze&alY zPj+h8&!lw=gmW>c z7Q$vdn2CU?q-XARPPED_!H_;nsE2lCJ_e)7~R zxe1OaR$hwDN{UP}?lV`Z9ME3dM^)=#dfqa;_x2VoCc1b;I^mbPY0QJNGJT)A;u&uy z{^U&ZZLEP;&k0hkJ$~rA!VgF9k_Lvfk;X4QF|#^GoRv6Yc11Kw>%)Elc{ZDmv4bDexPEyh-&Qk5JYK4aX%TDjGjE)vFu;@d`{%)H z*QSXCXM6OMr zYvI)Ib?AB1mZ|tVq4gi}U#M4a=o*QWEE#5XiY!s}8DH^97BBsth<^E|_`QEA#?2ie zdOe`CVE?T4dHb~CL$I&h8ex=sUfO2{0)D1oLArtTBb^;jRSts8<1n`Dh9lN^lE2zI zN%Z|nvwC7}u{kzu=arF|A2J8IYa2w)H6tvn4X2&yHtDo|Cdm3uIbYolu)AV9`j}Hz ztZak0;xGeJwNxzkZqG>D(Cvpb07jAi$1Y`dFHT; z4n(b5fk+@O`dPYvm-SL*r|d>^yDygQb>5iIBmGf2#A$a?HqHW`ZJUvJZ!_DxwvpFW zO~mdwyF}kEiKMGphIkDJ$=;9#=qo+N;y?Ag?S>`degxyf<0azuJ#WN6$UxuNRCc`c zAFeQA6mHxjFTe`=`-~FsyK`3&RAP>noXzN#cbTc~BtD+PN}B%?LoYl5_21*+b#*)Q zW|Y&|*8qE;Rf|U}%rHhT0Dr%#mThtifa$F@Fu6I9kMCiNM$-KJzs}bY17}}G0?x+@ zNgp>2Oqd$6%^T!YMbL?3^XIOSx+|Fr~dFo6|71D{> zt&w!-QwKLo8J#(=XW;#3BZSXQ#`fH8Vs(){di`6E@;}Dx;hj3Z!g@I59-b0`5k9=^ z<4JBUGeYWcV=ijL<|6FzZ4q(N8qeT~;buF^3NDf6WnwbEc9!EseHNggie_$S^2Meh zPY@j5UnlC(e751kaIV|gk-uJ1F2+%gb50{&KWj`y6YWQC2kpXinZ3;W0nO6GT+rBZ zTcphlK*Z2k+&7DnxOAz9AofD-#UopH8Q& zw`ReAPRE9qq~F%;AZ#8nOi9SYk0F=Xv#Aa!yJS!N)|sNmMh~29CC;kCMmFk$5l+fR zU|NtzY0W6wd;d+wy0fHp{B4KJiR*DDjjr24#5?=64#!PCNTQ|;<>lL!@LA27LQmEa zB^w;KL^5O{vR4x$LZ&ZY zKx4}d>S;Ki7%%d|f>@-_V@A?SOV*!&;>jt+})D_D-1M22$N70dWY z=R~m}*AG8SQlR^Ejz}uCKt^OdTBHTc>h>_m(0Sfc>7F<=LIY;4@whZ`vGnxY8$6=N zAkw0RGT(RVnD}}P)RoVPhwg7sQuPWtvi0oMkI|@KJ_VAA^!Ee>yMe}JPVR_e)xW&PGnkZ;P=1;I%lobR!OELEV*b#ctVirF(VXjqMYLBK&J6HA6MH$(ZC1W zkRaNkt>EJxj9#AZ?2y|C+PQOVx!oW>4A&>U3TYiZ@`hy8DGes7&5GS3O$b~`|B?>@1BKw$dDp;+6k zHwzzQjO4T7XlWTLGQC`|-hB%uVT_1Y%A|H7+s`g1P=?yd$o76-@zD%)$V0BNS5e+y-vTjjp%c1}Per=ADht*e!#`zPay5saqRUYZPP?-~h0fw| z2kN)0hvdhRueUHOU^4hpvB?jz_|LQzHJ_X&HS0F9m zzR*-mA#ZgOOb6~}IroSwM(p*aH>*X|KFWlm-rMocgtA!IKrHe8ug(wLNIUMn^z$7n zg`6(2#Dge*M@2|Z?HIz>o$%y7Tk^&FC%(Mk@JU|RKTY~-RXjcuL*V~xfjhKgb!+p- zulze=ct3CWk!IN3Iag9(T8Ft=9drzd*U~I&fLr9nc38JrY#3#NqV20-;v!+mFKf9@ z{7}pvUm}(-^yRzeoaE-Gm8CW2T9~(=W{9P?#SftuxBl=zFjDz8Jv>Q%>uVai@-rWqIYH7s6 zn94e()^LkMeX+N$NZj5s0~RztukF-9SlR;*WAb3J;u6!_;f&Bjj<6gsTfCm;jrz}_ zxHxYUd$VIcQig=Xnt7B?eB_9um6`bTvV~Rt1#$~haeH66*nW5k9~e>0XQcF(q$LgI zKQtq`wnwH2qrS|<3TPn~#*zNEWYutS3P zW{A3&29tumyyb}<9PQS@yZb>A+E)t=YggjeAu!CZ<1ZhNgE)Uiloth(?|d;XmdUZ} zp7;34)ld26r_aQx_cj<;9f~6_#|!rrlpAt29+Sx5k^Ny925Qg8t#^&0<8Sit_8>pY zMt`Zvft!5CltJkDGL$V(PzP5dpRZ}Di1|nF_lp;dWzCt%z0qjwI;DLMFEYGPla+{v zW6PyxGK+EdM<$E{AF;L;(&s#0gn|Wi!q7wmOP0pt$6Xg3IT3@o`;^$fu3z|=zx|;iTEv0V z2FNR21|w4+vCYXA!elLEZE~39Hbpv%yF%NvS?I>7;|1lQ-OnB`by(zwr*^*3zoWzD zn@Jzoix@bD%S5HVH9mX{#)m#0Z2!~|D4NRg%(X#So9IK~MSOdm->hzne$&^&Ynqgu z>q#@=v?N&6H;Q${wc4V$0l|Etq{-qyA6H0bEJf9q ze72x?4ve}vA?NyCv45XFa)>$q?$;`*#Qp)F`&|Kfk3-q+p>ttye>s%qofAJ7OAy?H z*xENbuy04kp?i-pI3HdoI@Z|W2)+K0ALUZ%${^g5{8#4}CojaLnZ!#`scO&S*^nAX zUeG?;_i~zfV~7H7UpT;?Kb(s`{wokVex10Pm%_JfyWU>sAL}?_;dMK(>b;`!Wf+DX zNPwHK0vnn8f-j4fZP&)%Cw5But1ukBJyck{qHCG_fNyh_vkwb~Vi>GYUezShClS-B zIvLhy^rhxz6dD7# zj7H_K_8HFJVRT-vUX6EqO4u#gnQ#h=z@(^pk+N+jj*m`(%E2evgN|14S8Ek;B2UUX z+LK4-F=eI?F7VE=vkvz?iwGBz(U%jOKm8y%#e4NPl`CjHvI;lx>`etSUXs)#diCeF+ zwCm0|zmWRy4YNe=flnzf;{)a!EAd?Fa|&g`u=A07>4UEJ*!X!R0y;Ibc$0aE-Ar7R zE)}BZK+1}Gm5KRoZIX!-hjaEmlAjp7T3GycLT$1=`Y)`Jdc252<;SFU_T%-L9w;q| zqp#~kHQhJ;@5hm*ZHMH;Y%|C@q~d&hAHJirE}9k7FyZq?VNCy9d(x9EI|(MAQ^$YY z9*clKr$wieZ}9o~bBy?#!v2NUbDg>tKEeBmIQ+;G_vxB63>YgmKevKyG`)VGo$T00 z(vyrZLe%L-u~U(Da4E4coZv52y>OdfXi&fd>oC@fc-Mlw#)I-o#qanxn4A9`H3hY7 z>Gv^E88aCR9#cL4WR8Kpez0;Vl+JGQLL6libp6%Hq9SHfZp9+pSWzds=4#?bpEzt# zUaP$!<~IMZUIC-ri`d^(^0<*tp=Dx@P$mz3>TF^KE^1)|ifr-b13lOMc8RLRPWbgX z09mOf z=sn&StrM~u$CD{^Tcdbc44YJsby?j1S8@?XxTBxanA4?Z->*b_Xjp zb;LHy42WGPSOaLFl;#^QP?>Aru8sU5 zL$lC-p15kz#unZpw*5%bC4M<3HrYF%*XSg4vL3@8=#J%w?wj+D#Xp3xQ8GWevyivO zu9NOItHpqGN;==J59S5*-UlyPgmmWz!g==_j5c_V{IJWC=2H!n!}$m;ZM8gF(Gt6- z_@n!@a8Z(FkG-_R%{&yvq^Wg0(Y*`QH=Yrz^fa-Fd~G+Kx`;n3iKNk{r1Nl`5np07 z4S}*NaHZ>g(Wu}9y*4-K$Yimxb;QrvpbK^9YSDbu67jYESd}uq%yh6D`majG6^kBx zco1o=iS3iO`;K_xu8CWSrR+wjWWc_myz_N;p4vTMT$-KC_mbub zYnEVS;BPkmw<$K(MPSREe9@m~2$|HwuPHwxiT^%^Z!B}=8>e3qTPUaFA^9$iZY>aR zdl=))zOCr2wu8M`?Sb>8y{H;fEp8V+#m;f>(c|g|$;Fy__y@hibH&c^Z6I%yX&4;8 z`->eJPRN}?=Z@ubSX^rz4{YcQ)8ECy@bXMNHcCd~@PE?6fO(jIX# z9Jrc6xx$Yn>sJorixtB8^2@8lHR@r^*4mJL8$IEg59`y=$!HvH*VNrzD*9i7iY7BL(}+(>r&30Bw~}4*tVZD z+iQEj;}MXl3xt}{e7@%p@z6}&kUK6$%=ERyOLaeZ?{#K38dZ?uB0;oLgXndMG_faR z&~eW|aqRkhm^@wHKA$&Gp8+M$MEvt^6kW&*()sB+q@SN4VO@QAh`uYoH7`vBRyt#Z zt~Zjc)I>s=2Fg^4JvaBRShURm4P*bS=Wk4{h@ZR$>#n!5hZpq`JZ%m7{HYXMFL2Dv zTiebJ3t6Iy9Vw&QYx|iTJ1lAh)2omI=+T1f|(z67D?tAweU0W>cy z#m7s%wUwPHV_InqRHv$N6&2F(?PWZ&XDAWn3Jqyq+BNSB)Lxl~qgoAS`S`Q^LZQ!f2Kii3m)6)}?if!!rQ%hV9@Qz6N@qi$>U83sE0257+OkLb1wf)?G7>TMVz@N5*Q1;1zG6vF0hhAFh(z_GrMH z6Axi}{Vw;gvPLqUS2x~{5L(k*&^0a@Do24#UNB4IM1dZa)#`9%684ZDT;;!<9JaD;$`zBPpa$4hx(gx1J&S=VhCA- zSZqALNl4`F5u`)f^*jT%aFraw3bb*@_JP>hHVad_WkNsoyY$jP3A~q)Uu(r};W^w6 zQv+PF;q>;h4ANk@{R@Ll&JX6FxsWuT;TYB-Uz8P5W{5XsG+hV)h{y_@_}$P=W?Kkyg(K%%;q>gT>;+I(1xXO~TKwf2EyVbuq_b zLwnBkkmb(coow58ub&V4!eCi2^*@_fvbqU=H3s9OntSQhNt9bula9!ljV$65d1HyY zp5L!TREAO>M|vjuH?~Pm1r6g*2842}4;kXdFDLSbQx?dBJJRbiu{bRyJ@(paHm=+g zKCLlWVq7QGdwM{tJQb%x4@h$C9np<;@jdF~`G8st*q?}o(e5m<-%%GYmSkeYBm-9F z(GjX@MzB>Teu(xP9MO9Uu9CtmbnkQ7k|*5R{+a0KXi2#fix4+vjL=ZGL(PYH+W+oi zGtMdF%Opb#OQK#>aUKq@qMggTaB0BI8h%-R5bmdhGZXjOX!fOyc=fZwu~Re*&V@j4 zxC>+PV{u^EBwWg<69#ALjBe`>>&wTa5qY!W-QNfK(X}F9DT!BC9&XRtn3G%0D+&~_ zxI-~JwHyP$ZAn{z&Y8_=Ty@vd5CuZn$`RmsmWI?pfPVw3x}W*X8wm zuHPTt6na674>m;6W{rz*IpD#3ipqTSuu2rFO3qGy=A zFg*e)+rtdscso|pJGO;7Eh=idC`Cg*lORF~wEZ0sx z!3!q-kZSZbK~C>2cwW0(8q_L^(XN`ZWQ(-asFpDBz&zEjtu7>EBambg4t@_dz<%TMhW~*s17XOWL_2VmCSa;8J(;K&r1{J&Exi@ka+I z`c;cd={7Jq?2nYC6UtU)`k*c(9RtSq=2zYuVy#>Z)_y1#ZY{RB?3)Fftb39Xdck)Q+adxFPQ|X6G`u(06QAlm5x3P5j%`5J>4h|Mc3FyY5`{IlB44kWt5KF}72U)~TGTA!01 z{vEE`eUt>s*TdHE6*9NVQKl}PJ9f~0Ug|IUS}z3qorrV3>U0#FkH7fB-|{WLmqI zngrY7?H-!Hr8lzUvU71JG8(jz7iZ~y@4a~w${K%3Mph|vt=nNdabBj#{o#VquWX>$ zvqt*w#A0;%9*WtWE7`6_PsFgLSe{cWoTu87Z;8$YyLU*|h1np?FO9Nc`ti)$nixDI z8h_7b2`L@9q!ufQeK3!$A6duGo+SR@p_5`&Kd=8Yl5zUNPsulxM*jUrGxsWgEVkHN z!N}YfMlVJSvl2hz%q_=*ibA%qas>RR7$B7T(&{Q*JRX}2HH`>qRYNV0pEwAHTO-)% zo$*|$QSdtFf6|VvZ?GS&h-|K5>%Wb|l6@1~cdsM6TS4Zj4-5tuO63#-h`mGkyptZV z0}tn*^H(oi38)oq?v8NmnS%j44{8sOspW?E6rlI7n3aEy<8O5YAKB}Ybm0tQOQv{Y z@bEUK@Y4?22b@v5d#6Y+a)$Zi5WK3FXMJlMxz6?9eB`$aBBz@XK0k>@xV)!O_-&4w z%Na=AmcgX`hvH5GaY=eKi)gDf{(99FUiTraZ1L()9NOZGfA0FcSByP^65WImjpr=e;>A)DJvbQ%hF`qPr z#pi2;k|*_MyQ9$cN`|!ZnIU@8*?ePG9gDc0z}5E^@kx%qq(|@Q!Xk#w3-+?iId?n; zJO5Yn4{F&XA%kX!ZspP()e!Wdelp4CE(@z6oq$IQrVtP3mx2*qCPyQ$wzsz4M@w9) zp*+yV%6#MvjwA1vW9@+TB0Fmy%$E~8eS;kv_|6k&B{XNZIVd{N4ye~uXY#Yiv8ZwP z_~YJhc$d;ULYBPLu186a*EU2vFt$Z$S9(r$PhsaC42R=(b3`p@qUYl*_|zrBeY2jl zY;_e6A)U{l$q}r_7y3NO^Pu;6nRrgU;x`Xsc3d-Kwll|IY}yP|UZ(lXds9p~7mU9_ z+oUojHc&a7imZym%;U-|yqg?~z$}e_PS?D0L<4PR=n!$`|zjHyy2l3_2qTp2`mOLWuw3V%7BI)AgVwNDTa{zZ# zvqlN^f=BDa#MVddD5y(DM4tqvvPK5cLq=fs!e-&2vy$%_a*~g()Rk5h)*|+xf=;xP zK4&9Cxc9h|{8IV=@oTv^*d<3qN>;P0W)cig&>?Q-9pOX$rP9^2i(M$X61qyDWw8^f}~K#*z*`QBrB&K+Nq|nEyf!A7+{%dj|D~ zUl)u1UCmKCJ_!{ECb3z~ja;*|Px}mKl^(sv)I>aq{v%bEbHT)QRv2V6Q*6_TL-&G2 z>^r`P^*d#XNlSzAVw^{*vr;|HCFFE|8QXG`(OS46iN>%sB|`7CF`{;n-mKqiNo1@t z57{2V*DP2iwqA9n`_u}Hb?!)QWW8`BeGx1^l`#z;d$efuB*w|#CC7w3l$+tV@S(NXrNlL|Zs=tJ`c^%ZLj(e-!= zR$h#fvc>iMhUy>~%!p*lSEnJhBo(jv92X&mKIpgD5uFy9FgUrOpgP{B1Bs<(T z4YrhZ;&5rD80F=Q1Ky;ExbT4OByUTcF8MBB>=aJQo+wR@#EDr-?0Mo(e%iV(>8o1A zDH9_s4JA*vuZQSEb6|&YIY@WPVf!_cc&o-q-b-bcSoScE4=pU?@{_&GIyi-4$pxSG zI)Apa1Cob0>29^0h+ufNRO&*1bj#{`^QZJhO%*S!k$20{G6pP72H|%#B zN=plw@y1)_bK3G>nQIjjZbnr%a<3+iXfqf zGriVfm4Pht97HVPvnrVLwpO$zl19tW88NrZrINF5utgHmt!s$6WQ65TQ7B&9Tf3mE z6?(U1;8DeJe&bsr)skXJnV3?g1F72QrM_CWz2p_%&*Z+Lf&dNv=%19 z%TP}$^W-vjq<-5YErLDOaD(y;YjkKz6z^0W5&Y2^|GHbS0l8za{=jrd!|KFx@^nlH z3x?6@ZPIE-e{8>;g~WXiFUhn9Rnfghaf!@<_Yulq-D2b_M8Em$T)O zu2@7GsmNI`%U;O4;N5dKe4g9JqUd{8dfs?HaJ#rZ(F1Mrq}xeTWkWWM=XVv%+BG(+ zM|9EeP9hoyIEkF=#A@mGUq8QZQys55Gy*RNZ4nVmBJe6?5xirJC3{`MP!b*q^LvYV zN}3JYVtt_+94;o3hS#Yo5lipHuF`oF4KmD*RCJtwZ=StSfw&BI8jyeze%*DY=#>na()85asj^s=3n~Q0> z^O=!qI(NKU%9XDc6DW94d3#Dq3`!g(PShZ>v1P9nVdZ`UKy_t)9v{H71t4@{%j|RZ>kJ zuP!b`yhiSlcf>Im%!}ukQATYr%$|6ZuAl0S$y+nA+pm>*J#e6VItypWgZxi<9_q7K zz^=n1Nv4A`KfW!9J1)r(J85>>_lilrp)_UMTLh1RYfGiWB5B zx;Hiq)i1Y5W=#l$Yf=s-eNyHRJ{aQs))eT^*(5f28KRhG-~%iTSy*EdKNftR47(OPfg0as@@(8QoQD=Qf zzcvU@T|EpZo`!~5xO9hm19uA@gvN)F?179LBGXfG{PQtU{M8dJ<#zBHGoQ(Ns$$mi z|LXjgiB`Du(F-FSj!Hi~^@HY$bToar$DRuf@QZs*+e*=w_%5*(j)3_CW<1Ujm)<*LTIMd%xsbe)vx4F7E6<`Q{p5pM z`=I#EL-Ene2!6w(V593HCYcjk>~l6Eb#hqL>Y-RUiddE|_k}9?E{i&+q2~4o>5;TJ z9332jCE2E2vjed-E1eMZFj`z#YKzE}MYyTq%GA9^Van&Zu<{@dLm*|JsYa0xdVpAJ zPZ{pZ(s6IuF}BQr^rhwTuuo|azjD+lvx(;9Yn3EDBK-Ko!2gkS-hotqZyaxzw09}m zLQ_SNd(K<--h1yEl9^;CAq_3?}InVQc zzuqqG-1yTWj&M5QgrHCrp+@_cDMbt6O9hS6j5 zL_q%#J~!wn&vQ+dBy-yL6_y*MzsXi?zT8ACBeqe0@_aQ7B+iC+B<7axkebr2YTm-7II6v$T^=RBz46z4$td?^w=o@+fmf197DU5}CR71sS2{bpxbV^v{O(N_b?a9r&T8}Ww8 zueHV1S|3a|-!9gLJHa9~j7E6OVodfnV!1Hb|7DKy|XxYH^+cB&wM+RDNkO5C3k&-POP(g~!6+ z%M2uFk_W2do%F{-hS67N5ikC}`2N|6{0c5eT)DmIanAr;*%J#-i;mn!!4j2E7C^ah zi*b;CAqu#5Hdu-?Gz~f4F=`IMk7kGG-}x4NOF{nk70!Z${Le9c+AoJMF!# zF|yBHvDTmky>`BbvBMY1kP-Br6WhR#$zn@{HP)m@!1`>ch`iT;n%}b8OJ-hT-f`V9 z=Ec-@{rvsA>bT&&6bDECk@k>QV&GtT?Sf=0KIL&3&c}PfGYev_))G8EoCqlIWi@T) z__87tH&1w8%s%IfQ6I99_WdPOrO)!tupD|HW#ZC5du;Ew9$V_aNp^>g;alH^aoMaa zF@B>v%_pppyQ*9&*A@U%{UB^5mc=%@&t`88z@<62M5i^*#04S#;jf(%?{2n;xSEU; zefsiAqI}|4K`%H(-y))~7;u&}S z^sL<{b^HX?H~m29wZJN2LRw zMdOTVHl!;W*yNuycPjA0=iyc2%ro*rsgg(U?;)*{o3(uWoS~R;?+i;@uK|PROdKxH z70Hu`dm-=G&K%Cvcfk~Q7g&4l7V1h~I7$Dv-l0PoQh)RBi~6?r_NP*eDSJ5@`JcSR zhxOJdd$=6o*E89ZN5mN;&GthJ@*5IAVS!Z|g0_#AD(^`^yjm#cg`4sRBb{+&v@@|G zVnrMYYKN`$N9Im0&QZ5o}Sm~iybJYan`o?19#KB^4pcy(XOh?GKqwIOG8g~9( z4Ch}Dg~D4^lut;*X_MiS5l4f$)h`#GZMIDKSvuoSH~M2SS$MwnrP=l(u+`hy%H8uI z_th4U4JjL9m?1{ZkHop8OzBGMe~0X*y-fZy*3%@F?;d`dI~x6yj`$hMza}5$GnM5e zOYSP8ar|f$22_b}y3Sbh%Lx_ZE=x z*+(LP=ty&#?(j8U z#JJlN#e!e>!C;xz@d)yZqIaA!um4!peVnp!t&(8nxdR zX%{a5k5~Ysb6;4Kwd3(m+KEDH518{GZ9esA>a4vKyKM+i@JPocsGZO znSZTe5gCq28-v-#n9k@VqkuPO$tUHai#?=8Ps@@O8h`X4GcOZLJmWiRIc8Fi?gHMwu6}|NHgTfd{6HUyV;$PbC8i<@mqzcKl8HMq%T=oXbtT#rO1HFU{TU3rh=oJQpXJrlAMM z{c*<}*L&h+dP}*+^|84mg zVY-7gU-rcL0&C1RxF^=7B;glnPpzM(N;K9qphEu(R2Rv@E6))D6jn`ngQB$}m*jY5HPx4%vMug?D%-3_hPy0}WY>Vw>Zv8$N;fnon7 zol;-$K043&3H>JFv%?YBH~F=554urZ)YQwutlTr~{iCs1uB3yW%WFhNnGSk&U4jEm zVbYbK>iDLvLoxbZG%GwoeEM70czInH@#L>JlJ42G=Y~w)qlCHpCLzS4TJ)`Sz{$hD zs0yJRD7z3G38r4Uxt8r)MP9i_p4j%bQe3S!gzD*JY?z&|wTyy@9NH*9tK|$UQ(Vqp zKDxn6o|H+e_xR)47zf;VRL^!4Ib)Ki6O1EhR!`6Be##jA{|x7k#~&X4rw=~3KNDKC zH;=NW{NLWuV&^C~Y%W*{h0d#3&mrf&XTg5i7B1G z<19NjUL6nTE{4mahoUWXCOWK7Md!c6B(-@#eEkxqcJ0m7H?#*-BLB|p$)dBT7oHl1 z;YjWlHnz7Gv^v;AudPDxMnm-4xUjv>58q=6+aO}yG}W=Ep4ybnmyWxmE{T>T2^KBQ zLU;9VlA>NJ7-p$}eSNFMy%layzCk%0#2i+sAkGpoBJ6fanU9PmcBcg+!?0K!-e`;- zyNEeEtB=+M^5RY3nhyD|!}%G?44*++ONF)@#khZ#$h)?QJTuZj_0+CnKn;92=;4l6D^8d5t4=*+14bg1SU@!DpYX#GSB+-9eH1S&&p|T;6mHR28@YD46 zdCu#-ly$zIdU&>7`e&ULI`miqm96{Om34Em{ukvrs*)}@elD)|PQ-zy&$Q0Iy~pp| z9D;Z5#jL>36I(u5Li2l5(S7vk%(~fptxn2k$KW5!C@+w}8LCCu?%ZHZ9Yb*eS2VZD^)kgw&9E-&hZ>7*!F+52Go5F^Q$ zehcx8_>%|626CSSXKd>bfH(HhBJv>ZBJ#t~e^D^&`K2?CWy`l`h-_BY!~Ic-2u+g} z+D;D8m`p4S+S7Hmn2ofnX$aG<6}zPVnEJ>bwZ+-&596pjFG2b5G7(m0hp2wu*s?*f zs8fg^{7RGC^_DZ~^Il>e3wP^cQGCP~U*@lcwf{@WX#Y`s>n3}?D0LIn&zYzXO+`tD zjyQD94@MvD;5YCjt5@>GYY%s{CEOFQ3*z8UIb4I)^CgBg)oASd3DXx&!9L>2geFJh zn)N23b=RDBAnB<4HkVBo-OP-TB8yHQSbH-BbDw@=9e!D&E-wU)a$CgQ`PP_NvjlT*oRSQymFFi<8uPT9XGKBN z9MbVEp;@r8s25f^X_b$0&O2C1kq>(HwndB6eep=O1u>S*P|yD)8L9CKpR_(Adty(V zo??mI!eHpS1d6;2XRLUcidhz_%qX>zpG6Ne`xT1SujW7oOHerPx70|f3Kc^}YU`KL zTyK*HG-g<$cEBv5Pg<=B9!s(4@;sVfXGqhcY^H$FT8(&$V?QxmZ=DRPpP9R3-$4e~lwh#7K zN8kbFtz<{i{^djxQs(WKI99qsTQ?mm#Xw$oTn}A{b9g>+op7+Gd_c1t2wP*8HoiNi zG?VW=7=r7cozeQ|pCshg3qJYJv-X;AXYGIm2Ys;EVuHvZ@AJ1#@i^RL4`V~e zVb$09?KM9nQ3n^lQ;x%gFsc6Edj8mv=IXgIEG}#rmw9oOUw7#uCT#JB$vsdZr}PQ4;OZ(|(`+^q?xC{Gw%tQ3ZEdN`Gmh|576 zv<_dd=Qn2#MV8B1x?d10Lpc)#yH?FXWU~Z4dF0;tujc=mG80E%%0bBNlL_xh}l{L--Z=P+(LI*ofAAnj%14e5vGdAM&znUbF< zw|$xyR?f6UgXumIVcUX;vL^KRT**4Cf8H#RC@cIJ5R9seTcpgv8r2ghH!5u(^XW@muje7ybh}EZPu9TR z2}>|+?=!8U*!z4gy?$FwF$=Txq&c<)3dT1TrN;$ga%VqeA8%ou=)6|z>y5$r+lAsr zSM+I)!Sd{}>|bwXUi-p`H@y5R{56NjQtHcGd_vl8ca)YuW4j#BL?sZ((7* zs4Iy=u(>yew;D={$1X%h)&hL?qm15N4meI;rrCU<=sU_5y%#J%S@&S3Gq0AbPwRy4 z8E3@SC_PLlNI?G)vSQUQeFS{XfG$7H(if?b&pHh)X|>`B8|A0pmf>y(&9F2#8h_KSh{Xji=pC1h-YJhHyYxr# z8TGb&^r4O7-_%*?K>nkV#yY|?lvsMb?C`L|Nmjbu9kpgIaP_<+H2fP-cIN~7PU+3Q zsy#&QjSo1`Zwidv%;8LI#{chUAO0{$pidfho6KbjzCBQ3Zk9@l zI40<*;!t6!IJeaW(;SGQFlKwvP12LjxDo`rRbSbU8Y}c}2*&quTg3KX)+m0H0H@uj zBrnqB`SNl@-f`U-aq`Yw%5_g@ulb#h`H&va8l}5RMHizMOuyDdjJ}VO0P?K$zWM?O zjXI%ht0kh+f-tQ$K#YmE$FIyJ6dFxsCet7C@?SkrdGCmLdTA~sD=BMi+HdK$sZ}`p zVTAU(Yvw$o#DjdD=ClKzDGc|9Q|4hP9y)GjcQ;#M%Z^|;w0K^0lk-JL0dWymK4Tka z8z7+}5k_B&#IhR+JiV@f*Z%DzaeX(2|8gUJR(+-zlJA8c>n)M!SRtKp&JU(0-iUm2 ziFw`k#rV0zjyqK$dVi;!WSXCM4n81h(IBo=ae6y{c*1tdrJ6vmzige5A^lq?S(=md zFk&SOgK)Xd9zl10OM()g@}jAAeCmc*;)j7Fp7r#`5!nf1&meacMZ{uR&2E<5dps6A zAWfG=jqvKKhhwer#GDF~#?ODs=M5MN?TN80YwtW1M38@H+BtD#We{Xu*rTYI$cJ|eXn5{g4VQt`d<5$kwi9s=kNqrZrD5OVq$GdBVIuB_MU zNZRUYcUNJn%XF?n_5aSn48+E)6q}nU`^cEGKz7u#ouvEiCvn6==`LaY(gjv~{h(kn zfSn!jguk5njh~uOB4VeRU=1-s%U^ql?Q30dWA_z8-AeIbuJ$&cPL*YVj@E1aVsy z;{2F_Vx6W7X8B~{qtSVGmNcAhk7MD{TrFhQ%t9^kU=ss|Nj|I%<+Eow@tMPyiIZXO zu-@PVwd+$v)6+(b-TwholI8glISFpgv_@z`g_vYddAp=3YP8LiTA4fJ?B*2+>GFyt zmCr{S`SjJ#UKHiA^C>Gl2QP;Il6djS2$>}h8{*__nCObv)EBO<5Yo;HF4z;{i^r}~ zR_yLe`Mrr~&Uhe>EHJ@2@*LgI@2yqN&GGAZ3OZdK%FF5XFVgGx8oO5foh88qwM?{_ zn6N$fIj%3`x7;U)P(|39nW#H`RQFA$k?w@5#5@+t2~z&z{yOxaxnHF?44GOJ3ATBw0} zhZo~m(^IX_!^?Sp^6}|;m#~?Ky)b&Z1tPCE6#2uE}L+2-O(ZXo-c_fk79WY<%sVb{g5 zU)xjYyf;AAmjCK`?GSbFL6ng_xmMgC5s2tvc91E|W|x!!-=Fi4l~pE&(=0I{!wW+! zCKcTs;fUWeBJh=U;w`z9?e-!H6)UfZz5&+wu_Ya^7TuQ|945!*oh|v9s&!)eiCNHh zNMsSh*yDPVeb%Pkv=cEm2Hq29>ERejK9T=(%#_j|LX-SQ{<|ilxYPn$ zXs54Jk}oD~bw=Y|@~_>~W~P#A{%2!9oceHB)CA4KebVXCm(q^icoSNB?_f%_zvz@{jg8^=#T&HX{>V3|`1e7AIW<`4@f=z$ z9nn9`3dJ`A+iQCwaXYpoCu5KNbT-iWA^#%R1ILt)2ty?ev=}ai@9JODt(&W0K5T@x z-#Bv~LTnPXg*1D7H&e9f`9g{OHNnYi*_#5=YY|_lGrTX>ZI7S~?OcqnX=YEO4KT)+ zG7VixBlJCqUl?+Pm(J}kNxC$ShtCV)H78eypB0|iPC5pIFJ)4nF0?B<6^7j{H<)LQ z3+h$td))y)$DOVXiOKZw86Fo4tWC9t$yC;n)Vhrncya`~tU4;5ABjT9b`L!1-i7_sdch-Y>v`|3jUtWuy|Ly#?QApyJ zgoO24kL7K!HEbnio=xHN5*KsB#izLJ-y-R+&jC16WdrrEbpZdS0&;@&r0#f*%W(oBM^D8w^p9A1*Yxzug*uz(7=x5IP8~XiNcQ(%s)># z!u?Fxzn@;X)!7`b6*RY5_x~Qg5kqow*!4G$`RWr5{C@L&afZ&Q+5ZBtB|%P%{^^SP zoD}R-OJ&`P$HH&E2{8j7iAc9(-ruE=-!#uCl8db1#m9yaXFitAT>{>@*bo!$#li|wTX`(mj(rt}CGOR4|Qn-GXpU4J%bb5~rP zG^%}W(_y|oVg}M2DXgam|7U>dhnK-4`V?E;s1Btgl&C}*<$7a@J(FpRLp9m#d=#+p zlP2mXmWc!Oeq6mNtI>ewHWDvXt&eMG5x35>!WEMk%wr|usF@`e+o$4n;$6w4A9DOy zCrjS?W1SeMH5;1Olkp&WzK}))Q2voMWcQq4~y{jcWhj-QRtQ_1ABYnEOb zpp6wBX29-7sW6an!aDU{M13{%#oxEoECI?b?Xbm$y^QEio`BS>tv6eeof+1<|4r zgCagif;ZG)!Hj39DeQFAxO^f#Oe+GZKa;W9*RWY_Db=|GZiT7R!zaIWtWR z`4^9!Ex)8ECcMOoy<@eFm7RI=!T`)5&SUP{Iih=CKYUCgz9iNBWBRrjWE6}=-MlYq z=!7HRJO^KMnwYGf0qrOkW2w_6(WBHBO*|LzJ6a{DbtmxmM?%{5mcP4rqoEg_&7{NG zqT_}g{r#}h{I<9@I1H`NQla_hu;l)bAS4%NV!-d=dH@SOtAVHpaEjYFudU)Z3e~hm@bPN3IlC8MOi*(=H0P4GCE2 z?uRwUof%uKf(0A@tMmDT9MJ8MJ3>wuN(-o8a8X@^@4>g(lC@f>|4Zy;ol5aHz<~H< zbe=w2uQiCY3i-cRVzG28zYVH;nv|29nk%?jFxG6g!{&}pSQ7QCzK_TYb9kr7nrjce z8*V5j9f(usI>LzJTGFC-%V6I+jD~Zd9WKAA6=&zn zCe~3h97ifhg)iw8c6pM{UXM@f=R!;^TkIbZEtF|z+jhefx&2&Oq5ni&T&s?C2DBfH zvP2iJ=yopg(La=(^ky04-=Aa-pXQ)zbqvm)s1^_D^(WEm_w6}M5_2`2zv}J8=gVY> zU9oPsxWf+nYE^`iM-cWjh2y2z&aUhIpLcDEYQ+lj+L)1UA{;h7R!BD=v&Rw7Wsoy@ z!v2u%p|@fzu1!2HHYn@EY-J8KP5(&xI!(d)e?%+diOBwUt_P4~^Ubb-eAs(EBv^R5I zaBxdfyMLS6tN~-h$0&CO=Ar>(}e^2_9|Yu7d&k?Ty1udq;8oup|22Cgx$?I+kxA#s9b; z;aw-Fh=#gFNG*27EM0wxdyj>9yEG8lAANb~a!2glM7p2t;liPnv~?;0aFg+8K{hpf z=HcJ`?dcPu(48_V3gfUKzo+;}_r#{|%aK%kh7HO~vg zM`Vz}vABmc|^X3*>j?JtzYOS78c<5IuH4vW0P*)ScQ zjC1SXN?o$G@n^<#RPHDh^C=5&HTfDwByTIyHul6T(m4z~-o`p@vjL+W*`r;X#d`8j zts$T9q(`SDuTPBR$1tDQ$e$46y#~$7NUwg#Q1~kV`?WI>Kzp~DWBm{wVu9qgd*V}b zIMPD{Fu8xEWdG?IpL(h!R_#^asEC1HNd7DnU9+wS#Va&zc-?v6k{X?v#7eD95d zP_uUJjYEbv?j$=y)&CqjqdL(YnaK>+cD>it>WTcwY-><6@eRUnNRm%-OHx){c(IGLuCIXV& zTkJ}$1WU?Y+k1Q2B12Ru#JA6Iw4$w%_K~tMZmICz=hAuRup<6Y=B9MewqT6cwQ1Mh zB;Ro-W}scWe`?Dk2fV!Kit7XWu+IsPcw)yE9@%(Fc%*?=fJKbt?xu%@=*_V zW-s4N#CT%7>O@tE;a@0s(Ip(20|pA8R9krJ5a-t9IIA+#z~rE4^p39(eIR5R6_d)DAfQ> zU}7xn)U(8~4+;F{!V^6ALAqqmWgj@6H^rEK`^1!c-iXs8?pt{`=Jl+G-*bP=4_>|{ z`i9xy#!!D;nkgp+C3`?-dI~1)Ol7q{$Kml)Bcv>SB<}Rpg~6B(J_uz#qlX^%ssAi0ei%S!Z!GEX9f^BS zJTAFh3{J^o=C<-s4WOLR`*ouG^=O#Arz{3l1IezMh0xz0&|dQmNh4YI-4*3W!^FV- zwwM(hfbU%cSbWqYZZhjPpa1rRD0^;zRT;6^>eN#VJ!gbNk10FP`V>1cCz7XZDB#yi z`UvX|!T3x6|MBtJZ0JsHR77b&u49?dUEqX|ZElcvQY_Mq_C`~949Xk3aiu->q!*xU zrn)jo#z#56fvQ)j&TrTxT^r z+?Rw?rf;Q^{`1jq!89mll!|fbZsb9?MJM}hMT6#fVQLHQfUDbBMw>O(uJuFIs(f)% z-T{yH#pAKkX-VJhBRQ^tPoIBWu=(?_ZFel9l#IlRKyA#Ol!EKbJXZyAV~F;*$tJwT*&A80Civ((QykFtg~4uT-0HZ7y(3Lrzv2K~>*94$r#u8- zt;wTm`-(M_oa@TlCGv_0b?u7AM$xENmhxx3j<#U$3hTz*XoSmlkHoKgI@sAY8O&OPq6h|VR3c=Ip@XZ|_}!%nWKe7OpKSJpGD7J15K zcEk0YIx)PK_^aEkFuh1389Ie#b&A2bJwK2?q#k?IE6Px_4-<{M?C`VBA4Ajv*p$j{ zxU4IO@89ahXa!<>l5YQ`v8?#I)Qd7O^Ps)*CObZqdIPHz-1T`RI@0caRv((nsH|dR zh(oeJpO{&t_r)RZi~$liy!KKo+HuMi?-Ijs_D?51XrB!nUM<4Ap(WzeE84xQr{jW3 zx#Y;HQQYf>8Q05MC-w|j%CGG>!Pli{NME*w;LQeWEcQIbn$m;utDgtnY^e}eiRG{& zl^C#|>m-{`R-@bd*XZW1g!6qYvEfQMI!A02!?sysl1Rec3u>%!nk<5ssv&w!y>LrQ z;OnZ7@qh(mq{j;>zgSFdukD4?Jt!-gdZ2&XioQz$umX6X41ou*J7}AHPf@FjI$N~ zH1{N3WqJrcO*|K=UY?lo{)V_r-qrrJue{l1zhv&00N9ROhLfH{`MSM^ zxN) zu}o*0QIH0Hc)Z1|f}a-8ZpTL{gnUteJ$#{_@f%A+J$hP>SBIXLz%f_hK+v06>Jik2h2rv9NQj!)u6^~Dkz{nMq z!iBVI$97m_Q-2}tBuk8rwUl4}{Th4FArOTh*QJP^mcoK3PM}OkL;RldNN7uS@%v;_``ku*7%?l} z5)0CHG0UU+eei{GI|E_y<8YYfc%$c7ca}0$1v2K7(Y>llM3651Vx%u5A2v%LT?~ZD zo^;flI>{3DYGH%fe|5fZvpvj~XJePgAFb)cs0@yz-pT1*QHKSjbKXrJ`G!We^`8?i zg_B;N>ipr8_E_rWkMX-lFuybv{&B1hFZ=sR=nXf*fy8LcUEm;W&e80&Z51>%H?YVJ z3i$He6={BTVroPP%9M*D7;-nnb3z< zvyhbe=zMAps&ns)eOH{(o6afKsftBS#8(`k9FCluoq6#y+RYKiMrK-tWYb!CJ|M)5 zFFj7X*S^bmg4YFpvp7fUUrQWi51P3wKF$s}hQNgw-3j|E#GVN)a60`SI#qqx;}6wH zU)_kzcayM*en<9xVQ`h*C^pa?U4>XQ+Vd&zwLlgV?$5@1>w3{^hdMf#EQQ_fCTa07 z9Smrgf->t;;aTVoe+z328o8~g_}~I`n-`9vD;;>iWXg{qSW865&BEr3FNPCaK3H8y zvJ~X`^E%#M+u#1wMNA!K`W&zlq54*^p0Wm?QuEnD^$@&^wQTpp4k6!32zezhv3VySCVie++`*maz=? zWS%qYAtqSfOg@_ZmqgQGcVw!r#-*q>$@RMv_|{ZE9?>;ZbpA+ex;rNAx|)mQ$nOyB zh^B+*n4@|yN=rg8vi}2NZPyN|DHB}qQTh;b7w7u``J`h*?$~f zD9}B}pjLzh&OznRL@b*kFFpU`5$35~#tZ$!{FE)_1(#W(@lKQ&e8&au)Wfy@a%S__ zPr}8jnW&svC5kp%;>XOy_Ilniavr8OM7G!S6=viEDoTV~x1kcv#Zf#{$${Ja$PlLT zi5S#55xcG(Vz;&e)ehmhR1en_DvO( zo>pnE;dNnlSR3Ng-m6a!4}p``GKBOy&BmxmaM*-cy}urau45fZkDZOCeSfsRrI};P z%v{WxKaa0)r1?#oA#4@i6y-PhLv6Jqer#)GnWQ0XAgxue+uOv39^|o`?%&?Ge|4D3 zLx1RU>uz5~zy>1>c8J1^o(`hHjqZ}`mLvGtN@im;nz*^Ha4@M8;r<~oRIxyCM~Ot& zBOb{wgE04E5Fh16%w#=hs7bvZ%zp6*YKue9A?qc1zp4?~u>sGlC*hikC2Z0{ zamIXuxbdL@ahkH)J;ilqW#5Zl2YL~CI-JA((~FgTGFGX26wA!&~^Gh z?r_=`jeEUOui-EDmph?3HWtHrOlId=AMs;fJL9snK=_@~LqESHV?=n;jl8_#U4FV z#FSz!jGX#VD65;GL?s$Gyuzf;wDTp->luPPa{Q_>ckH z+hr>5FB*$ShE?LqBNt>Hac)a)Ec2KTtQ>jK{ImOJdP5l3lBlz75hpkLLDce%}M$LC2n|4kKUwUy%ED_ex5 z5u@_t!#PxLPGTexCz{Ta?A{aEN4wS2$0eZq?4KTt{b9 z*lkzrVIG!)L{>6kW48}C9*v4pgUi#&XxL;MZ3&FiH*XjWg;n2u3LpE2{V z2DtMs33swDh=J#`cw>m*_d}*g-a1T!rqzEn-|vP8()}&L;-pfqTpxUW>V-G=FEiDR z0qE8<8V6pLiIt>l?KvS5(`NVAnzqjlD|#oxJZ%_{Zqq}q{!)|_uM&B~D9bW@1ssbk z+1q;oSet8%|MTb7R)->xSOoj8^kj)wzVZvLU%0Bn3(-}^0j23a?Yf$4bA&^o(Ws+<*yug&zF%s9=iza;%nrY}ZN{)NI6swcx& zqeEI}$zfAV_V(|2nlbC(p0d_K3h_7DFa(|CT!AcjXsMd*v zQ$i8vWe!tWiKMSCu{8EO!ozHV7-Q#*tDOU|ZhsKF;ok$_?@{J>BRP4@X+9H6b^f4? z_*d)x)=Z3C-;ZioEq`BZr8?hqkaly_ zw_B~E@Ag0#WZk>)qP~_`cp(_g%ZkLG9MUArN=M4q3Q3cyJlFVT#B2Vp6)F$tnI}Km zrqvKG+ZI8Np5uVjb4-us-;MX|;H`XD9Q&PwIWkH3WSlRFeqW7drsFjMRE>T#W=L3y|NQupn8rTx2vZ(W4 z?q6$%6T050*z7N4<0$JgCI%}XtFY%=YWe1{&M3_(5XXn;Q||FneAVtm*)e+9W4at} zVHa2uF=tkOFu<_kGlduV(Q;ndBW?d`_PB(YR8D@7+3Iz1mw5;VYNTWIyk|_W*aUfM z(U3oKQB1t+jOm?n5LM7BdDwkCx47WJU9^`86S`lH=SJ;X8uMxXnD1_ne4}$LRo4@y zTikK;(oGR>)JR^g&-mLgmU+qeQg$9?A`BSF7q2vd>GvqucF7YKIi!71Ovg7>9rpRP zEaVFrKH5GO*ItC88_f|e9Q-LMSpAZ>cBpJ;&hI5JkzAZ35){UYeUuxc{B$Aqb=bp> zTvH^Tu@-_vwWv%n!mgA^e3uE8?ifxQv)pX-32kN<4Cdp_wRBj&J}XQ;<8i&k31cqV zvdPn@VyxbOb-vGFXDo|xM7NN`(iOr9aX!>nttw&HUU6hBC3Zk{h1l@Z1jfYl3-n#D zHHtDWzuzF1{^*JPgG&k@nSX-&{gz5Ql9#>ykOkiSs%ImEJTaU+nbny)#ln~rOe5`U zRLCSY?^P$rMfJpv8&AdJu9U4wT7)<2-9-s$q+<=1Yzo?eRt;P%a*E&KK<8%Mee;&(7%SoAAj%vaO*Mz~ zl~I2pQ1o-KnDo;UZxa$QR=0rN9Y}fgq&FClT_u7`$>TYF32askk@T03;NFgw?R8#W z&lC6jD1&^9vY1Zaq06d7JaRnDRG(=Br%d4QR4yb}eW6E8yj8mEr83vtQMN7}=SrV3 z<6C-Y)u3$9(`SVnaSw+7T7@x3JF}~orom+0FtD+e;_zzH$qI9N-ioAEXNbQT><#y} zD=hqs6Xw&s*y&V>xZpv0q=^xzjqazl zY_Yatf9(D7t=<3!-1mxqwC|JmCq7bH57z1AH@;fwOZ$8#nD+H@ncf&}BPX`S+M=X$ z7)*VlSkv=~_{jdN^NQUW1Ar_U0WOg(S5i6KggmWuf^X;wpQ zwNctutY*PvEdQ>ApQMfSd}jy!5>MRzoG-PX>xTTYSj?z7z%!X0q`S~Dz`|~Ciku2*FTw4x^Eq+M4!Gb+GO=QgZWRN1 z(^+$cvJTV6voD%TymNvUzuWpwoHcYHK2kFFpY;(DGy`!A%);`WYgkGC7<|4(%=$mI z!tsA3on=^6TNi~*3=FUn2?a$;#X#k(J?QT4?i3I)5Tq1TzyuY$y9+tX!~!HGZ3PU( zz^-rJ^ZmL%?tOf`u=mywv^+lKWXo)62{k8@9x#DqlXn&5Qb~vD!NerM1>_P7&LCg7&P;_h% z@2e4x?b9r{@$PI^-#Gwrt7f3w zwV9s?)4>5X%Dd&Xi`PCd#5z6|ljc_NdAIy9hxYpau?{Y2F30O^;(Lqw3Oa?kxC}w_x?k35~_RxLqE^cTv8k8{L?yoq`xrZYz}&AmAU+(6$OAKT^ytakyw!%xw^Iu1{bBn^8;~-J?n&uk+M+!aeyn&OU9{7?$9*q&DNfJDV*3+ zE%fN~f@jD3q30~>ciExL*Xt3xr8*Y(wf3@exsx&U$vmv_ddLI5n&I56SafxUi{IXJ zg~rfqbXv8uZ?gx%IG}Pw_!8kuGody1 zpGx2ZS9jn}V>{aCy&;dZDh}M4CYkM<{Oqxr`sS)m4B^V79I&u#34Wb9!pf(Jkl7rA zQ2Kv2RhhqCU z*Q=I)y6Oi%EBbb}i^acae)wQPxtEjI*sXuW8ebZSIZ8LV6Xkcdyp6_wbs61yXI~6n zp8=!0aza~^30~42{6a$>U++S5r9}=x(9A@0|Q)vW$5 z)R=#kocWPQTrp-4b+Dz66jRBdjcF;A%2Pc$cym_iq@BS)K{L z1Z2VS{tM8m-pZW1dm_M*_yPe%{M58$+$7I!dhQI?bx}o_y?Cx*-u{~3^t7NJss-pZ z+nJxZPQ6!KhzFv(p7k87NIP>k=T8qB{2jTHbas+EWT!=YNspq{6;iK%ROxu)816qzwM9nrvvxh*`fNUA#ZP z92(SbKA1&fcD4oP%*|n&Yz-k}Ks_v_75p=KY9g4M#51p(=YeMGcaUlP$4+$7j^a}a zhU}~4C(cv;$zvI=RNNKyt5OthzOxjTeA~noX3ix&ZwYa3!Qb_W!}b;At)F(D%`}X{ zz2|O{e%L0L4kS6W!}s?9CcUN}jtx(Vhp3D%LmW_dmpofE=T98$0yZQCuHkc7(Trvx zkM7qIHHUb{Q`!}OS&WUn+r>T}#Kr146_)B1{GOK|W_4NP&&Q&YcfaT^@;3+~xnFEc zlnaXJoBqvt3x7kt7#W&}Vim-qJwX$MaX;n@*I%6AIZehmaC0fvKDFWfMJ`zLGoLau zTbYzCb)jD|N8FDJenWX7b>8`*`{@NDuVW2p7*&h?2ET=#EzUTnN*28JO&O#z#J6>WH)oQDaNpWN!dD;?!0j~>3?!7@mZ;uX=w+ez`6ZAi?4h{uK_~{_bAqepC3b&4%}vo>5Rbmghf|I(hP+1GFCP@0 zIpl@Yxrs1-G*DPV=X@n`4*xsz2cEFSrNVUNCm1kCyc1@_LZ>PshE4e zARmP8|IhpmRabnKPJzzl40ei5g5xu5*qAr+p~NJszp@yACXE-@9&SQiLNUIT92VLq z`C;ECE6JH(FeCtddQjJ}ybn8fOBMMOr(rhrx9UH&L*>L!1mBdU=aY7ApOc~Bb(~2L zXShSZr=iMqyzcZ|1Z-IhvoRw?)4LW3g}<$Zd!N&ZfgeEG3LC7hBEL;tAg+-gPu-cm zS;VastC&MZwTka{w1do?5Zqb5QamPx*oyI)7_#*R8x>`O;uA{{R(OFAqH}kiUM>Re z_h4;XwD3lAB=Ngy_$JEV7j3n|iJ@Y##^vP*-mnNfqmI4ybiwxtKJc1xmA{D(!~2L- z?2;a*`&Ei~a(y$bwla?b=cqL&3ea?@A$6~E~xI~p5aLt zM}FT-V;RJTc_O?<5H93Z0at(ZBl@Z1r zA}-KAWAT(~6ZmY*#PMD)n0e0#>bf<9iGM23nG%cYzwSVlJJZTk$L6DxC1-wSvJ0-k zM>6LNCw%aF@FF}9IK+0}6(IZ34`WeICswbk`Cl+Ug1UE4sLnxh2Gh z$OCNY%vCZF-)C9}qmO|~V4S!*0 zjb0zKQF(0x>pM0A*C&|a(9{aPaBU3S$Uh+$5g}SC+knM=s$qEcr?6AT4TjID`*uYL z-^)BOQ8fN{Mn)zN8Q(P`sib+qqbHiUIcy}@r#Ro4j+45in#2Dd4 z?-@MFE({B>j<-Tpv4gmzwA?a7a{^CEML^TkYMcj^@_<=yTk zU{ql;vc4V>$!L0m2QLKQH&DnOVgv0?>cKs|f%hcuRrRVI+_$!7QO5>C?v*Z{{A}Sv z)T43uss$eLAEMEF+Jqph8o}wyOYS_IygGfIak94}pJuTHu_`NIkaLQy`!N~rYpF-D zw2o^unnU;+4Zr>2Vn52?{T{FuHZMC_+fE%clrO>`m!o_<@yeWtt83L^%nJ5uqTgJ3 zv{Oz~x6=cm*GcyueN>#V#+x{?!T5db7P~<`JF*o{h|nSppT5rMR@h-97Pmc4fy(_wuvq+%&H77w z)%iYX`gE0Rh@DUu8IA;>LAp|hO)(^D3C2&!KEmdcl5-3q>E&^oKo6<{rxz;NfBFO>p#JL!PVSY=a7l zZq{})e+N$ z6p_9#F5xS;TkQ**sx(|%AI|G#T=CH+3oR>hS@=vP^qWdKt07JNgmVmLSz4gbNF=(^ zza8_YS7X4Chr<1lzOXWOg||&CH~!-WHGN+gzY1d0-ZlzTUcVRAt{mgH?X3~wv_PWg z#7}aA@1HE}nqABWxy?nw*F-#BQ_WpVqS5=FIW(GbSdpnQ(lWInP_L_!i8sVq&QJ+Z zF4?-=6Rq|BxHaq_^S=`YIlBA5&#U6n8~w4jdj@(>suK+oCJM{%SV(63%gV$RkxGJ& zi@-Zt7T|QO6?CcV$A$dw>p{=)) zX!s6$YFo}`HI8^E4uzsWX?Jus9^Ent*5{k}^YbQnFItSNQr-EZ5PF{Xtiy$a_t?#Dq!+z5 z!eLEqKB^`hK|83!!(kn}8sP!85I=hMtr8Dv4JKc!9mc1gXMtb*5hLw^O7A;-l?G`- z^OoW3_9LR-S6s2;d=xwn^%FdPSmDw;^1xfI=Pw(H-)5bGkRl`Iu0IG`7P?4lY2lgV zot!+G_$KFninf1j7gi6f7M=}w#mD~eM$K$zELBkAc4yn5px=T0#frjH@f0`+I>dOX z<3^V)am_OtnK}{T-IQ6&v?u?-jOQ%;<6L}RpNJc}M|u0-2#j86f(=Q=>|u}=p7)r5 zwWYP(n$DGpfut87Jthu!q$~(|SM<@uWVh?XFVqpjmn#1Hjx`P+jYVqaM%}Tgw($C# zibYG5gji$ZTfR?3vt}lbo}Yl7?$+c@eZtgf){Seh#EJR4_+IG%MErC^_c|HYxw%2G z*-i8PuXDU^vLo&#hM=g$n>xxV?>vM0g9c?XO?7457-~g*(hdA+MW$dGd|Hqx_bEAD z)d;h37ZEw+knoeZR_9k*z(65^FJ*yn9pnMIo8Ih9%~Tw|p^3-qYkAyUC+MyT#gwig z{I)YOK|drTG3W$yFcRS49)%IxYq^n)8?uA*p#4f+WUxC7#+O+~7 z6{tHG$|sW^Qf@??uH&oOq3ud|szlw8+Zu_#v;fD6+bb_-A|nzSu~F-aEGUj52l_AV%JwwpHclg;nnSlZ`d)u@Yh4YejO%RS zf_XStlnBqtYQFYDG-f%PK`t_f{e5eM37ymNWpM>J%%r=ZKD~!Ml}o-_d%{`P4^O-P zFtef5Rr_{1T>4b;NbfhrM1Eceam!BXvUEEDI8?vuwk+3y&ae)*I{FU2r*{ zI>fgJ^6?iPvGWLd4pb>Z=)EpF9aWN}G6h^8e0rNkY)OZhRSehpsK%h#;j0?16nK zaz7a0jN%MphEq1m%K=vX*0I$Q#JyDV!H;=9#oJy}W`yoV^$t~Rg%74WD`UuSx1MJe*y7OTRP?U~8=Or)fAjgcY|z5{ z&<-kx{G4&wzeOttvYIq@+@rjYCTX;^=lhRW*?;sjY|fB_ z-KSbUQG@PxFB}kId{mtLhqTzLaBNn+&!%e`z#`iLZ*CC_%YiiV1<{yWutC@0fi0fQ zN=1)eO2XBw`LMd1DA91*+^Em%i9LFqe#Mr#1Y*Z*@;Q0!;`1*A;M_{Z3{v=T2p8&9Q{>kp|wIvJ%@Kr6A&gqIlu> zX7p*j0L2Z5g!|;_JNeHNZyOT%jh>X}0Nn@aoOjAngDf;5eX^E+4sgKM&Omfdl;szS zJw zcgi`VA~yt6R}a*UqPc$Wp)9=6RuZJ>K2f=I5d@E1enI37UH^5^H}Ykh%ww?H-;}&l zhq#xJfR!@jFI+i*=?rNWdaSGz0$XqLy}s@cts)+D>KJY-cE;HGp@=t)W2N_~o8Y)U zhW2dW>b*>nBb$gkk+Im5?#oYG)8L`^lwI5uM*brM2?Jr?8_H#Tu)z*(dv@)S2L8q= zLqDgM?+$Rqn{*FM>ns#sy5^0#SFu=Kx}VMLqmSV?ec(Q;hG&S(v8EzPGTZlENo;eP z{idDP5kkJx4rGJ@#y@K-ITITRqmd30U%gXbZ#YmcV=?s{)&FrNt5kdBZkk-esT1CnIqeniLT6S zhhNwO_&=`|u21&Dibce@*$~0!M$&F_8^-9Gkv7|eSo!)6k3j6b^Kp4t+aEV?J^(I6-En6EF~EXm`|7Ytzj zHwClpO!zDE#0lEg7@&56t?EVRyb1N1kcP9W-$H232*XdUJkgoO_2^vRgkei3;!g&7 zY3hQI;<$+)Yw|%`ek$%&&1b!{29w`g3+vW4@v8h3;oY`_!m5?y#l^&hlU}ca_ul1v zPH6z{xLBaPsHi0CE^*0DxTDeH6SJlJW(EEHQ*{gZ!Gahl5r?Yz(>2lQ)e3@GW3KSs z`ve~lXa>C-i}3WBHNPN5v$s(m?w{Jqg6Z%0!`J}nXYTQLGLfjgYA-qSo5R|$-lRp+ zCpd4jD|9b2xp&5May;!t;cSh03jVyZ_ zz3dNL>K$17F%cFkmPlrMPjwGy^ofGCa(^L|^CXjfUY z`%=@;JVB1UQ?)#?$P0yS_IPsSh*F*!BJz8h)M@cDe-Ma#Vp4~KyYXTVhU^c)hv3xw$kiCsA-~wv=?p8m|g~ zSR@u*~IJ@7{RjD7>cxC+c?1qR*wTEXMX392m}wy!u_Z=wm8=u z#^H;w#E^O!xCi*zT(lJQV!?bmtobk$f2rZ}Zv!w=+8jm~OT^9JLhzC1^^W(P3FWkt zkD^|R@i%z*bISIfAn#7g0Nsz~68e#Mxa)*y450n=xq`lI#%ev1?8mUY>r!){tk`*4BV{Rm=HfE6O2NTVr9H z9h04{iL4!yuwK8GuX1)n#Ru{=(wx6P(huE+#ZfobK{jlQKDsw}Bj$HCS9USSHI+q3 zc7LUNkM0`(5_2$X_B=tRDFy|RCYad$eaX^~5fDuwU6tks%}u0*y4Yj-hHc!gcQD+~ z6YttWo-J&hDtKnk5%z1pUn>8g11^IdG-|$ILCw_ZKZX-XwEDZx1+_2u;N>pIo zh-iKl3$~UD$M<+6HP9Z}UXk1h^o@G#iOn|yS>ZluxV{;V&B`s@t;G-Z#E=g(7|wTX z^a1a;3Qr8EBgPa+J+uV-p!Z>qY)K+K&vWO9&nx?#BHtIQ5Y4DCUq4ir#l$y-zs5XLKELU*9?~T7vi}?H}3t}1V`xp_;&tz z=JPZh$4%*e+E1Hrejg7_MtPImP0V_$7uJzxvHO{C@g>p&8yup@S5wZG(+*g;l@N9k$)ip{iL+pt&1EOHFt-tVMvMoNjM@we=UsLJKlh43cDHC@4!C*`i z&BN-M`vSf#)LoOee`@Vyth4dbSm(~W68+yT~7I;lkBeU zR9yZy3*(w=`Ot9Elg>m#?n0FK%9KEqXy#y?>U-9f>5GL5>u}^t8Q;7q6Am=XF5BqC z{BBKyT-!MGiLT|1+1_|T-?pmoBVt$LN4OmQ-{L4p$?SOkA>6S zO}fkS?O_?80_oq1Li2e;I{#AeuQ-SIsH2Yb9n|CX>p9yymbxz6&GBo?E^aD~caVwc)@Nj>7Awgjn)s`t!zAzN-zBODemO6XMN7Wf17K_b-@I%!FgU6OI z#o0d4F!h1a;TwE+sWbjb5$E~s0NrmL;kY><6P1FZFfYOaZIrnV+n39io%MkEzO~Rf z?ZJ+8%ZC1-0CeFR|1dfRsx+^jE$+*7dpr@U9jb&Ea<_TL4mXTHKVIe zr==Cg+GM99B2W))ZT0-!TT}Eo8jpflBXJvf*S`%}jd9VPEOAT({t#zhXUuY*5)y{2 zcq@tDKKQ*RCQh7$%~7@d?0$FnUL?L^>=yC$AV1u3i$&4W1I&hI_OZ0@a6eMbjptfo z{jo)`PHELO_~we?PgmpLHeEr-JrccX|LyYRbxGWGnps}kNcv>w6C2D@&kmnlxAEN< zQ zc`vs`c%W@bz&|~aVAe$cxQf{?N`-Xl6I^x27U!ZO__C{k_*ESUrH4`M7G;snZW|82 zh!#HKBHgVo#X>ejnja*lQ{mOMsJK*x z4VawM0ILxb@zv59?wNrojo-vGmFYQ|y7>Rxo6R!l)c*gO|FN9170XhH+wf6*;*AN$ z^i;+swQ`=(6-aC+^7+LTm1GltGKl!gf0I5kO+Qa`izi;t$}QZ#ARfJZR$$hd8>05M z@xtrq8G_27!@RW34BC$pkh#Z-_v&GfTA!5=eO=Ec9}goB8c1`w%Wn-JcFG+a^zaB2 zb?#_`Zg?X~ReE92D|cM`>W&Q#L7YSz*rf%bV9rFgv2!p!Pqd6!If3q*JFYCh5d%qs!O=s|HpTc1A-U?TL=CZ%!lX+e2g}KVU#a(nayyqVR zy`np;rO5_Pj**yYdWpZ(azOdo6v!q#5ydO23sq&_LQ?ih{w^yVZQJyaHmg!xT(lV9 zE_=ZJ-gS2MEP3p=J7crxHgA<$0Z-W#=qfoa%6aMuS;}At>ivn^VT&!4A$=`g$IoZK z!W&s>y@=c@Hf5R&%>C!W;(jw1(|s*B)Ev5B|A+j#!xuVZjq#N5Z6X|JMukt@9n5uC5C$li zLAQJ-Uv)AJDs$X1O>QVVnk_|sgx;9(^)cU@;)D#!*PrO}U~nB}^sLr0(_@qA zTVoE~KGTwZ_)`~A?_7|K>X zQ6~nJI;JYsaup3H98>Vetm`toCLj`jr)J`8^JO+Mn4SykFqHb#@Fmn?ntq>puDfZ9 zPS0r&{NqmvUvk^IZ$J?B7Mh|`LzNGr?^kXzar`wmv1_izup4CrbG1tTakLY97E^Ca zbC&qxl~%mh>7l2V;3F*GZGjxKg($pqp1ZH1x#c}E6E5{&k3D95&&k552+r#kk`nc`FSo2I-a`3qX!cD%_8a6E1d| z!-ulcrp0S{OsYQ)^jnAOOh5MBEgOvT)e1V-_|#F0;a5&GZI3~0&ZkF$TvvrqzxEdI zGmG+rwXX0g8%6xI|NK0`c=~P6WKMtDK`9VB z!?~5Y-SvUu7F%oz+r}>?gyHzF5O{1*VE-;m6=WJ`3gh)&^ZXime=ml^wZ@Sf&!WBg z%w+goSjhrZl(Ca$i<|+Cym?0w0v=nS{+^zwr+yP!K8vx-q*UmBfV$Tg+v3B!2;OSe z0kg8Vh;I49V#)8la`bR?y0!2d)E_r^d@R^PX`Z{f9;eQC*HalkQ`n)VhbxqKwM~A= zzXT>=QIILdj9J5`a=IVw(u7NWIe#?HAK|y`k(#Vr(m&Z3@k4y@QR5%m{yqx(rIz8F zV-?pgmlNvcnb6w0mbx2^&^tOApA>1f*U!M!5;rWrdxMR04aebDOSlx=<1Nu0cpmr& zB^CWx-r)w!w5&(=NhR36al{7dKi>Og1HTmKj*9b%C{&omG%m})g7P*)_croRX+}tD zPDZyLAH);AOtD3O65b3c=T#Sju%?MPjHKItz7|4WUspu+_{2_9AB2k!z4I>%`12_X z;I2dcAVaQ+vOZA8YL&K-UU-C$8Dfo5I>b)zXUBU|9@>-oCWgJ<%y!%k!-^9E!jkUt zDrbXJ%L7Hh;SG3Nb{8$vz6w)mw*Py8@@_{1c?6@|2G~U6*bP1C z&8`wxpNz%qIC~UX6|=gZK}e@OOwQ%ooLZ}p`YIWvmrjUO$M^ttk+2yeEl8iSLv9_- zEO%)m&wR#wl9&_6wy zc5r8S#DFZEr;d>C**@%B@O0YOk3%fIo52yZJCe7TFmRS#2*fDE0Q7iO%GQ?|Qpbob z+CEhB`?HAU<(Z1*s=IXur5mA$o|B}s9KK*!Au?PgCc9YcZlR840)G%y#El(r9 ziuAz%6x7IaZ~FIp&67}Y<`@gJ(?h>!p}0M+hAZ#!fz|Xp^xmW?k}6v${Oo5caQk#_ z>K=rE0VYr_n!=@sLHc=*D|Q(du#EL|H-BsZj{^_*H{zh)U+0Ug-C1IpTVYVnO2dbk z7wo2kB@)evNt=D1uj%&+li$edbruuPr+fzHCk~O!^D`cY-~!!6=gj5e9WR2RyVnUj zG)mal0bcO#?~c0Yt9+&s<)mYmBJt>0T^*Wh)=x~uQIqk)fnSz*IAkG|SLX6+>mc;H zybc>#0K2v`3Jd)7P^z$>&uEH7-C8SL+bP9Hkyl(twM}h9#dxpLylH|5 zqJx8Bm>bXBYo|hgC3T2W-)`nwGyM4(3&mhVu^Tb3!fMt+ebE=DA0C17jRN}qUdG?G zk@xb7C61Wcv%(KrSbkecqT47?H(K2{7i`;DD9-N{gwFC<@b-hOL*5W7&uA8sujWTq z5|fy+uBH>)biY4wg73?fsDO^3cae5p33`%w-uGNIlBe3hN@!(UW)fS>k7k=E+qiU8 z2ZqmjgQC8Bn600huy^+V&vsdn9d6S+_t4*of7tARv&7(b%VI;(l(egKY}a8bzt1QH~6RUg^hF`2+fVdBxk#_ zdoXf}QZX}X1iwY!kjApr=so=w6Upo2`*xbAS3TsB9i*90GDXbVHLQ?!CIK%sBxk!4 z`ED9sl17lATrwuu523{MkTd`<@8d1TI2}0;NCgj=Y z@=q$pNWZoWgVc@riozHa{n3Zftdnfnvsgrv{`-B+1Kz`SF|M5s#`n872hC``*7|Ls?v)=vjOttW54= z%gV39mv8PU`0aw?$^f3b%bB<_ewdo8$j-INV6vwot^_pknNikAD^JAopWS)Rb~nh< ze*evu8_e`}1a3SPB&@SJ=jok2O+5?wxokG|WEJgj#k-ZB#T9LC2%Hdv3*T?Erc8UN z_l(3q&C5Jn+7pF+)3L3tRn&8shLBnADWnWu$%kx+#D*;3UUj87%Ono-iL1WvLovH- z8;iTtBPRaxfJf+dV1m>e%<5ENasjlz-Vlhf-TMd!7TQ6hIvjeUbzJSD3smA#C0W|M zeX`g?p2ePhTlmi3iRc(&3K!vzXv~r}p=-jfW7qAr{C9j(mEm3&Ymi2btv3|DSTrtUK< znrZD=j@}GJw2y%S>8o$aPkTw<7D-u0#k(DY(Q|}9)JEQBKQ0=f^0_tUuOn@W?kfsm zF?f)=S@-M!E0w?~J@WS*G|% z3cAj{aPaLT{%^H2>_UBU$kUTsCpe+DZ#1^wU(QM|OhNTgQ#?CX&y$sm5I<%KJs?o2KnOu$%9EU?_G+NHbxlj*nGUa+m zpT9Xd6xr5JC{5qQ%B@UrY_&$Y=$qM|oq+_!AENN_+VD9hi|)!b-!n3Ylzc4pkQs{0NN=AyHXCnxyk}h{5tzQ1Vb8W@eAUk=Tq1vz-Es$3 zVl)jsJ}Ke_ac}&udLV%EGgpfW#bXTv(dHD5D)9m4ci9l5yLq6`rz*ZA#s(GiyXdaf zrfcWx0_R86V|ZCd82Bn0Kc)0=&;3ow>QOQ9=x>e0j#un!IKAsM`>jsf#w*e~pnkX= zSu1z5ZoSk6%OY*b44*y04kzw~!ZzBG_q^+epwvuAt#Rw`ir`PycA(d}cG@d-vCVx4VYMOcQ+BrS!B&W!IljwvIdr${`PV7R|rYWHhkpR5|}x>xaY1G_R6AUl$$+ zhqx##y4hD4vEB{4h?AHqBjyV?M38=vhNva=qW9w!grf0G(7Bq++vSbH+m>LBfe}}p z8i%^026(&a6uX?b0H222Vs6v}zWZ}LJjtK*eeN33aQg<#ZLh&-6Ga%&dAy~~hkQaC zxclG$T;|KDQ)V91@Et-uRO$#8ns`GSaW-}=LA&{T@nT}cc_b(ya7P*cPJL3}PE#kx z>!Ok&yTjme*cpQBC)UvAi8T?fxae5OU!0D{N1erZakD9VqwwDs=Pk zz#z&{l|~0}#bQs=8-t;>TA9f`Zx+t(?-H&L+{ag6uts#iLKtlC&d1BU;nTNOsJFPz z?v9GW`E`P14_h-Z5{+RNnD;rCDLWFU@t!MQC3_Wz(u}F{C=d@r?=WT@Li?svxE;99 zx7!d;yH$%^IlltTPB20d_^3j0Ay39`ajlL%Mf+wHqRiI5V545*uiFP zD7K`Ai{E?sAYfrSrrN$@rMpODc)kqdx}W74KbN5zNJ|dRlkyvsq7;|3VXXf3F;Zkgc*0GhmgLt;C=hBhwt}3|nHAP7OW!RFR!oTHdzU6W>PUpf1mqMfHin->ZV8H?ZJr6n4<>_lAWOo1xkb ziCc$_bfWi>zs#MyNhRAwcy z_S=V;A8RmDy^EF6zR7i)fSKb`cz=54<3cPEdc=VZYM2IB`~RQkJ!$VSH{F?dRfXcH z1j-t;5d*RNLDpnvgrjoqICZ0n9~N7{UL_XWRG#Y^P+vg)?v*(EUPmYnk3qI9kTB~_ ziSNZ27|2=Se%&jk|HTh6D%LRY+s1F@bRc198=|}IW*uLq3u7~Mgi%2sxQn?RR=9+q z;En^oTH^zo;B@Go&Sg%mDrkLXhX}t0uC#Ck+(_GWXf_pzoSU+Zwf9`{9r>} z5(SzO{5S2{lWe@;XCKD8UuqOyoOvefU3!rJsk6hWk0JOi)tAR!cEK*vAqyUyVbeDl zz_e{4d21f>(!25SU2j0oe-5jhZH5eGbsSz$&cjLqh*L{A)%6< zPnz3%-t)tmZ61Onr=-V!#{k^SG=#^>@4s5*5sEM2B%HQqFY=iWf*P-|vE-BZGMH2RG_i zqy1*H65DY_7G=E@uz2L-MuzikK@#M83#2$=A`>SfUZgD6E{z`%WoBLdToFg`OUjmQwEuyR; z8p4j{`(hk0NLXd8d&vnTUvNJgqpCSyI$?T!9XqyB51ucA{(Nb7#GDEn1 zH&#EsQz#La3B^xeQFmkz9_7)D(r+SX2E-oe?TzuDx3K^xbv!sZ1FNNL`ItiTy&Mmb z%-(bHL2+QBAs~zAAzbomm&ruZy5_9E*@lrh3 z&*6L56VJ6L<;db%m}vt2U8HHoPTa}IPl|_Ey%z>Xj$}Ws^@0E3UU(n#m{$`+{&uAw zl#hG!KEItXDvS0Yn#nb(g;obs`Gd zK9oHlxRmE?SxTMD)V)_5L)~qfusQz!Ge3{!PdyhuiB@Ap{ox-KNUuO$hd7vp0 zSL@+J*aNP9$OW(ZdE;zimUun!Dq_mwu=QRoGa%+tZCV!QFT2lUf7{{98tT@(|5dbG zekN(jGLjiy**OIJvkh@;c!_vF?ah?QL-H%^3LAC96N~0JA!eSK&joeklm$R0W00xE37U1=FKTjZ!<#);lUA-s8 z3jDfZ>g9IH48H}Q@GEx2{4t~Weq!`pj|hhEphT81Rvnt}ba7ViAwN9D63HKcrhoxi)%3Cthn<~2O6__I@2|LE zo}4#sk1gh1HuO7J42S6KHBsbDdBM_ao}hGV4ejX314Hae_c}xVbx$nyH3>Mj^aN8h zi$i52WvgFSkgqQswV;lW!N&Ls5#@sjRH2O#RofP zQI0poyEsKQ0j-8kcHvS??pv*8bXQG|IhjQ&D7hu zQ-EcDwOB16jukzWyk87GVSJ{@0$~^ff#*99MPXRLH}`Y_LAT2XE9~= zKdj(JT?rU=#6Z#mUU7LD#x8cnXZ2J3d_xR%X1Y=?X#_iG(i?-mOVgeA3BSG81)u9Z z@ur^#pZ?bg+v`Gc=wT}BBz?tNe*xV+AMj)&W1I|5M1`M%IO@taJoSvjut~u}%I*jl zZ#0Et@eix-iosB(nZ}ER)?6I>m0~hE1 z5N-8R!;g)FaQ9IiKU)-t3y}smUUO00yp-NP6UjF+!^(#UnRCc*QV~UYq1AkScL#JOXA+menvJ>}fdvosFl5vLZccgR-}lWV ztecolDTs!52u~WH@fE6+WgP2(%WviQk1ffF*}V+8jk)aM7P?C->cORd1CPFEj;YOb zXL2(TI|vTgQb77-dK>GxDFW$7^oXUI!h56>12f&2x;Aatz@KxGJWNrd&s5}kVCG_b z*qCn>d$uGa;_5P3^Ags7-vX4U5EppGT|R9T?IFKouy9tJUY`c)T3?(4A73qD(Bnw# zI3_}j!>e-X`>{A#Y>6X_I@q>k;-Ay*@gMg@tjEFJjqe7{Lvs5Cp8E)vxlIq{1I;x*<#~Fe?$o~+-5In%L7xf_2L;e z>8>H^g|T>ej=J4NQP}=dgaenCvk|st_;YYNlAUk!-lP1mQNAj`Dn$$autL{5!yoW(mek8tTFU55>cvW$S1nT;%XEy z_2)^J??wLY0Ao}d-r!qOLs8yj2RGRqQT>f4kh^>jYNwSEyxkc}u^zZkxq*+{V+Vh_ zr|<1QlUh7F&lW7*&)zVD$iW>dbSPx3qQZ*wyY|Db^0^3{A8dDWgjG=Sr+9p#VT z2jhD*amw62u&!25uqp>=kK4+_=7b}SW@T&41(8glyx{wFrtt6YA-*`=7B`m1N$#zO z>g;LmW|H4%9eY0_3|oqH@NMIDzDqS4DoN(#b@3PJ7BoWc*;VN6{48WH^1uPgqD)uy z<@HIFJCRO7{T@x`7d#X_w<}0;QvM1K)R9dcYQMX4=S%+B-n1Gon{To;Tf*_=sV?=7 z&*d2_Qej@^h-tUBvh4oE`KTu5^_xXyJ{zgyMP@O$#$)y}(gohX!;oTI&TT2gixei@WQ6b>&%nh0{zp>;rHVX-?BIoey-^-^*^XLa&IftkN42O z+jvZ9v^T-re&kX6zJkxyNQ6x!b=7D;X7fsyVPcCjG!GQ>ExqG#c@gy$9vQ)Y-|vn1 z_0kdzC(pzgF|=oAes$$T??)lAUj}aWTFuThPDfXU5t1J^@Qe?}xI`?|&AJNW@G(13 zTONn}6(Pc*0P4QHW*}h~myZv|CVHD65xKLa@8>{teG0}erkS5ZZ>)J_j&rbG8U7 zJ2zAsErRZm{(1v#TyfMe3@x{Y2x2#D+%{hS}V05tMsh7Xm`Aa+gycuv4;w(hxa5c)=SeJ?uoGo0MQXd=}d5>GRTX zpC3DHK|QzspZN#JQV+#{S1JmDEXZEK6BJ;Y=2wdGR1JQ27l4NGcQv9;@`A}Y}u7Uv&u{fLL?G4?3j1{@Tb ztZu|Pk8{W!bw%i(N15jSmS{-}=ep#ls!edk$VWj;BWb~5|1$}5Bf81u$!xl@Qm_VTQ=V3rC+1)c)AF0t}kbYE6uR;?lj3hA3wkk&1cQ2 zV_Ug=NIUgF<`75ecMqY@8|q0jrtV`6F*h3Aj%mMtqSt&Yrqiq-B&BHy!n{0Qyxs&E zcM>Es|0>;+OLr`QbXW=N+ZcoAf#wiRs*&8mk6p0EiI!|p){|yLo8Lq2CuMw4b%B_& z1kr~!@LR;WPh1iPy(3?+}cyu?56&aJWXTqG(cNpX{RzDO-uMSjZb?8Bi5 zSh?v+JT|v-BhXQ8jP>F*%vO(dvh9?;_j511L7GzES}#0XTg6Id#X@gHCWa8R_riTw ztV&HLJ?E)tON@%pJjq3(&mX7TqsLcWO!KJ~zj~a2j7lq9JaCaEYR92^8uf=s)$(Hd z1ni>Q!?3>xM3KAQQ1IOoexG^@_4YI~&eLuEVm=Q`_ryfvo6Hv(v3{Y$a5r8Z{k+@k3R^#I&KK-(_4AnGhaL*4zh`cA`dP0LlSx9#vI+w<}}U1l{6JJ z?WpI+RVefFG6<$#;o>ZV5F9y>gMM@0vA^BTV7eg*s=H6|W|dhBWJA*u6(=c*|OJt&YX59aY?Gcs!yyUC~=* zBs*8wo3iuL$UXIhI~x%{bE}8MZ?j{w6UN&HBYRp3J4^iYmqA9TZ*AZ~Eyj5MF&>|! z6~s!r(hxAy6lPx_o?oj=4YnJ?_%iQR>OC!a>hs>SHx_~7AwDShgy6%9*wJG`}^3y zJTd~S77^#+yFJ48rDLG{cTuT}ItDlol9Zg9Y<0%8 ztE1WKt8;|=m@5>?zvkVu?C_Cxqha@K`RNTb^ZTb^^xjqMxa>5HBi}-E`~&{`#Zp`f zG{kwbhQ3(e2tM^J`fj`|B#@@v-PBB?+n*+1(_uvyiG~xkc@Tcxmc?U*M|>sqhFe$o z&_36TC&t8}C~T#~Kkqqr0itzcU=(zppY9%yLwyB_hV#VK9G#=4VbbK=TzjQIWV*{-Kl#*<{wKrOPTl0i*Nv9ZbKb?9op$Qy5ph9=!v{AeVm5S@8(Lr;U4WI z)HAAj(tyW(j>6t%T|}6kU>~$&(d=S|t8KTr^Pez?jOphanIoEgq6G>^>(Qh4M66uu zg8uey(0AUzKT@{!qg*IuW>wf}+2L3&o`#=wjl7wxX+llgU>sig$ zEDgu{bw-kolFC2fcsbpUZj+zcx^JG?-D!*Q)3V%Wr87B$e%+)*=K2>pJL zpUStvzrLh5uD0YFy%$2HlLiHy)of6HIC18*VS4#Ge`m0aJQ0qFHHsC5_%-7Fze||Z z{88}G^u&H`TWsIx!+)wR!lTjN2#lG?M%WL-<{){vXEpKK8KmirNk@e$rCM7r4<(L1}jg34uQp+{W~mw6cp-d9($=gViNBK;EWOYbkU-Cl8+ z`p_BUGw*N%%BfE_48cMBgQD*1DI*fQ2zQS663*PW!;vz|bFR+k>q>~LFfd^fcmwC#MyhWeSILOucdr;B-Mb`qYH0k+a+ zEd8k(WcH1K`i6SGRmKlP^i6T}*io?*-7>UZx!}yC3g$t~+PYPy@F9&_yq6esd(tpZ z|A1a}RV$9SOY0kLJ}Q`xHbeA@cs%{Pf}2ui>ge(RIG9h^_^s3j8y^g*>zDY>;!eCR zsl%p6YuPU1n;qGDTd13LlFQP~y}HXyl9{R^MwZ%?K)hzjY=+THJa#443e9{g^04nO zjfJjX|ii^&MxR*koT~GP3k6sukvO}HWD1Pn+Wz~DR z!$B*8jcJ*Mx2v`BZSH+;OMCh?<0zzdGZ8Nt6oAqHX@g;3nbq59D5>g7x&`$}PpbIi zf)z^xnA^d5h?y%d(RNNwA)Y1Om|~u95u1EX#wnc?*tDEwLuJTw81I0w`)YZ(aTsJ< zv*8~mB^u!U0Mc2~`eT*P2nXIo;@bgj8@?K#|+iwJ9x$m ze<-~m@5`gn?AdWOfjw0dUi0@n&%hoFvPjb}x8=)6$D-s~F7~%>VGY-(Vb5<%Tn~D{ z?FOgNjlh7qy&;Oe-H5YNXK+~MvXFJc58VPy@nb?L586+AQ<5vDYzbilkyJdI-Wu@0+-R7#>)@#d>61H%G4-2Rg^@MOGMm*5?j1W|IFTKEyAxo3*lV1nTIL9!wjEykUpltCOjG^ zGz3f$R%!0%1DZoHU}QG((*yXpDAFwZr=q1LkCjsxT`3#`^HhufuU~2IVLY&1Ub)hvCeL@fd4By+!K2czSUeRDSp6 z?K&aITeTYBXH>Ha*GQzOYh$DLTpk`Ajmb`QYu=O30xo$2QpC**@F+9+=uJDS4{T@M zWCbqKNToOU-r_r4)-n`j4%zT}@LqHvVvZo+U@!PqW$|r2qcG%xHl9}!1LsF3%C5UY zQ|AUNnID41w#4hSspNYilb~-Mj3SGJBCSDQ*k$2`{U>CElMn4-t>lZT$Mbn#db3;{ zm56))7+YU9oIcBH)YtxqtK{ZDb&L(HZpg6l$C`xJPp5^2)iwMNXq*OaC;xU5f1ucMXU)j_Z<~4DDlVLa_aEdrq6FmP{ z!y{j~K#uOO|7rM#ueYL4A8CE*FGqwB6La*AiARDcmkVtfc<5*bmDwHaQd<}X7R-kM z^~v5W=|qkFU96_>+?s=rh0*#oLX>AQ&kb~k!CE)myX(#m?Ic}yL?C>>C9~vrGqL!( zfn?^Ni#3JcMa3>aj!;4tbL}LsiHh0bSyZl>}4OCK=B5&O|(Ix5v zdwlSyu=i*O-+L?ss&SOXpj)loj})v?p|{zLITt9!s?4?=|~Oie%fC$^DT+T&@QWwZw2LI zgKF}rt)QNCmCLN|kUuu*I6`Ot6<)3Bg+s)-vwt%{@1!g-Gc&{S>(4OZ3bV!KP2rTs zTg}IjM{7ms3RvuRVSaAWn72e5BH06c?9e#G&osfsG#U1#_PG$Ys#5r>SHTZlpxx=T z4H|!r8ydggFl)*T z6=!Kd-anbIqa1(jQ8)aZ8_fPuf3K#`c&MJC-Ge;p_sVQAt!|50YFad!>LTIYRLG9? zF+s`zdtC3h!`0m>kE4-+X`6oOJ-qS&5zXE7JujXX-pde&I8KZFW9{V^CuiaY`SVkx zelUOi0E~+?m1L#{4GqMK)lSfzK8DTAogg$7C<P%Xwq|re5588!;zlX5&cwC05zn7^*dqSeR{ycVRm<4_~O+oyXYW}KwAks&f;lAy}@e^2xi=PLwRQ2=ponSwi9^9V+R5hB z@V4vW$m~TtuCv*qoGA|xedY!%BFE!4eRoysyCA%4J&z@xe~&Lg=DS1=PO!wyNr|{y_+ETY&H^%b#=+_QEqAoGGpaCzOnRsi}2@` z4dz|h%=g>AgH!jnh*Z~L(woK!eY#B++T05GsF@4tjZ1rHmIdFJY>Nk5Qt(51HM^Wg zp5%p^ut>YkhxS{HEwI447r~)vq$xjj_&-ipI{K~d&s*<%hJf%Qxik=7=b$U( zO!K+@ZdY6)-Me>|zz#ng4iBGs7SZcW)AWznv1|f86HE@W<=b zCNMdtz>QkTgAErbckN)mqvqgi!fYIMtmo_L_uSQ)Se#DYxJ(XekgjLho!it0cp-Y`R9ZK3$)i~t-dal{~%E38bF za?QgjD_2{?3yE`nc55JJ^x34x{mt-%7;y!OEBNQ%lu;Y||JlAbITF)@DZf3jfSZSe zW5XG1D*+t?cq##5kseDBjr#+ z$-{Oc24;HlV(H<@lt0zSCv%$ZbEEL;FR{if7xP?A%8yK;TPpWr?=|N_({d69->u`a zI<5%n;R18_LEQK@bwsX+fz!SdEOw?b3Wn2cKX{kR`j}%!Kl11nj1skaH4DK{k4R?w zvg#0I&k=Bb+*EGixfE8^McS=%7rPi_j)x7bUJx=a4o6&~O9O!yX7Aq;tUg;(D9LIq_dc5BP=x3TZ= zBK0*kulmPgcFczT9ZkGhLs>I5TllwxVq~_F_&L3)TLQC4TYJN*W)bVCLJMbKr0~A4 zQ_%aG6(+>GGf}b{%rB3V%y#EWFC?kipjY>;;^?oTl(`JXxxB;d$~F_qHP}(#-W`4~ z#}Bn<(-6Dno8Dvphj6v;ravq5wBSNHAopvUcs{qiTq|K6mR$~qPoF+QGwDb>1=2F) zckuMd{_v#T{jK*XrnFT_Shq$|cpl!sbvy0xeS#O(v@GPO>e}EO(M|ts;vgZqd^!YU z3*2jL;0?vpPyX2fTQ}Q_9#uD@S5`5$jk_f14W^#Q^ClQLBa9auC!UrS@g*mQv4H~z zV+R|A;6aag?+L_XclMIZb`QGmZHmdlsveivJ1=A0%Z$K!$`MGnEQ5bA^^h5@WuC++ zb#R^x_uy*YPQ81>Le0<}lgd{f48b%v@`rtr66(k|{`!XtbYjbR_|H~Y^!$W!12b0t zLtf|%R26pVSKu818?#`Vs8(zu}0m^Y|+LY z4^dxo9fvU<7U^yL9X&bmKOk19`Ib^BEpQV1>E{md?A*zsW6yb&>_R za;WICX$N||zJZuNQt%^vrSB+fM3s4S4ZU}GYWy09M910cyTh^e=s3wfAH9P5c9ulI zaX>e&*XV?ETbE(oi3@CsXesI`d#k0b&80`=V9z`^>Id4x8XHLW`)Mc1#wJtl>6s9T z2SyKA)VUZK>QT3^>mB~vItYgM({bqUYf+J&ny|cpQcUK{dFica_$O*f7zkYtqp)kd zA&z&QWxqDXQ#ZH+TK3T0hYyS+|6UvMV~ zBgbYycCtBpU^M~;$5i2w+{9P<=OEyv1tQ<}VyFK;7Q9VQ3%GNKPiqZ8*#Tq8t@dST zAkO+a;M~;htVv4+KeT3H$&h-!r@|2#eZ5igG)Vk>6=icg(&^`HXA@srB5zJS2IQUM zSN5jjk%>N%94wi|Pj!fVhvA)UJ>Nbz7_n0XQAMe zKB6@ncq;8#?c^yu^L)HmiC;yo_O`x6@$_S^OqleF=z|rBJLNmcA6j7QIsn)zsv8LEkp)okwRO?iV6#x z1^t%8!giMqj*3v2ZD$e<=aUWXYoS&c_6#BD2!Ar<>nO{NOSLpt(tZG&Q@aSwE>sLaPgf3F}Oqj?)+1i*usbI z)Tc^Zrh9$$9*y_Ge3vk+6ov~sD7O*vhC0XZ=J7)!%M~`y&PHNKC;h_2{^Dp2QtRXxYVr_>YK8J_`Dn2^N?oym$7J~ zJ9uDkZ^Zs4zjyH#v3GMg3WQ+T+Z|!cKAB)sKU=6Syu&ppANQbNBw`BM^nSZN#BM(+ zedqF1LgKS%sLj=s++>H2TL;BtV$Rz17UGGg`cuakBff3tDhmTJnLH;yj*epejw%T* zX$q3PJ!-2Xep-1+w3@Jy)ZIEE3+TOpO%~6<`JNVtPQvf6XlHz`YuIX4Np8P)vYx*)n`n_zbM#PT&k zL8z=GcH6GM>{O8#rrEkw`WM%wiRtT_Kcob|#2UdsQU?O)8pF|tvRa1TcB zk3wj^H5Om|#8$czM@WJAa&(iem=cH9kVq`~S|%DFJYG=Dn<(__S-|7Y2jb~Q@?_lf z;^hY&@!?Y{#%)`}Rt$+GuDd!OJgMTZi_`Gf%o>Uzk)q3%9Z*WY4lkR3!fkq=?vk@Y zV~RI_v~n>V&cxxOy*e{g8G*R3^gBj-`vebS@A)jl)#v?q!+{W3Jy;2qUN_lzzZ`s1 za)p%Y9(LWw8_TV&(bef%<}%A48_9EnCv(W3$m&mfRGN$+GrXuT{ej?T*8O?!*q5yH8Y- z<`38Y-q@PgM>zb=5kAFUu+7Qm4pZ$AVHApx98Gq-bp+JpR52&KiNE(-0=+AGXlnc^ z(oJg=tW}GIt)Fi3%%#C_C;s_=z2Soug0P#u!%ix0XPe)uVECz-m@=!L$3{D1zy#tP zo(L5C6XR<|Mk;0RUobwBvaP)m5LI-VXCKSOM%v#R3_RH;M-4RX9g3-~b$q*XIQEk_ zpfjaNTxuGGZ2Ful7+ztSwPrZoW`w*IHN029I2hkgLFc0bdh~+;u`#IGq#z9Jp!?X2 z7|9(rH<`3sx>t>L{K|Hd{?^Cw0 zw{_`AcKF@n+!1c?h>G}Z@vsIr9G&S03ya(AmWc}#>3*T`;+rT}RTCyfeQ|Xv>F^0L zDA_X~R}Wkk_cWjkb+R>mZ*n%}jt^!}vBqT|F`u5`fe#0qP$BNC_o0p6HPd})P7V@O zS2*I7OE^5r*6^R6mIpvPU~29XYU-mwa|c{=pKI;X^W`(AiPvH6jyvA&tYl~ zs)Y}1(93A3x2Qu;FPY~|O~ue&7T6f##vlSPm4EA9I`R--?f-$Mn^2TR9z7=w$vl5MCynw|l%vV+WW7!X!aa0> zWS-BN8w7z^7^6c*Gp9jH!i`(wh0g}}c%-)zey(05ndiBe9U-+f98QC?Si9*=*lU?X zuG<5yYPTFKX>T9hVj(&><`M1>IEm@AE(v|NhhWoN6T~@2aN8Y`*x%%ewYd@OV%cC! zdpiI|#J_bL=!Ekcq(Rj5;^yA&FsX|L(<^4RS4=RhG7M5D>Unf48E&7dW1dnD>+4{N z;+qqxqp_MNHqb6a>`DdsiRIN7gV0Wzsm9d5Ou5(xZ!Z$pcP8h?N>NZ@i!pptz35cG z2|}`}s!;kNm%lf(z{yup=+!o#Yq}&rNk<#1wM9%g8-f5|Jvg>q<+ZzL_tdn6QC7C- z=xpj`h^fTC!{abmmNIL`j+mIeo{uKKTMxQjuDU&gRV;rZ-244S&^Wh?JD;?|k}I*; zw6s%PXh%Dq(-<7Fxy7rS>HTq0kmxW0{!wUsVTquMkL)z%maKi~jdo!(|3W?XFSkb^ z`fr&iY~gqz$wFDMwcp1h_btSz_kqAVGk$ub6KqAPn6P&ZYrPzaZq%!ItfPvL-bUS7 zOKlN9B~Daj(194)DrBes6{LoEBW$fD)>e7*So?PI zL|uPq(cfd7<4v~N(-|i>()(*$3BTLZ0Tw4hk^l0(Xx~RQ!7Ic;;;~syd9-eK)DbCv zM{GelVeL`C+UX42x;YjG#Pym|dW+izMWSz^D_YntQN&ov`_umX->$xSofAG?T7&^X zbZ`A)3mLy)3@OlHZmuH{?>QHVDoxzKIvoXH3~;ig8~gC%k+7ei6r^Qq_&M68D@%+q z{Es4+mJdbJB}Yk4>d8M9m^;nHfgbgoQNBQn?%$^>1I2&n4SOLg1t*R?XGNJd2&O*V zBR5a;QmJe_ts*b@Mn{&pMFYdKhQdL*o`3!vj(<1Jp?JMW?3Ek<`7B$U-FS(m4mPI_ z3nO@Mtl_=)wZYZtJ=VM*Ba$EMh7CdFk3Xj%n0~Rqw329vK9e*w32r$$=x}IczpsX& zfOct@&fUEK^GL);TVkc%VCHYp4+GZy6_)LO!cUTCs-7~jWpOmyZ+PI1Y5+EgQ<;O; zY-E1|u6@1F>mAK8>~18kULG&LPZ`1T4qar<))w|=QeFx`-{b^dWEYB4D@~Cw!z)bNni+pbW&zpEg)|^AgXdd%ZiOoRU*tJ?%_aC}??us}B-l&&EOjRW_`( z3V5_C<(`OzQfg<-k`5%{#1?Jz&^^p^)-1)gr6wpG(wAN8=uUgcQ(=GBGoJC;AH{h# z*f(c1e?UAHyK|Id*NA1$zs{ljfjUfD>UkG^4~)?bMCcL&aXo2HoH_)1JHKbKnlX^S zMO~sfa74{)kVmY>`+U@|k0hO1)8<$9y2Hx0Gn_!#>8Kt|J7}myfXzx@O3V zw!ssnJDl%~M8vpE1TXogxAA=gK4o;F-+81}@lNL>{|Q*-UNo zOz2E7gEsNRE=*s8iM<@)QQ#;#ksXHi|2XFBBl%>yEn8AvJtI1T9h@};5gr3jpV7oi zhr1w*FT(PTGW^0q56oANMU7=K%in8?d*f)ID6Qx3u12F*tQwTgWiyXj>I3~4>X34dAa2oD6(4xjj-ln*R#N8a5|%-L?rK6INPD0Qd^ z4W7B&wx0GS;xfR3_9vxMxa&3r25v-}r?p!@t%QP*Gv z;r&--;r{Xh9>8tEa_BDd*o=3#bit&!RAkT0XCG)zPMVQ8*&#dB$|vt0P$fqwPMNEW30W$NDSUL20!*R@~lDjaHf8Ob$Nfq z5f#pudM^dG(@NPky34gBt4q9;@}`vKF*bzv;s1SAd9k?T|XpBa7IgqV- zme~!9LkzuT(z9;yOM64`s@fh&JGP0&e+WQ7V(eBX_7TcPIOD+i|2z`;yqmHkMj{j* zC$!kmvXMBOr-FcnM!sup2Fx$b$C07ZY{}~;VdMSdLZKqvXeftO5^sp5Q3|}56R~Lr zSR=`53p?|7E=JqTkj(jy^-efW-cZHlKygl|JC<*Y#@AVmtdi~k+Rt-v?{OuskzRo@ zmDJB0?aBu1(!|r1LokZ=|2qF*v?h};F8`SL*0dn>A$D8050{uO=^Xdg7(!!j4Yx^4 zL1Ah-qtjXy-kz~g`J*T#jk3bRNl}=!ULC|07{|^*-T^ z@(X@zM+7e3)RTBA{~4~w&6kN-U|hn+gi^NVw-yH1-sb1ecwkG5y~J0uq#_m($%`@h z%`-M%h(*?nEc$(_;hN8VFxW4XSa|$xXd0T9Eq~S%_GzkziAb(()L92 zN%9!@*s$nVu}Ha~h7~*a^EWCPSajbCdHn~mn#nz&=+q)CHhRXR>iy|%YlWA)M)86Z zK9uWmLG<}3_Nzbz(`kl3eOu4-mf1nRjBYR|48)DPkyyNrxYpl(u;g{b=}A(<{G-V{ zZ(k}7E-{7jHdnS!R|5kZMq{cfX*J7zFjSgY!)%M#hB(lL&s-6HbPw}5ZAP3qYq&Sp zaBpM!b4h35(&WE-U=LAh(1p8kCxs!ou{a;2hAOl6@=2Zvl;4>TlP53PkQw20Pauy$ z@h*OAEBS(7(j8Y4g5w&HVV~@@#LtfXn9%_CJZ@_og2l%rvp(qsbY?Oy<+)o|0P(PL4MXViA*(m z2pkLgW8;h_K8-Suac#u@Q0mQ_$9N+tKOScaPO~QBr|z{1#T)V}+*2 z()mg~Z8zr%+n256MgQo#gP4AbA4sclNW@}8O=NB3D*|fK zuf-k%tZ;YVD9XazdUSw-2Z6HnA^WjbF(7Qde!eTn_3#Z(&vDQSj`qias_~q{x(qz!d1 zyF|Avg@N?n=hd<*^2F(^q0Hu-628mL2}|FHKyO2XXy-aj;d#7+@E?oV=xq%4{hfy| ze`>_CLusa#GbqZRVfK$B(5=W6wp%OtzuTcGcC&~4%Wa}FQKXq`c@p=wj}V*S4Cy=% zEdRcSFQd=Y5c*81omFQ8D7Tb)Zw`vKHu8I==`b1&-0zTLv%5VJ2I-v;uBG4R`Gvt~ z^r7wn%1k}|5rFW4*7(@Ig=M&_Vr$}b#PK?QZL>QRxfcR1g^C@NeNaWelO~Z**oAX} z)Hy}H)p^&rug`MCdYa()b7$uKOA}Go2TOK)wZb6yFE+s7oTK7Ne?pMZjGV{}D7h9@hj~jBX+@a((K7Z;&nqN=h z*dP_y4i*q{=|1m6_n8^VVVM4CoVa{tD(+z0(7y2hGvBJ8Cq{Imj$r9Q+|(-tMv==f&9s~;o+p-Xha0AnukT1V>KywLi&xvm zhd&Q;6&=(U8svF_o=+&bt(>(IzXvv7yB{T3VjX!Kl2@Dcp~JU9W-3B z#nVEFaZTFv@io=VlX@8r-3*1(yAp2u+aJwB7GCw~#sZV+=D)8uggIctV9!K0fOH6F#OiG2c(y8v4wZEDdj`TtoapCNK_SNfE;*N(lUNGA=NXT@cp0)18 z_dl?T+nlG}vtSt_-rKO4m2vQBnJ1a~)q_%~BYgpmDfDI07CmsRd$Ta_33(|gW0Fy4 zj@8db@(ueFXg>y zifv1npYu?R&+0GH=Pyw{E`xkT(YSM}-$YU5bBL^C3TiM9ED2!E{3lE(t z-c2VNEy@c}@hV6ZrrC}LsVnFw-z5|hzs0%K0xy^N@>91Gu#dh^N558Kqo0igoJYgY zs*zt%u)~Zqe$dM75>NMR!@Ra0`VY+Y1rd3TR8-ZF#Zn9kM(HvMI~t$ z#%o>6mSzWHEA?s4w7AJ;`nh2lWo%weJdwlra>=HWCg+90xyN{M7G-b4#xb<@V#30lXgFOEN%Wk9l)pRI zv;Yr2xv)SJHDu2H|IAmSx9xfxJM=p=kQ=ZR@Hxw{cwjlpyk~~5CFJ4URLhk%*x+_e z6uO-rCDMP?EM$J$Cj{rV^6$qZ@$R(_)?c2=|Mic>^o3^d{JDws4Y$Hc6HVmj+~&W# z(QQP@PNL@+E)2wp*kGu=zQ=N6UD5uFd|EF{cYc(uTpQx9oAlz zxFyf^u-uZ1FE35Pp++lQ4!**w_9Vcb7>|41tGRSUIF?n@-L7o@usDS(lEs7&%IfGXAiigJdy1A z-+xdCbeI`bBS&&mLw{rqc0u98Xts3oTx9FaLq#6-UR|?C2eJPCVydV)@7nzapA;UC*Y913Z>-3+uU8T_c8nH!jH%;WUEJ`5a`iH6?YOH>JNW(| z7#r7LaHKvZX-gA{p5vFi3kz-r;9PU4XxQT>Y{hcL63Jk%H!AugmzDWTiFodv6y^`RIe$sG!C)pboUIM%L`5~#w784>it>A4tn~d z8)eo`n7fs2%qLH^6ZuO!t60VccO2R2iBW0ix!#W`SjnYh+VoCQeVC?j&dgS#?c5+w zvbMS^_O{oEUzkVZ#VkEUTbyQUS?APIc$hRBJ4KB=q%wuR3$)Pi`KKs(&`;q+-en=& zp^eY%9)i;^^ikxfz%L(;!KbB;n74B`JG*TjChAXv88N#`OX+u#daaD71&eEMyTds& z4E=XDFuDJ3m*nG__^pcb*i_g()RJVTra#c4%$6+HQ!aRQbTH&x^kFdSsQ3+OcYY`A zuvzUId(hJgK63NnWm&`L(2ii~w+OlU8^~|tg#mk_p#4=*2>f78IUDN9ZCK7X7SjFa zJ>863>zM9{GU!Hw5QVB+i4uL6b4}G(Vv2k{}aB$+Y`Sc7b30RnQxZ& zgh3B`Y&O(k-CYsJ3+s491iiua>?PXHs0oyD{zJNCcro*wZb7|>u1H;3%k_!x zdL}XstLgnRZ2wcicyNKR>}DH}`W6GNaeC<7Hl4p35C_|HrszIpGgBwMWSENvl+12( zb9f?`@=K#Kv&2(wdBNY9JT7WAY~wLE+#rqbv&MP;$s!ao!P#*7D$RB$Yva173`X>? z;}f%~A0}EG^G;qAe^`-%y44HmR&|YOMG>cACV5x`s=4PGA6z7FU(X}`^bUyV)-U$Q zX}Mv-i#7+!T==1B=PE8u+Wy)LNs^rG+DP)?y_}0{p8NU52`P}4GDJ~uANGEFPi$NG zSg?|L#!G1CjZHQuE}R@+_B#;fqp9zqEtcshs$z2{{U^Gf=P!4}c4EIMi44VsTcc6) zcLfUkf3Oh;6VOzlD)Cr$bwy){t1cGFSh0hynrKdw!;OME?lzLVtaKx3da_v@O!L4k z)g8AB3fP##=GZ;T0=o{}=6z?i<8aeAEUtpP+X-EiQ9LEQ+7d_X|G7Al*;amb zWCEOW|3}hU##NnlQP{#(6ct4zZE2+Ap8rBD5b5sjZV;qVu&_`J>`rWvd+b0ALPbna zP!zlS-E-fM^I`nW;AP)^)?Vvb3~$f0vBGH;XfT|QC$uwvniq*SZi|n3a%|G*u|nSf zIbkPtHy`^*dC+KYlm$6)ADhaCp*XvIVCD!nb*1MzDSgQvVhs2u{C4J zyC{=u4;zEOEVG63kCVtFc)f;Cq<-mB&hfal{FcaR(geXRN=K5DjeJ6066y)fcALi2 z^RnfZP{I^00v`BL)&{!k7L_U__osN(`wt`Pd^uz9Vew4S- zWWGM5aq-SLi2K~<%dZCEo@yTYpYFzAm)cR6!AQw&&nX{t_Kpc;tJc?~2CqhQJ!whN zl+mM{TIV5aZ2DNvBW|Z7=MDL0k5`Ler!1)NRu=ZBZ|1x6sdLaN9I{5XeCqxrOwcH$ zw`(QqwI+dl4%&Er|1!6~y9jS+-o6gV6=gks0hOB^#oj-Kj;rKTJ7I-4uLHPK0rhy& z=ljYZRkrr@DA-BMq47^MH)?l68gcHPE&M6&Pd^Vm>W*A|`!c&em@>p0bS0koAy%Inod2px2c{r;DRCqHZuGi^P3?X~MED%i;KYP05@eE~-SlYzUn0 z$g>T7>Hoj;tT1Rp2Y>4y1;wqD52BpZTDK_lU1E!2?iFkfz162Bsgo&_7B+Bn*nc}?vrK}4J5~KtdZ(Ycyn4{n8Ccc5P*M0BA!lqSOeDY`kHZ5S1Iq!Fk zSa!tlSH7P}-t08AMa}^#0$A}E1BB-&W6`_@{&BTG62H=Wm3%mlzQx04Ts(BARI#Qo z8(baZf!vj^@GL|j`5$66nyfxlK61; z%(R1avH@<6zQN;-i18a}k83*%#nK%CctPKPH?wat(ETL3G6!!iU*ms$LQt!ihc`}t zMKg|?z+qu;beyZ_?}$y|waNsF2WrIk1`>1kwHrz|*0J^fBJlem^_QGI%kQLQVpmfH zX|i(W&W}T2eLffpzlI3|yOHPOXCSUkTEtr^!=XnEj?eN|?0HlwmeAYkKMnt6^=c&a z2*dE@s%*+xDYzYfAT0E3<<5J8sZ)A3_*Yrp@Qm&S)DyO9U@|+saVl!g>7r?NBR?*7 zrmn&OWVTv}`vpbg_J|^Q$bV$kq!F&!tAn2^S$sEfN>kfSu|CubWk@Vakbtlx0|n9{uu5tzwn>m zGK)Nn!_Mnq&*zSsi5clw^^aku?Q^!LM>HnywSe!)^*rNLELytJjpMpJ+dFx@&}ueX z&^_0{4^t<*?qBM$ZnEcgG;O z@4~OpGr|#iYm7SrYzmI#_D>3^XDtkIjk&Dw-*6<4`~RFzq|C}2J$K03N%6Ixo6$M2 z12J`zg^YJL__KvLcO4D3q_8MdRq{Zyd4m&unR7SPdb$<9s%zwQTU^U}w8aGE{ zy_y}Sul>VJcZMJ(*p>QVYPiP41k(B9P}uFZ=orQe+NN59bU_KXS!)MF@)Yi|x8Swp z72#hs(e!>dJM|>Tk>W|UnVaJu~`4R z+gk2=imBKB;C0kc;aW`svR`Q;Jnb?cXT2DAGTd)_)gT`vBYjd{!xmwv2ZcXx-uvECZ_O5W8DmE@UM^FST0F-77v^*ic~tf?n?;oB(8 zH_gP{j2EK!FO7sHZFWNW#v(2^Bn3vcI=FrCrg-V16xyZDAxb&MmRe`xYzT29cirIc zjT50J;|wd64WjXnsN-J62fBOu3-f7*dNb+RdF$F|6JvD`*TtK%mlq-ZP>7JCeVa5 zlH(fqIsaH(-(ZR5efEnDnlrFN?1`VZ>R9SZTZG*QN`FzOl=YlpFfCA8c3 z{4VJ9dBndgpzQnsdz26I;EB~;)aCse;+|5%i6$LnEi=P*>Wz~7>;Sd7G2}H=63=*3 zfIiC^Cc;Aa6r6}IdsEEvO5t9@YQ)s1AotY*cJQhJ<|rvcYElF7LnzDhocctGhj8_I z1ZppYOT6@J=h)!JA$R2QTijwt0Cx2v{Zuqgq(Pd;gP4tiUPK%3JDHf(7DgyPHHkl~ zONExK721E4v%*bwh|VBSc|#qaKsiv~7(1Ak7K(2cCSc|MSZx0EfYr=T#68{r&-}yh zf)Ep$gG1+jiB1kRh3hRT7;mfRe`X|OM3^b=2XOJY@rCf4;tu1}H`p@DL6}Uk#@nA_ zKAkup?sMbmcCKhHWfF`N3j=U6QbtHrb;Y^j0Q9HcUQS)-U4E%xm#vsZV;Y)&>EOA_ zcK*e=2)}3ApkV$G)^%43u5(%>8vcf1A^4(7U0RoA`OdeY$Q$m83;GGnm^d~EU+AD+ zs*!81bipU$CRD$+5KnSVL&@w?bj#yBaA zgi=)lAEp_JuoZJq`>8@KokRTp{Vw=ZTghr}*+5Ke4kf=E{B1C0B!^SZx%j)eV@fkl z-2O;CQ2T{+?KFhZ@2t_)7c~z0skqu|M!oZ`tkN_F=Vn>pWx{%17@mpIRURmRuF6(w zj~8BO$w~B_WA2_9a>WgMg6(+^2Tu%pA0nCg^0GRZy?q981Ml#G-4^0Dbv7C5TZ?>N zwh-H6Cq8(c5oVjmK*7oa(Mr+0Wqbmpw>rT2X(UTK)F#|FY!E)k?ck=@JTX(>9h)jV)jAKskjdiJtT0 zcOpg?X`<6*53}~C&ZB4}$ltoiO`J<1YY~W=t!qRpRO#I`_!{!m#^E3Wpiplw@nqVT zMc~J6>I_B6OK(K#Kau5mY+(<#4-(H`_i7j`GKOa>F*ffOvgq(Zi@?cbPJGZ z_$R+Tg^uTMOd32?h?$d!#y*-@8GV_*x=@O4D=AwTJzunY<4d$2t&z-pCt}eYyiIwE z@&Nw+axmJ46LY&!m04uSA#6V}yGon+oSiNh-a7#0;-BJfJ!6oUU5JG%FEK-U4;s_X zImt|yo0#O`cDI>$aAq~rSEfCg_{n3deXD&F!ZCQB8pog&kuY!$*c9Nsx)p*<&$B@@65z3NI))v;#LxW7 z#B3c;oVVH{3SX50XTLD=Tn!btsyAv%C@Xh=Dc=*}itCL5aJ!<Rk+s@(wZjQOJ@Gt+xqx@cOuwC;^hWX zhN7O>VS%CI7yUeuwpW8<0RbJP*1J9lgQ-b`L-W^)h}xzS6u?HULg9qA=K3 zStvT}mF`-ojnxBuh zzNR?u$OM;5@ffw+5WXde{N}0Em>8b~_w5VV#yf`eouUMJg9hG8pLx-CJD43G%&Y1B zs(o!fava30oH8$QN6Eu8g7TYtLvc)>G8#uFh}M=r5ISD16Z*b-!V6o{kym7nhpw7j z+q@83w7We1wuSjy*rST;NoM{{!5>x8%+oBN@(x>aXTwWJ z%%|)R#XDDLJUKDYT;Gb`{=NO-|7EBUNdCdWuY*vwZ!s?~2t_dEs{95zF{cx0IJQO` z-aEGO+PYlo8@I%EHh@(%whEgc92cgl)$k9$Lb1bd7FI7C$v=z2@#Y%!UezTq-P3yT z_SS)nN+XvZNc-0(>U@f~6eltAh}Py{QMXqt={a$%Pim8YHJgv0mWU-qMp(bjhP}CN z3~{_HE~Sw_iu}V0R#v!hcddB2br^1RI%8U6CDSgPi=6#dl9}IrBLlyc^5Jo;yXe*U zhgfg)1x?`xg$oPQp{%Kcgp`*xrzfT&FT)fR6k>(*<8b?o1$44D@SxGLs4JR_F^QvD zg2hB(LhsSSl0i*eit-NQsYfJxqyxQ$y>Kri1Q(y?Q{R~mekoFp_0%06v7!hfd4~N8 zGe!LI2DIkT`!Tav&`OMlB4uZEw#M=$XA)q##~z|Hk<9Yj2x6S}m*_bw2Y6GbiW@e` z_U3J}L0CPX`lR#@v)NzfBBD410oHWCc%OuiofYu*<kNKq&(5D>;Kr1=K=5{J@o#9Q~buFH?ULb#FXt;EZ=dW;PO>dm~33iw|;bl zNH$91!;i2|govx7GiEol)J})DlsUS#)bcL+S#EZB!b<#k9cjBYg3AS&$JO-atMMPvX&-+SVVCsXveEPN6>!CgR_ZWdM8*2HG z=6H-tG{n>I>uQ{5mSH(Do2V3A_)dNCL(++t^>7VOI+}o6^L-Imaa2^#iFi`cy@l*kT_TL+HSpT?G7t1x40-CDQ*X)U zQ4d1larRav6%W(2Fuy^EA2TLlj_w&!f7rE~lSD)!#Eh>%ey2ek7K_dWf6fccz{KjlZ@CSnR={Uk;@25FaQk$zrb^rlLNO(Z zzD!YkWlBC4Ofkk6cadOjk&3fvCa?)l<7tJ3c>a&F6A|%j=XfJ5oves`@9MeY6XIE} zvL{BdG>;;`*w~5TcrAB;T_vCR`#Klsyu8VSwnt&3bUr*QCySQ-YZK1?t`s!dJNVs2 zlpBpS!Lym_{H9bg>93Y}6Sa!9E~1Xp)1+f()$z$w0$@wt>;E+TkI#ZJaDX4IWNxur z7u;Yp+#fpjRop(v4KK*kZ=={HdPF?$7c>7q^Vh$LM}w9D)?Ka^A2}G0vbh#Gu;&z$ zl}W|)myTH0aFwec2!>rB2UtlDFrP;rS|jqo^g23RP^2Cl5#@G50vGdM)lQg18nnNx z1?y#!PF-qRIKFZl4{FJz9yW8FJJXw8{M;ryO*t;4udLzUn#0kxY!+TQjN*Aw_`B6YyeKRfhjW(wL$#+SQvKKIl*~tC3_`ni;RZZ@TKghQ$-|> zZB0VYTOZA%^T~JmG7(|DwFEXf9ShcJ{Xa`PG!v_aQlHWLXUy|nG_(yFcH6GwY477O zV8>hu17~;VcwzC0k%Gy-dOl;iH*zRXcleq;pXoq-JI_K9pI+H~Zk-QhYY zLZ--E(k*KnxDjTHiNjDfl{gPlJW`7CHLvNeUvY$$jJ88}tq{qcueC4*kIre}<=`SV^N~H``YR$?O!IR? zJXSFam>Nx}S^1s#X7Ua=x1hT)nlcM^+IHB#{1mUg9FMq7k<_(!Lv%B3vT*;qmM~%d zBJQ(<7Y2KX z@4jQv<8c5kCD|h6$8vsf?HjCG@&ad9A7{}vV=#G+Dh`x1bE^<1#1pd~Hm}8ZGaWG0 zeYj-LKY1(>HpPbMI={X~^L{S8X%^@P|Do1eJ9>+F?H#g2XpD5L_A;SgD!71R(^goo;S!s_fa!{d&U(OJ^w%RUmWzp zq|wBDxpItIbf>#Ut)|4EIn*iv38cY3$Sh?&lp_&ET@*R--qqd%La})U{eCH4VoM9i zv(rYsp|g(h9XZs6av=jz-kqYaBTR&VCL2MuqmT>U8CajBjnp%@#XmZdpiXbA()uc< zs+xkv*6ETC@uwm4Q8>sGCb?Th7luVs*P$DRJnbtSkn={b3|D-4rLEf7l<@ zXG)4=u;hR`ER^r_^G~AhS3-+U&3!>r{ZUfCdy?R**0zB>y9;q-sVdFWOWAK zQ7%}|dKf#QDh=P_FG6(sBR=o3KgJM8DBaARZ+{zv-}1h=Tba#vc}zvMsR?E+YvgAh zIzZVhoHS=eag|;^Y(5&n!%ieLt|tBSpaF8q6Zz3;IS4YJi<&E;Z2DXyh=wWRJb57H z3q$ecm?KithH{5ue`1Gt;+y$4R+>8(#?dY)Cic;$oP(;eAW#^FO&*>>V5e)gL|>-guLZJnfEAxqiq_ zsp7G}UErY_1*wCbqC~+AyQ(Pr6jslFeosK-c6~e;c}DCsBmonQf#0#GSaA{gD&_3) z$k8~?*YjtC z6A?##@tUI>#Wu>+QAioL$c(M5hHgMZztNqP?j7A}2ROK%bk(JQ%!Rrqkh%Q@YM%}X z$1kTryT2wDZ|JCrqus3X9C@FvJYh1)F;I6C!DZ$;{(1}X72eH}bWt^AY6#;NCg`$LLjFB_-ni8lpVo%pYij|s>d-|J`N~B0clf9iMKH=TLvObkqB_+LDE}0J zf8&Y-+ugCmO=9>`9L49*n@q-R4*uhtjc%1ie)oP7PfpusZ{VhjWVW}+-N)kxPiWtr zD0GXp!%NcXRHroX|GLn>$J3scS;W*L9I$V$f@HRvl2>h}9whyPA)Di&ew8xem;bVZ z#C*snp3I+5)%;u|aksifVzBsz=x*C2Vf#2uiTD1=YX?Nrn{ztZ${(Leg}$8zrXSeL z%u-X}Pa5M0-z&W8OfFt4+9K`kBGKwU&Csbki4`@Y@VbQV`y1zC)raN0lzMW77wzc( z{ut{xGzLXwD#Qb6=Do z*df{SFB_;sOo=r!@OV-=-_%IFuW|Id;B!DUEn8Vw<{&T8aOTe>u9b{Gyv?mSvx>vv zule{oZY`UBJqg{RhH~}Ge2~jh1lqe`&xc%5+>4j+?>vPM@4pGRiy{%RY8H~@g84%7 zx6a?^j5`y?v*Uy1abH?iqTzgwrY^xLzOWniQ+zJd2N^y|&{%Su1%;*|_lgEaKh)s` zwh2(3sE=}$Qf6R8yqC0@5@tf$Uea*1obc+@WhNyezez93U_L+2?F)&=_$rAQF3&~d zzZnZ6i#bB%oI*ZuXBKi3btv!IAa0gU!dzm`kE=P%I@6Pp_Hi0^ZoSN(KO?=DGy)z} zAsTHMj-X49xMkQ|xK!~yy-`I>J*8VUF%3^Cqn4$IK0J!xhPY!wQ`g<^> z-QFwiH7N;|#L@e&e{g)eJv>gE!&~=85Nu(5=iA2JO$8#`$Dix=uIEwVU|+)_I7zKMT{|4`WkrOCwzTNwUuejtzvA z$Oa>4x$}Wfz$>kST}J~dlNot5UpS_4rUK;1<@wlUXm zTgaSsq8ram{{1KQM~u$LuG3RQ`(C#St?$+geU3fn+ZB=#@>?J2Cnxj#p81HVv6XPo z78W^BhnOyAp^iT~7l@~EHrTPLP;9?03bJW|l8&nCbM9yw=!;pchxzQOZoqT$kxY0c z@~SZ--K-~$rPlNGE2Nc?XL6o!M%>aZ5f-}y$v!_UX&weHC9YSGI_`Ks7X94m?dLGW z-1>L~u5b5;L)S3j!yR`lQ1OL!dMP(}?~M4Ua2THfQ|^`yqwng-*s+yw`#K*Q{Y5xo z-j}_9^iYVAKPUubpWxrz!{Hh-9i~bn`Q?9c)JyIT`=T^9Aj|-Jy|iFU*`>}-Vm4^` zAkW-F{9tP!miVSo4)7UE`<4d%kLrlap2si7E+E#g6%-!^F%`N6J(@yY+u!Q>;r1~6 z>Ny?vx0Q=WhlXO`X*;-{+Q8O^+d;v57HV~F@Bx(hPWH&dK(ihqqyBWOo%RtKT?d31 z_e{KAOI~@>aN>Rt2j1Hd(y~ujcu4|0tpwy3Zs2OY6ER>Fb(*e|XJ?`&2s(~f~IjR$U)H`Sz_ZOOTr(*hpX_#brhc7W-gRnfh{crXaIVVt-Hi~Y+ zd!l)|Q7rwASmDL25EhU=5)U@_g{|%b?nt@j`k%xv-Y3N!{L=6(JR3V-i`j!`cJO-@ zh-DA!`Pvzq@j==TvzH!Vk2g7Bp8ptpOsM58l+E$(VtBq~d`&#v?q3;G2h8w)%pH_H zoo^52@n`tZ*i>A98ZFW4Q)DLz>FVl|T&?GQXXH3i#*)03QlsdOc3J~n=r0|k0OrZg$>RaxblFg>8q09bWKi}^kf5HszTi&F_be3x8gG@;vjF4kE7St zFiW{)c#>~0{_7=vN`W|{x|=b}?V>2`^GjSgbP}nq-vrasQJ^FTu51kEAycS-*~n4S zGwVcJQxWkP|I=-P`j9u-&mSc|f5b8&lQam_dC8tW7mBSA8n?rtHSs3Vk%l zEn>6OBXRrv3|Q!URp*CBqlCVjhR?ai&RCIG_n0#to;=F!%ZNEoyGOVDx1vltQ{lbu z90|L4MP54YI%q(l-z~8Vc{`6<7+{-o6?;P&x3PUlH;X#UWkM6t>jh<#x++AE2UB;F z63xLmy@je2e{4SIhU%ls_@3=S}CeqcS|uYDF2P5l6VnxuqC#fclF*OC zjLd?PJ#k>;uCv$S4!H5i437uj;IjH}@$cC)Jli!|)Yu#X^SQ(hj#d$T?VX5c8-fbA zVqW`U0T%0;WALDtOz}t(A`a?F{PwbcvN3AdY&e}C&IWc!i(!kE^Fe8KJ@tWdX+ z+-E2C2!YjiPYln^VugeCA!HemzpjzrEq21VeIYovTS0urx&U8~8o+RaNbsdSA^MOW zHV;bTs^kOAB7eTYV|QkiZj50)$6)-rdak7(gsX?=;M4fQ{H}j6JgmtJlDnP#Hn&5S zf)l3t-Q-ff@fh$S4~9e4M1O{L2otw%l(5cPIdu=I{D018FP{&8b?Q)GUBNnTIKXA7 z4i0x+=Ls!=_#`_AkERuht3=dU78-<+K6luW1s-@g+eb3z4`shV>+PSIaWS14)6ZsD zVh_ojpS?X9S%dUpu2&<@q+8gYN)ZeTPqMRv;?S~XHtHhJ@q&ZF7+p<$VVC-u|EwoQ z3h^69DGwLMQ2zZX&EYQ3QXV|c720y)65S?wX9oH=s^gQ(Hh!bqBGmbjj=Xa?Yu(ug zJ(t}P#$SEP9fp#RH(@#~uZ`p%@6X5EDdc<0&1ZFa2H0e-iI#u{u9ipleUUfvhg*o- z{siE`J7Q&u+StT`bZGTg$L+Xze8wW`4i@P_dc_>J-NqETvBMz!pq?im2*>7GmQX!b zE`CDY2N!MV-qUj0&s)IyToWH}xd!q-?6FkYSM+Fd0)nVZ{l)QUE)z(7 zSoHZUzZlGR?-_~N_xnh4Rgd(2pf=74vOT1DFNF*!(VUN6&e_>0djz})fJ{X_U$rS0 zqshx;`K^@Il0WUtb$M8AujO)83E13^LB3*qP4bOQ80I>n{dZ5neq|~qp7(~{+bjH? zM;boKMdRk6deKU?NrI)cnxOG%A%9Oh$dNp{FCPRqnVEq@%ha*Bavx(G(qZ${5Q{pl zas#a_7+B9l#^nVfsm~qw{^uM{Y*9h0Ne~>P=Sb$fcYZ4E?@`$7XvXrdDWG`1vSgnh zLc8aU_+Ui*cp>gQLmc`)Ly?eL%N2B!@cP$OR6bc(vv*o5u*CxRtlzQA=Ob~h&kTw8 zGS>7h?gZSy>Y-Y!=T9X;bb6HFH`0&&d&dmhwZE3 z_!rU4r;hVNdKcxP*8CQq3--qz%J4|7Ji(r&XJF$I>dc+5%k51{(0rbH4c={FYnr2= z@L`6;hcjWtQ0aa zYn%r3AKenK@=1WhR$V;VaFFHJ#>2@`gyR+G`P*Tc#L9C(wo9d`NQydQY@G0Pc^{!a z`5L6@4)`AfE#ZngF%iA#yH}4X-B7@}?^Dpx{XW+mlu!3J>Ub#mEy}&qD!3-@5dJ=@ z<0a}zD3~hXpzc_{IhEey#*PS|u$dj&VF=Ip<4_b_&p%G|#moV;2fPds9~Z)4A&NqI zV+%77d7`o;8h_J{@PPAKQ2nNf=fh^Oy(i4jXVm}q`CEob2r?7!bM1cdkEm=|()XRm z&^jhf44LBvX7GAl$GK%DzPHkT`E!f8<>3%~-bwz;2`a+JG$&N)g&^Ikn72(`gjg5g zR`eSdNN*g~H+s0*Udc6=WZ~N?f*v#sWBWc!$9+L5Pr^9|N5%M&Na)3vI16@Pmr6kC1Mk*xYdB(v5W6=%Ck zbej=6uXMZOctZ~)8i@F7wd^pcjhszU_%r<(tsba;{tnlV5Wf=r0zkicQX)s zMcp@;Jt7Vy8>#Me5n#`X&~xOUM~y425)H@ua54tHnuC_GZo+|(bVN6L z6F287zgn4wz@w4Gh`BAYKRr>H7&TdFkz2?Mf5%}lWuo*MWvg|5fG&~!>md${5+XB(&v+Zcx$Z^t98Baz8W9K<*oL#Y;AD9({$B}N>p{T)D z_f>@ZW+j|>e2-5oas+`Rsjs|4{Dtni?G8hsSXRqfd@^!ZO~rQ0^)<)iQbD!kxP9v_ z`%br6KVwV0*DmK4S;Xveb$~V7FKYayB&^vxQdoI!J^#_-1ru3c^v$y7Lr=9K`|T%G zJR2-LT9XXFVUw^m{1QL7w+O$6PRBim1X0zXPMD}3$K;V;g(bv$3@n?5R)qi#*A#3b z|KiIzYAkrs7(5Ce4qJMUJgK2fFHw85Rg9+axS!C)w3U87MfQhM#V_{Mx%D zT%|lz)bdg`guG#~<1JzH#-rNwXe^SZQf~0)HTI79_JIRkCH#cD%}E&VK)i;ToubSq zCc^5$vjwB%0{)OVx_3{i;gbF>aqy)jDCx38uFp;OhkpLlSOC?9S9yR%3c3Z_;C;h7 z(b5dMm64z6@bun7j7ku8&2Yn;_%hx%g*rYcd(#l7$6_rNact%kcs0>|#HH7F_ z=AUT)%r@cDSRD^!35ba`!y!!-J}Pz|jLL}H|92B>eq)5R>ahsCT+iFTP`{oR z^e&4_M;sb!ibq%K_-4|?Zo5UG)nJqPD&qBS%_8rCk&@uc zo$;eN2(D(uyfA(tE)OxqwW}}KukvJUJf@2m7L`2wRu+n9Q*LhBFm@zi2=4BAN4)We z+==walJ9fyZILJcL`=4gcGQ=al*P6ZFE{oSu@>Jq@VFAX{W<1A$8M^4cuN7w$paIV zBNEO{NQaB5J|?TA@^JEL4?Mu|?w2P!HO&MjX`@j&qn`h+48jdPD`XT6;uG6KQM%3p zgYlMC(fKAkcVx;J?W?OnM?ijbwGBU<;aUD&C)UML#R`}&td-f zLkG^+e8s=HsjO~@D%vMM6f{;;@jvU5u|G%`P6lVhp68MCgWtYroG+;=TOjNo-h!6oj@uW6!iQ(Y0ZUgpKAky%LwbLveda0n1f3L;JU( zIJUW-cOe4he}TKY<>J1i5vkuNpVpZz>}4W#i!0B7{)8J`DIy2cZ{@(XPY+Rm1F<$| zrb8^&7eeGRv3bAn}p3w2M20eSU`R}h6S0zbon~&(TzCh-JDQ3k8%X3RfM#= zgN0|N*SO1XU%Y$dfZ0#&c%|qKvVXimbGHFP=zBdJume6WYT|b=5C2@%@brVBXu+Wt z=-=CjZ#PZ~hsj%hrp*NT6C(LMVl^c8ok>iAU^b;-6xxpT#;F}Gynasr%@}8NTv{b(;-RH@N_P9f9w~UZHXlO| zRIqKsQeZoNB7Qht;;#Re;=TsWF5_I0yG|#3-yOxVvM<8X!%^g&vy^lWuJMe7<747* zO&ZI_2nulQKOD=?H1lcH-z_6U_xtZZ#KWd$LUz*>iLZWtQW`!a>tT=KV%9S)5&{1# zP_fjb+F>hw_7*sy-?&r$`r<$adCGN+*u#U0m|rp(JIb5+Gp|MPK5GuCpx*4k^A^F;bfaKs zc8PCNNrtqoIY#VO?N*^%W2IG|yG&i;+uXQC_a?4h3M1_g1nbrBj|^--iC2$rH$bSu_H&y7jE ztRM-Io6V4!;?6GrGr>pto%)_#&&~Bhv3-y=b$$)ziIyQyT=!;^)Ty?SiENm^{fV(A*1mmyWJ-n51-oM)XQ3ag*Zr$l%#4I|3Um5DPF=O~OeKM^?gzJV2j*O=RX5`(n?r z28nJ{Jt`9Rwt#h(EZ;Gs5UVeS<9bao+oolNTy1rXG-=>7ZM~sO-m2pv)5NxqeG#7@ z4g0MR+1P?i#4Vi+r=9coOXsEVIXoAA|3tIhTg*^u`~TT)Vjl%dI}1FJT_ZkEZ}v#) zlPxEw=k{^LdJUQ`neFKZ-=OdLE*!cOD|$F19CdWF*X^e-%r>5fW&NgL@t_wq9ka>L zrmBtRh!#dI6>w=bM*QyzzUy2e+P>0z$!0Pu=Bk2T^H zhBPb64K403JR|K*TU|i6KaD(EDjOG>8fITN5`7%|09(6lMB9mz!iS;M=aOy$@57P& z;3i_KkhZ!1WiUH6Tn^WS-VzOGIpy+3(L3Gqh!oe*%mk)pK+jjqN=Zw08s&!`)RW%( zTsF+bYT!#2u$`-%uzZFb)(N%zreP|~;^?MqKd~lbTsV%V&VkQ@(|pXsM121dh;!_^ z=;o)%LLaNi65VDg?XYgt?{><3I+uBpg_q;iAoE~9%P`D@8U6nZ-FcNOv}EIuy(OBL zED))jdx6@eVkFfn8XgGNq644l=nP553f9?K&aE@Por~CrfZCUm1Qi*mw0U5EU|Z^SM_Nn z$}$|c#}VNwi}~RPZ3hR0%s$c_W7fOZc;-BTaHRsNn)&uptbUa#CF+PWkfk6eh+TG?CBiuK3zvks`g zx`eCz=|aGeE}Zi_&#WAjFs<)oH0@~S3wk`lioYvS7URfPt!NPzt=S+HT)xPQDaTsy z*A!XTRJapql?IgM`Ojl>zseXd9;ixoc>jxjC|7pC=-DA+PtSO;h&b|8w6f}ZUf5|9 zft(9fJbmRWx<_op{Ts*F%gG{49Mey7hczvagT3?r=lsmBeEj<8hKaTHOqO<~Zf}h7 zFsF`(X5`|7YywPdcbKml9EJ-MLLn8ZEGT8T;KZUpwDvFN1MG_76>os-f@kc;3F76i z(?zYyCi<+>oOHIt3IActddg6|JoQ%SSN)K`rq9Au$_oAGrT=+61X71wajh(qt%xvy z+fjWi+26n?)YF~uegLYf#)wCbT!1rKhS*eYAyjpwV1F-Nv`$Ro-n8PqADFu+_&9EQ3fZU~z-M0m8r3*D#D z4d8YOSEX)Z3%_6}=76njA_mTs$=Ee@8$bVf0W1etqWF_EdtllR1~2Oce0<7J?~Q~> zn1E5yvV8YYy8rHX#K~JJ%ny_Ze$^aUN6dGOga2~NHpHC=@Zu%32<^#z|; zOCH@XD5GWLw~qH*n~ok=tg$^`fwlOk3WXtq1i2em`SY26Xw|nvRIM#v8S(}*n_eMH zrN3}Kn>d~1$qe4y$fYbxAlIAv6RT#4s%Jic|A+NhY}H*fdKg-6$XEDOKDEU!9ZfU++t8gBCsab+;x zL>`t#R}9Hd5=#y>5TbP{BdAg zhdAjRbtXzlOZ54BWvMu`MLU!*_3Od!tV`AS+ynwO{>RSc4 zI>w16l|CRQ$4*p!ZWlD%sOKVV8meyx@%Ak-7+7zMZIRVPU3Mb^2k- z>bg53p|X}uF$~6*TKey|Il)i+yg`25D|FWRvSThHA$7qlVM=5n-(!}Cy)!jYvf_?7 zWk)uo=niYP^Ei9?BonQh1c_E-Z?OouQo%_6aZsc^BN5%nk8&rzpOEp%4{CSpFu2ze zF01keB}-qSf5SO8*{iua3;?2X0qDhtXQ)i4vf>n2nh zp-*xh|5la|Xa?v3qYvBT1k zw_IDY&r3CDV@NZwbH5DZYldP%T9g?E5H!% z67{gCuz_E7a>erf#Fx1~MjVy01ch1Vn0wz!xFDa7Hgg>mm?m?L^#$Y|osHHF5$xJf zGt})JCE4dgY(sI%W)>=12l4sq!|?13dAj7cGr3XJ(Y>8`Z7Xl^%Wf(7J0KUYeAPrf z0-gzz|E?BRyldk<{-t1Vh88ZwP2w-U=OMOj2D0tfGy5mR0bQz&?!RjJ(xOnP5-)d# zJNa$qQRZ6YipcwQEN`|q`uMmbwfkYd`)514*1gB*Wr^%dA7xlBY!W(09pv5gQsJ;k z3yXT55i5LN2+w)MmJhqdmZ-;KS}XAEa}8f|GZIf;TBBw50P~2i;b=PG3h(7Z1f7A@ zQKdrN^Q%jEBKaYQuJ@<8Bw}?u8%{Lm|Lc&wvLGLi+D)+UWj{9LY(Lm()C*BMt$d7Z zH2P=@Sll7YXFZLC-gj#(xf;U^0*o=EV~S+X_oLs_XXIle6s`EhArGvfocpoQci7i~ zInWp~1sD6|@VGPcVR1;GHg!klYh{k|lhSZAujjYd$3PqfNf%YfvqU_m9r%ORRyJ~= z6Ph!o!LO>02hp7GT;BAxJjFlSC1Hk% zzhvgmtC%9(TRBlEC|bxT9(Td{Eq-|Ym~pF!W%zrYxPLVB%~#HYOu|%{p1H~&mo1|2 z6lWyeTO~Tb^*&Og4&nA#Sz^OPpz)~{HqKtje^!QI!aCv%Y*J_6-YDVJCkU+j?S5J$dqhT@RHh?!E$<3dyM=%SWHw=rKl4>e~Q)W&{bvVk%9Xb$AYmvjHQ zu_$~u7v38CMP-b1+nX}Nu~8L#=rHO=nB*?eZC+*5XSF&M=Svo{zMUx$e;JGW>n`#L z>S^p%X%3xJ(V~Y*Em;3(I~M3a7Zfg$R;E4;3yOmIgbL~u)3Jrt>T#^wQbkm#$w+ql zwf0`fi*Td7;&<`-rW9;Z%!RY_C02SV3lj<^q2DQ8u91*L9BU2iYG25jZzWP*V>%Rk z{i??dNW|SK4ieVoT^4}i<#rh9ew6F(j6-{16dDxTL^~HV!7OZ+#CxOYlZ%hH)Zn+P zQS7Bloc8`Yke^ef^U>s;qN4|?>_fbNC6yrrBzuW3#i zN&gWA*W4Etx|a(tQ|tK51u^(tO*8+gBJXx57EWH4DC=I%s+)*Ca8(fpNE_@v&kyOR z?P2k0f%s)WAO_CxgX@J`EVn0V#`JDEqPdSh$SJ_xAJi+|!-EM682l~!;@qzmYMG3L zA2Wc~vz_8N$|P$10$k45vXHd7&^~5}0~S}fu0HLL=1x$0TWmJPk@AnS{#ZV0oG_Q} zk7bzw67Jc|m=#!{F%5rzy=EPEm*7sbE>g}{@xB@>;dsaeeWt1~DUD%Rci@fiCj9}I zdme~iaaPzk+MT~15CT=&X^wtKVs^w%^r@SIsg%3y)#{4p+o&gKoxFJY`U2d0YmBcN zHbRAB68UBHFtaS4KTwLnb{qQs1h}#UeN)sN90|+8Ej+J=yqO{^3^+1~-yr@<68#F{9IygD&lsF=m7;Bk^D9ky=>8#y88KwWJ;nSHd zyhmOR2Co*d^6Fsbs33)l2F;S0FAdsx&M_=A9LdEMi}8KkYzgaf`%fdd2>+Y;y)Jsg zWR4pyUV*stnJ0Ed1)!hXZ5D7m4I_7HLMt$hyDFrjNBb0vGIU}&AIwlbaR@vqBT%|@ zF?GoT{bSdO^`}JP=U02EmuzCQ^XA}7(R4^rc$4h=364eZZ zYn91(tD=s`V=rsJ9FE0P3vEmo*vbyhAO;#`3Drw0xd!gee7v)9*<%>|G zbCk&|%!Ny^Hzt=i^V{+{hzy*9;MYZL74;v@eJ6{1a+i6h0==PNh@U1ZwG;AEFz^v| zJgfE;debdqj;f7>X`ePF0^h!S;Be#xk+k;&K~_UuI8E8}cQf5^?-;#XRtx-8ej%Re zo6#PBo{c)41TPakboai*7bF(one|+x1eb~;d$wZul4=D1kRkp~2>z_JLF1cM{0aT6 zFPVGcO!gEuCQ*^P=Hw+aUyt(NA10E&TZmNy zn}dfxp6fmfUQN$RI_yDv}3als{%Zx2OGV zp}6xlVch5pOZ8P|MvJH??tnk;RgV*%t%<|q zk!j$C>-a4pAFCcrgT8JD8$CA}<~vANU$L3XOI0F^mcMrs_1V~!!(iI}Mo|C!fPZ}y zh_q2wl0AP*crgARpbo?lNo-7i$}MG0L9X|8o<7u_a?ix-cU2HOdgUUQyf+s}q0+G_IfQ&Bid`qCQt zBDU-~@#MR-aP~I&D~##0l^DVm3$w)5{=q0TnS=V|MrL-`8`a-j@Y(VJ|IZ>4;XM*C z=EQH2A$cPXG`0u^oA>jl5sCQbql@i@wc=LSSd1XfgIsbAJ43AKyqOH$de(Bq))0iw zwnjonf3u}Bq0p;#LHiGBLA1;VPF1dwJ>T_{8?;}~!^?9bwuWxsKGJF!cYF)qe1rUM z8>gYVpg&ujAqBsAO%lHGR+VsU^bujGSe6@lhQT0`_Q0p%tdY2zw)vXq7<-*BBoA7A zPgkt4f;jt46mpIx!m#TNtIA7-nVverJyW>mfpjd{G!@5;=dveRA{^W>Sfb}VDIu

e5opx{MgiWm1$hnw(kt+N`ukeQFop_k_5<8niMVS_K+xiekoO(mSh3=0F zXQ@eMepm`+TD?rsrv8rgsENVeNrsY}>;S)|c=y>FmCg!mf{BKpois#vKlK_P-`5}A zqGuDk(t!`MrX0}GPy`*#XOk`)plZ7*Mo~sg{zp1`jL<@`uZd{wp8HsKV;zQg)d+Um zqH)RJ0L#yYaDTUG^v#(Lx$gn˻IdfF53=C|^XX@U5dMQo;ozWh^^A6mnR-RiiD zCD3kM+~@_5gUx(vw<4U4Am7@Lwd`Dp3vsq&C3=ojck=EA8KQKgYHj3Y>RelDjZKfb z36np>;>meOv@Sl!otK1SM1NOoS$9rU)Ng_yIyGLR?R=r^{|)j&wcj`AmZTTmbP(aX z?*-QTbrLp>o(%7Pm$;m7C5~5-kM`wuQNXu*uoLZv#tIn>*cl9O8!ODdUcztP55dpk zxtMT7hmD|_)9_^scKF`m587Suli0Y?F)zePv~#tF4FozGxaa*PIAl(_Hk$d;2INs` zHlTahD`qey9K#lgupqUR&pH)}+=;X^wC@uwcTf_9gTn+H#d2=7#v51YeX^~)HJ3|x z1@#y2u=K=WVbaj|e*9G= zb-H!hq3)R~s}356O<$xj*!V7QaHej!co*VOd=pQKCcdjj3O;N(&k6^mL35=#eDbGo z+3WH6FIQWVrRwo&G303f`KRqvI>o@+&jHRlmszV{5au~K53mWJ~|XHI}hv3DjhXRqI>FtKQwk){uR0{?dop z-i^lRANHur?HFc z{16~sr%N2>j8KV&FB{~JXfNvH8@!J{bbEuFn(MGX>ImEam%-#rZ-qI)IIg7| zQ1dSF?;%mB&lQkPB`vx^E*Sr9D(T6M{8;Zud>`$B_|&y#BeyQX(`o)tvR4$!vfOcQ z!90B1k@=j>0}Ul%d||hHIPCSnI`Ucq^|5?QYk(;}179o%6vXdwH>TdJZn;PR7we5T3Z? z;n!LLGWyH;dt%MToi@OOY**HK$rM`#$x=46nTKmFf>xvzR{tE#bv-D9sP721&jIuC*#^+;fe^59|jLcAS`4n#oqqnB9HO#`L z%pSiACPuxpq`PX^Cm$Toae=yj9^X~%4r94_cy?UG%KTGctvy~c^Y5?8#Y}UCe1jp> zZ~H`W7`j6!cRj{`5CcYPln9}^BY6$&{Id1Lz#JaIR$ev6mHis{)!M>G5hrA`JM}3i z3gWAiV_;~Jh}?N^*&3b-(;;f;*Okmm%ajSaOFfHg7x5lB2}l`ai5V&(%|o}bLu4@I&2cX8S1&`oK)0sGX(WtF1j+c6;YG-p}f67@!n!CAdKJoTX~;!TMQv+aer>Wd3>R}Fypd;>oym53LO)NLJKQR~w? z4|=M0NUZB27-&VJAec$~_PcvT;q_;Fv#i}GdS{?0gzc3U-mG57jm&&-`rcfGzO~{R z^!)5w}^f@v_3Aws;{L6au?U@k$ARMu4%%FA4 zm;cm_hAefUMy?spy4uH4@7DijzFl7*v~HV=ix0kuH@;YcKeDO#LV8!VQ7UYYk4KMO zJwE!uMvT}%yn3A@%y?rIf=UDl8zH8evUoIy=MQdR|2UCL_7I;v@fa_#3dc~J1?brE zQ1o6(5VWq(5RM$m;zio22t6_AAoF$# zqEdUZqR2-=^TTx#J>P-H;aQr2#C!QDFbeC_7}`tA*xO#FFi0BRZ< zy*=Xp-bJDM9%Z`}#4JY271oCToB3N${rlYUM(c)hv(jw|Fd0NFsu`MsdagU-9#D2b zH=C<|O2?4P>d4!EhgthBMdcZ7WSDH^Uh@m!`pW_CLzS3X+;H@|@mlD%^8t6Fo%4CQ zHI8@l<^x{D!+oz0@{VS)ngvG0Pn#^6`74jOleSGW$Vy&ZBA*ZQJCx-)Y9TznlSEw% zI@pmJ$8RLY5u3pPy{@>j2kGQvDv*)v`T6dlFeD${KkntqwjkPJsXJJ-g)LB@i@x7% zQFP-9Zyb>dpRRP&{ih>3lGG~fxRfuXj=sz1rY2yL(nS2o(BS8G#h@!yA6wFknCdSV zj11Pq8seO^SO-IA;tb?m&JvGQ4M$+^T1jh@s#7)-ve#rf5IQL;PsyL;ouh&Iuu z+lr{OY!dD-+|NJxCt%j#iFng`N*tFLi*w_r67T33%XOshYpE%|cAes{o5Jwqrxi}z zlrq!ny$FM9iQySCM7Yr14`yFo(bc?yM~!ty?;l?9&NpLA)6$@`emoZSB|YD*42d@# zV4y+!@S&$defoCcV(Bq%xM4BAR+zzd$w&?s2GevajQ0*>{y8R?uAxEP(d*n}_dLX( zpe~zb!38mp7{hZe4F~enIAYK8vchF z=6+iz?pK|NE0ja)c5xefd0{S2RWlsB+{k^MQepQa8oqH|X0?>J?b$C3PoGW_6g$%} zSxpVDe_z*58n>Ks1I8F6|Bh7_5NrDRRMd5r^Q!tJ1nOBy_Wa3SB4N*PMd8esSGna`ia^ivnQJ2j7g_%s|sUbF~nqW^k@!1Zof}E=eIp3W{w~tdVIqm;VD*i%c zVl0NrO@-gAMSPQ10+QTkV3%4ji(N4W%~yIz_WX`D0r>iD7MkDo;;*6?K#TlQ5h1&o z;#C(+sHBeh0nJ>^t{9mDd6jppV>v~x7<+t#MB6D;h(W<9`u*9iT&pTWJ&Z@EBPP3x zJ^K-X6IV#jFF(yUj|qcC#T+QSJS%D!w1vuo@sgQ;s>K8Ss24M|Uf{d77Gu^y6G)Se z5n7WBcPU+*I9$(bNheAAVSz;}3q-E-TQNX(FO2?D82R`^P#~36I4?>8V)p z?iD*^xfp+3smtSgDc?{Oi+icmSG%cNG_0GVpt)p-Fy+NsUi-!yhsej~@!gWU-0nbV z_xCWa8zKxyUjhY1MLZc@$4v&7Vk5l)O}w&1j+Q13?5H}U%@;;S8s22P%4K37xm>xQai=Bs?l zL-YwoETnR_$d!7tzl-pt#Ou_kO$oT#;Rx<=m05l#E{8kiX{VegzAowK(joAaYZJZh zD+o!8&4ts3S={(#8tfG4?fJJ^JT#i-zv(1A>3NietEA9v(L}<-kxNWLLyk3GEUpxN zN-V>!^C|G$p&|733&7%rS&}_JW=H^5zIDf9J404@M;Ym-=(FkAU9M(RfSTb3(01<4 z%*xw@=Y1-LlW!Y{MNHoRbOR(sEAgt|)CsthL8hsU4WN5v=lHSMO7F`5R??mA197L% z(aayU07@MmkeS`WBHy@UX9MMZHtps2l`}E@uLfmvteKOpfVR?J$kA=#CrqegSw|la zvv-M?FO9+|8HTClwJg8O1#%7KSFUN~N}mG|NsQq67DZ-7rC~6qw{-A3Md4LdaRjcciM*@FbYx&3-OMkX3dQbWR!9mR!qa?$km%)rOBXk@e!^UA zyFebHOILVwLkIO0zJuTEjUqp~p=hM!3kH;Z*i%einipF5psvAP8sadsRv$zCi`h={ zpyuU~pJe@I%ASYdrQr;O%wHz{LprCl`Wzf@yvn+!&Bs1^OLY1j;CZV&kVxGFPlDP+ zj#HHIP3@Xw<|kz(;s|+T{xK8Me&)l8{&uuPEllm*VmwPVMa=2bTs}A)QbVmI87r&b zq0s2%jO$v`Lb#7F6kF#?JejULJdoT)JEwt&&CVy*T>$;gAK%LNd@RG8Q4W|IsK7=x zJQI9IZWji1tKs<*7E=$8iG+1*G9d!v4qG9tG@SM8V~Ud@>L`BQ!hg|zls9<}nr{o@ zzERXea%~=UVBBOgFQlS(z6x$XOyb7<$$#}(8@Y4r*|CERdI1B81=hk%-6J4tPM;sc z%EbRXoC|t5A^-L^wsMRM7Ht(_Qv&sR7)4?cdBI@?d)Y)qMpArM{F6_yvLVb3B} z?7sP`w#Y3V`&1`WWkDO8-z^RbTKbr$Q_kH(sTbbT5*4-z>`xz&@MZT{;nI_ryz%)0 zoH;a0;>mpUh?qsx?{-Wklhqqe!!sRY3>B{Pq)~;a{%e2%uV;yNFVBJRFJpYO^b?*r z#9{aXeLPNC#Fq^s--RZ%Tkot${lAIA+0m+!jFoALJ9T(@g3dvF?W#hItE3K{ytAyL zM+&~b*OoBQTDoQ9tkn#-^ehl{#I<7D+ufM3eFXMJ2jkj9d&!(vBIeoqZgRNa^A7(> zx|HYwW%)0?636~>MTeY}M8j|Cmx$hm6R`YfdF|l^@o3VWioTQESz69wcupdnt)`TF z&5gsV{dVZPyIOQjMNzn3I#_TkSj%^sQny(3o^l}uJMu*M znl5IRmBeOHnF1ZVMjjFwib1K=v!lP-?DGfGlWXVUbJ;lIwx1Vjw|nDES2mxKyBv0N zC*onpW2QVd1#vJwi$A;3chEAH{e3uk*uE6%ras{I`jo|XGlzcV{DywUPv50iYTo9ZF+&kUiLToNWx4&tBpp39`7 z~DmlK9{Q%+@A_llQ|3 z8k?kretZ4UuWT-C>{f8E0`kavcw^*b#yr~6u&hW0I~um~vjdl*sg*eOsr{LncbgDD zYnx=w|Mic8y0s}LoE^zW_gsvKE=%+|9nNO?m?Ak}4Vy{dlNQaRceWGmJz?T=fj+ox zFb^HwZ?U~ciF53tBI%_ap`L@BVdU>Q=FJW$2~emWKpnU(d>kGD{S-yO}Li&7l*5AV}cevulVK?fC zYT`8wnWzxa-B6szmMwNesN8Uj`qIGP)RT|;fF3&DD%YO%ih*hKzwg6$_F+{jRGvG- zl=kyyOT$n_JckqA&Wao>CklVJD+^}=a`=4er={8~dHj1uS#yWlKaH!Fp* zk`r-Gzn%xa+kmGd197KiyQrn66_=jx!qt!w2pUFtrQ_x(DKFvDFG8@YnwV)TC$en~ z%E$^B4WrMu`GbBQcyz-98`55gP3+u|&iZ5cZqjp>CSfoAed#=?s8wB+2Kmp%2(J6U znzlz_P!jEzo67jnxCF#pCoYHYL6P1lMWH!=kWkQnEk92F*dZ>?_;J>XuRoWDWaD%M zuBc$OZV3<>jzvw|d7kk!4RVuo(LU2p}^{k@Wfwe=E$#4tr;bo-^at0!-ht5I-ItW>1iY_2-o(O#9CZQt@cD zHZeI@vPkNO*)rJ#x@sP$zP(GMu4Bs5Qm0aHbw>WUN?!iUr)yQjET_eewejYuz;jm;OXHLUIyO~^ zG>l#oFX0TvWv2i_QWhq|r6nOqd@ zpT#WYp9{OJ)(ekEHSp{G<6*_A&q-C0uUZ#_k@9BfQB%fbjm@x0LmnG^n)&EK3*fTW z2HSiB#E0brF|EN(vfF3&qrcyqKG-Ey&GWsB@ivh%lbv4du!}P0XWSPq7FF|a^6_vy ztp`W<-QuejF?iNsD%tIa{~>m!jvjgpYvfQ4$E!?7^t-m&Z1HvK(4o6+k6tQ*OQ$!w z)69Puvz(W@q@&v;6%qk%v8dD}SZ&k7&?{B^=8Fy_-QI=thAeh_$q2LtzmVjuc2lob z%+(o^ENy1r2<$X=lI->$>q%!Fp^N6k7JhyQG0f~dai+Jt*z0%!w$$oD*k&p8B!2J6 z@mlD1C7OeLi8|w^p=Pc(yA2U`z8{8&mrcBn`66Ov02%WKaYZ@mP9N=z#MZ$LiF4^rbnup?U@^q*;EfW{*jKmAAIgpENV)yOlW6Lu~XxdhDhx)}BLGSjGbKga> zeJC5(?~0IDHc{?W>D}M&9fPG9sJ`NT12q5FHNC*Z#)K;weZbDiSI>RcegK0 zyxMUdW|jD$x5_Pct~4F}>E~-Cm&&hf&A?A#5_HVwuwJAM?*1W#xx-rcgfW!I`OgR| zJvCOtYHo95^tScZ1{s1&@X{C>%B1(x;8S}2GbFND>9{8dWT0z_Ix{6PlT0wNc@@Zx7@HVyC2$*HE^+Z5_-sMLE5gOwzet;C`i+-BzEf~ zQO?@wLhA=evR8xrsI#||^e_Kr@oe>E%GqckMxOY_pHeXEuOaO2P!CsK7BVl+!ut=K zMYH6y!LE4Wd#@2fx1$RYUoca$=P%bGh9t3I{>^-cv8r^pQo*#bcX`&&wGg%n&{;Ty zMHIIQBQn+rqbScMc*SGfGCkN#Rpi-y6A(U7z#zx<%=efXvM0z(^c;nu3$gmQ4Q?tg z5a;Iwp}x!=HJ;bma zI}dmiEaUU(R%iun*zbMDM(jw&3b_gR7`~B@9FvRwFX?{NF2|ZKjKHqA7ZMGBV@o(j zt^ME34`I<5T|^$Ujx;ueI#yabbR;vs)XxWFwt7o4wv(y~piGSN^@}Wpy2VS8Q=tiN z9nIA*(C=ih1*BJmu|xFs3i&b&m&P{pu~VpHx)RhmIEZV0UyR<=)8l8hgPl|%c9Fe} zWY3@T>n+?Sy@koqjiT>I9tt{HdBPg^d;H3sWT<}BMEwm--a;M#QM@5`pIpOAd%NSk zh8l*)UFLe-La~_aJ^wWPair%QsiLRc8_z0Z z(7Z-r!Q1`ZV&zh(glNF_&?)hA+gR9~(j_Ls5!QTwcJ(2&GyJLNeJXOXlCm7fTE?0U zn?_xq?Q;+^Ww_uC>PVUGh@H!GIolG5eIP9($cptnnNB@s%J|n^wXbIZUN)N|eZWw5 z@613L?QIas7C+^dG6|46DnitlG2Hb_0>0VN-EB%dGYB`syz%1^m)pXt1N`vX%L$hq zAy#&pPi!;Fb$Hxj{iQSTBug1p390d$IvpDbbKR2$KLNE-XGHU&1%V!Uuhrmyg6Xg$|hy%24^ zY$SKvEtIX^bjwAu=U;kegvuYp6Z_D@y*_3kavXV?#+r#1k_W)G-T>ZP<_p2HOEB@& zWJzD)+JsE}cCx{{fM}NeRUTfp-Qarb9yje3jBl#8Xu92-&k$4R7kTi0KitK{q3&2U z$yKuFN0(ms&RUfUfM8|L<%f0n09rsT@jHu?_z;} zUF3a-zwa_KMkQ{F0xL_^R^Ld zV#~&h{Inc(az)O-Ufn{Gv&wxOt=|EUSHp2RFBHd#VRd703AdWN6wl;6F(}=TO|DWQ z1MMgb-hP{p{!X2q+vZ8Ss|v2W;d5MH_?wf4+=sZ?CpDmdr@YqnD81>PnB!~RU*-@K zjfMrrnC4i8J8ti<+%_?$b?z(!xu@j(nul=WgU|X zNW|9&d9>X<&jWl{;QB^m;+sW_q@J{6WBv~0d%qVZ-;Bg$b^4sn_vNzcOYz8x^q)Kp z_QFsZV?+Np^Hr|;;Va#{ob4&Z%+Nxj_z<&?NX3pn2CzSVk(-6m-|Y4om^!&qbjIT~k~(Uk za6DD;wF^PJ`79i4Ddbb2kAG}wN*SCQCtB0~6?-xSP zhiiq;Rt?;+HjaGmx;UUUj=wKi0{s*-*w0_b-2LbV^-&Hp6KTGES_q94Yb<*aApZLx z2xsG6C0vDLrCz8YzmC?IJzR8YCHyldqhYuko4HU0TWjtKvncy{X?+}8uIs{k!Y=WL z_tX_4V}p@r8(E)gZkXUd39g4Jb1fAHyQ6lJnSV?=6gxdUupm)ESmf)4y^8KwTE2{L z$t{GGpC0VW-!R?#^m7Q%z*5^P?%JFIlXzq3X%A;hUdbTF@44XS{E$BVeQSKcs#M0pP3(u1C*)%H}iWujzq>8M`-=n&XT>|@bR~m zWaf{!)QRI`Ixxg)qo`fst#Bv2M7a0&CBK}M1cjUGl0AQLL@xaD%(2FKBU|W5cW^cy zJB=>$L36_K=3m6Vc9~c!WiiansV8gNRhDJ!j~TU&SQC4I`wox5^+AiU+VzX*DCrhy zZ4H9Ys{Q;ieSaK?8TC)YmorPnx>ZxrE$+W8eD@FmwC0 z7<;NIyM0qyxJ&+U%N7T$JWTAwU6ftj-H!8}jqLl)bO`;G@agSVzG~P?$UZhjQqxfO z!{)K@N9BqCw{XyDRHPcW@I7Y`e@GTQl&XC=!n={+O*MpWCoNVvH9W2~V^$kR7ii z+4C3FWuWkmHZ0G!G3gKS*ylG1n)lapd(snZ5164%Z!`<=wiUugj~BFUKl7TLKxn61 z6LZ0yPkco;%AYP+Dxb+(JdI&xWC)wfEz}J`dJcJVcpqP3eLQi=&P{^KlttY0WGenf zPbao-DC?W60NaMY!askG`Ll)S`@sq;OnQ-yN1ZI&U9jT)E{2EhkecFxR{^BwTq>rn zBz>GsUdyrvdf@$gX_ybb%;%n^Ov=|u(B7|7oBA~l4GkvL%kYEADN;_&k#bCwx3%gY ziBqQ>@LB1cDAZe5ka?se3=`#Yi&kRKsJo%wN5r=qtboSeiI~v;B=ewq_kv@Zk~x1& zsQ@-ttubN1Dp8T*eb`oQN6WI|@b(SEi(|w9*D2vMRwUpSy+@+=PGy%pRpD@Sq(slL zxaf(S!`*QH=X3EqLw6_~>qDNd27Y`(GW@MIaBWIO?NSBOx{nx2m^p{n(i<~=8gv6o z`3~xv{3jKbAJ(~$kcm#^x-6v9>VRP@kb%4KwSxH1qE z?%v^n=X@bYzDftxZ{jhX!Ng-&fZ>Km+4EKD$T_Zvq3wEH-Zl-p3$!S=U%=ANL}6s< zGz{$Namt5y`!&POvG>tA_Sq^34Ql_J^U}ppSoebbJQfc{eI8l}A9AKkc$h>O!Ef@_ zjhxja?mIgh87pX}Dbih-{$CUN8^C$pMSkF8J|2-zYo6?0QE{(i+@;>@hE^#d*e@9V zV`fUaOD2wpL%NDT?yQ^6R8+>J%agpRfA8?Co7bc9rU)g<(rodVmx9-nwL-u62L3^J z3CfS@!sf_0UgsZ)pVbD)&R@-1AB*tXOb#)j&HPteAUdC0Np^elv%!eH{zyugP170YPS1b3c%|sH))jsXGEQs^(Rf<6%yo@Lol`#LqHvkWw%k1=Ft+ z8^j%oOLWmKi+p8vp|IX)i(1zbGj-A%y_7ugyj?*UtKtnmPdCY&58l5L5C7A}z(eiq zO-eG9R;XjpoGSjhI0u=gz+sEg%+^j8S}tvpIbZT448B@|BzyJKDICSNb{Jid$lfQK zqHc&bROYwv#TR^_`;>fro8`qTv&$&!ZHx7`Wz6 z!<5A%`R=33kVzSqf867f(?wXhUIqUdw(y~L{#f8jo$F5p@s)+a#PjioLB<0nP|ozU zt0G3+PT@yg3h*Jp7}Zh%>`WJ+(bZ3)=h&u3!GDM$#!8im2OGrV<_-(&3#?*Ex8112 z-53V+PJBLk0UCZgqH^LRv(+;qAXgp?&A*d{Z}FM1xuOKc^p4t?{7l#uYQwtpIqSJ= z3HF!i;_93AJk2cwOB!dO@7{52(6;e{^0MB-g+&+nEZHEuDJFm8Eql(CgVC2V9euB7 zun%>{NOLzpYYypDip$V>TLpEiOhrA&XV^B%0F82fg36#|BpuX4!pCr)w}&z#1H*A= zQZdW8q=3ube}w1f@9_}oi#%mWUMZViyrU;|2d|z>cbQ$RBFuxjMaaK8t%)};$UqzA znnL7q*wF$H+@1Kpncw^K5^TGoiyHao zZ+kA*Z*<4wUVUKX(7>zLCZlPly2OXygLd<3Vw1kF?O=Ipqj9Ls5c{f1`O$&IF{NzR zi>uY5sb>_0rN&aiz}uyiNA|^yl-WohZONN&(CyNHK0Y_+GQ;SlIB`-=vfIn=CoVy` z5rS%CL~&C0VZ3iWHjjQRYZE-+^adC2A>K=Z* zyaJC;3$SwuWq(D=SU%*oAfvjUdyJrLosO=Anbx-?3oh!`aO``9CDL0wf0-`sP|oNm z`JNsZIKri&)Xec#I2N>%S8Uf8(%w+{DHS^F}zO#%g;4MRntVo zTeR?5#)zdYO2OY#o_CU?5VI^5PYX3*kr&JLd!}J=pU2t3>0KJB7~r zBFS#=Iv^F@eyC9oq9&KAiiL^RM5q?6WR4*ocu`Gv7wyYD$|(|s%47%InJwP+G#bvP z4%qPU8tWJvfV-RQv6r+mWBN>yE_jJppC~5%OBuC2>m@T^yq)we^0Wv1I3>>fFB?53 zm_gU+0{iK(gmTQrcpS~CpOF|x)C+9CqQBYiuTl6MZI791Lxorce`MCo##zr?KI=>; z@m^j+XTxQttXG1|S$f#oahwNjDTK^$Q^eH{W9It@!DhonN%l&ecC+)g)Qj<9B-c8h zMN8%!oSvG&0y{;B?X4o&?K5?Qi8(z7Dk2MUjRy5WYx|I=?hgB?o`JLP#$s3h6z;U3 z01H%%5MANVGJ>ZA7X9$2XAAFiiNyH8hI<3?1nM$aw^S4KZ6Ke? z7P<#LEJmGz9yE1kiwsV$z=f{{#BmD{!j4lvNS+?vy^G+!D^g*d$xv}Pgsrh0i({_8 zg@1a^IbzBN_py=q@W-T(omt(UEs4CbCECsnD$_$NG81% zU(Ren+MHn+J}w+rOGL12F6Kk%e!Ag_Cw_Stv*SwR(K$;Np{2Kpx#WdsM*o}n^=j02 zJh``I&)?UXg4Hk75L{GIyTpusKgplt?EHf@R>mTC*fgw4DC0R(mSU@v4c3o6Aj%l1 zBrMP9FO1z?%J)(aKw4L`odE*Us66H`}du+>c}5FSxRK$BQB#l%{C;E1}$ zpJGk7ILx^dj<>nBEOQ01FM`HNW`164AuK#i5v{s`6)cK|c9;QDsUsz+kcF^f!8k9CsF{4n2ObhjXXU{?XZEi9$E5rB`O z7Hs05@p$xJ5tp~#;g?c#F?9g##wLG79sPTv=;UreF6cS$>RN(s)!Imo7{_Irqi{xk zDtUKSvr$(VWxhw@!*uc=KBT)1aim4uU%Z<=l0}Mz`)q;xPYrl2s5>Wz%>aOyrk&W=RB^ zR@mak(p6?>Mv%4;<&L47#tO}!yb($rF=>;RaWDVXh*Q$XneHFi>c=Ulc|D%c)m2=n zGY9q0M5LFEVp+Fkv8DBiByW3*I_Zk9n?Z4o8#nhRy=a{c!Uiv4gx1H4Llbb-sfDli zo(Chk`DOhcBX+JW#f5eQ6iYb@yYHnTvRWPOm2o_8csj;DnF7~BZ{}D@`JT)nn0UI0 z4|__TboB53>o;kqpZl6Uv*DPxo!y_{4zI!)DD!UQPFD*=HWad{)LnnakX#F%mb)r=p#oEq>WM22O3W ziJf?jeTWK#`y|qH`W)h#QS?>~4aRJ%ucBrP6-;lsApH5Wk3X+U#nusOi0xi0UiG>N zo?C42+4lxpaw`qr$;WOq{vtPwkHptUjQFAb&1T$+#>kVik!U(p82gUAKs{!|KO~p; zxVZ!miX$+@&6#a0Ey0GhlOf;x1mCr@0M+!jndL9dt_^!E?3hw6d}%+xE6>GX)o25F z-j?OzF&Wg6MHzXWRF>gRUV39?cxbioM8$=O_+t-qsp;awLCNU&8I4noo$P!#Y52YW zH}h)_7sBnNF*L6%WYaHA$C0eQaC+6uckhnIESssg`J+^PP9}~z7tHZyL>2Q@_JGfS z)J;!&{<{)-zfd1TJ8w5z&f~Frc{pASF%%-MWWYOqEEF7H*QVadz`|Zy2y=SI^ePk4 z?xiE)r@fJ1ft|i%Gd*XDQGi1JA;}i3;;J-={N@sG} z78_5zSuz-Nn;LldgC#hiN^h2Y)|udU z#0t^&m#y%5uo>44hC!--1Xlk?x0!Fn+;2}feB5WkLw_Q>M|)cy zUJN)ek|mfa3T>@@g^IW}+<^S&vWsS;Bj1X@R$2hBaxd!L$YDYV?SZdG!T9`nZd6bR z=Nx04TDwHF!H2v$RcoQ>_DC3P5(}MZ@}GP7@$33YxDjYgTB1608mx*DBL_&doq}hS zW0kf;OpmYP*8Bd5^z}sT3F27BXJD!HSXg)I@g;u>v2=`yr0Zld?W-?lPeq2R`zdW= z993lq2)KEU^`H#t?|Lf?9CDN&BLDW^uX9oK{FdnFaw}oM7(v*+a~XHm%fOD)3KD;2 zrT%jKsn$iE>}l2~APxS+6Og`jfe+t9Y@8RCFnO~{v~?3PUoXtSmUDdsm+D|-jI+cC zUcfIpMx(vM6IP`n7QapnMGF<_@B9u=KV6BwisS*79mW(D9tu_;R|+F6&TySG37GnJ zB5ZQUarquG)MKlUM_sF#KFu4)FC(#*av$}kw42?Ufma~`;-{o(w7r}Q1JMokYPK)5 zKDeTD#y)Ovun3WJb#R3`LFDOn^CsbjpqICwe^yDvc|~nxz1bz!PKbunG<_IIon$i1 z6SrKoB^v&)>KK@X&PKUzsadLcF$QP5L8W-C5P8`LfiZKjnJweBkMeL_P{-!(&)D6x zH2mnTCb`>wr_R9%Y66^&%CVXD&jj0;9fGFwHa=`z1Sb79mCSq@uW;zl-EFhi64s?F zg4G`_$)5l53w2oJ(bv}16Vi_vn|48Q&k;`%Nzc=^i?VSBf;s11~XC^bi?Y9s&Umx7>`lsDF-ylw0| zq0ymGcx3;IZ~vBpA>?WI+o8e3O_HbwK!^MT#Y|K%X+F&{*CPN?AMl{#UM{C=L)PTpV-RU8>~ zS{&(;jJA(Du%C0By~s|-EZY5?4qfEo+o&J22PE3g5L4RUYHFZSo-Xt{6aYEc;YegI z4;vc_pFnV_!4GO~$)7PxKM+Uy`mq&_Q zGQV*;4S%{5^VW7YiyUB%@PmEuZC^9@ARe-^{ZvV()s@yLB(7x$DXd^N^&ZgD{{NZ( zntbo;>3yivX|}yvEK)?o$`8{QW`}2D#4iQB`1rc^PE9)YTd2eI@ng1ZLLzxKC*uD| zI`6og_cx3ql08FvQySWu&*yu!R8q1-ilk`oslACJLdeQac1X_$g|f;jBO|k6uVWs+ z`#it@&g;Am$1BfsfA8;gU)TG3a(WX_G%iFe@vl_2>aui|v4Z1}|Ihr8ZsLBtaggl! zBD%dc{Y&oxj_>&?><+%q-<}V`tavBM%zvS^6q1YwZlIe{ajJ4-;4Cq#iCU60;he zG_Ot{WNe2@)iA98ME>3>wun<+!{3EO;D~54?jF)- z%Phy@%!L2X{5~JNp+%XCYLyq_NVR$3N2Mfp+YK{Qv16O2MBDKvU&_#-hA`gJP3+TX z_*^hW`PlXRWLXNPJa&dl_7TzQC^ez5tFJJF{=N6?#q>VzCfV~}t@Vdy>O4H0l*bYW zlV5k#7>TxHH@^tZm0`{ zcWT0%jz#}@b!N5rBX*Lzgr%0WHUv$Ye()})9^R@9n2u7C==mkKLz@=f{&^U*d#8ZH?^6m~e!sxKa;&HUBU(guZJtQC@dfG~L8mxDm)CGvBu$ z6U~askkh*<-fy-V0S7Fgcj*#i`e_&-V}wNMi@dNp4|ZQ%AU~l(^hPNj_T(adyjxmm zAm8z3UGl;$SjAU;3M6j7C!RkyV?BqB!`Cw^*u1WlFFUgt0mMZQ9XN~)iD(n%tF031 z^EjXQEde98{(t7b*dGHHNetmf>sYRmfR>`sV0W5$)ivVH?sLSq6aL~$UqVqHI}2}Q z?=Z~(A6zB>cF?8+d{#ym?tEAY&D&LM{5y5T%iR(dR#oyq#Y9A%(nHs!ed3{4A|XR8 z);&I_nUfXyalYtD^!zaLg!|Mxqe@s~+o2tS_vAVL_pq`sqmp{yn`Ys+Z4RHZcs({> zq&)2QFRXQF8Z0!mB>v1Q*Nqr{YC5zIjb}@5KNVIC+AS2Q@8bU~qQ0y);*bQ*;oE35$~@dx!WpM6u^3@2>ULVv!CbZAy-umKkqg2 z?4&4|Rg0h@&JhpZ5D%+s9ti4rlYM@*1gEHnx+CQu+0=+<`SSFQ96F zzHrQ92}1O#=a>AM>f*(?r00bfe*`wQ|5|u>O@LnWDc&=w2s+O!5VvVK)AAaOhZ=Rl z=wnZLVnz&fdzr#7dlc`H9}SlRhL{H-%!aafb``3UnQ!&c4-KDc{H zygHvQWMId81?=3soM-uDfZrJlji{+iHr5`;fAqoj@@9UgPduL9H$&934dTV+QN#=p z;h*x&Y(d|7*eXk&nJrhi_V7d~K3;%7aqn%(%D3M%vk>YoWa5~r5*h|{);?CE z+X1mhiU&Vs3j&hx!&476N@cu5V+&$JmmoY{#74`E6;2QAC6pho=Mxf_B2>p7Gq$?( z?@jdm{Wu**E@msc{Qe%FWp@Ad46(tL>T4n)bmMjnxzh|h<0QFKea_TJezcvHS6V#7C9w>KQJ z>D1fxteV&Vjinw9cO2?bFWPy;Q0SeYBzP$1@q@O$*zjrwro0jHzH4i`=YY9ZnGgAwYVQXp;Q{yz9FS;(o)>`$9O{N~pugYz^fDjAb8aDa%>s-to{q=Qo{O)opNA9gdP!#feBCtM?xl%W-kWPb4O)RuC{Iv8}SP+^0xuO)Qd{bZu>i;2R|K! z^Z!^2b!RhqdT}PczEs4v%gtirqE(O!HOG*!i|k1+Vr4%xltujuzv~p|vHR#CJ$ETOl zEN^R@a6f9Lko!x_&kjz4HFY;E-=xAX3PteAorVNdvDxp5nZ0Zjb)q%#vGbQ9=f7?j z{l((L)?wIfGeffHhfZ3EJzX;pD|e7jKUx5mq={}@50+f1iHZ$3h12baxcbN>BpU0Y zu6Ca|{^d&iD5SpBi7l+3FdvP(btNFpu2gQ26o;l=Wbg!(!JFaN;AeYpP|o%MQbXAp2Pt-(-@9n zrPkyRo5K(94MPtH^3T}CGt1EoVRWC3{MyWW^!3Htb<>ggQeK>*m5~jr{Gr7@WExLg><5@tL$#>Z+cBM#C01(_|Um*m)o&_9$Y@!dIuvwR`+UI2V)<|`x=aOok`Q_wgU4>axBpnx1W^-`gZy1hJWcrjup zS|En_+Y_sw3xm2h2}N$l_y_e^>TxoW%zP)GI3)WBnEEx0C5r_(|4@<4eC=ue2>F|#k};fEKqP3aCOtLh_RCPz2LfOi_B zP`y;VOEn6S!-9hQQb?TMNE^95clEXIbY(?VcK z5)Kd4MgP^ysK*rtMTr|-gfm-~Ff@1>MMv?ES}6z`cBN<4t+*!Ooo zi_-K)kJPDn=y8J&T(b`2zZl|F;wJVyVm`Kf8$i29BVT1m+3@G%q4q+(HivTPR>W-^ zclA5_LNhto+8Wxi)%@?MC@d#`yWZ?`qO(7ZgnQ{qf?;JI|NPYtm2YNAx~^86u0Z=? zO?scIW+f?U@E@;%PK%4&eN-tL)=WXJMw#dk=_F$gl%rq3FqHg`LUOGw-Tv0{*FjlW z-b{M_GF#S3cPg2SBP27wywC?v>#4uM;e|L^Zazwldr7pN6?7|SSz0hYu(j6pS{nMW z3B-SS!$t(g;?5isiEn4snGL{-5R7cTEn4iXCah@dBb-xS#|QWDN5fuMiEpQK#S%2m z_rliCxoq#?6nt`~+cD|+v+IiSceEwm)Fg`RjEEmUy&V7U>lO~sd~SMSjQJ`H`HFSR zVQA`zhR(6fzfcR+0sSO7tkjytPzZKKz_G9558M4=lt#Utvko!Y>seq*N+=s>#;?CG zM)XumZ1{I8i=7aMFT{HNulGu4c`Pcb7@lsZXEMalzT7zr_o+BH|F-DO zyh*}>uhtUALi_Iw4E`>Ubs;PCAaFM!w zEV46*JJi)%NSYgjjl#tBnB(%0OHzmrB_HheQ)>pF5Bl zylfMOtXv^PT@!N~%4XWTjhARUCkmnwN7-|0y%IJv17HorMx{M}*|cCNQ1951V1IFo zYY6!!JYn^$nH^X3Md++)2&mZ43%(TKR-y)$n0T1ge4Q#}H%5}C=)`@&OpN@rKs)qx%Y%j7sN}V!t-JaOGQbD*+`GPsJ)cLNO z%l$O+AT6&7g$Zr!gj6~#+sTjkx11m7u@SkwJdh*OVc}uV1=H=jgtt$3@l!SQnK!Y* zjb3xOlR`M6EuG-sGoHB}B0Zp1TQc+4y!J)^_wCuEPQGWo%h+|Y6sH)mrlpOVJ$3idH@9H$rx5s#fN1lp*|@HYt?>>#^-8c zqWpQmv%Qk*&q_m&lWG!{TKI?M=n{vf21u2%yY1iGp}4=%2fMTk1m|9v7+5DK$=>E3 zNQdfT4Ya#GW-I)XAr&-U(tFinnUBeC^lqN5#cY~21bq3;-uF7sdt?UVO@|#U$4uqr zgVOQ5c@bW#uVO{_ZP6+=!s_~F?%YVaw~;cQ=i7*`)1LoFR0RD#rv;moB)5#;GH$W4$-jD8K1F z=mwXHS&x|YhFChHjNK*;+x|~~Otom_E;UJ5@if+Gga>MO|FM__;x zbs5a5<~5h2G5xd)b}641$sRHkZrCXZzwC1P6!jID>ZXC|X4R~FeHwA#)N%h^J&#r` zMZ_pKjA-5@3Z2mjrS*Gp%w8VxuPD1AYb)U-uXazQJAgZurW><)JI0~eV+66$TKLZK zK2Ra9`*_vo;(ogG@!6y&e7-gCj!o&%_t1cA(3V=kJOiDr6VT`DI~H^*7F~A6s54*B z8v~ZZY_~n#W2!{azG_0%pWecYOC|iar9Uo*xxli?k&m)o0*Auc7(XqStt?5wF@MsL zXwEB_uSVu~Q-r0*icD^IQTOjwNQt`zvn{c}1Y@*%EaZbL$xFZ80T1-Yv0Lx7@KP*; zhnHKqd+8Fq+~JBX@4typb^GJ1-E64-u4MalbID7ij6JU=@_l2A(f-mL6RvDw=WVHP zeJA~y2hXj!Oq|lZ=e8KOqmEVO6DQ~4bZoMz<3?YDVQ4)SCnIl*#=LPBb}QOQ7z<-& zXQFhhJch4s68Fz8B37X}M%rCwr^3@Q?z#akth~r~g%&~WkNY&T=GS7>9wH6^^7)5=ZVO0a8?0WAGxSlOaSLR#Vq zVb}=H-Rmgtd|*7P^i=uJH`xfyCELlk9jx9D`061G%k(DRqiPv!1Ay2~e&W$1LJ?x_ ziN|wpvcey}$lg8;J_-l;mzxEUA|1!}i8~AVs)c7tH--GORs5b#5{yfA(CoBNT>L2q z5k2iuoqCPE|1lp~o5w>pp7`EY^zQHIg2aRp+es=9&{E0K%XF16EW#IO)utimau%1D z%Y(*Q6_oaDV}(ZP2)Uw;|9Y?7_hlnEjc#XkBiOE8W3Y8?o8YMbh*uXzV1KF=?rxmJ zjqgR`v#K-n_9QZap1tmo+6cei%s*f7#gfozSW_=AuJ_Kv>4B=yi?tS#=(&7dLjzjN zWB49o`0VLtgq4>TFpCFvkZT+$$=eS1io`)hYxsR1#J%t2;-4oz7`~yJ{oXkj(dtwK zHS!AoeIgpS6#Vg4N=@|Z(gR`P=@daB;TCtM-F{+<8X~-PcuKD{2y1lFnYf1a8}5yb ztCZoF)yUZ;^6`$QoRNLD`1_4eXwctpzk!$8%=7?ANx33U&MuFqwX)1$@K4#n3FB0qK5>ZJC>mHhTrhoZqs)3`2Ghk-bxq z-KcsY$YG<9G4U8LJxob31I!jAh|PnmAU}Cd>&q#G5)|VDDoH zzp(XU!;SF>UnPP~-c~lKU_SB4O(kI2U`lri0ri5vEE z*uVI7?dvt9hfA5`ZtoxL(c5H+p?OLViJoIgzL)Xk z_9zj1@}r1Gn#N3c$mK8_Ut&1_OMjmI&3tgqY7AGPTfdjHsJ-O{jt^N43})2>{{QS8Q0Bi2Eq5!29oN5H+1- zb7;5B>Z=BYrh1;gU?cKYQ^!i}X3?tfP8<)}1GUd`m`*c)_bF>=<*cQCwpi@&bZ-yIZtuK-a%3(V&~w^aTfQ?5=F9Z3 zD65<0I1%@fIw_{FySh15lMq zzKiBuX3?I4F$+hcW=9?GHG2z=oOZy=GdZFY&RwLFZNa&UE+P5Me?9>-v{?mkwbW>= zTuNT6VXDlFG^i?58Ohx?mRL9ka%fh}{whuzK>3RsvoPP`5Hawx@Y7Nr6YrbwmQBR6 z8)PoI+g?tN$7Ty-Of8#R6PgtVw==fTn^(_n6X)S+*E9(~?Vs-jIH2>~PEj@a zioYFj!8Y4L!s=ncFdYx{Rx9MwCaQb`J+bSi3@qdT!YaXC18Z? zVsWPobt`Q1zz6l4%%XfDs+y)E@z8$$b6g3r9CdNF&wTbMZY-wvY7)H5tN0fBOb*f2 zhO*Z_vFgD%)SWWK>$WpY>%BL$?Q}3J_zEwpi9$t$6EvgO+NvFTfP?L|2)|P(OsZLk z_bpSg{zeu*cq$KTt(1{$)yC>AO7ZE3H8Ca5aE%Y8c(U9Tk0y;{J-&>Ax6uPh-nOq= zB-%;JTbn1TSY|LDvV+&K ztK@BXc|u9D+eh4qLT#ZXz9nai+w;RvyV(wFMqOr)!ve55kGiq=A^tr+5Fg5CQ8xCq z$o!2aGLyuDT4^Px2LpnlRpEW+ta$&56coGZ;B?<=rmT^H#3`1K7m4*vV3GkA_8hf*kBOBBBbn~zD)`0l_(E^~rp z=D%JU4___vij3UKzV-IT-y##JDPQ3eriWqj0uSgfdS;s+K%HOG-jEB|7d-5(HBmJALT(cZccT;N*b=n&0m(xvb5%TC6_a|LbFj@GM6 z&chzVJf`tBixAvjLHx|tbSCVl+={dz8r+-t-!oYlK1B{6IxIv7j=Vr?TOkhjJSCh7 zPeu0&9hhtn=He--$f+~KhZ#%Q_Ig#wAO0fQ?He8jVJ6+Sy^E!|Qe6~Qm{WJ2Q6=;7 zU4Z&2Q(zH!ohQ2HV>$VI65p+4%jS8b#-ks;_i5y>->1N4wGMQ2G;7U1Bw)u!BVw9= zW0?+7FjuvdX!xa7F_>I7Ny1ool4dLnIv_8Z`5I>z(rl*8-BDY9miS;T8EQD~M|#eK zH1hDMATF_<#}^dfj0>^FQ7Ecd+zI9JyP=dXhZ?s??Dn(3X<9VQ{v^Taj2q$)8M7Wm z+W2?SaJ-n^!Y|TJH6`5x2OOS@-&s))PS#)HsbV9a>`xg?DGjK;+FENQmrjQFx@c-kyP(KIcTYx2OtzQ+f%x)@wPnnZVrF8TwvMTxT|Q^QO&0 zaAhuALCi^K%7?A4tmE^IXvX)pM~g>}=oGqW_b;i*h9{Xq|DBwGxM|p$nLAbDWz#Cx7gEPuS3Oe~# z5>E2E{#lrsJ_ZACHHpvnS%I4gdKh+3%ua=+!%JTe2Icj9%GcFM|K)}o;sc`K@di<)-#W8LDt(~k zw@cVX-0xhLg2I{F60XjM^P^zk#G z|ME1;qnl1ek~Y$PuW-lAFf<>gj?0W9+tb${VB)E>Xih5>bSE#wltI)@td+$VN>euN zjU1#CT3LTJ>LTo`felSNxZbvG=rtK)|JC8_a=9EXZn-a5$v@)#gNYF|)Dp`!dhw+< zvtdDbuCGJ#neuSJlb%VVHZ=1I4U5n)XDV)7lNS$Kk_(S;(s;*M3O-I5P&uS3@#Nnd z*^P~HWyp-Z#Dd@3BlmQF>N2Lg2KjprXISE3-e6v|KALjyj+oSI7xSy04?PZ*!+T>G-^l-sdOl@RF;kxYnU9@#@rH_D1>@MO>ZG z$X9koLUa8@+~1ugzJ50h?$on$=h`K9za$VlDF?%d-Ms1SMr@pBi%C=EnVs@b zT$>>lOdmbvg^BTq-9G`wF{Aj$omc3WBZ2q;hShNZKC5U?!^+j^0I z&w@C~@g=x<*Bnn@{bsWlEyqO9arl(GiBDUahnY`_<1<5pl|VyyQU8tgxG&~;TZk$8 zL4?NX<;?#?5?0c`m#n6eKw;ZP}N&Jg5*VAFBnmzG=8K zQU|vxgZZDJE%0Br07oga>8YXyqZOZpZ&LSp*_B}Ajb!Mkk>WeAMc@+U;P$y6VAhWp zAb+tNUN~OoSIY9S^pq0%{8`DyDp1FWrVQpSYT$+K$IW z7_$olbWoWxOfvJ2Qg@gr&;zEwo{K+h@J6rSe}n-;8@b}{bY$&Sk+AWfnr0yQt1dh| z-m<~R;t@#M{2%V?d0^ct47)lTQk`|8ir;F&{OVqkJ%4OPATC)uOE}3_6$0`1(G2ue z%Vi-SQek{>xMb!}IB*Yt1L>x6?vyCSsSCf3Zi046r;r=D9LM!d;QP>@AC^zVwm!BH zUZ}GZ3&-K+u>a3|(Z&E6&zyvF*T0I*90D;!Y9=O*KE$3yXMs15#xZph?wp!|FUQCO z`FSM^xe<>GFX=OX$E#-Uo&vO%P=@Ql1NKoZ6zi!UA$!&_p4FE=hfyAQt#el-T|Zek z^~6fjb!$W!rP-fG;~<*FU3pzFT3Q5u>ihcoH61f{=wj^edLA5|4fUhsIc(i38Y7c{ zG3GXi{M%djoD+hqgAAu97V^C;2@Rq-Si4xI zDADi_Z;Hg6i{zj2h-W3rz-#ld2wL9E-^u&IbJA4F-FCG~E=-=tV`BxC)VxfG<2UMq zrw*(+IfeN5wH2n_4`p4c4p8gvFX8HRY$cBqY1CYH827v#4YMNRl8xBK9`^Uf6ehyQ z#4CJy(ih>-j{;#pb0?oZCIb_{D&t|g4$t~b%<6$wP?)iu{XM*Zx*ruKdd`yt(NLT_ z5d-A1#W`2$-Die9l(HJx^vGpU_I8HXZ@P&PGko6;AJ`52EEbjH$&<7 zpX)5~=M1fjz!%b92aa%NEm~O^WIGBI7xJJYKMqHK%CKE!L!p*eD=biK=V6l* zk-2Mvqyt5!ayg=AQa<8dB=fmTpC5Te7;94>_uN1fuXQ3WEumuQ|MfbB*!a|SsJS)^ zo~K7ivR9`Dmf?M*Ep{D`W?hH1pg8`%M9+Dop8(}H1Bq^b#xM#?UHB->0nJ^)`V~D$|TP9$H$Pb(*ZxG%;btzp)e=CD{6Z>tEy(G z+F*d}am{>VbRl})QU%-`M4yg4#Pf+ccqx5Y=xLXZYU(&B4+!N~=jCG74_llW8pWQh zP{WgDpCogBgjon8i7^$kL5gpu=lk4^9(Y!AfY~hefnvmD6w6)bCs*dfW}zbLD^@bq zYu>0#>x<(h)Jv6`3bU|r$ZgQ5ZBx!cj*Sgea-{@gCki9hnIkf?m|xFXjzg-Gkdm(=L%Nt2PzXda?Mm}P3;lT4Xyqn$!H+q%!2)WGZ;5n77@^2PSnvN!}r3t@VvI?)v4KSi|Ba>}RAcpP) z2|sQ0NMd6yr0nWU&ZPH*;-MMCRm)>sv>^ssFFY}|@Sf;-gPWk0Y9;YxvYxqEpDZWo zw>|m22)XJ;IHZ4x$tGkVw5Kk;Gm@Uuolkw9kmxz1m&K!Hkrg^UdkZ7Ah@o*^gt3N& z{Lgjrj#^K~oXcjcH$AH#n<(J+pBDZpYZY$ksp0UGo@`5A9}JwaLy)$7!OPOA6Z0Es z?!_wHt33{;iu&-KU&1P;*kj(kVW{fe#LqSnYq3?p&ZGeGl$}x7Wbc8$&bQgO1V5Nq zxTA0Uem?R-KD5s$Kx*M+_T88|!St>QEt9Ia7WKs>dXxW6cfWYGkc`1{hS>e#ER%`# z!TF}K=wW+>FX|P638Z_!+gM~fT<;+Y7o9=Y%ay``p?i$gQzXx86n zmD<^KBU8ilg*&;<+bqnq(#L@L!`P&S@^Fi5mF)KRCt@H^GxNXQK6^zh-Xu66Q89_l zq|AO;hb97MHuGiw`ay4nJGSqX7vJ#6fd=tF`ad%l80FbZrz=b5{P)5%M8%DR{;)Z0 z;$TOF$M%E$74qj$#vfhg==ER_Pc}<{QLYnm^menRtKQg`WFyh=<)=mY( zCqt-b;XYL*-nq<#Z&HD{NW8BMP*T1h+lg~2vM!%JzO);^hpVt zZ_kRQ&lkdQp#{z-USWnZnHXDOjy?k}@&%WoabcRdWajU*NTiJRBs{erCit#diZU}N z;-}~HXd`-Rznurya%a~6Ll$&9ssH8NF0MQ%pL~^LB{RSM^ibRtot60Tj}0ScTCzT5 zMvmek3)a%zlCne830S0W4_ngzAAD@${m5s2^PVGACNc5yXF-_eIg{9YEiC^<7L40u z(WRNf=j>gBnkz=Y_a&@qiv}(>-w~Q`AK)WDC4kC?&>B=K{X~o`HosO!)zqSs-gRJJA1z+ z6`O6xN_hBJUy>i-Bysf>HP~wd4dLH0pP5X3Ew33JioHv0F>$Rs-`9)2%RgN3KsB9Z zlmDm>`6RcPHglEQRVe$W3hBd+qU!H$=>Cw6+=GY7pOc281I8hCW-#AMnc^v)W|9t+ zJ15m}uH%DHeefQi_#+(C$ipydY9F2=O&s-+9>iljz#KY#;6+-c?OSS;&niGqQ+iLI zSIA@(7U0D;X?zSN&bbtIUZ;Vv?1e`iY*&ONh+$4)K z>C;6p4>%-RBdZ}K*7OwQ?MwKHilyk~y1M(ys(Zx z`dEga11WbIm?iR6euzHltKbrUU+C(N$L>Y?(An+FXDCu%YMu>b{%9~g6>Z|6^pVW` z!LmW9T|NnJy}ygy76u?j=b|E{eo`4&9`j8#u zRa3q*5*d`mt6eT;y3_|z2N8xS9plo(j<|W!9pPhJM87iJ1jA1j!u!G5-1K!8%$~?1 z?{ky*`;IR7SgwM4KUKkea|ZHgH@-3SB9C~L4VirEoh{ueiusj*)8s#Sc%!!vo1nXU5~)VtKqj(!!&@6(ZAC1=kgOvYN+z$p5ol!dOVKO~aud zT1bvi<%gyvAnmpuF1D4hwHNHsr7{fnDeLD_NuJ(f@~=||N}pBHs9x(1jp*BK`mDtW zq0bD~?&k*+3eZg7>zV!B*n&f2VgIFp`ZNylkjupbAD$0Jobi*9yEdI~5Tm&8%jXRF_ z*wLmetQ@RLe)1hW@XQLVJ#LB}QDfNN-SW^9wMcgR=V$0{*v}k22YYclVj1;&%P3PB z%iQ+bQMaKcWW$?z;7Na2Rk&l#R0VMX9jup~8IAS<7Q*r149rj_&Dk!RFONv0?(4CV zPV+Azj@WceM&i#=JQjzuArmG3oCogd_`cE&#@`RHsT)amy<;uW@MZq=}8zCs$Q&wrQ zqh#hkB;T)v?>sDh>CDC^W*E7PKsHeOuGXW+U zdZ_&+%dgFgM*U$^>^T|8TC(h65-d-BJWc%E@}+PQJ4k%^3a3IKpD+_kf3>pB<~jJH zGz$K*X)MgavauwNcJk(S z)_pS-?ef&&NOxOaUVsDS-|DW{WOijV^S^wQ%zT#zq3EcvLBu|HK4)+k4urbEdTKhm zDh-Hd>EjqE3oMn7A50Ezezv0KtViGzvoX5%urM(=4es??*nB03e{7_8ir5J_cVQ7* z=%Nnyo*#sv?f3YvUtu^|V2e>pdUIiW0t#nOLx*z}^V9Uj^GPlUPPxVtI@UrIrUk8v z_3Z7T1(5FU1I4@sF1<7jhUc`<{!F8G{k$}+OE$u&yr1k!MJA$-*dgIZJ&(M6k210c zs6S7exrCYuyJf}*6;-)hDDZ>KOgH4;vEfFQdBBq~Xm35jHjsa*_?v=c&wse+KCZc~ z#Fae{MT4Ur;7Z?8Oqn(qia$s%)iQ(rzG80Tk^-m?4 zJcPTtVvOjF=*d6og7{<)!IQ7$Q|~WD_y9+VC$m?-5PCPIZj>W=%%La^me+=$B)E7^e&`ik^-wPEX$Rmh>sns z^47{ggnya}#d8PQUdL=i4wZ$wo(aDfwi#C1Hn{n651alu5f*9sNRXdfGeRl~ZAVPt z=_+O>&f)01WD7(c;|K4=V1TBFgsYJAa*7c8(n7-0v9riVY)@G{>enp(^L#awhUw$n z<2ts3eE!A#br7p{k^j9@iqW4uq2_-~w1@VwHPV)tUfNsGundP(jV%stFXR`NWTUIe z7g@Eg?3%qUzFw7+%=wUtRVZ1h0?Ue?%#*x-^Jum|7pw9QJM)n=jrxl%cCqQ?9SEc> z#ecfZQH0~td0PoHE&VlR*au8Sm;GJVtG7Sw_fEl^7yG%cdjYYNsmpBtWVYLDEVhhn z5YBW~@*m66aQuQ6zSr&-kMO2WSKSH3d#Ytp$9-^m+5czzE}1B}d}gS2Ew(jy^8iQU zPGP$7N?}>i64(s%K(9O5{PoE-h?CRAsrg-O6SiVr5Nk;94sja;)h4wufDA>nGaxTb#w96wDaAKP6f*NggqZcyj= znxlO9#Sq9z&%gwgPSO0QTGSbMN*M9-ATREliAQr4VQX3|9;{ge#T^z{_w5=}cFUq) zXNHd77x@{tSnRlFii?>tw()W?5R3)*WDF9nj|oEXQ3rI$<@1G=)TuFI9(D$}Fx> z7?wPe?oAcEdddm}T8+itivBER$S@pkIxXCEdCDzI6EW+XF19#~;?wnFai5;K?JY~$ zsh$qdJtl{)$|k;PV-O}NJ7T@IAWr-cg6n!S&?}>r9WTqq^@$@Te*49B1(>r=3nR+C z*w39>FxR^yxz8T+PC`M79)ebuif={7;dg}@%)QIlpG7{%qtDfU`~1R_;V|?kUj2fn zw#Ufpb)bQ|Jq!$l=lycf@90Q+|LUl9TwV;B&D39Z_A5)#plk(w4t+*%=C^xx^(z?yU)cfR{gD6C!)zwuETD_RVkiqeBa54z9VC< zD6|(_i5}d0glF@!ki7k{5J4QsSBtdpH8+?~y_JIXj|?P!`|e0}G^D%}ZsyIFA|g}dnkX6$4uLX`45ax`+Wzq8|y=TiT|JNS>(%= znWBjqvovZiTu4FZEd#Vke`oerV$q;&CSj(%ZO=mOlBv+xc3osJ)=Vf_Jz8>~J@?oT z#>SJeKhuWG&d9?Io6*GcKf-<-Nhgn+Ji?FE@%jfv7`xJvX3-kad#i^~h**yk$Gf9tacv1>37EXfgPb1nrh!cEnFpRI><-sfc(9q$Ef6||c<+FV7_sc)Rf1J#- zI+@s!sfe(zn`_6;NXL)8T9o7HWEIriFn_Ne%1YPsOMSE8+ya!j9~1S|*A(1qdkFo) zO1Q7zGHjQ3ka%+To+0hx_jIW3&tv+HX>fTw7~+L>yud9RszX)qGH{{DJ+KS^s;-CB z#@B*b1l=s!bS1OBO31)CD<;X+{=Bb^?ttFdJF}JNTnZ&kcoGW2eu_U=gutt7I&s{p zSmftyXl@*dC1*|ezX8SAm7$OAHD#>5I}xFV)E`>tRr3Wav8;>c$>@j7b6_NnU$?~v z$K(9XnK(>#@W9NBd!p3GZbELAxx|x`>YR<#ha+&hrb+BSyAa)bwJF!cS&UXD{{9{( z(dzpst%riNJ8V827B#O*#O*i4lnd!C?57NSewiJlx{JBJFYyTtd~i|0mHBPf#jL(^ zOI;rJs(TCp7WAQ?csGzgT^9xGU$%%) z+|KTH`%pHN*tq1ezyCZ)l07eo9xYPO{w(PC$q{noUvuwL`u*=IU`hY+TxUP^txq?^ z664M6ql_=*F2_KnsewN{8-pwACXyZg$GK=2Zx!K#QUe?EDigh}=HbzqI&SPl8m}HP zwLZTV8Ia#~#DSB->3s+J$D5=NypxyoTkV`xgrNl!5#4l+C=~R*7C8YCw&X35kHc$X z5DnfgV>>G}8ZF);jJPmR@C^vUqV4uL@+yyy8ng^0o*vNhVC;}j4#J3czOkf&-*wuA zHz&;D&g59pxM8SSdrBz%`h<_ROha-Fu^K| zVyYY|9|&>koe-q%pN1uuT8QPIjj6AOBkSUF-oCqlx|KA^OX0>t7V!$oJFy=~AcNBl4xK8ZlV*RZ=g=M}5J6 zNDhXs9)ZZ%j@sQ0MaXk7&$C@JTfFg69KTT+wBPZ!P zsZI#P&2%e#9^=lve8LfVVG?3p(%FbxK>HzG^t?~c{i_A&b8!rMsWQ>-h%RinU4U-a zGeTc0%GXTOq@I;v-oB0gxxx@5ilAiOS&9H9w zqr1C~S~oM@K#bxLUD5&9^P5sxSQ0Ow--Dx~Bu{nW>z&`M-DeFqt_(upLwkvC(`Ric z2(Shtp2zxjrs31`K?pXllf3WWu~&uJqQ#;Y>0MxQ>+r_(wZMBNQTOuy=e%lE8qPUd zWA+3smTahlW%W|%Yu3usvO*y1=P2PPJlYwC4-PYs*m{^Xsjq|_qprro)?EG7IvmU~ zLXOoowqrPX*UwRIl>GKuv`0N?7Z9v{gQY%;!dqerUDiFpbN!=m%h45n>UTsx_f8SY zbj>AQC;O&kWI!{ErTOz{>^MoTYUlJ)_)K)ihi^wjn;ufG z;W6b69eN8}@}e;%QUr0pY7UhwjMz92&3h)X4R(6Cxo!;3?P%d^l&PO0MP9;5>x_RY zsM%x*=1j~N#HAB+R6{cJpV7}D+QIG`ptd|vEb>Xf zA!m2YzId12{TYZ|AyZ%;eUQIfw-UeZ$>GXBQ`j-{aTxrrUcyPckd}s~Y<2Rf?h_{v z$M|ZqF5Zqf%X)YD;<%Cq_N6xR1^wdj$wa_z^R>43)^|W-<~bBzUn{(5SpvQI$!K_< z#S0ItL3+3<&JXWo2J}vR@wOt06?Sm>Jw;gi)ExgdDzbjP6mfgWZ3z!~Z&(~$7nxvO z_ZP#dQ%fn%}4nIF|4dTh$CNpjqOU(2| z`km3}SJ%ML?ubFsIU^{H$r3BQp}WI45u9@ySSqrx+MasoXzv>MneuMSrlO_$mFTO^ zSoHQgAq-l1kk?0MLL*!rTL#pMt$P(i_lG&k-LEsf9_i?vXaHxObNs^Uc%(n3PRUWk zNfTnB8z_Qd@E}2ke4hE_DSGg#fUkbM41AqC4Ez|2nVf@B8;7HMd<8EY`H=W0X{gin zV%qD5VfE2!;ke3EZoNARGY!Tg$aEBsqdjE!R5Q5U4rVqL4)`;03@p&Z@5U{ICQ0r( z+9I*+^ic3}PfT3h!nz;j;2(<-aQu?WNBu+D4Mz=JqOkap$=X;v?~X9Su!?UVoQ(I; zBaUgjETjuDC`AhW?M|$?X^9d=9LmUuRdjtMd|31OdMnCD{tGp0cA^xA*o`@3L3P81@GTWd^o!j zskiQ zf8`d!^Iu04q+aFj!wPZvj~w}ySFvrEs4E~^3WhEXT-Q1S`=@I{RYj}Tp|JoHPg+AY zMOqj;IS!jX8zXK@HNTseipF)0u-;!UTCvwu@ER^F$Q{k$yUG`1;b<2KJ#4t?<2)Dy z%Hr?HBW%YKJanBJ&ICj+xY+I42xauK}7nLALWiYN~#$t}2G3*nIxp->| z8lDnUNX>{HIID}RCk9D$o8}GvSnQuK!{Gv&GNzW*p zuboNWzXJA*Je6me_ zRZvwOhs|e8*|O>+e6bu){k2{-GQ@!LJ8Xhkzs|8T`v^!ETG5^3C_my){J{M#a9Dgt zG|}Avo__r%I{LdEQIQ zEaPisrDTO@N@(vb63X7PA}gJTGP1JDN@Zka@6GS_{{Dd@XWZ{SuIqD=$F1fh^WU6| z1}#&VHxuW?s|3j(MnH9Yg>+762EK=Rqh^_saQ9~frtk28UPT^%e~4~vE%d#8;K3#( zQjS5DCieN>;xl7%F>t;Pe(wJ(-7@!qAT%ZmhRQPDem?<6))-=_ygqO0kbr~4H2b`L zH7ic_#_+d_NL9JYGssW$I@lehz9F)`>ZEa6O1`J?d#qMv7Jd*P>2A|*e()n zYTPJhI^PU|m1l%e-}dr!^5{Jg{$KMC{9cCRwN~gi@+4Dy6G+}`Ls(3{K)aV1^bKK< zzqCSfrtul^R5|SziiB^J3zo8O7^WGe@``P_sNJB0cRwGn#woN1J=h0Boi}s09V-yj zYasTt^kvKFel_3wrZ7LYnNQJ=!PbWUSd%n?%SXh*lb*jx7IADfF?7$bF~Fgkt9;}e zx*ts*f+T3mURdWKs*5&q$4P{DEvYy+SPySiV|jf^9_dpY(K&KHt7$bw#-WG8b61*Q z+@eV*PkC6>=jXaaU=3xcjGnNOb)6K5FZu)V@xujvk9b<6i~OI8t6ne0&};os^j=P4R-cTYlZRsDFAc$O>O3TpC(67$gD;*E zi^Ie&H(xoFa#7Q;=0I;`Id0=qh*N6u(HhaDckS}5H2sVN-ZmZU)#!IP^%4*0lMC%yEu7q(#~hOaQQO!_ z+|{>NCd2Xt@k%zCRu9r6{nh0`m_MwSV16wIgF5%ewalYjsU;r6LcI_=lEAlu=b1k+kgvF1;!Dg~2}PU%;v^kjY$o=hpi zEUM{6<=71yah1`yIL2vv<;hB|$9hI|2(}!LtsA}Z$ZL_d0V<_6I+hon9f!JpL zQPf_}*qMw$5!z@dDXo6jBN=yk8;gB@ztpApywn158pZtk`wUdlO=oM#G3l}ehQiFC z@66&rA+J0?A8W4-!sbD~{LHgRWIY`Vo0M$kLOP z!j>hFJ`cdan@3sjS<=J%Ya(Wu8y{e`5=ReO!>Fo^u`SEcQ9?J-z<{cC_s9oY=7nFj z4Qy(8IHnDC!w2Gu3>+SXY2OFKzMw%W8R0J+S9BJAwU;K)cXDBGBoDYI>yWqtpH5j~ zYW-QZ`C2kI$eZBSp)A(kUO_nd!pK8Pdi&FR;-KB% z4|dALuXt>YZ5=dWqH~KY5wGUqAx#R1`z4~_bM{PmuA z%&E1+gqC8~Ih=R{Eehfee-&|(=cf%68TdCIhCzj9|I<;IS#C~t|^`eo)*5JEvIu@B6RNSg}HTgtF zQ1;4p2|QMPrR_FuRbP( zT;(n!X5yCmUtyWuwv9%K6-5|w0}B?9;?;^NvNaVb)3Jt&~N;Fyj1}d?_}`4fy`SmFGz zMNLjDJzKYK)5i~YqiVAq2`HLrCF<>;5}(gww>=c(kMdsmxkx)Z9;;5=k#@Fm71&L6 zG1Ksx8)dC#4ieo3&~r2%ufS}wa#fW(K6(5)06{O9GM#LR=T+Oj$or}mD6x>VP;SaW$jl>B<5Hhlj3>nj5c=o-x z!(U;Yf{g20SkqQo{Y)bZa`{&HDf!A4#w|n2J#(?oKSa9L;Hn`Abd*WQ3^f!irhR48 ztP8oz&IK?x86;*JYUqbzb^9>Vex)*nh(x-<$zxr64d3jagO39Zks1&xO_6J-eA_~t zANWMbm_}^0^X71joX*4Vu18{K5WdoVb9}xfy8P}a?smMhX?C73(0Aptto#{i%&I0} zbkz}NV4sdB2ED<0IPrNaGU1}s4)xNW#yk;;ShV15#EX1L+I@S$xZ7QXskbp zyf-U^4yLnlbIxE?ho^99!&>5#nINqE6Dz1m$7;1c*y6I4_xf`mJUs&g|ITN&1$tOr ze@(3OGbl56fVYFV!{6ve8EqMWwP8H-arP#za6cSedzD`zhP-MuG1JPmWwxKP5#Xmz zjC2oSVMIF8cIl#`Yzc2!lY)fv|5yr>*r-r5T&Qan$KtKJ@4sucL5hzwkA z@M+NiH!?A~;&nyQY96?NR2a>taa?8F`Z@w_a|=A&@P{sHT{bpgI!7vQA2pZ98t z$9iJxDE9j*Ejne29VG{aZjR;r2<<=XVl+iBZR*1;lzLggZ(1$8)i;qiAC~CUmGg{P z%0#wvg7v7L5?Rk=%ntNH)i`zGQ|tnK-!EXGK_-8)C?0Z3lX0C`#QRBSGSx{BvQFJu zm&qzvvFxyr`Jj~_zqSld@0*EUDkJxFxFs^!)h=VRwdvmRP8~f>uW||b!dBJ+|1zz# z$1lQy=l*CJdz;NLN{7X3C6x4v=Tf@STz+qXV?RRJ_9$}{$gT=wJ@#?uvCEO-WRCom zt7VM#mMX;i{a4#FwSutOzzT|kE^yDj_t5uQ6{4kU1grEkocB?}-^^##U+H@>Z+jp3 z`nR#}#}Z-st)Ixf%%{89non*}+iSuc&-n=tW~&J6hrHsEzT`!k?t-+De!N*B0xdya zI5;SgE#2aYOwwv7lCS)6K@%MB5bsW*SQ@BQgsxTQn00%WaAiv(oLc*#+o!qw^6?zJ zHgW_18^ccAG{&B}FGOAaHMMB^%-x`|zAL{~6hXHdFKC+WWJL#qFnXvb>UA%1h1+?M zH_$>*Q$9N~ZaQ{)cSL$z9asNJyZWK}qQ=sY?j!fNTOx4mH|E-D32M3$W7+E%H#G`;8HK{c^L`tGEGP;%=NJ3g|2+iY2c8^q>noHm5lota0u?!(}#k;cL|BqBsX z9`74!`1ynB*mFP^udIWm^IpFok3|8#Z*LP!6yjmI&m70YgZO`@G-K5Z2%BufqJCSV z+r0nR^OZgeC`(R2Q|K4j0;O=cr&FfevIERv5V24clu>%sk*CLIVr3Qa(9RaJ*|e94 z_+bX6gA=O~w#Q&dfE|t~kX(*-_30(9nCf|mztM=p*9Su}WBMJb?cC9Vo0qfjpi3Gb zJeSxY=1L+PM|I9h?DDll)9Ujqmu^P0h#izrcZR3GS%m?ke9-&QK55{N<*4ze`{VmA z!d}k^`0JC_!aSGz^<9SbDZ_C{Tf(}ZwZVo8b(FqpW(JNau-~UCaxd>%u7g_u!}u;{Y}pPySY`abwuc>yLr;(X7~LMgBZfpG z{HZHW$VD=%4&Ib8+Ye(US9#Ctv!Hj_SG><&K9>cfE5vb{<0jltPDOUP7Ix@F^C@S@ zzj=aY>^+m%hhQ`On%yikCNoKs2~()tD!8d zj^AAwi&1ll2ly;SCfyv3DC!3iJD#T+H6J#WQqni<bvu@S^cux+%2f%++aOn(VBQ0CpqHFA>3=5%P< z4X2z+9pORz0wfRvU$-WMXD^^E2I)|om?~wh#6>vbrG$B9+xYd7nV9U`hnTnB+5B=9 zoQOFj*7?qn%hAxu48xXb@JmAyarUG$Hg^tZAEx+Vx1u`wJgVohO$%{yAaL0nvbH|q zP}U_cVc>0cendKw+7wawcsakbDHBCo`k=~tEPL?N95!d_MK9I+lI7^FYlcI?t7Wat zQFwdB8k4n4SaTTFMpH`|$z9+d9TIS1{|M4Bv`bcuyoXKv1jfB85v~-Hr`1|X+|@sG zDMDtB87?3A%sl#0Z(QI8YiCooxz<={Tl6bdWhxt0d#+BxEV^l?UiiWKxWppNoVd!ww7>cw5AMgu z;m3x%(v@m1!oyY-A^S%f_qjg{@5cIIe253{cViP)Ke0sYjjK%lWD?phsA2B&8vbm? z8e(9&By8OtWzt%k0ZUX|2;9i_t=S9eaX)X}o`pd2c9!k^$~<{Iq|_UPe=Fvtt1@9V zldKcE$E1-S`oh?&@7RJhd0dXNY#f$&V&d|l+eP+3+>OFlu*N+==q+F7W9RwSrHpGc{zMOn!-70VpZsySa|QU!=-Vj zSP|WZ2F18x-Wrp&rV77rY z=kj$-LbW9$!cg4F8R*PGytOTD4f%KlvEv`AOLSt}ljU>+=s`x!B4n zSNGyJX1~gpvT%Efy}H}3NOb=(KjDW@f1EJ>mY}{o&c&w4a@3pN(Rkk5Ew|-=YdZpqJ`CoPn-^itm zJh@cY{^gH5dGy7cjCx_`%VusyJLdyGNe7iTp2x~BgPE=bH`d27gKyqY`lct=_JeAq zd+r-)$srE`0@h3E%8+6G+ z+7(?iEE>ynR*`pe*JW`hzs@}#u7auPnOfo(gH7q=^(ZT0D#wFhYCzf9HFf;D?H!al zltXEiw{$|>J?Iu4$KzEcf>4l7zIz2xdvk9`HpWpOaC6;rW_~z@@;nVNw$pk(+L5$s zX*Tc;)n%qXjOq6KlxeT6;({w>j@SctF6#~+Anr1HU&R#xnkOw8b0|<8755+#gFp0(hs8t3Iobig>)f< zZ@xVj1&e*D7D>56UJ>L|bO5tzHot2!dOlahpAR*B|K@dwdrumJ!nIO@yW{#=%4F$6 z8LkrIco*4KH^)kcuk1=x0@h75gX^f({8UjEd;IHD@DMg19-u&m(L`*$93B@}LndE`C&kUz)-0RY1KoObK-A+~+}MS3+zbRP?)^e`I=QS*^ zM>N)Ek`MjqAs%!$4!&y#W5$2#G_2|*sAG3u9 zwt?!~uT%rE=I6}L$Nd{_*gkf82%i+(8m%-%s5WJe< z!R}5Y?OPu;bePe|pDX3VL^c1RKED#3i(`Q< zIKOBc8++OpfA-14G^3s}QX`QO;w)wq)*Ytj-~i&UQqAvaJr7;?`C?lo?c~i@A=XP5 zetjpf_y1YqnH?9N{MpAZPfvpRTs_P++$|fkG9OEb0}yF^gMHZ$44?0M*zvxOzi5nx zb$=Ih98e&6M}2~Rvk&Yp^$~O}C<9d48zXKf^A&G5K{?(Wf0zGZOOcA*N$N;)-^iEI z=euOJ39N3aFeyEAyyjmKYkoxNG6Y_=6Z`qg&IyQ8dg%N8ZY^O=KSj>fxpg{1L&dF>q%??>8_T+Cj}8P0TLxvup}lgm*2&;8Ck7tsnnDkiMNQXj zD~(x%_vyn>-}#xeq09{WJ@yH9#^rp}qZG7KKh}8Xq-@^Fc66DVi?8JGciWSU|419~ zAnG)4Ok4ub7#plJmXq{$O@P*O30{0x7E+glK`vNAd%X;2NLfQb20gnJ zVBfTjPbP0#SwtTkYLR2BXQ|>y_CawEzm0fP0s1EB5Te1?9ax4a>h~gs%wyWKeBrW3 zRqWwU$S;IyqXc>jnXE7}0$u+bfySY?nbM|ooW9Wu?+Tamq`g^K<)aI;UgOxT{bn%w zenGhRUpbEmqr62ux=Hn4E$h6Rv<*hqnABqpD{~G;>mYN)?y2Lmaffnm_drd@Te|z* zUG%fmj3nkQtYX`4igonf)*|D!5l2gn0WuisZRQD(Ul|FO- zXd;}s`GgG?PIAu~k#v`K!q26C{N1d@m=jJula9&EU%?w@l;0Qmx}LvF%f{UnWyJ23 zNVCu9pz|g@gm0WI%)FNbol@FsZ4Kq#&l55F1AR`@g4whHQ#u?e} zUHIg*DD<%!BxcdZtek=2bprAzZ&BfS4wjBkL7+h{6Fh>TKJvG4N287xq>*+jv@eXe z8dsOn+~j0phG6rr?0X(@ioQ~vUs%f*Rwv?;IpqfwpOL;abP+-ul!b-fY5dvBIdG<# zR;S#9zi(ZQ7YFn(d|VCNZ

  • Mio*d)bPjs??PHn`AoPi^)zY6>VVbom_vIv9*gPk zXm3xq*V*>#v47ZHJl!>cE$eBE>sxvtUfRglk#FM9As^KKXp)Aw57G+WCfl<%U+uNXdQ%B=5Q13~fVTV^^WpTFG^ zh7V~Hk%wUEw*Z>I2BT+9DqBPue~)at6(iP^B)T* zwo>-fNK@3e2JyKuS*WgMxZl-|bsT4nJ?yXWPh+VS7zQIh2@WqOzU7KYSbO_n#>oS0 zQQr)_|4#vOUmSUhP7caj`ygju5o<9_fH`>q>`Viywrf%bH0&_!=4oa|bN$sTmXP27kuu$7d=xPF(>2+olJ%%4a)4|123EpSv41(S zc4cSy9QizS*z5xRz^&3*jfqga>WE$|x(RY0qp;Cvfar~VOS_|C&4Y2v%7b-uw?pLx zRS5Ns-1lHUy7yPd?D-v-;%qr&R+Wg}SZ%sH51pVVGL6Hnb0MER0CT=?WlBGMaV}O~ z+}jMHyY_@B&LZFP_U$O-h7Q8+?pN6>;wXAq1Ymz_70>;z0C}|E8`fzQ%U)oK{05m= z=Q+)=8z1x$HI__116?23LFM~77D>L>9lP}K`)(aKxf6w>N(11MnlIVex)e|8-+uj2 zPx$_E4rYw>hPrhMU)U`N9>Klg@}-F-+NKhtQ61ZqH*)PM*%(1{Ux0!-)1mMFjQY!> zuKpvIp>e7m)^82qi)9hWOmu?g>P74n@iQEM^}!hRtGtlUfrGI(t{m2u-F%UWb_XTA zbaxeuzNWzLp&B+vM{++kx+&A{_x#E^Y{zd?!nuUPiwg} zaVh?ghY0O*66NYR^rpP;Bi|H+=}Lr1I`^+#6^oYAk!+raj*`6{I%Q^E=-b z;*7Th>-I8PXJYkODNMwRxHfkETsrZ`dO~r|a(?pT2IAk)jd*@EOYC5Q&vF-qH{ zlW;&g16EeOC{y@(wZ20xe%$YaJKpUqm1fVBr^H)cU&cF4%g4u#u5iyaW!e9k3Wq44 z{9nz#S{I4>u1?~vetB^eo;(o{Y@5jRW_#nzG!y6^ujf`%a^Rh>jE;+?(k|oj5NOyJ z^LI=YddLyWacdv6E)V5vCccD}yrrj8udwWWrigZaA~;UE%eB`J?Fogzd$V?qb8~1vQj>Cy%7X+%CY^o!-?8XT-@ozL|tr5pu0po z&o?C>`&XuYA(igxE@&HF%cCMwaQg<$JN{8kfGcw|bO-P$4bFGjG5Ixb#Zg7h$JXe1SK|B*>3 zChnGJum0>&jxFA3_kf{aBUgwGMW`pS^j+Iz+5y41Z_+Ld9C?8sQ%%F1&uX|*R#rWn z^h*zy_QST|SL~Eg0urN)MFtKY+@br)Dje#q%(h4kg|}PYh&8{oAq;MT9ths=&EwXE zLHopD4A)Cz>g0#IWZVr`rquA2TPZiNLLcG23#D$>ltJ??n|30PgvrebI1y|j?sI-x zl^_PAVE>%4`7^EYu;{nYP;-k{k64JQ+(TrYEv$^iBFcT1`*4Wu8 z<(>>h@_nqT>@M7nTnwY*1OBhEj3@1SA76AF<<1&o?GWEV6_b)0d5UWRf)1-9IK2Zq z)Igkmr`2N3ugFX$4@w`=Gkdu{9}l;=ARuA~8^i}=*rXm}&3{}LgR>H69NrZo(>oT0 zXW9a;cd2LQz0)yd&~ywPT+8!f3sCV?6`E^CvO%vbG3Uxj!T;Sp?(#kfj(c=P2F~5m z0^D5diVr7lu-pYRut`Gs7f0&2TT%?Nw44$7FkjO6av3Za`JlrMJ;8KiD6Y@(!j;$* z{(W8!4joj&t@b8%Br_Fe;i`D^Wdk2XH9w=w1paAi?2~OjMCxA>R-SF$Yiqw5tDyxcg0sRdbL+t|B8-PwJ-xqKOB2HIe0tRi2#Y7tJ59`cb|DeE_$ zbhud#80l5VCtfD6z3NzOeBMv0GQLGv(=Aw#=3V98_M}2-h$^P-x8P-4RzRcO2744Y zv#(uepunlO*yoR+8E2jc`QIj_$c|2nM9b{{IB!$S{Efold6RNLT=(7Kl41N>#2%}E!;YoB)+uuV~WZ;;+D1m1Hy|=9mY~R;ZbR3-DR|!v4L!4 z4@oHX`9`kp=mce9dO79Ez693x%;jHxq#~$oD&-r&-or1#i#Q^SE*0u=?o% zb%`MBU9|)u`6FQybD!<;$-qOCp5m_l?Y$h#cG5*k@dOsS)f}ar>V)jla(;4e5)Lge z#rp1RWpd=v-gL$TmCJUqLd_Ytm1-*1{B2LjOFI%sIr%_hF!(vH4LA+S&5eSoQU>f_ z%cD)@dG$T59OO;ap*`1gHep~YdUWiIE8EL>?tucd`nY0Yr5Q`xWhCqiY-PVL9OH|s zBQb1mfAlytg0C`;L|U*EdMXJ_<*he%ZzUg7c|9-wF9&;uD8Wu$DlPWSgY&sQcxgCQ z_%SCLOPX{sNGP7{4L3B?kBUi#%h0E?)0ZhWcD$W6lpoVaX5SAKx<6BN^e_bg{0~sQOQIGP;GC zp=jU_w*Eu{&Q{n#X?YdzwW$D`ZN^}q!aZqbqO0)qp_1@0H;tRzUu=qVPX+v}xo>|8sB09-85cuBkz}HV(V#uKMpj`$H=O ztB?8MVC+B^``Q-A=E$MhwvoplnujNky+n=W;EZ7081r1@Axs-c8ptQA&|g|seQ;D7 z(ns{etAy9Ad9d24PsrkF}ZU41)w z`R(ueiuc)0Gl?-`(iMJ^8tyhK8>^GFi48bYIysm4mKxb`dH6`M9ZGqK!A3alIi2@C zS3->CkvQWduwOlG(4+j9@Nb8|tphQX%-u2X<|o;7`xL~zm_*#eYW6fK1Ji?hiX8il zkTT3#U_+diZR`qZ$mg6j!nm&!tA^`jV?mPyM#>FLcOzvWDmdZv7t+;xWRsC(BJNba zk~-ZQEl2|G#6CauYzAiU=!sP$uFJOCXApZqgS1MOY;;&EdeM#GvCA3WcqSjabzG3V zeVf#?kyyUF2OzGuyrBPd34*L$@aIH6A3*%c2VEs7Ti>58rkif zhr+c^Y@|~Us7xysna29%$%vk$i^oO!-1mGQJ`iiG-=l3TCu<1Sx5%N>i+VmNFA6cC z{h@0eEGuQpiC5~439B1e!-;eZs11Z(c`a97@Cr_!!{9W1HyhVvfn2o{LRs=&zGxfG z&Wng=+r3=oXj6#Vr!J7F-(>#XDW7hME=JSd)kh^3bDlflYG{FEy4Dg@^%?}XuDZgY zmkV%D;b;xhkuE&_nt*rB*ZW| zSl=$aWMPgbx7}i&pI=A!<^C$7m+EEm3itbus5zQ#`<#jW^!+^cYCBgT-(1#4 zZ5(2-|2zi99@&3sI}O?ZKEDeU3l!5AIY8?}4txyQ>$ zL~f8Etp>8eu}h%a>W9d+O)U8_d3jdI
    !-XS3mJ&)^RXGH)De@OYLht3Ht@#Xy8 zl?2?VGo)IvTGm*WgBMGsn9;t6O-Y#nIePA2@vGxrUW@T(fB4nmGo3VP&{&Z=K2ALm$vQaLv~lvuJZmZriEt%q!+ zRTX!Qi9+TRVnN>;!BuBOVBJCwIPF@_WV3y6p~VPy3+s91j~qykC?a!%RH|N|OSyqM zsQWfq=vkbKPu6;vpcO{>=CsEfXO5$5X0b724G@rfPdG9CI$!gdI2-6MW|wSR5rN&5 z@!B+d8^uD;#1um*ewAP3r*GuqLxB=HjL2oBwA3wvOjCC!^d{7xjw9)z^L` zqPMp(TJC;f8;DE%>3}U(1Xl5p#sw&SJra4;XKrvDC`=7j61`LzmqL-iX^%uTKm1rS z=Dk-!+435$dNdvGwC}3en<_2c_yR$ji2JXj2I=`Y8W_1)oiBw(O?z4swu5Ldo=}nJp15CKs(be zO2qHeMlc()n)eMZhX3(lVE4{RTfK~gU)x_XwWxg3uF%~u$^-2=zPvk6L9x#yXvm6~ z@zEp%kM1J&_D*dDP#o76C1=8<0~49TKg-A97875T!XM&u(7;tGM3!*bRi6A}fc zH`WHGlAnU{&0AcLX4`q2-Eh<6vuvjY>8rm?!nb-EGbFFUvsdyoS3B|YlR3CWoSD$X zBGy2E^NSiIw3tn*s`{G;y`w<*(z`5@H~=S>If}h~#O`buc}>98ORuCCr;HVR2il7a zoI|8xtF4e1>-@Tn^!gzhSo-k@v;3Tj2ebpcxAF`x>2Vk3CYgvx`7Zs?h4>!1&N%;u zl3WvFFmRfqc&lxuKH*w6<#N7sWCbPmsJPb~M>jTdgJVqy37v{h<2~7xVLjm1^fM_m+XncoSyx$N;O!P5E_lIb;PQ@ zdxec#k&fx_r@@6$7TCxg^%3x+FTcEA@EGL97)W!Gvxge$!kdbTj#~B zkZwo%6LsJ-f^wYW=0bfpu&+f+ru8fbGd3$C-NRi7)J{j)W>sAL9?fSQEkKkvWz|K` zW3iNf+pVZUh*vG=15d@_Qi>%m{_e&7-;>v%w>_NWO4*<{!I-qz9-|EDj^?-+8~zNZ zyQ+?~d)Qauso!ED+VUy4x=b0(>MGbAW6Afs=3!|E@*bp@vfbG;VBn{OiPz8be6OV# zQ)~e~KSeh1!D8I$>4@mFXW0_Da74!MBDlWryk*~pEehRS!tqdCTCqAQ_X*)h}Nk!yz*cg zMvzD4?#vYFkmMIw5=vYu+7Xn0p!?%A3&6OLm!xmNmdp@b@Sng!&e>sBpYG%*Y~&wS z&4XN*LAW*Yv8;d6415^*M7-5{(99UwzqhEp6s8jQCP7DJo%JwC#HzOj1fV5NPFw~i z5r@28{;)LB-%$9P`GT!L9@o%|f$awg*7q37FPTNbpyv?mmCIlUspfyN=?wGkHGHwv zeJoqI03UBuN|TIUVzgT(E+sz_wwop5!B+#wUzpB+_FRLkvm?-ND`Q7U6Y>4QcOj+X z7C#*yiGy$5#anICgfK+=dSTbE-R$)9OuAi?R-f``)rREan;z-tE*G(h=7~7{%|Pt! zcSg6vXMGv%uN{QB>WlF{w!g@?ygVTXpHGiRq5o^?Y^zbivabaPgbg%JL;T7D(8ZwRiH)w_+d(cfeSK88V|EDezi63@h!L*~Ju^ zJAO=rY7plGD_6sLlqU8*n#dj!k8`s8QNi?aIlniV_@6Oah}pAC7Lrnkwege_y8Q;T zRh)_5x3$H6j<9|yDv0IyPkX78xdcboGPFkN2+1qwp{XY@r6rj=J<7%HNCgb(-pnEv zrQsoYZT{8#bFtS7eV+ME#7JW$X9nl--&7ygbkcA^-^)Xdt zI_n%@ffq_Qg~2Pz`JwL15Tt4W%RUO+vmg@ppA%o=S}D_LoB@Z2w)pkwJl~nN1m}E- z&*`NrJ?;2SP;8GD;+8z+rXE=+FHnQ`Qd_>iVinf@XM;cUwz3T)>337Eh;s^c{PUNk zXgEjD7~)$-yo&=~I#RCLdFHYx0%hk0iWyap8e*{J(hz)Wc_IBBL%xub9m2PSJ^ZbE z8eV!TWBAvTvj0fOi`!P1HQ@?#&Pzim&HFuaYI$1BGMX(c#Jla|opCTd=7^;DUV^nz zB5m z51hKCvxknp&~-Ef8&J=+EK2ZgswNJ09UUiI2f-q!%8lpZ>@2$3w^VU54 zcfmo-C9Hql4}P;7h4IDpeE$i`wdrq`F02uTNi?WMvvERyvX&wuWc; z=3~m%;jo@@OKLXFU8wq{DDLpDDb7QqD&oBi3ALw=(P1(vP)9BWwj4AeI)o%8wr2WvrP~~>EYeynRjx)gH zqs9D2(mkkMEX0=!O6>LvL&0zVbCxhak563@gNd&_VADE;d?it+wHqwf{JQoeJoM;< z(Z5dfFNIBr`w@!9Ux%eNW-qbdC<6g1kA$QH$q1uatjp05e#0{r7j8PhI?j~&o7qCI z`kT1JUpXxT=Enz$p4mRc1k0}SLa|;st0JC!8tp{>X)>Rl%Z1%EEnJgZ$(mggvGB4! zHm#XhrMil;$UO()Vc>mcFmy4xj&wlywF+)*kc-P9<01X~TDnRyRv5I&M)Xfz9G!{4 zQaP-Xzb?x;wGp>!tr7O9ft`Mp3YXrxcw0qmqP|%e)?$U;TI;38bi=CnZiW1=U4%1R z7lRj2_VJWlu5Ae;l-EebDJr|D0V4adZ_C^KE#&)1POOK(Ly5&Ag{WTw- zh(F-0wwr%aFTtIu8mR3Rz`p#jfI?ZNaAjvX-@7ImJ5w|A#S_O3()i>)T5N6(Jq#gOuU>F^a!$S&!3a2EbJ* zkzEM4fNS=3;m)vfUU7UGG(D+jrhSgdNy_rJu*2YMWvugfVz_m%#pssveAiiGf>D-k z=1hI*TH9|z-pNSOGrPVk&C5@f#C=YvTox>e>HUzhoF-+3;M`#avCnUCipS$$=J1)A zD(gu45N{28+?aEQ^-K=OtrIS=C2qhz*Eqb^9tPK$ucX&n%}JxUUF`GSY0q|iyE5#K z$YkzjtI+Omh4xQZSl8+_jGJsq*>knL&$xKJQnA4B204kkSr(o))BDh>Eqo^rk*2XL z{sd+4vj*|-@+1yY^7`aajx-^o z?e$@KPJ@@M%fTgQH^>_%vM#PeF<_#S*ynHl5{}s_u9&e`D$_Lz!;AmuUhsez4ry7q zzD5qqwkB}pf%!PPMGLD61DM3t3j0dW2%9hL4fBmDMsJE|@C7@%1C7ec-vbOFs zF;3YCvHEqq^!H)}ZSlaoQLU2n0juzjQS!iRxM1m%i6K+Fqb=!qwdd;wPg`MRw?IOl+K=x#(du9zCZO zvH11A&Sk7O_h5m(j>g|Zw z>q}VbS;}B9z9}?4yTXT8Qif@Xop`ssw>b*uwcIdg$u`#eHf60YaL1f!7kRy92|6fh z5YxYywK<32w(lq5AIE++-GiLcwb5&sN%hw`8Td5c91RCL2z`gq4dtl?WPOhFM$+g` zO!PqKsB_ZoE$)Ky*#Fo38!-zIc2N-f{Qi?)!BUMF@mtk}IJ*=~de943)u`t8Xu|2D zIILWFOPW&s0;$6bz?@Zal)M#tmzm?_vqH*5NQCQe7Yx_5W1HLUaYU}0c(?7}Z6OkA zH~Yc=iR|s%5EQvT5|pM~;I|6M?>0vX8WpA0&ZNPZ{Z&ikUM78^yK}TYKJj9{VC5R@ zB%kT}9T%i_{fvYOUeClnzl<`PyT75_hcIt`uwMi^=Xqh2aT+^koQwmbJBl@byiXGp z56*$n?8DMkYnqTba4F>k+z@(eC!uJQzUZ;?4JHleM7oiA8nB2hwis0MRov~^c8x?} ztE*V^Kgq&zg;7TNf^v4#oOGBHIkD!C{gn%g(V95>y@*|-Y=Sz4unJ1$LeVorM;V6;Vv^d618v2Ou3_Em(|>pxPfDUSvDk>SD>gOl81V=9I$(Z>FJ z23%)MGDexuY#zOuy>usy$%<|w12bh%4Bq(I!RJpyL>((O-Z+K zU>9FeS%O=|8raqlz@B#@mUaJ1VZhpQJ~25Nh6g(LHxnc1 zSs7-DjDy3=N);#r0CaSyY!LF*98TXxuvz-)>^5Q(V%#9~bmpN(XQ)NY~mg3wc2UH5@ z*;nd4?&!JT>gB!MK)Mt*IYZI!#4D-6XbThwQw~nPj2vZb$`~F8)LO;Pm0lM+P~`hGR<+-sXT&b9xEu^kXS=&mFCcviTnuVv-vUN8M6i zc7ISVERE!WQ@ePlJav4I+%5L=W1W)WPrc0oOD!H;n}AuAbvx)!D61_VijuX8C@!ey zi$W-OY5D-{J1vpPD^Z4>wI_ZbyTQ&a%c9S)J1l1qW=Hslxq#B%OypmhT_M zE3!gH_R8KwW_YgqRN8y*r6`q#D3QH)(<-5*Xz$^%ske z?&~_AbKZwI#t-~7`)|a?<4e$Td8klclZM8la(MdjMU~CkeCQ50h4ZMN?50y9e9E<9 z+givq>s#@DZ!&yjqnN`@Tj9sh2W)$06_00RJYY%~+R0;ZRxX;A2*m23 z-`Co4VX-r`b!EBU$1upNcth&HgH;*MhsK;fxUGJPI~8`IdPWdd8^2;U z!!W+x$IDE^-ba9jw}IREdWh^ykF@KY$1Ikads2)9FYi*_HKxNRm1mV1A5W-<>vid ziPP*>_=hAD&ruOa2a@Nu*;>q1X_=J5|Hd4Ae=v#J8@SNcv@5>-yTPAcTMA(&;oDa{ zm3nmzgbHO&0(0y6doAi4YEl*b_A*cMF{ZB*9yN6phD?vgS-P8#e6fjFeV_(a@-r(b z9g~!dFc&(%c*?eGW%Dkkp@?|vf!%%l`7-LqG(6f*^yFBMOTfNGov`LZ4IfXL0Lgi6 zdYXeJO`&ZF=@$uY!|Q^<$au^;Y=WpMbNG|(S@_}8hjLQAn9*$~a*!`*p5w=yhUV~=mt{Ad0!4zum)XHw^^cV-Ud zg?-^Q<_??LHG=l_&gi@P5Rd9Yp84JrG2zWSiPQG+f?k%raK&C}FxZhk}R zFl-%sD)li>sfO7+CGKL8F5O$s@~1Mz_`VD1V|YYzxG@g*Drm#I0A-r-uSO) zyz`_Clw@bhoYZs@b^C3GVYrn=U6cJUu`k3%m^6%G zkkKCg)iVd7&fQ?XYZ#jxNgN@^!@|~#Na0Ck+^@GvZBp7e%JG(;H2Y+D@po7@rn>QCQ0CPErG9`N9V)Y3UDlHVRA(& zunAYi?6MN>L>}7vt%lgxpw9AjNs}9JUfj=a{X|)<4L0yOFojQ&i>ExD2e#dgVzY-2 zhS@f4tUGmuJNH?4>4l7{1~iVNezxJ_6({OS$S&|?;R z;b@C!rAEPjLZ@LY8c!W z8cB-lz6-s~mI+JmKIJa)DQH$z70>gF`lVyrNZMcj*u;J>3q*v0GWuVr<+%~Wk?3kA z?q^FbMZ)V1y<06VvcoIG5u-=Gk<9&EzkoPVa|Vm&`BCn+7~XliFf^coUnb^2TZM|q zv42f$!UbQfp)sX_)$~ci)lO!pnODtY!(;Gd59I*|EBIaCPT8o}F7P%}5zhS$#Yw>f zI-aRK`cE7V_>V-!(xJ>|N+yOYDq!Tyaz4$s6>o3M!?WD6Y>lrrb=>V1bPhixA5;R0 zJ$fQAQkUzy5PNVP@xgr;u{4FD_|vL_P6>@XZ*UlHdU|3@B9jW+m!ow#;Ciu%9hAwy zj4C+{uZZR2Np~vRXn^^Zv)S^_PLMxwUbym|I(9q7BTLg*)a~76)**zRjs6h_*bDg} z++1i%pRbOa6h>kM>8_vS9{S1lkHGa)1CV&YR?wf24r47j_@ut9>ex_%+KDz8yGBMx zRwWl?cc;@zGq=C zjcL`=~JIl@7Q{fmn6hB@)mb?fXFDN_P3FpovaJ}6bI51rv zkCU%Uw{PBt---4pT63EfbWKJN(m)QMJj=g-NJSX=&AOf|l9(67VTC^F$izLXoU$5b z9Zpy@B8x9J&V=mP(Kyj}D0@QLk)N@u#C^TVcl}!nn}f=DoYjd(di%)p+ zyd=EnqAmI`&5IN8&D#VEziwj2Z9{QnqAXS~qMUolYGSH5!G7gjX~pm5Shn2_F@I~> zIrpWMZ;)Uk_VDc8IruqC3H9%XG4EdX*fZ~tQ1zjbH@YWbeU%oPj_i@n+C=Y#ZH|1DW?!xbVos1f#unCc*OC|39o0o_h&g(-d7^|WpGVMzTXP{p%L*Q~AYk3%mj{e=?e6p6y*~UQ8%~IUe zS{;mqUaTwBRW7j?6KGdXUaag+`}xA)1jH(jLjKS%lE0ahQ+Ze>m@cp2H5*gV<()Fd zM^;HkCKiJcCwbxK7Phq|887#np@_1U$?syQi-UZ~eH8q@rmey9o6fLuQWmzvhM~JM z<@FAy^11XodK?>q54Q%g=&zX=7%UIj=5qd4E{Ap^J+SwJBD?=e8`XVw3#$jT^MVtJ zm__tL5)!Q?Dp7TW+6v;HQ?phB(lJ@X6Rgm^UN?@>jcJ5`R^t)mVT@#IA8!^oy-c zr;N5#3s-Iw@kX08m_}IAp3jg){x%nuPrAYSyBy=^_10ip3iV%`jpiO@D_|Mqj_Y3| z*{Roq(57U9*@v%iRnaAwe6EVH{79_uaSy1uVb{xl02 z&+FMVdS*vmXcYbgHSirjR%4K=lbE;43}20E(v53EcCmui`PeeX3-9yldFLA)cpn#l z?pZIHS3)4ni{6PdKbYPruh(mdx!SM@n)yr3@wM|`=CCvYpIz;sGwTfhJR}Kc+r6+e z>4M}=yhQlZUq$R0AG0I`HFPe`Kj*{c5=ggq3&6MEJ%oz9L>y^WL`X>ur$h~c5>2oz zEL}2aa2xu!)1L31B5DT2;2EjbgVx>R#+KY2jn<$%wkW>$4Et)%U}S z>5ruIHcRls;JDCt{?OQ%%61VybK2+Mg8juBoTd&UC;E7?s-QZ-)e3Mz3UrhPV$)&p})HZX1a4qhb<);whD=~L5F z#4g&kYL}V8qE!6$@;0p?kBzuwq|sa;os;_%%6`!MO59QfZeNj>9- zkB~Q>^3i&Ccd&DfLlOH~2Bz+fT!qdd2KOB>Rz5&F=tL;?opi(0;5sI|YzeATsY5Mu zH{Uj|1Fv)fa4Cg6!)xrY)$^bbZ&}IZjwWH`Tk5crR7gvA=Ag?6>L*oiWNYGspzuUX zJm*h(LC<`b|Ihq>f2pIkkht6uePPV#CD^%y{0Vf^kL-%kP~P&-seP`rcJ$18<*c+(m6WF62;GuEJKf#Bd1Y9%y01 zqbvO6t`G#i^u^YHy3!4l`ThGw5xZJ^1v#3T!dp6T)6Ab*nU3c%2Gr{@lXcIw#nkKu z!C9!_&o{?0QrR?&$Kxq85!@nW5{Iv2N6v*aLE-Oi`1913%aV`uTvtO(-i&JDxW>G z4kC`qTj9apI$ruV32#65K#%bjRc9Y(V+!?jNGrPv`jm-o^q|g~pJ(~vU)1l`!&A)I z8kG175qFhDAEw%&C1|AV(sN&5Zn?JuZ^q3=%k3UQ)2l@M{6(5WHD$3ovN7+AG5+03 zmn;lw!@TDSh}x+L2l-f}CR&JjtBF_Ak)gvx@4cZG@w0Vg@I3wo?F*JbeUq=atDO@Z zME~11L3*y9FZ52unz_oN_x@+EEs$JyLexbC;nVp9yg6=!y0v-STfGJO^go;Kqr#ly z%>_M!cJ|jhiyy970S`kr%J=r?cJ5(lI4VHvS`r)kA_2knzl49+YIydSyEt4v8{1nB zNgOV;VN_Ze?%6jBYe@eY<6;bEcmDM!us`I|m#{ ztz*S1kvMwI0l6iIxTkhJP9`z2bKH9CL}5aht?0eiqu;NJo=J=3X6g4+l%=J-&z2FV znfx*GtRC%wYY8>{Tk~dgJL-d(TMtTNPQ+u(PiyKPlNDCzMiN8L0i%?%xcjnH=(G=l z^m%{QePeILnEij|Z=PO)sCpe}o>69>tGZ#LXO0j%_9+iJm;@A2KHchngg~keNxo&qQD9P)9TWxjZgs`U=fvsc@M{{y@@ps%MlSwHI-WW#ZV$%XW}Azbsg`R&WsW z>Oq`^$i3|TI0}yx9r5()R`y34gu((_;vLuW$BCI3P&gHiqwFQ~qJ9c1CoB?Y{@a>V z%4&B*ShXFG`IC)rCy6QHUBm`o3L^ieB6RoGa&_NW1SXloHX%`ZB_#tnyCsN|y~{e$ z-elOd-Xa_A;;}8LHx9?8IU1~dF!@g_O2l35XyQAab?QcZ(kf|uZ7Pf&YU8HTX*P3r z3f}3MV&uNF{J_;X=%fnxW=S?Xoh>abK(&=MZ zzGfb@GE|{I{s@m5l#7>(G^tx%iH*+D!9&MgLfX`J{_=AIDyVC~zD9>POn;3}YSd>Z zy~)158H&7d-H`F-3O|&+0;i9;l3&eFYJEH$E8+y~OTW%0ug!q4Uj{yDv3%SNI&&s2 zBb3V_R$oHB7^A8Lx9mzDc{l+-0}OFuV7_$IyKJQP_dsc01>4~?A9iKNh}c-mU-(dW zTcA6#FSq)&n?}HAZeKdT+6dh@Q)li;8T5>MRkhly49}`9p=Bg1+%rms*L%v0JuTwq z)V(+>*b)r^#?14ih459mSv=>v{)@yzdk4Jr9?73k*T9tny~T6>I?W-tT4{up)mM1x zl6B~5rv%sW{Ul`pnV7h|JCZg`6i&sY;vH$H^$|;X^NB(j(VqRaB$55m?1`A34Z^U0 zm$`1QHE{Xu0ROYH-1+b_*i%1?3NK+rXBObgEDsE3^}Hf33+V}6aZf9Qtx5=jS9XW+ zUw75L{YiKfu8FV5%&XQ=R-#WYBay3+xIPuDY@9?-=C4b6FkCniXIdXf9>z$7CiiY) z|LlQ(OK_#1kLb^NSy~LsN-bP>sbvH7k}%<)Ji1iW@Mfi4bbD-!t-CTL9__TZ&7?f7 zq9UAL#Ny#B3+OvhpA`9Cgpa+kJky!|PIJYuRb9lHKbP{wVj-E#7b&WgYLq03^s|_{?-s?)l*M9HRNKzb}#JmyTgjV zM`E_M1LW==;y(&<(KKN!LEqj>nqtQaSL7{)T`S`FSkp}Cddgyx<8|qiE!mJgsg7gK zr&t+fK@kcIa*n;PPN8_@U4>dX>r)+M17Ypx(Lheu10HsJ^HN8ELQ|_U=7EPo} zoSMCZ4X6Bl@rD**-)hol(&(Ml_5U+JfEcZdtX$Cc{vwM~ScZ)*KDf7ZH&^<;9*a&X zVVL3=rcN2#V|japdAx#W#V29bLJjoS+an!F+^2CJRv5Ldo)v7Lj~=O-Xsoa0$DT!E zk()iPJkItD%pmSucW?L`>k9_@%TfK=2kFxj`Ldxq(ELna-`57mbTkslR)tz9hBor!X)wSoGoVk4i;; zU-I-C+VRbQGqF^nkIv`wS*0>{f$bv?KvXU76den%JTuXgsp^=4{2E^re!RoFEhm;s zA2+mG?&pWzZz13J3fytkU~lJAXVmDeqPFuaAr&tMD`D~3DrqnBM%E1=o`&Bk*25tM z`qVpbw4sI%xe|vcM&H@Kihhds6QFd*73LS!gygZ22psK!vy9@udw zp2)*L)WsEV%lxF1wa806pCNqEb+$z=8%~#H@p@xCpG01fppYeq z3O>YIYkHx}j2gjj=0Tpfn`YV|LyXcaklI@2;I=8T`ok+&{QCL$e#{6bme=ym=@E$S z>W-#>Hot}u5oj?54&AdBQlDlZpcHn9dikn}FKFs3_lM$$*Dei4I zyhuWqY9maG|G{c0JLy$y1)mkCxzmR{d{ZBRj~NdnioGPlvTurFM`1B#yRM~4u+Bi> z?{4K{?;?4eTz{1PU`a6fC5QeQHN5-2EX@3?Pu{OIiTc-8wB(TgrcnXo$ba}Z-W(n7 z>-amBM0D2cja9|Y?9*f7xnAguvVa@B)1IZ+wWJT~93Dvrsm&+9#2rC%PdzvImx|*T zl`!hsmMTA*y*@UYbZ>vjDkv9ReqUegqD{|i!KZC$*!@bG)oNJ_xkZmy=h7Umkr587 z7FSWv;eLtmdOQponK>*mkeC>ozKL`GK*L>3+CClAwGK%V^zI?x;WA=bHwhcoB_Qn| zeZTDH@KmGMu&CL9#++O>Ah#z*oof+V_n+nV)X8%12i;GczerP-ufWIYen`B!huxu! zk7Te6-aT;VSNkPm>@@?lMoc|@KXWZUIC!DgqdRQaAKDMM+lfA$EnkSs(KZU*7QdCu zm!Bxqt+x^`gZ$)IGqCGK7er5PmhSS)L#dk{Zk@ltq!W@6{#65Jduw>jzZBBod!ln- zfn+}U`V!nN(4)1BFnM<*Y|HHsyFZhUk$(lv3%k*$OF8?~*9~p--fZ1_gGVe}kAb%o zF;crTdr{I2{g-74PI*sw(wihqPS6l{wXckb`%0|#ANNby^qbVNxuivqKUB$cHc^LT zksaQ}1xP>2QwI>~z{ft-GIft-uxaaqOF_GN{-zG(xKAg(^e$$QV@JKcmBPUx6+C5o z5~6!+i2Q_|*Vf|vMSEo2zsigo=HuYt|IhZv64D}0+v9m=j^7!bHCR^QiG?P5LZ=0x zV7b2d^*xd2ouf>sw<2O6w6htT((ry}Hw>sM<(lMWwV11q-s}nK z_PXX`U&+y1(Kvq90a>74!s4OGII0QB%`1Gm<}wVZ=>zFtJ!y$6ShZ>zkMv_m4*?IXlsl;zaEf!cg(P_l+i%u;qda5(iQDN!D>k*9TpL1N>A{rS{a zVz?6SCK4!|Z)WCivS5=fgKtCPxubF(YRS*PYF7YLkf-moca89C%poozFUr;u1B@P4 zAYDXRAIsOCXp`N~GP*6G^Q9rogKBxYUo<)_Jz?DWq2K4>kr+7{FsQW=(wZ~yvamDO z8NI4HCl9mKx#{>ZFJBds#m5PJ#Bq?wqLX+d`e6E@|Jg`lr?m1$)h~yviWzpLHhhy0r{nT^Wl0Y0k8FD`j&kf^jF) z4VQn{agPzC|Gbca@!||tg83Lb@uhHNLmjvIl7hv#nway@vg(#n67(|+$fNs>Id`N& z_+yWR#IyY4jXYSd7>0R|?n^u+Oz=9dDEjSN>X+l!U=w{Vn22PZ*B zNe%|#HC%@L8~uX}5$KX3`JmK>E~T-=o>D-nIq|YQ%rM~ET0W%Yf`pUqTrw>WUh2B2yi~+q ze@&!)x&ivSPdja|u?`B6o(OYmVgD$P(``C^Codl25$&n;J|s4m%_B+BnJGf{5F62Z z*}g1;s6CzGyShoLxL^|=8tR~Y%6ayIvJzGr|DXAqcZknMdcLztp+xmo3LX>xBx1jU zp!78odDNA&J1vuU(TvBcARicx>ca+;zP`2F|7ZTKPn)QJz8juhmtlDd%6M@jL!9}> zT{93xyV^moE%}wMS@8N~j`dn4Y}jN6Tpx8?n6jyoyU&lJ?mt^tPY;kDC2#N!>fUV` zR?jlVFUPhx>Y)GcJbx?;TUT_!rr1Gj`$Y$A3au2zbt1M^OfqFo)x}-y@dxXmzn?tP zyRNZeaSO2QiaJK@tmUKpW2pPo4j+wk{SMm1K%>C}XO8I!u6bcJPkbn6p2Rm#q#o@i zSu9Vy$0Uc+p*xE*o*8AlY04%%(l^8RXhYVp%p8;MRf*jt{sZICKHC&M$4%nz{>EVK z7`mTK4P!3E{tph<5NH0R#N{wZ@Pu@0p~7dGXZW>g56^R3D&u=$p&F zXbST&Nz&$4Vjf00Vq-)-J6ygBy*TCR7VhK1=1g2VH39Wuo!Ry7_DELRBI@>oMpAa; zpn^E_eO9Mo$xBT{y*b5t{zyS(nGu@a*6^3)y>b6yisDuUzc=TLQDrcWbT&ufV%tgt zJG$Vce=65on1-i!N7HU#EQ|c;hI2+cg--7$@U^>XhWye-e1jUhuA>W?ZQBI5dk=Y^ z8wogjLl+PCYV!;AIoN2~8w*dwu`oUyqnFT5WLP8rQyGr_<9fk)ub;H3IT5+HhT!7+ zb|y29I)69FAZ2O-?@o7zs%PXGQ<}@}t2!dc<&@YzUcN5@y?5)1yIQ;US2#R+9d@WH z3vY%I@9UNUwwc!QxDin}IK>T-$M5;=DT>4-WAc;7*$5$)nP@8SL_4`xRVIr|Pdz2(U;YF86=`yOP=NhcQ*k~tgHYsHrI)b4;yEl1n>iDZq z*$DQP!OP|h_UJNcR@Ki%-QHs!F=z7C5U|6%DoY@S{1`o~Sonn<{F8#6A+}gnUCrxU z@~C@gFoJ^aNmfmg2zF`;A~R=Y+;ZsHdyB05;Wu(HUr83rP90{JyOXe_dslJhe>`y) z)ngW- z(n8Anq?Pi1`#NyOdJWoNgt51g=GYm2Mu^*bkMEjRgu@ARwm1>T7xYiXO)Yo48x_yy z+!=;`mFn=_dxg7RUyj5GFY%o3GHV?%W4c1|ltftCO1Z5G3a~v9&XetOV6Ltwa?&3C zal)+~^}^=e`?%MYc*Mw>k>;YxeJABWd7%XUF^5^mpam$sX^FkZFY@5#OyKc&jJj_t zDRlcS$R^AauFibMOaG=p*_ZM}2KL3RpU}=xJyh!w9o}w)9@HGlh z>&2yu^h+@5u^sG2w6HUG$O|`^bZnqAnCTMqtQ; zUgEBH4(*Gz`u0WE(f%xFvK#S8$@BSqJpWLz7D>|X*j1;*8fQHb^v{I~qm#?ItYISV z{no+vquPA=gIv_v^@eFkJTvY#0*iMj;Hh~dKcln?H)t>Xa)3m-CUO;6h%YgVo0;0B zY&?D68PoQ}^Ujm=ksYKB-KM$hy)*53>W>T8u2=Af&D7^ut|Ri0i>}4f{@E1Y_tROc zM=Enlgy8ar0IU`X#)zv)XN5n3TZ**9y!b9p9|ivI~d^IuiXT$hQNwMrraxm+wxU$sTSmQlQ{IR&4a1Uzm? zV*&l?&S;^J>$MGh{@5I}FYbcWZ+?<_8FbFCCOvc91VNYHv(HS`k$i43Z&ftKEt^{5 zSm+S;l?fXm! zJ5|RWi-;{*Nf|w2qm8(i2;Wv+I;VYQqsOLVU%m}=Z&dTHqqC5^)CXCSjgqsQe1%E( zx{5x`?@^?2x%lDZIB?C-Y@9Cb45c#%SwnLY@ib)dX;uwSo|=u2k2)~?n<|;PwH03U zSx45&!-YJt11|Q&V5@a}j6xHu0FuB3zk4zIV?$$qGel zppSAGzeb-xeWL+^IgwbzB88r3|D?k@hDJ@BFS zkMwZs3hdkGjUCmy*_!t|pxQ-;zMJE@t4}^mhiK!y#b)+!dm=^`>caNYl+&MX(JpeD z8|J*e&Gr~X<4}?fP8>eOHT)BC=%NpvgtkbOk4_b|Hd_hrRFn9lVWibh`6v9Bs~RcU zff_S&IDEgwzEfVty`ekqTGj9*$}oP;Gso}cC3GAINd{BJCHCCp;I8O~x zgG~AT$!XXsYmDD{CZaRI}~MI zz3FeUhaaWSW*gKQK9>fucfJltSK1?VXjk&=lw_>T>yFWr_eh7W*#P~Uq-zB?vqJM= z2z6@W+5VD848lRZr4>1TJ0#Kgy3!4=_v;GkPnRRf#S3?KB=DK!^E5cq1>cq1SZQ!3 z`6!eqFTb4^+IPUeM-;C23uDgp=5P-=BkDOj8j4^>xwhLf@w|LiBF1cV#>H-HSe)i? zj9aTNYV}4tL-FdIm&ib_ra6=Jp)*$h^At8l(Ghw?QNM4da#3?&P&A&2Jt#*4({$wK~y2^hKFP9oFz zOPC@bAZYJ+%FomPdIoWep6_wwTZiXj%4s?eyA-j|4GT~;u&X%dyV85an!JVGk0nXZ zE97Epfgka{?z4=^t8nj^6Ya6~@`;;LaNlZ}*j;73&>lmx3dK3UhO$et$@1cy@A8oP z!sh8?S;+-9>RJj`{n5wWkJbE{RsuHM?FqRMMZYf=**I(HgFYqt!lSAP;@>*s_V!es zcRdxEvLi5X<7ie?M)$25WQe*`yp9oj4E)%Q5FH3 z{{r&#uI+^l)~$ZSdPkw_eLr+4*a+(mWy0*}A7S5$S5+fElfUA#0`mTmHW)%arHPd5 z{943KXwF|9X#`(;1NLpWwZMj5VYgI|^Pe8E*mKba=F3KLErl((J7_v?b`-N?1w)Cc zLJW}g4ZP$1Mrik<{r)RqGgl|Y)tC7`H&5GcBm^t@^jgY z>II0DJ`qZ;*YUOHDd?xr9V*$+r>{Bgo;}T7yy)JM;!8QN zYmxvBL8u!iFY5N{L&MO##|woU{CH9dahu~hVO!Qgw)q?Vopoj4h8nK%mEHv-b&xwc zP10p$8-C|S;Yr1k)Hoo=sfNQ|5g!-(aSwC zyzr4UO@nlv&{E-NX(3;^FAa-N%ONvyOI7gWV))qGP&c-MP~kz(Pdj-DB%65PwtT1# z_d&bzdCBf2pt(_NlB=neCVCa zQ%@%!B41V)H*`OFhc(r&!45^@BdHzY+bZa6->ENtUuc(fA2eOi$+Hr6mM8JU^GJ*S z{#Tec@47TtvJ+MN%&24UHd`j2f|ysT)a6mb`Qr7clGtGOx9yUKk<@{uWQF7b@`Bx1 z%8e@9h@7FXq%JuwEG<7gI$B^5APb z@n92W!8#4#;|``_*9b#Anq9<-Nh?}3;+oKOaW}tsWDVX@AA#DhInq1dld*4*A3k4b zVaI;0LPJg;G@hyC=gMlCz#L(K8f<4jyRpN#Mog;k>cA z6ZS4{Wt}ci9`mUj7B-gh4M#f=@o5zr<-?dlvIV+tIVD`QxX-Qn#{(~oakF3&_t{D; zj&fV9s|#m$)kdJ4*a-jmFf#{}UTW)s9~X3`-ouG+f8ejM?WULT%_E(3bUExw2wE9q4LlOtCm`BUr$UceLUV-%PQ@N-EF219rYT%EioS7o*P3aL&5Lv%S0?GbHslP z=QsLaf@qAo-4m!Jbqs}Y^X7oT8FP4-D zmUR#LJi8?PJ)`Pex2#cCw9N6L$OPL@Fg275Wd)BS`MbI$VPc^+7XQtYYF(q;L1a(N zcH7KYeK1~4)kB0*Egx+Yh4E8*k(Z;@k7-3hvz+w6yH>(;oh&G*{uci8-WSturJ%C{ z7Ik~X{MM$RVSuW*pZ&9y-UZ6WNNqJ_Z#y{&IW5=O;$Kz#2l-F3gKW^IGn&_ymqNj0 z4o10eV-dc?aBVyFT2f}p&yC)L_q##XcB+tDl7jXLs$#D8-TWLBjW>h4*K+p0(iCR5 z&kOzLT;^t(F-U%Gg#lKwd;?|Zl4m-=F1D17v0Mb>Xu4a`oKMot!KKoFg2Jc_mfbHH zZC;OsD;;$_nz|hi|5JhPUGu7~m5C^E(#H6j&&%R9Nl+3}AsqyG*5$0roCFS(<- zuw9yP!4-SA34JhaQH-RnguhSY~a5i3N&6pFv4DcV8R#ZSwe^!;}$T zLftX$`z0RvR>JbK7It@S7Qfaf0#+lOu*A}ze>xrtIcpD8WyZ5pJKYdHtyFm8m%u~2 zZp5*4HN1{rDlxI&h<};nZMMl2_PQov=0$DMdl}e}2K@`x_`cnm8Ty#uip({k^F1lQ z9TtI*l};#l_*pu*B!bR_eNb#w$&_Vt;JN0XaI4;v?~3Zc-C6UXQ}uz}JDh~VNjf-E zKJ~Q6@Kmh*Xo-|}bu4gWG^P)+g16@(-bb6dx~zbXXYG=*zB7b5MplB^Gt#B!WFdO} zZ$Vf2y7XM9t?=~LCw@UA3-6JFJLgp3_Nki3^vlL_x(8}MD3t*)O zBn%l7JVfth=-g~L9Q`eP^ccjJj&_8z+Ag7OW+jjBlY+iIRIqZ+9_d!ajYyYTV~$!g zOE+AIEc!0|H|On$XS$|GX9K=@|>Wo^Vps?LQ^NnP)S=BhPz&JSab zi6ii%q`RowD{fzbxp&;*@2w|YUzd#r+dqPVgSX&)g*aekaw7M5fqE9*2{bW4aTash zMZedOb0R0F_nKtH9Wz7Fd3D}Enx1E{7rvGrV8agvL(a||`$8}BB@0q9;{3o_MUa!5eF{+K7puPN|!%le9w2xb7Bw%9ie(*c_PO?ejfRzjKg~+`X{Psf1>&eSu zZ8Mju1Qj5ebjdv0JKhrA5Jl25HQlXZ z5B(O(RN}c@bqD6<2f+660oG*VfJcUhg{r1K)LW56U7Xsmo|P|sNI7nFqE4=9yV={( z3voA1SDf?KTcU7anlt*}ZuJ`xLOa&1K8W0DB?Oga!C==es@9xoa;%rY|8Hy5)l7uz1VafBAFgPTSwwv*g z>qb3yq}$j;WJBes7px!kVQ&NIU2*G|aK`Nh_kJCU)j#PzzO!B0677y|1tr31U*brU zmv#E9t{8H&xax{q3H~0ng2{MAK{-4LL+@x|w^|;b)RBRaU2XC1^C8J&D@&ol;1*jW zm&q?PVI{)Rv;@9+S{poXk416vK}lt=4fy7! z53S$n!Z$tQzLMWn=VAbN?URm&->r~v)tWsHF+tP8MnSDo%AHLjp#R>1dTc*Q*LknP zO!C!)RqbKAH?pC7{x-jjy z!nS&(K=BCWUhAv5=7Ag>8*7RP%M!_n*mS6ku*Q>zio!O-SnSufLhFDmzJ|OyW=+&1 zIbUFRc6%T?MP8ikV;pkeGwY9_KKr|5#84G%zL6qK`0|9m(W7@zi3+r>O!>fi>Vf)b zi1}l;urD9&uqCEZ7_ntH?>sviSx+pG_Gpfjy&^yMOkz~NxyGEYhNAMR8~$aL^MPgA zc(?GkpdLPmjp$3AHU&Eb1K$dMYFP@>KPba1caQW=c?z6H=^|X0vwLrY@#G23eC1l+ zqb?R7KU24Cr(C}Q1u-yP;(~#*bcKT06&SI=9ifp4e5y1H>+k#&#^~N*>NnFN4eu)I z^E2hwqLDJ3FYC0}sG}CheseZY=nV@II7Pj|}X zT;VgPQ#YIn-4WL7Nv*PIhuH0}FwC%zU`dR}@Pl26O}3JUKgq=N%^FbOJCiMw@F8&2G?$E9`bV&_ zoFV3CBjf3e{aO~8P4--UHR=BfJ#aa^fY{&*(XX3~n5FvS77yOd5O4Y>N=xo!L%Y@! z?|Zhg#UZO9o9!U#^ID@5z=%1Je(;7MG1L9-BlzZoOF z;3}JVD+ML}Y1e;;^SL`H19E}(v!u_5zD&UNqm&I!QWY-$iNeOwP6!B2<6DoVV)4Ae zSY0=gojUG@enG`Td*|`I*NPeBP#9Sjw2m;x0w`0ointD&f3oU%PfZLdM9im_O%S1w{r@A3R|S{W=H$B*XC6!cQVj=$^cPOorI@Ih1xLEZS**=i=k(%*b95lUzHr*#e^BEvO?{h zB>Frnu*TXADr4|mU(3zAiS+%eYv0-6& z;wlfrtMOQK-ca=6xas5|pZe1W`TMZ!c6XF+|0$m58z!#69Lgp6g||zqDa(JZVzbb% zw1At_U1^dWJr8e-t5Tv1VID~NcUM_K+ddh$=4**rs*|K`3KllF)%~!f^_jVF=Uy{Y z*_F;e6Bj+h(Gj;={CTfQVemQThKE)0?E4Qlj4dq|ay1fo)2MY&4eExZDGMdj{O)0K zKVpcRTosBVsMD=l3v0gya0mUh*!$EG+4atBbd?Ey#a|Jsi=^CP>T2*<2V|`MEIoN= zDfH=X{?2y?yQN8)@#dex*I}N#A9cHAc+2BBX=t(8NeDmH1BE$LP8<2q@6~37cL5FT ztwIK_QO~SVEqR&tQLcxWPM$%JB_Ug83eS&N2oGhGdC$|?xasjzunfE*Z8_9|dkM2~ zv_n^@Pe_4PQ#WMZujbvVvLW}`7;d%2k~0Cs!)!A_Y`m=SiF_u~N(+&79JuNginB`* z6~2Q#pnl_--{gq>cY|NZF2mtU73%F(X0ib)ko}b;?quZ^({Qg`8EfiI`Ca18jv4(w zlFovys;!H{ASIxHphyamiiDzs!C7mlU}JY+V}l)pba%I?7>I#|$yr!fpkCuzs94v+ z7Q{fl>HhwJ4;~J4&pqZC?=Zj*_dHhd*&g*nu5n$JGI2U(Gp3hV;-1+&xi!6aENTKV zFP^a!>Ta84*auzoOU3TYB&02A=9ixhVWp?+v9MsfH1lWZ#b8pQCYIjcBR?@V1~q^5 zabl5Rx(AmcIDGp@Wrpz;^d${c)d4V#1bd= zZA~+`=J(mAw0L-0DdXs;twO6^D(0W*C@~X!XIkT6=VQ`7|JaCfJ=_GVcT5qdRMIfy zVLy~~jALtujD|1mVE=8Y72WTy!K9_Vk(^;5=X=P@H?);6-R{9h{EoxZC?%+utrHb9 z6QTG{hq`%uSYSMPZ}Tqj;7#R1qb3}6N|ePLtR=Q|Oo7rUcRX8gi2Yc;6cMATqr$3M z7%U*R!wfGd_3tXX8T^OWY0u=h4*VzH+=#~)U1dCM=pi=hQqR%+4)}POxR?Ew!snYJ zTD32VLm#Na`ZRgEPDjWym&L+3!U;Mv>2|3_8I7|&sPAB(i1H0bQ-6*!&kwR~QS_PD zWlG-5B`xvzJwO?~ehGQr`UbpdS&40J&3KbDy#og66ThoU$hHtyT$sY{ zL2F_!#MA9_9pz!?9{<6I$ApQ;JMytfO%KO!`?7~8?eXngxwOx(pxg0)k$O@W`G;3; zG5$zAUXIt`V=b4V>Z(4h>Z*mlXCUme?U57yz@sQU2%&y`QPb0wcRrVda;0YeW>rHa z(@(@;FBL2w_l)hSj=_m$@*>YI5c(AflmRtHRu5BV7h%OU51eD^;fKVpkPt+fSz$x_ z(L(D$JS@6WrdTC`6_<>{x~2NkZXf7ET9d0X<~a|QY4=Nqrk3Ew2_JK-%5S6SF1DZ}+DvX@)(2_l%(B2g z6NK37N_+S=>XqJ5EAufM$c?TmOKh~Xj%&dN_r{&T{$k{wWX#C?!Mi;@$eiR+7@YEl z|DE|SUOhk$mD#X4cSAPBtPXETOD#FCifsKT$b-yi56%>PRx*-|-QYQ(KPz>yK-Sks zyrKTIXuoU?eqC}#;_rI7+AwOl%`M=&PUVR~gW_S8s04ejqDtqbS$Ocl5K%!2)I%Hv z{pB5zzA;<8y^;pEJVz-@RakDrZ@jq8Tq+X8UV5fK546WnWiK(J=NfnxI>Y69DEs=` z4gLPv!i%*dh1sw)^0I1R{l_ITTkS{W*`ABNxz~8(x>!tm-WgN!7K!W$1z7)uGMh>s z%wjC6tMlKc(Ent|FN)@ha^; zcR_N1GGE*r0`22gl7{o=R5k_{jmCvN6Pfb?Hxx|&|IBBVN(dGcm0@`z3) zwv5MP_R@bX#!!#j-#tGlDIFzS|8U)SZ>IFh9+yXK;~%?}iER<&HGQOk4Tfd%UG)8T z`_&1%CkQrq_%e(UniyqpQ3P0pVf{F3j4Dm>IO0Ry1Z#RpeEW4fH^7%Xe}8>AHA%@h zQ1G4iZo1Dt%t%DWR%H~6?ZS)hk8{R##PScF*ehRaJlT3w^5JZp9S-wJ#?s91Zjp+K zBdDYKV+<=eKAQ5F?U9^TE3$j8gL~)Rs8chPkKCL?zF8%@4-Mus_r+snOB-ketrw&G z8;I}fk8@{EGM78l>oVdz_gz*l;)xHi#>N;%i`t7n7n5;1)D`Ep9%Pj*OYt($T$=eI zd6ipEzV3hVU-~5IgRj>HRK8L7IK|I4fxAFY+KlcFKic!WYTrFkWXU(Wkce0O>n87x<}1%%H415 zj&=97xvB1ELg_n5-Br~Jlo5X37q%H-kG{DeF1~>8xHD0-IhKablhskWMuYY5X+*ij z0?BXR^I0U0ROm|GRrdSx5q#JUXBWk>_j|`+C_RHLe$|RG4+G$$(u4GUnYxSg1c!a+ZI_3MJ>N;|o7;|_O+GA{a>;*^4oEY9^A+N9(K}bm-fZ~>@{o)& z=mwo-yV##e%V2t*I*YTa#i8AS)Ez)Qyb~UHBy|nIfvK*jawf0ayd-pJ)5ujey{o)u znuriXW$8Y<`wDURFOeQa-Bmi56Y!sx5fZ+du!XxVd3={M%+2kfa6XocXEz4I!+gDn zoWB|MOC4}*;bvyw>5Z+`v^N&lh+UKoUw!QdUs@`Yjrf)hqYw>P&-3A>N2$y2Fmc8L zmI-6Z5gd%P#v8jJwv2AqiUX>onLpxB2+os->~Ammzl|wScs!W=ucuj6@p6>J+fx?i zqFC~<0Yfg1Kz^T>?3lqa9BcE4pXhN}n2nFcl<}G{H?ywvxe z7qommCG?cja6+puZUx_zeK2GE(?vzz|6znEY+4JwTxZNVKzsg`6g;#1!S5;@W{>`% zzNE#!`R}JyB78_9f+lHWTyT`EmscGO=dQ$nJXN^IgcJMA7;V(j#Kz(8&}f(myHUB! z;0Uqt*aL2{|D^abZ7npqIV08cseEjK3udqaeu&r7qM*B64}OcYMR)q#Mvv`^YZvy(Mz~mUC(|3O*XTG=@gxAf+V(*3G*3~xi!|OH zynMa?=#+2 z9B-g(2=NnUnx`r&{v5j&mUftZ;x>h%2=BYqe|F+l~n1k0n zmC&$PiK!4fr|01a$!|aHX$;;y(U5fetWQbs+HQi4jayjTaywWpxy)V1?iN?5FZkbu z77`Eh^80Aw*tjEK>pnZQU;{#D_QAImdqnBsJO~37Y*;mgeW#n+q0!rTyT~%JaA^$K zA`PTI+aphKTZYTCG|}|BTEx&ETmH!!HY-y-ZU%*8V!E@$Lo>X)7QMopakWpl*g25& zme3|%y8J$~$w|bYcx7mR-7eCs`fN-Z(*`cVgLtiZ0*dXGP}66F*sw1P zA#``F{j!{?HacUB@p);tPhJ#`%{tWW7~EcTR7=NiV&8pCKFXe*T8b!L^0(Z%Al_%* zrJHI2wtd!}MsGma2g$XfYdgdmaE~0lg1rN5Ebgyk@`TR)nL^0}UI&LVbV~3q4n;c;TttI)A zp0j^d6r4+s>{<)v8_A3*MS|V|}umg@1WXrqJj-4A} zi8aKEoa(e3m#sQUyZ!yPA$XN;kH|B19x5(DcoOD{YgRV=d3h3Cdwk{7w!EvH)g>10 zZ`HBey+CBCCZf+EL&U!`VO{@N@bX$YV;1GY^9}Ltx>(@S6>l+Q#%63Yw1?OEV0LS^ zH)`o!vfiym7z|0JyyM%LT4^w?r@qqej?G(uGRFx{8xxPdCt8{2k9x&0u9C7#V^2&@8qKZ+^ zU3E|N&aao>+u#C?t$F<3(0rj^8V`{`JB&+F<>I6gXoXwjb%%DmHibHOJana-?BdE8 zc+lUD;o5yN-zk>-^Ril2I3!k7Mh4=SlO2o}cnY}zWi6@Weq4G8Q)_g^?-%*p>0P+s zA`jm2+BjCRUiRu<26|P{EubildnHhh>S#T@2$(M%f2O0ZuLF8GI~Q|`d1#u4|r?qI%QNoaleg?BmUBDOD~dz`Vdw9jwNh{lL1dMGQJ zaq2YXYTNjbuJWXYb<-!Fu&E8aUsQ;e6WK5dABmg88fD4XiHDP9%)k4Dh~d{$kbJR; zo5lVs??yAt;<+;7-Hx-NpQAC47{~Kw%}BrJx*I5V#EU= zx~UhG!b?Te{yfyaZUd($li9qf4hXogg`ZI@6H_QF8g!ZZu`Kq=uLZ{iE93TKwA*jwAzXr0Ax3%+aOJwNAaT@U$@>S-B2lY2V8=3m5*^laV~~EB|ot zK3n<91tT+d@q4P{#81^6sJ-nB-y`Ia>urOI&4(r3zTj8{2CXo{^rop|b7>0BKj{Pe z7t!qL;V~$y)0Fo41pD=v?bu72^W}co5b6pr_%M)l?VR7}0w9n7F9*#j{45fYE!7U!9t#lt8P{xMeT}C(gE+~I@L3~ZPi(PB-aH=v` zmax5*4?8|t(r{jnNI?Eq1CRFU$yg0@Xcw*F>V*chVb2YV&)RLGU3y z{$JLycLVi=(k-~nX6m)v>xz*!c|2QVl34Vt9-4=}$xAt&Wf7D6hI<|#t@c##nUwV= zR=~~=`eGYpMF%^WOLKl&_p#U<+6I0}wPNCiAUuofju&UBuj>3dl&18=ur9T%d{Zi% zqZ;|*h;VWHK_a~7wt?xuaqLK$BlSV=mwff6bQ@iAKo9TF=E?m8aV&>ffK!KWQqFQr zVjc10e6<*AMmL}Zc-m%u)pEN*y^UwTs+Plgx%M;P-k0O?xf6Deo z(@Zv3N7j-8v3_}id}0NjT(blH_C*KdT3Nl6!1y?X7uusS zrdp^n!BcVB8y(J>K^%|0g=IQTn7j3I^J3p`nxX#M9Ue}-?Z+k( zgKUU&{i(8bOVu- z-%YyD+Rs>nMR$oo`f~@vwq(>V`ojNfa22`a8Q3LL!rs^v*0pmKo`;i1otX9$9wk66 z(-NAdwJenKdb6H8;#%<;VLm?__o9Yliv2g)hVD~&+#F;6`9X*<`kn%_-QRf4s(Mljnl$GtNejAq(**ZQie))nk};p=nt^J2KJaNMvh^&8y_+av zJQC23x-6IK4`#06?yy!-MoGafG4jk~tbWoDN`;KIGuJ}Un^38j@DSY!5Bks!pK2+* z9wtGjmmw~9+`?8r>xsstH9RYHpBOVQ6z`9kljb&0p1q8+CyM>i`uH&;!z8Q@^^~;w zF8}7j>W>1}%%8+I*f`*ba}jT!xJN8K7Kg1->hNmZD?hrLa=U}ON*>EQt<;J3qAk`1 zSBnV`!%aUw?F9V31rb3JrM^+dzKa8cDE4SILK@rBpw*yLj_$ojH_ zmj{g%N6CBHdAb(tpXstG^K7u!>yX4Z9%vc?dPENtnZ%SYd!6H^M2gg$Naqq%5kro5wG<*={-7WVGhOyb*{z%CdPn?i0Z=!FYJD50V03$m(X2pXGB3FY+uChlxphxIhsJ_s+;e z0vgbKXEE-5Hsu|QVxeKB2i>G9G3Q_67<4j(yMnsM#H>iH+Gvey7q$36^I#O7>xL~W zW5mndvDi~M2+cdZ+5En4`0SX=Z_S+~S_6`ybE*xh&Z)8ohmBC&oFg&q4HD>QeyEML zkM%{*P|6~$qx-eSYNi-B7Pc4Z{UU@iYyE=|+@qW1u^cppm~DzqNI?y&c#}*Fp-<9% z_HbwtlpTDE582SV3@B|?gMYaXADJ8rCzZC8KV2rK)6P7DGSR7Vek}TqCA_Yk=IJd%zPm*ub51~IP>*`8usDT_mPZx7LkG?GGLT@~~vYkh-&Jo(= zk^4m+(aW(`m3AtHc=*f~KJT@7qBrsSI+?0BkK=EhBp=Rn%Ey$|XK~YC zxx$w`HZ9G6_^mcYm17G@`)#j*{ZAU$rry!mnxq5wvDupvxLI)L$cB1Z28TB z*Cij$r-z#{@NIYWG#DaA_g@3EXu7{Ags>ya+;DGdE}vE(E+*}N1f8G5(5b#$mXueA z2#aZWDQbAg9byjH=}5g)=l-SN%l$5xJ=U7_e`*esp%?jx*Og+-l|V$-+e)mnBQw_^ zWs3v)X76BUmnP%m^^bhXLRV4OEfuv;#+ZsU#`{ELZ8G_^dlS?6pA6)N^uWg<_t;Ik zDO+4|z(B zO^Lzyn{)%2TO~R^q7FD=fS3M-vOx0H=(buRG`8 zdi%cU9-xHQledJ?-Z6+;yPuC=bXc}ONDEVMh4K^oUx*PcvG}^OEe;&$D!htmmq; z=s7)=DW7qG_vj)%MW;--yrSNjsp_aV+$W!$l!{NpGZ}E2GUxA>VOT_4bRAtSCYpys zXSoIT9#8Qo@r{LYh${{ycI76N*$mX6yM|(fz^Zh#iErYIuRUgY{w`1$vxEPmKURFd zm5di|T5wX(V|UYSaL?$Fw9jw6M;(g>hEUrvRowUzffxI&U}e6Mm70%5@KX&WEFrCU z`9>JJ_d-~$p}eUR-G;vX2 z&HPWCqdDodP7(hoI|-HPIhZ%7leEuYS-YIx1>^H`!q7y>fvOj;xQC%a^5~g}g~x z`yQ|X{etl;$QHII_lZ+>vFNY}*u14twp}=oFCtmWPq|Tk_I_zAw>w=WU%a{jH+T9X zd%G!by%3AWHo8)GN${BntU1&fT3g$CY-o){TCo-8z0~60Cxqa+L3gNbj1@YDpgEku_`^%^ct7@AT#HS$`sohirMCAE1*L>J?;2v(L@Zor!n0z ze`KA<^2tG%mhX(Gf2_FKj$}k1d(UOv8Y)Lvr(l3~8?5tr$+&VNVr?}r@%9$+bZ!Ht zMQ*~k>M&M6+mcT%Kgl`-9uNoagu*VI^7FLMPdiUHCf7bt4~b@Ne~!k(ExPzVxJD%C zWl+|qk&hk^St|Luqt>cobg~csH8LI!8{6W}a6geXD~3$|gI{JBgbl9})u-a{d!-$$2UW{*90u`Y zSqhT((y_w^ETjFiXi>~U~S2BcwvM#vfE~hYacSO-O&yu zmrlug?X}_F7i!pDyLfT=7-dm!P}c0Er+7X-6u#435pp@2&AHGY*JkDOLsz3j%Y{r> zTdJW?{tDTCQHOnlr{Lf48ZOt0!OC7bxS=&)@3OBa5^(W_J^E#z5uMNHp_mx26V^4$7QCCq&vY}DIQIFpPp0?($UXYq zk@>-(v2EVYrk2;aU8g>kkSo^?nR zcjjXzN+m1(tTfei@ZHIH71zTR=jKdy@B znO#Lw_Y_1>CVKVzEo|o>>dIJql}A3@FN*0q+4{Q+@*L*NYy2pC+hG7P5}&cwH0q7@ zb%bvAZV~dMA6Av*^27frvIXlMv3!1k#6U~WkH_=(YM8xtpM1dfbbO67hH-NZt9!c~ z6T7RScvZEK2ZSS--l;s&QalEWSeVhQ_%*64KX!Qoz6Ux=`6)HJZTjul%8!l7U^j{R z&?4K$w|5#NYRpq`U@&>l9_UgA#0FPxACPXc77rp3N%^>Qq0_`O%@hQEbi!f(D7Ny_ zSR7rZjy^8Lt;*Vj6$hLkzhfw0H~cX?0!Y_gnZ#9(B*N%=3;(FMQDl*CKf!Au*33A; z5?kr+vFtS0{Ip+~JdA+jZGEiT+g=zON1%3CR~%irm3@v|fv`R%(r)kdGZ29zdLegC zN7-ZA<(2KmNm{+b=VTa_DWGJOlQ3$@fk^I%!qTnm;mhUt+WJG9`Ahpn5Tl@z)Ll|_ zIs+=BU9js!J@FNT(bL@q>Eri_4`#%`HysR9@1L?0rjGF6nIvgAe$`3n!drP=!x?$- z_MK4qrz`w#JYt(VQGdE|2fW=_CESA}G19xUq}7kw5Q%+{S3mj#PmTOs(ufAP2@tN;-qD9wC zEbS17i$NyRZm+U`9DElkNLsy8Y%n$~vynQ-gZ4%d_k93L`#)xb=y$YEwSh0+6)F~y zhWS)W0f#1zXWMff;gnFy_3HPCZkBP-x9fnNR{8Rd3*wMlXM*)ATiLMe6$UF^^{vRdX{xaRrL(OPsQ=i7?Z;V6odQ~Yi>v5g<|K`LTxUzzESzv{l2`44p zez;aRCeVI-;-#{fOPy0CJ$j-4y?tz;nm>j$+v3WjYSLJSg6Ws=RSP(~{<9}W^e*D* zxtT&SG7kTSsY*9ld#6NPp4kycRTX&IqiEFrF~r1r%2K_L!NfN|u*m%;(vAfP`w0PqxT@MTMf+dVKn7bv?L!+)};*mq82-V|Fh;vHRsM2j7`)$hk^J^*#1Y!9;t1s{ z?yUDd;v0Qb#CxAxV&Z|p@HQ;wjVpJ{EL^qe*%d6!{9<*|ntH22f1;(>u_qrBsL#mN zXD=H%wKs0|xgyQ{byLDHsN?@<{!Sz6i5uP>Rqbk7Ep-F6@8BeLj=#B;fo*nQcw&e* z+wsN`f5zwYwd=~n*@!so+e^3F8)fp2E#zmYGl%1XJ8Y@l3gW}5V)&qHG46CY#9=ce z#ie+hZVCr>5Tn7-h%X&Z-D2?$IOPy7&V&rcx+`1wr^o5cz}p2k-xu@E%45Xl_!Pu1 z*TexeJ!a`oY36&WhNG8?E1tU#V&8~y zV!Aei-*lZQvdJ4zpw%MH{Dv#W@cNu7`Ebq++d+M2#CspTL~Y%gM*P zz574BB5b!Pz84Ie8P<~ba#?;TOxqJnW!fDk&!gK))?4oUBUC&OOGb#@AAW51cxL{R zZe`Ccpw5UDl*>!^7Q>1{;pfr~3-)YgtM`w=%C9x8uDmug19iN62( zMJgh)l5!=VC|j}SD9cRtM{fgLY0rnImQ4yL8?v-D=$v<1l8b3bsA9 zs(k%=3&w7t`%9$`5B?m7k+geI1Xjd!kHwtl*6?sTCsQ3Vn2U-(>}g_@(3~59v;s%` z_&q@UVAMerMmyVkU$%9M3;Jgj^X8xsQSm+#ej|0zfJE7?j*pNvV?-FeD=*b(}F2zH%Eeyb3Z*AV-NZskWry?oVJ7qrt$=U>$F#6lPH_UKb~ z;BZl;)0=p>>{g}RS_At?yU_JpUD5aA5n1s$8=hQ#S@PIFq;9o|9c)l|-cw9FwS!o2 z)G^x(j^OMjyjCzQ-jNmd*4Wv0fnBXiy%3 z`apjRYqtGnSCmwo<9jYvieZ#@&>n1y;9lS57b`a6%4!GLecQ#p=+J$Mqp$ zlW=s@9N^qSiR?3g;=Ju(~)HC+(+J5khKBz9=6GqFr%tZrUE6t7pr&9YmfB+(P2 zWX1fUQK{^*sWw)w50bn$%LC&PLpl9t*%o3#&JNrmf0vvcW2-um_jbZ%zI)Stp=lb1 zpEFFcE^nUP$}$vNGi@<(=2aFDvH=4N>~Zb)E^%fFbz4_|;{ET9Vt(WYf3Pf{IKY&J zSrd=VZmRh4Y_D8>;|gT8Q^nPV)na=w&GueqsG5-CVVxC$C~bQL)EaU3D;uzhJS9*6 z2@~#Ty^!a=mA?{gQ^`t`UhLshuQ` z<-@JS;qTfLtCOSI$~ohp9@bXc=WC}1qHL&>)IXc?{SoRl`yk>^BJX0K1i!1l_zk~} zLWAC^d*9c9@uoR!!5vpvhspVz5r@R(`H?XA-U+?mv=>{>CZc6k56r6F%VPEYkZECz z>Gc-`E7(jwPcQrz*hzLViSAKp-jc^MW?V9MCI6CUd()!^^7PKds7*iEm9!P`&uHS} zUA4&ZkHW0xPB7~lB~RTBB-_X|UxdvNWaiGGtg>$KYu4dW6d zzGd|)nh&1Md_%mD|2W-1y_a*)tZB+~x5lApsJ5ilPxzO3AR{{={c~H7mi^Jld18UG zE80A5CFOcZx9_$$M(ESKWb)zxnAL6sOL^yp{^!%BeLjvdK{GD3aPdu*r4ZBik~~A= zTXrXIVa}rV_-D9*m@zI3*ACdCO>H>S>`rXawYB`F|4uQ!|7J8VvckT%9`eI8C~Iao z049x3*w8O@A9?+n4>ArD6C#rkX#10&D;Ue3oOXZ;v1+$(EEP51qH!mpoiy7^hY&}_ z(vZ9kTbQiU58t0_6IZHQ?7BejwmogBU%bvkD~kSRhxLM?s}1)uNyUpEZ@6XZ`^pz? z1u!#IN8qaOENO2%yoReFJhD*i8J>bM7M<|qY8N(RtR=T}s$fRG#1Xw5hN3?vIAS?k z4Erw$`wZP-v^9aP8#@+{X6oRGX^ps4JeIQQyLmg$wlc-gOceD|g7QEg-t$Hrey&%> zNYCZs=p_1{bkvn*`r^b#9o`W-A|Fm?xf0NWe?VqPCv0seD$RiFXx7ST<0N_x%`& z_LNHs-F#fU_*8&4^9M*wW4pCxyo?qW)5Fgvxt46 zzppk8MO<_V5evSiV($=5&P@ZW7~w4Kt6 z>0UHLzk9WO`pybbKYt@GD%#_D$EWg9wzLynlIHw|o*^)@vBtauo?_Ba>Jbw% zgxaLA?YrDDX?g~~uMi=g(|y0&)K>oU$U<4iFPSLptWBMpaeN--OfM$4!^%^0MRM&s ztd9(*zJLT`(pq5K_OsHQw|q}M6oxi^4TjwV0tmfdW^#F02_SHfL;DT@1h zlW>38Pc9#o%(}mc!NO4L6`eBU)TiIXt|492N$)(HcO?#U@@#PDbfxG_Ia%`}cN~m( zAv;q$kDo9#mG=3aJ-w(mZwrq~OqI9&Lj0UY1*kfoV&~k*8}_A*w9kJqe~74nxww1$ zqiipaf%YHb5q(zX@i)V8L7j3jJrhOJjwB4NcEiKop6ul6en`ksKpJj|SBt%Ha%K^~ zwzgC@GgBMu)^C!0^$QjyV1tVahW57<&mLyrc`Gq|cnO=*&-yJMZ|WZb56W^*)-vMW`!-=9 zvAF*X3l|#wys%NLh;Kfd!RG3_!2N0=FR&gh-nykiXQw)P571+W>TF>&cdw-3W|fvvQ&>LO=4XGe)?++%Dc z8qRlttfd{_O}mZ4Wh-diixDM%qDklMhjaUev5e>LkhM$aM{6btW%7&}p8F-u{Ou!6 z;P+3uw9m)o$6(rT$|YUyEY@#KLeW-JOrO4yZQtpDeYMx5eg4#hPz;@7jeF``9zHG< z*R*=k4seV8H-LONs;~G_r!Y}4AQ=H_KX~^k)OS#D`5#jd!dm&)ZKj_k)7>RMDN;&VUeh}plX!*rf9yxZAShW-~1yBXSW_W8{wnndBq z?2b^Kdt7*H(+zQaPk7z=N4CmnFmF2gll{%lZVwAUti3(1Iu8)tzIdRnLpGmdy@(aW zy1@2&ArF#;2uI^Iq&sLp?h-5W%&9|lySWItt&EeT0Zu%mhc{1Bh3sq|zEGC1o_n#m zYUUV{UBf#^SBR{E0XV2Y{0H}E@{ZN+xcDuNi`W9;)GZl5o;UN^i;F9LDPt0=qJlkJ z8`yxP7##ngNjc?g5u=p^?;fVmKXp)69MFw-+IfkQmqZj2BWuHHOStNIitI;$&@^(u zqJVJbx7i&zr_*@bqv1kzP%17b{O0j(7RnBmrb2dBow}l<_;>#poV=llVLJ0fhE4-6 zXN6(EeFEzqX91hEGyLb>O0kRj=B(+)H?*-)o~Ry=N7IQxXM2)mx1{2T`)mGws=LVS zkc@q&n|b}FWHx>taqZ4(!p3C!sliz>(Cg9}*-7VFo2~I6pafBgq~qPAR{nS9znLD38?O}c#j#4%+djbO1RtE} z_d!;lm5h0hx?t~ZO9rZi^M&%*%d(@dfl+P z$&hE}2BF6xdpr(_5Do@IP-|JphxEy050AQ14?-dTa$t;Dp^}baMs#cYrz5*Op&Od! zlu3Jjb9oew8+Mdt{yXJ7cusW1&g3LEXXSW&oTG||tu?|sGyu`mhh_WGK%O@BF^>2; zVb{S#en2|~qZ6C?v{`h{<0Mq3cguYD(J}h*^oL3!XsryNjD;O?u><IGRfSgI;?hZC^ODK078J z>n~6rU&V5fR-cWQ5k_!Zu!&usYmMz2kMfI$uZZ)n!mzlM{OUWEgf8*VBk#JS!^jg1 z(Z>fy)rC!A- zWi*7mXLG1m^lqJo|eNA$zC(loxEvX&jZQ?cIdC$~SfKz8YA9r`Ja#@eq}cx7A+ijHZZ{MKAib|eAy z^Nk=b+Av>YS)KK$;_AC9Me?u^1XWo`?D`>j!LV*2c0k)b>`&uJOq;%y|I<%VShRT$ zp)(TaC%k96)s(;cs)1vZrk{#e&%h*q3z!t&W=V&lFvp5`YO{}t-Bl_0xt&<7*IvpZ zy%%uTT4O%{Vx;Kvl6GUoe7>o7iu@&Yx6LhW<_{MfW3kDu_-RnaZz*mTp=%#twJow2Do(^n%HsbV-y`^`cvv^Kk@k6=U0Dcf zZ-}8u*ICj@Kll@W;I9wIg*@<0H6|$Bn&Po8HpO&twkCU# z6s(3v9~F4Gk{cGL7xJiYbd#-4htFmW%#ZBEk_Hghle~Fwva zh?CUd^=RaVqW_psQ9xq z+mG~#LXxH~9L*!;eMYAve78Mb52<6m>BRf(=ZyMya#1ud7f0&7p)psD>4Z3;YgLTI zIy2jnf(bjD`1@~X)2d(UfC#0{J}qBIa@mA24*XSW%vX$$i=&<4JqAOv4mo?xpf< z|EFTTPAqO}YT$3rtiMV!W^E@ei}v{jQ+sGpR%OS;ono>EdB$iabn@Wx_`T88uj-21 z9*KuAuKdp91MGKJnW+03ffKi>4{PvP zQ8zgiBb!~R+b)SIl#at>?f=jDuyPyMY*dwmv%=^1Ny%{jvRUAQ8i5$C_^o)J!DD~s%`40NWxkLJYFEU4Wobm?b_ zP4?Adu%{c$uO&%yzU@p`3=PZY%`G`%Gil?)ekh`Oopt5>)mu=TZH~y%+B`%v4(4 zi8++MT;{{OSBS7XLD*y815?*Nm#fipWb%RxzTv-OvHVC9*39|J|5>)Ba)@~n^&2YT z;`k5Db|m%94bgzb$!x(%7cCoP1l|4Rvb^SQyj#0!c41PyNL>?-{6K5m@fjxc$deZ6 z--Gfm;p}_82fV+fa|efLF|J1{{4>Av<@O6?JO8VLrtK)q-F}7NPb8*goCZD^%@_VZ z5@5a9P@40tA8F42kn_b+m15w_5bPLa0kgJ^@*dNI5Om*8;ux#+9ETOuv0^esS)4V0 zk06)f$TE1(W9AX|mE93$IJo96kE}Q>rk3=hZk-gq zu&PMbl&y`O(^vBe=bnp$lM~>RqKE_2EyP3e{|_tbjLCL8*~G9uSnYF;TaVo@wC_ja ztd0p<-uTMzQO@X*8FgE~dCdCLv-RRN(p%{LTK;?(QXC36GuCALvK(RmB%LcfE*0k~ z`@d#}5^1al&xJR{6`VfIjAB^BPBgG@NE&_(rY^077 zEDpqpvE3z){Q}c{7<-@g-Z_d~zQP^$76nq4iYQ_DdV3oF_3>j1&UC}Uhr6YjKX`03 zWx93oX4W)u@=^>|&oDzT$3S-Y^LVIjQ-)n;4f${aam=T?l%?8dTtI%(&pdCb7e8oB zd=JMj+<)jsQAxY~x*N)PpT`iT};a-d#c-7)xE;(~Xihe@nznEo+RvcZ>N;S)Iu zot@R#^V3ck8WkssQ`Iq6D# z%XX=8a5L=+)sha}m3W4OR#@Wr?^uyecbqE~{jg-gC^p@Rw497&9^4n;M?88{U3VY z&uNDPn+oLmlvg#sWP(wKyI8~gmEe=wNi*N!Whj;pv>?XK1CKe^qrlhn!P|rOd~4Yx z%ud+Bi_Y$^4CLghcENVk}6Y&YL@f28nTOZSxi+6X^q!t!TX@jY`7N*d0F z-VxYXVFToF?!W1{#!lFmCG%k~Z9h-5`F zOGZLck`lswU5BEyr-t_4Ds3ry?@b7$Xlf66u9o)Ri*|2=v`h1McK`lhZ*YQpNG>H1pSyCv#1@c%4L@AV)gmd3!H5<+>&K^Rv9c?SRPh4uM^mJvPjF zs+h0ti7QHJ{QjmQk^Y9bUei9vGvBb5@(zjQS)$$k7v-!o0yQx2evbG=*|hApX0Uj= zPufvQ-F?=l*w5?n!f8<${3@yIg&1g57Kz+t- zuavgke26Ko1JIwH=U3bQd-k<}*7vDm@#aKqJ7)}iLtCcjL)nMh)$+_Qw+O@T0aiHO z@L4hSR0@g~bM&$ltm(fY_&&0jx2#eT%cTZ{jq8Uw59`^)1=KgxQv-hr0;(PlO+zJR zp#H1B!cJEuq4q)t40Sjr7M!>T6_r?2nsjC-QfBa-n@st{6)~pxGb%}R znDhqrQ`3nxP|P}$pUdX%E$%aLuUI|O3!6;RxY4a*X(0JqCweTA8EA!SN%+uG8GbL? ziwgfDX!mXh(@^>Xgt-vY@&tGOwo`mq6ou)t+u+d2nF_;~#M-6z9qpnEtn21AC?MVB z9}nk2_g?t3A(@Y8uf*&RIwGJjo!>ZCAr=`WQ9eZ(XNK-je7sYJOPf02+x%zDT6-~$ zjaQa$wJp@5u$5Q`!yHq+YKN1j`UCkuUbNv~TdYN%lfBF|-f7I?t((EcloU3p#FdyT z`P}0=`EXK+pU}G*?Z=n+Xv?os`4+eQJUkB5TyN4CjHOrap>c!ac!4MP2)ClF^P>dp0u%)+w)PJEe zmX`a-Gye$PC4-Vb@@IP-#k5Z;=sUC-beVZ7C-toGl!HJ_XHLrUB*PmPGT87q*FfDGhUVK5;eAlZt!P zF*l#?hTjKNv#G>7*3;I+i?39%QXGxW)_Sm7*1}8kP$Ul0-P53#7QgQojuA=Zg|Lbf zuI=7pk4FI>9oo*mM!O@aB1z6w^}kkt9G7NT*S{6Jv#K3+IHbrk|IeQUxE5(5d{rB< zsv#K`%}r6!cO|pTcEE{WHN2`*nc(DI7r!iFY0ebCiSJ?h(j5nNpRqFP6+E}(5x*N0 zE?!?Kgr7Qj&nC=d2^$j=6dk5+Vwsl~<9DbQ zuCzZbZk0sf9=-3oEUxt`xe$ZvD|=vPdKdm|z7K|pY(65gxVp1T8cKhEMf0CQm;joqpiU7iN5weK-U6hR{CT5i1Nl#h1OF7-^KsO{ULa+d^FNGCGet)rN}p zYh!Z~JaPwL-_|`|mVW}Rvk4hIuY%X&K&;6kEzd*ESlHiMUfvG+MVY!=$R5bpamv|OcO>f^+ir7G_?iV z9}B3u^*I#|&TUbld4;;Flb~Tt?`S?kyvvD4`aK7XDY!4a%9+EJ+}p}~zSDz&xIeFe zs|IE%_S5r4C+j_LesMp`Y@~Nnoie^IE?Ar~&4B5aR`8DAAgOw6K=A5LVE>u&hOUvQ zh&I7t*CZhsX$bx|v!ay8lhC_H>VM_wquAb*bEJXR&lGOpl)Fi{)EwJ7>C^ zY*0b)P#aM-As1(BjqvRLX12bvCkEx7)|HE*C($@LTMzk9bVReMahMThj(3a7Sj(8jcwKD>jX^bH z^psHiE$oC>`UaB60%a`D>MgU5Q&&;mr@DdvW1wZ)H6YX9pKb}?*mUQ`IDVv_zixI$ z^d=4Pg%WvWA4Mug&&|NxBOPVdam1`-Y$lEVGXQT*?{ zZKB6zVorW&f!n%da;qE|&1JZTqAnpW9*F ziDZ6!7il{V)Gtt=ju>YX5xNnMHl&T(n&%hDEB?uLiXDSHIR>y zw883m*V)aN>8So)D{DL2O}$X~DxVMQ*MeQO>WZ2DisW1EP6J}ChqXYFdcI=v)Ov(` zU5#-;>imGm63U1XC(xMg9aWKdILI2=SL?hMHzwgl59;Gna^Z1fe34h1#a(qus#Ozm z(A?}NKUCkq)}QE!VO`4jto8%Nt{EvfS*?vZ4rVO*ZF_#<+jdr?ww?NCW3c>a8~8?# z5HowHqC-eGgjpuCfa(#%kJ7@O{0lFYbMY8wOAervJkCkvon#mvTO~S=iw(^{xfRhc~gGhvO;t&>G>N zj*6|68B|pzJ?;7#$*G$UU%&n%+io2thWrY}WXn$YaY+&{4tNr?I+;H(ox#G*+^{Du zSJrl>)Yjr_WIq(|xhxqTev26av+(19HXO{!2OFd-Yde`U;_+~nIRYcPvX}l=ShDUk zZ?1VjXjX(Er=J}lo+yGXCEVDO!sq|pAhcJfB4%bIx87e|UEse7S}_I)x7Ogh^W(8j zqXi14<%&L17SfiO!}sSQsnMwu|8e1je5;j68=Uf+dITGN#N`$#P%8IChI$6OdEX1& zgHrgU;%ISpNGAFo|H9)f=16bW)WO!!4-V}w@T=Q55VHlETA;8yz%Cc=G&Z%!E1zl80{OX;)SYex(q9p0>fqJ6ollONg`m zOCPRjYWxqqduj|bM!}~Awf$I@lVO3dRoA&^|2;x|EXN@KR9^G7R4U$~ zhjizK@}7UYM-s;F{muXRFx`rC$!}tS>aCj@{Uxaj^f)iHqbxbG2<8yewMX(aMPOMp zYOi*{hlHyv=voNWQf=iu-~FOH={5;mQ{%7Hb+i*k8K?0-x3-GEE0Pg#?=R0-wo|b* zx(q*;TH&M1Q?{$+5>&1H%m48c&a{m}R){f1?M?Cee3W__s8{z*vMCRqzYg=0$Ol^= zAsBUCI`&H7eSG4XPG47yIh@UPuMH6c+Gj%blPX4@Fko8??Xh=KnXK&$(Tk=2C0$wD z$vPQ_%EM-uxn>QkYCj69V^m#|DEE?XRS*^wNs<4 z=O=`hpy8<=#tc}+oGU5EByHtpy5&MWB?j)FS|Y%_rD)zr9cTAR`wA;#Zw4+wI}2jG zJJg7CtHPi-YL8Bb3?#8d8OpVg`3WQ4(va)@j!%wq6p6*u3ruW<(1c7Dv~@8GOy9~G ztCQ5ZU>?;9wQXY+=Nw{Cx}5GHF=yFE`t$y69r1RrLR8;RMA{@b_)hvN6(=~M>Q{uk z=eN6^ilrqDe3Qiq#rkn6xF4WIY~`aYPcspjo-NSN{+PJ2me_imT4LbM7G9IbQ@7D< zV{9F*#W$@D$F%_#XnP`7?C~Ieb(dbqQXR_nweE$lW(j=dQh$-;-v=x8N_g><{Zj89 z=D4>dNuK#?y~&3b)*PCeCSuRUL>zZFz`h+ptl~BGgnD1()gjx(9F=f%+Gmc<$&%t- z?=YD6ut#9sRrc#*CKiX(@moV9#Z=;R#Ldp*?q)5R_w26dqDyyq(hm*$CtyIBI#&P9 zQ^z ziNlMllj2fw+q!`-%zMhN(s$`)+fBS_`ap61cnTWsX~}&1XGiULMOGzSaJEwTpQK*t zBSx?vO4^Qb8dTbK!#_{vCHIkd@Iq6b`75Qd_&%qU|9zn)J-xgh$4mb5r+zc}y}UHk zPgKEqljY(s`EO$vQeH3nIJ??FIkT!=^31oQXLtQ^V~jUe6J5JRV(M7p$PL=eth0iU zH_rldNhj>6*$=&wvbf$IFSetL3vL!?@mXVgEQebAPPGe~)cZ+0j#6PUN`xDTOZ& zn#1h8-LTm%hexP~iND>_(eXbOT>2FwrJa0>(*ZMZZyoJz7vu0uuN9PDW{O6oIQS;C zg<@tGHgcC0b;#DpGe3S&2rM4i$X&FrZhJwmA&I|C*dWFehjUCC{l2=ER`(f{3M&_7 z$|1jJtF4o8V~_@Vz0MbXy3qS6edcBDcS{8??fJ&%$K*Y~*Ehnx7{BU-)=$%i!7z-@$!~Uz{68TZ@XfebdIL4&e17UY9moHFP z5<@08;M@^!RR4I(etn^t-&Gyu@5fjDwaSM9-2y^KJz&{$BcbeX1n<>*g#G$BbRg|F z!s4zp^T0g*yH6W_@_me$mem(uU9z})k2J-LjuM*4OLOOBAk)3l10!FQ@Z7Z3V#{%w zZwK|T>lAgGj7@^;Wy;XCYr*q%~3sySw0Z`nyEq zmq@sDG{Wwb=?blb(Xc77Mup2&;-!S(hno%5P0GdW6nE^{9mfw${v$02aKibmDSXrV zt>W>YLBmj9P*r)Zy~apEEKy3UybEaN~W7*9g*fX0)q0jY)oNSTr8>J`diDzx;eCOzcN6Tx}m7P zl!>N0b~x<3huy4Sg1)0$V;^cn)WulrYU+khHD*#tj4~PvncPKd+074wXK&>8i$5p= zX)YZd_M3kW&SVQ!m!N&XYkALitcpR(P8}r8ic)NDO*7xj1f%|(VS{OZ{zTb?-;)%g zqhl0ml)6x+^p#}w*@@UG;e7iy;?cSE!M1AMh{b!8q4mW8F_Fue7QL&+ z9=pKLkk`xOa5zSeFvkXGrdUYahGTneQSfolxFp`! z)dR}2&}EPwdQDX0&$iKgJEn)vjz>j*`fMG#Q2)`=E0WT{zFaZ+1N-|cO0+t?4ofU; zVLr@LRL=EA>ZKH(J$oM8(8&#>GqYrtLfVE}SY`Kt@y$z8*}=DH)o&V!XnR1izKWA@@%kJb%!Ijcc+(dFNAn#*h6%cknudUbn&7&QBE)6TNW0RU)tZP$Y6) z({Sb4TdrtTQvHy)7Dh+@@_siPS=a1%tSwfP_5AE!4`6aHI8dU>-!II|K|ua@6jObGR#6_QCm0+(&hi@65Eh6?DGdFiSbv`Dcjx+UMu^u zf)oqn`dr~v%XW)-PUG-pY6(w`JtWoZlNY#rp3Kj2`;dewSAX)SCf34XPCe}c(}*9Z z#CIur;?Qx0JoB|OBQcS3I+B>CP$vI#zcs|E8E})0d%q5^J#10Cs6xE|PCo5xvAoZ! z-_rLlUE%yDnZLK)Dqd_)LgÒ{O>il2+~(D8F??D4wBUR5q32KjG3ApW$_{uza` z$3~d!lj@Zd7lrdxR@nBR39mXw{aJLQ|HnQ4vYWIW<9NQ{L_B-RT(S37CU=@UL{tP( zMm6LQe{))wUA<(Fc1JeyX)|lZk`l_P6}7~QGvmZVV*TA2XN4(0!r8l=QK%a8|CxWQ zdL2yL+Ct%Hs@USP35(x;jU*rZ`#P-j0-~c#MamwRU`b`roz|R1C{zV()>rtxT+_~ zp3G~j{IE``RG#^x>#3WMezT?1GuiRDC75~oKUvS$UKE3aowa3cXM+Z1z=?6OSM3}d zW|4x^KPbzTtPnNyy)}OCjyjv4(&~BLU{6e>=H0i8kB@zzZMK2OdqgVMtw{$zsDx+P zf(0x{L<{HU(9t?3K9lEp%P1Y}o2lV7lQQg!6~;I>U59tkj=+?a?c_bbC@BhEI#HMW zB5(GmohLN6#PNY_j3~(ThV`-nPVPy`y}vo;7$wO5%pYcnaDSnO-N~lHtW64Lwl#p$ z$>l7?!v#(A&+~4rcZkCuNDm)FEHBdY)5}Qvx=nnxhRdYa<)C(GEqAhv7F){zmHq2^ zL4r0rKi3Irs_S{#rV4TV2ldTeQI%)@wtkriSZRuMbROyBlZ$c_10c< znV;i6HXeJ%IHPZ`uDpBN0QCHl$t^Z-s@6aTvM$&26+K?EORsyP|KVc3d)xpq>~B3@ zt)7bbnW3y;mNnmHULpH-oJsrgd1N5(`Kvdiq1i7-TuMx22c1S?&m0YT&o6F1m~`xH zt~p9ovQ4YQcVc93ZMKQWPDnFD~>9DknZp%!dTT-PVIhtri2klc0U39sV?{kuo3o@_pamv3B#LMES^d zFwf{9_gJ+IbjOs+7(Pmx%(|7kB7b{^?88s%Ukm3Y-mvL$Nvb{c79YH)P!EwdHWt&p zX_gLlm}H2eLkaNLHNz$wC-#7D&J$ms;Fb^ei*NTsaf5zevFD#D%(iw!&f98TcUifi2p1=AXCG_79!6xS|^2~3(u^vY6hG4JO z9X?Pk0iW)v!lCB27i{cu2n=``Q zvEH_tmAA`8*2%kkk)FG#IK!}|M?TLplbH73c>KJfitl`U)yJ24c;Aos051307ey2< zPBp~Ol)a+svp57++Ms m#Lb0zSC;|7U)1`cRxM%H>_hem)jof z9rd%geY(WE_uDO!F80RIKFNF`E0cPRYlTYJ+47#hcu+EI;=ju?|BiPu9@|mZVOlux(#%&jXyotq9` zU$kOVq)r%}Tf)bTs1?qXvycXB}vmtFCP^wx@x50)bb`i=tKYuyxRpa?>F&~*_*|_ zJ+W|((8l)ImcpN&;|KehAa4IgcF=7pG%mNo#MLz-Bp@7is&=xrbKgz{@8)^R+Ky-J zP?Y?l3~6GMLNcVgp?(uL8kNbqvr+;D^4 zKnk%}J7KH8LKqLEd{c{_P!nyT17Rv`|C#KKTl8;(XAUMmxl5PiuEn(D3j_^}b_n{9^q=VHYt(*0sL_CSA& zLG0%r4`Rs0@;SFgi$PC)h@VW^H;n^QeWN)FM#an8&abcpjIvP0(~Tyg|JyW(DnqC` z1hY@wT;O!%EH~P>UD&ONzy;FT#;<0I@m<33o!P)@*cCQx3~|P~-{orkBgLlP!0KD% zCDzww=XN<^*;(pUrtNTZv=$0jq}Vl|RO zp&$1j_nsyEAg|_s>#$>|wLJ4@ZgWS~^k{kJPde&~$Bc4Pl(${2oq-8We|d~;thDCx zTbvv|3BRt9_iKABe3&*qJV_Th66Hb0leV+mi5&}Uj~ivj`NOLH;$=xFQj$7g*t4gK z+f`n;H7brf-z}n^)7}_!Xg%LJWlVMc>@=)0|IO38eqe335pz|q1j*!4(qDew7j>BeVg|BV}l zT8oV>lJWbn8t&`mvxzr);(GEC*{k_%3~^B3>7&K-X^NZs65vD`|K91h*`wtt7+cU2 zdv6{U!HMqB>lej)P5&(!n>gW|LjvEjkus96lAt-|3wPhYU6Gu#0Xa@acvE(l6_f>G zZNzt3+iCZnyyzPYWPZ*?zgWCaw}MWWw*0JpIL;T^pp-=k{+qNNiF_$*q1A;%1-hKI5475=z1 z^$%b9k5&F96w}o@VB{uK#Z>Av?yi)}9prq*bj3r;`*$=j#_+`(*@h#un-Npx-^`EP8-W9h?V$hGP`W!= z1v-_zczd6hBHnx;7TqZ36W@JOln+e7ApLLh%zv>o2uDMn%XwQB;(mO~(vleqk`nO; zdYa?)w;Rmo0d?3}cY;){5D{8wXm06-a|?b-b1I4Vxo|BHZ@yg|dG15~rR%xX;|Rq( z^Hj>heCOBRRlQd3z$hB)7rEJFU3$jtG3LYAfe$ zkJP2WxwI#)L=R;l9-i28GFqPbeWv>0N#uH7GGf2+Oa3LwLi<_{dR~N;%Q(~xEp z?TZjYC@)@nA(bbqsIk%m-O#E>9@m((RVbz;Ab>JQLtE!5{yHW@lbAUpR+X?F&w_C3 zhZ@R4$t!i9dRw&H$$I`C7t#z(?d87On=zx&FgTwVJl#=!*dZ6m=NoxXj|SFib5F2k zg}icce{p?N2Ii${;&+e*D|ha|XK8I=Q!Z~4frZgn{jxRIqz@It6Ua}V-I4M$act+$ zQ7E{kj;x>yVnxwFsIN=smrR;Ts}9y7dv#Zg*hc-GE~zlw_?^4(CE`LwDs=>_@A(sIqA^C_0P!|z;+kp-TG`rT^`bpYmn}m`MO)-`sSyJTJn^MP41Z?e z%x;ysV|ed$zO#vDK0Q-RE)qZ1#;*FRUJ~9-S4D8=AFRuXMCz5*#rQU2)Ecdqv39V@>=Y)Ly+bcoIq ztteacaK1i%oUN2fr*`6Vx>w0PRx@7Hy{4HN`SyK92zhLN_v?V5xCqww5c!&R$Mg4V zVukY0A>efz`GdjjrS_CJ??jBs2Sac3J%bYvtWZJFn`z?R7y9on)rZ<$JGQ#L4e}Q5 z=RFOog{fx*oO-sE_xupIbeI&mW0t>Qe%}IcKe&)D)7KChbOXwomCEmTabewwKNhv1 z8QdKvRP|X){I`ada9wkn^&>s@^DMe&mF*K22Q#R1+!5b(UrIWPdEBkUkdLa47Gu{9 z#S@<_p8O_TVfjbG$>40Bvm%h)E_5Sy>jwU^?^@CJR5mi!>0ro%66wbKY*Zzar+1JZ zPxFh$$auQZpGguEs^Vd0&;iQBJeZEQCHx&O@Kcv7$v@+UklPXboy~gb>cv(_JvQV2 z%(RQi^e*z1W{$P6vCl(;LKjSPGn<#$1(&lcxzfxs(fLvoDwJDeVZ?OB7DWtpCRjq% zpYCp7!{Gn31O7H_6}8npaCBxEZ>;(%Z9mo(msXMX?o}bac22_r;uU1&S1JMvQn2o9 zbMlIuU|1i7z?P)318Rr2#(#+^UJHw2NlPSkZE0J6Svef7HEf`zMA~DE-nded zz!%R-WpmZtQF}IxZ%G;|{(Q>8r#~vt%Qt3EH+RB3`~S~;cgpYhtk=TSq;cW_@s5ht znUTjMjE(H;PdA$1e9@i@LXGs~kpJ4tjD>R-H{jRR=iJfLkM~bbgXY8+JgaH7DAsF0 z)Wm_XIlG^^Ge>$ z2)quoMGr?qDYsk&aV^|sPUiSM197)x1E1;lSuswLiT!_n^W#VJm{(>GO!%;cUyaBR z7ICpyzE1;3JfjpWCKc_1iM!%|lf8NrjU;A{wafR28}ri9xX2BRsG;L*o$;j1@xOb6d9p#9-NBwd0)B4(<V&O7jBw};va{O5g*IluuD0WznN7bX>7JY z;E-5(=Kn|D%l5`9^33;sn++@SA9^eZV*&koVouR%S=%WjPIb*M%5LB0ibdtINa{d6 zyW{S&gK=3d^L>7rbmQNr{bbp|&6Z%NA*&`dutOQO;BqI7G-ZKM$dBPqD&G_a|gtp^xQoG;i^uNQ7k$L`wVyzGcgl>hoVIbIqH$)07Xa zC?pY2>34Fuo;qA!rs53cQ*0}COBOYhsk5(=_53d`k(g^iU3G_iMf~wFJXm6lkemos za|Yl&o8U&)O?Eap26y(g#;}k3#C6(L0^_XVv+=I9R%bpB z*lxgcilW8K8GbNbpDgS7g&+H2+WrE*KR=lL(Ran+Aq9NZnP6e{V*`etC0%jFHp$E+ z2NS26z|&ceZ_bNGb%j34ZYPO=M+rD=)&ZYac(Ux7miVfDUY_~AjeBAEwQzoPMS=8@ zvinl{RQ^Q!g-8e>W>N1?{9o_MCASnP&r!vSd-*KQyBF?VIKn%Bs}$!(MPp}HE3Dc# zUGX9)7N`0U)9>I_Wt2u6mwBavL zh7*6-8hd=B#KEh*i9t>`;%%vHK%*Oc+NQ{RezWXcIQuKZ@U}5ib9O+eWf5Pns#f%; zJ^w_s29CZNE0&Kdf!`rVB-^Gl-P8V1U-N^X2)rPCRKwA5qdjp>+bFbK6=T)5$9$ZH zA7AO1jzaUNGFNBO>;@=X`ynEEKP$iLh@~@1_}0kHV*coOx&dioN3gEA`KFk@OOAMV zU%^DgGR!s8mA#se(!+^+Z;gRJTT6Z|o1taAEAR5+rRaPi9dmM@^7S7b#e=mCczvxO zWdpyk*7h!___&#S9?K9_edu>2QQoI8PSL?V4eAYMP<+10lI|zrSX+Ac8CoTZ{qs@s znxoQDjRj70#=(oL|^R7NX1XHFv-LVDgTU)Sa?W}pY z(MIOcdaHjErnn4^ECy{3B8o}1A^+!*g=6J4oK}_%iLdV4L9lGDVog1dDaLBo2*=KzICV0DAMe$T?fm13=(;q1W>kUrJd!@c86UazBirh$ zpEJ?bM+3LEG~=u|i8{e)<`dV&!8Z+Uf11Iw)j4U&BtO1x>Kpln>r1|=M``5$_w*F| zI}gREnlx?@vYHJn^T6jDsXTN@xR?}PhbK1V-8Z=;9WkzlZu(fn4W{?QnQ@4otRZVV zb0#HYE&V#c0#gvWkRLI)S@eiT+;Xu83jZYNk0zGh#Mev#a1>*V9foQ8%#D7Fh zseUn#cEZD7WIaD?zdNp2Z{s!B{KU$(xyUgvLC4NVqzi*PQ%~j*S=;%b7l~;HO%Z15 zD-J8d(Q!WYqzsN^-$T7Hb5A5UcZw1_-VQ?twNf55*;?wbvmOhq`eD|ETUEkG*zwR9#W!!UOV^W-#7%LSyt1A? zN%*pW`ot|CNHtI9a-$3Sd~or6=u4u#5mfg4}6`a==C=pe<-i*Gwm^}C7+ei^6r>jc~o>fMe{0k4R;&zO-d+r!byL6 z4_#3qm_r(Mmwn=y&vq$(DW@XmK{MH(KcI0b_RRPsYde`Aqp|%vF}JHyyh5X+@FKnq zj+q+sD${U$qI>R~A(0|U)d!B3V)@A_X>8ODH_V7n;=zeSgy!uMDDJA`<|Rv3F~e=unf}7jF!O5SZOSf)*xO+kImQZU+f5a`+eVBE zeaip4IFSD&epKkzNAjLuvnd;?XMXWxt!A>Msa=ts$7#|q`u8^Qf^JQU4$B*$ zbH^8t_kU(bJbIvY`X;{oM7sFfDh{^y)uA*XN)c~Xk3r2s@cw*f?iiGWL&IpdnRP_G zZ@V5PlQ=Sy)!3ITXIvb-LZ11X@1$epu*baS%?ZVX6{HXMe$Qun9bs{FSL{W8p>D^P zh@;<$2d-#=k9itiIjQ+jDzU+(Q5O96%t-J@Ch`q8R}{c(wl|jUo5BjmdLgiFguLfB z>GXoWSu%g&zE#@pX^Bsrqq&jeQ^8)7KWeKIV!N1%5929+q+*PtF5zs!Ug|2pcZ%OQ zxkIRu$E?R86Fh0n6!pZIO8L_bHI$9wt0o|ZdW)iZ_7mSCn(`%S)StKs(O5wG#BGD)cB@O%djn=nLP9V+=ztV1XCR7|G4Pn ze^ZC!y*uHC?M5E3m$-T5@A;b%i-b>lHp16v;L*S!Hey#tBz4`wjRu?-gOVtR=%^?A zc2-npkSC-Q3VR%69gi=^R#j638rKM&eV({j9?n-pbYq4cB$#-l@l^dnQ6os(seaE( z%fJdhoD;elz9De}y3I$a09gkG4Zc}dDS{1D~|et4*^g6cWM;ddnV z&i)KhawZWA9vC6!LRYr)pfys}tK~g^__Qz>(mT;VmfDn+UO4I$!GrGKv?{ZiJ^Z4@;>nyYRb<56e9K4m=VW zdragTuH=)4`^FM1PUf>djtuW6MRL6!(W1lT-q_SDi%+J1=-#&$pZwghCHoBjnwLyb zQx)pkoGsc_rl9AXmN-~u%XWSx9_^joJd@^g>&e6rBM;{}ozIGwfp35*X?QTjgl}s* z5x>vn@pCUU#2mFgczh^}pZ?9+jDy7LS)(LtJC_%iVRn->vcg}n3YrPIq2#sW)neD1 zB9nToPr>66Rg@NqQc~|h4dGZbS z$LaN$>D3Z33pPvDYf3O$hd$2?Q+{YyG#-r5gXN4Q5iy(kDdu-Ta9hR(YFmL9w5mT8o+cc0xU+j5Ba z?_DW+c*oXy&h+8_TEpr?J5k++mfKBzK@VzoGs;?M>V=_k{F1 z&HXQ4v;n(N_sC6cK0M8@4{v*q8AV0*8n5 z@jb_inl|n@@LvM2x2lka6UXUDn<(C)_fzrGjaWcYfBAJEQ&Ijm7jZ+3;1m3@e;`Znw>_};gZW()+^2}v8Iz{F`*JR`Kn?tcmS!IvO=&RWa%4dEt~YggW<u2dIQ`E8^IA{+2L&Tq>WJS|}38OI%&h$i)%6YDceBun-lv+W%qy zwM)j~A}x8hKVtBJJoK~CTg#Zuz1^2@e*B!JFN_q$lxbQ{jLXwWp2E=369-R(a^q7| z*sxU+3csdsE6T#$iqApl;GevYZ-R7fPAyUf_k*IB3RM1(o|&c&H{}eGYhMqwPpe_y zC4-eWT4TtGD*iQbzxWgrhAlHK(B{_@h4W?)Tv{H=TUr+gpZC7RR>|hxN#m-^I;G)a z)q6f)xsmBtx#5rb7XG7MKXG+tA)b}C!QNj&vY*n0OP+`1IiFb^iO`qEFz?_i=7|XW zpd9p2MI`IYyrKV-c6;J2nBEzVz5yHf^)1%YK}9VdJtRKGp)>pdc~n%YmC$CyEYZgx z72b(Dz*So|be$~>>nr8m-t$%@Ww>cR_xY-5%6@}8qbW~oXTsGQ`eIUDEN}YsP4Q_- zU-Y0Hw`JQtY!>k}mMbgal*YuWvu??-I;@49m@}-OYBI`S8R1gsQDGgP2&usm`mOFs zZk-qK{qI`IbN-$0FnIW+@c*i_70>qf!Xon|-s;Y5cJibvzD&&Jc16KL{b(&3bNk_0 zWWB_nl%T7I1rF{q?>Qg6jfIR1$)csIWM81)U&lROj$)qtVVdvdEcFnmLoS*EMv$uJNh}BFTXXiW4 zQREV(<)aC4=Qdtquj#(lX2UA(yQE2at)RZyyhuLYvO;Vi{=}0XoA`9?C5l1B6wS|8 z!kLO=Y<=P~%o2_AY@ewW3)2I-GFL}Gk}?HvjBq@_knb5Ej-~_)xzjLh{{ZalL!PcL zSxmfkNBOJ-{?2u%_^spvgAS#a$+syQ0U6LhdeY7MqsFBUz7n(;l`IhU1EHRkBB%MKx18yc|y_(H><`BRp>t8-zT8 zV|sRwjM_CrkJa5|e@Fc^B8?7fIo6pNZiA zdcbn`8#do{0@7(m8Xx5?`tEkc^+|DDTThjB3G4=k?P2P$p=%IerGr81j*q=8~Y1m(px_4SAy~bQ}$<+HQ%PQfx3?>L}5(~M(OIJ z`OKl>SkHKRk8TH*@CfPxR3)1t7emwu%Gp2GdQZ#Q9j@0|+vWC-nkOZ5Hp**AGbhd2{ zh_RW!G7`KAu*Iv%(2MesiG%m*tjT6_TgX1^ud)A8NA~3nChD2#H6C`kI%mv z*z0X>2%vmN`|7@8=aX!FswZakp@Y)R*IoEF>g7nepCF!Hj>PZBM(C&NEAG&{z|v*i zP;ZgWPAf|=&kNdc?zgJbzo++QtOG4mqB-oO-Y@@OG@*vFmv*mL=xAtB;TQWmahHb;i< z2I>4!;-%HnL#NcZcFuI%|PD@>bL!{=013g4+5s-9t7 z?^m&uI7uI8=Z=-<{Hj7fyjc1_lFm9RtF(*aw2FiZNQkH?ii!auNWAwsn-*J4Q0&AO z6BVR8MH)m=Fu+daeeCYS0u^(_4s84$@Au!#TC-->;N{$N_u2cmOK9W1XUg4=ld&?T zk!FSEFwcC zK8NG=Ckxa!nku_^Y{Ktv_bI*WKuWX8#EpJ6q~a3FyE&4`6X(+it5&Q~fF!>q=F_qC zEj(J}fI4>3k~N%s?GmJv3wDgfapvu@40Z|4v9H}}etS?P4vBqtZkeI9;=Aw#uwHWZ zs^n6CTo@w00bSoKL(|`)n>q0E)Mw^;QFJ}UY#{CEbiTNUxC@Na#G8sJu&+ajlW)QYz=!>k_a{u!O>Hzmqok^ugO_^J&k}9XzY67hV>o(=L?=rP&NO zv=kbtzgGxzTx*Y2o*T$u&tl%GQv!?zXu&{VTe0L-ERHtQM~uG?wM-Fu+6H43S;upA zr$Sf?#L}_A$>QUXVet1*iaR-$ci1j8khbykyzMs0{ZD(CJ`9)l`9&h{A5is^yiS?$ z`tNVxesC(%Le8_*pZZ~@^Kp6Rs~Jb(Khf>-&xb!FHv`__o8I@ef>=rKIba0R=t74nyI2ATa!WuEyWn27yaAeUspsU<&-fl zHmOm>eH57y-41xQ%!+IyhT&HCL~3%iv}$#&cxK$=W!*-1SU=E>O!+=L^K=T5hWw?* z3#M$uZ%fJ^T)-ZkDdRUAV&J2zhf70-^1P@d;R9-ilT)JE3*~6^uTaCsl^3{$fW4tlCV_mPyRp;P6sTR8NLsz~`PlQR z_%gAc^0T^BxkRTU+f)s=cB#<&G4c2kt%-J54)Gyt)6hY5dNz4+R$8RrpR!WxP=ntOJTU36 zDmL51!$CZgP4=eqkAG7TzNj^#ZrHJ)^_|2m@vywlZ%+(IeP;{&x=^PKivdQjTuZ)N zHt-SCeX;g9 zC41P;HgWu^YZS6OiY_^KFWw|S6@z<;47O1k3$2Insja19B{BT6xF;0<60Ea@){@`T z8Y~=Vk9A%`%a|*e*l&N+KdoNnTMFtw34deT&aAUwckP^ALC@8z_?xFuxbaAQ?@Qm5 zH}hVDwMoY2NMjn1J_UCvn--qe;g+pk@M%swWiEGQjuVq1-TqC%hXX5%;zYKnw;?ij z++hb|M5nfxU4O1t@$SRL%}ekxy8pc|wcRs^9tG;ly(hDnFVcp@(1DR@%C#L`aA#>e zsh*n2=G=CMR&5roZXL?^{?0>Gm^NH%H%kqh3-OG#M$GWt2L8nFW zWac!C*9Uszq25LsZF5@koN0p>hX0@QqmANm$WuI%o5%9RTcU%^$p{t!VNB=H80_r( zh33UyQ zRLVLWu3U3N0sG_G)JAOy3$3=tRsAAzJ+qjnRETerG7U_g&`j~XE(Whp>R_*KbE?pe zM&vak@og2y+h0mWUelgXJ2IF>If{Jw^Hnr3Xe_U<8IAF3h2*~Cl(fRS1KRFdD{J+g zRK)Mpr61%l-IUv{OT~tPf;q5Y346a-u-D9w(R<4ZZk-#2cRW<(o(QJxf zx~|P*b$^6LRJ)FDH~8{JBi};h*ifuqwVIvQ=}0%e<*}71B3t(>2KQ=2j-z1+_Z*uD zlNxheQIBFl&Bmb3Emc(b2@U5G39iK&()#&Dv8}We-V448K2I>2W~Ygs;ny_UY!RQj zCKV@oHqv*^nJo8^@LG=DNWHBu@EzHr13gR^hx%yphZAD)J;(&HXG+<-`sHxXGLm=u zQNQfbecXJCSk#q`+N(hK2k{i~ERXMfl7^-iUXxXkbyZal!7&@DhJ_zhsb^=A6a3Lc z&Rfmeb01lWlcD;>i1nH>fPM^nDr@zQN5gTuLtD56xboRw8Ok58rZaid*o80`OlNV_ zW!zfs)^P~N?bGKTnw-FMdZfaPLSu&lFx?Z}Chn-E7C^D8+8y z;SlKu?&rq_g`-7*@IOC&qO@WXvu?L=`#?;F_~1GIH9V`{4`Xwd`+2i-m!Lp z{cyPJM$)?I#g`t;#7PHz1n$}|{p{U~JVW-gF@cHvrng{q8n%YfTyMT?UjaHKDiHXz zfY~*=2|jZeeQ}B9?|lcMUi2)#JYpd=`(A^?MRu@jd6s?;NXG18KWVhC&=sx7JSY~L!*ubiYcgMbKxEIGwZY2rer$%jC3b3^B;E8~d~dlgbk(A$ z+J38ajtkGJ-$;44cbp)4-{!xfx&@uMp-l>Y3(sW#F*(eO8BOaF)(Sa zgQ(|Il?EZ{NV_X|5z}f|>S6Isq}v0dT`T$4t8Orl4<++s>MZY-Ek-HCcSPn^zDCTS zcYQ^6p!YoG2=Q$jwCyi#H$TNZ?+HzN^K03Md3aGQwuI@xP9;@QF+UdX3PhgtkqNDM z7!Li}=6EIiU<+UQpn6vXot>1y!ed=P*0J);4=nXSrd|OVs-2J?{1#nmt+Hfhru~(8 zEUQz;jZUKLO8CHIL@xec#`a6aSg2h2C=yLVtIv#pzGGVy8=EP88U{mJ7el^gs-$`; z6T_z8BbAa+uIohL3vwvCswHc=(H2R1c{IDQl#gjIdht4F$Xfl?^kkUsY=y~+Qnt5p z8O-9E;lSZj{De;=X8dW3Zt8~8;;HI*Th(2j`THl0#PP6P+CKcZvU(*Uc4Q6>{p7)J zj&?w3O(CuD%i!w;Br*7e=!?;aR_^SQi_3yVP@evXZ9Eo*Egps#9#g?*rsrewUeQ}Q zRg)R2*yE{J5IxP^!L6cvF@KYopYc)3`$-BsQpuvG!-LuT#=g)^Eu{5df_XdBMA!-b zb992X;@L zZP$3ZzPMZ(d9edFKMkW5$LqLr?_|6^@r~LBn(|?WX)qE$hoUD-*fNDPo_ljDPO0E~ z#r=J*h9M^Zm6Tq|@!*bD=xK7F#q}SDliyNESkrk;3lFsVmLzi(9w}_`);5Wv8cO-Z zQzE-}T4alE<|?&q3&hXH2w#nMvHq8qV#vxr)bjNy-tR&*^n;9KAEtL*6!JE=!}||b zloCD+o8QFJ@}SbH<96L(&lwUDlhx5HU;izdMvp6{hnXam6n|XnkyjDO>OjlykaH8fVRhBK}rnA%0s{LQu#Ah?dPhCZ)Z80fZU*NL}V$nE62aP{9_yWQD z+o&b7dsEAp^THL#IAkc#{4>3V;O&eU3O)hmyVn=@PNkFM_$_=#2S0e*mQlrCaa^3S z4lM=>PM?_hT2m5`)=@(|GlzLCzmKHt6GiUNh87JerXmdv0Tex26XLM`Ax$YY2ybS94e<*C`X$Ff0pi_N$g$N%d6%hVXd z(s}^5;jfYTH9_3VU$gu~!ng7enmi$zw^j^6OTG0%PiQZ7wyniWaqqGDbA}H8N=B5` z4{~dq&KKps!MVW`MfYti%beH+LtkyD&o_?p@|{t*Z)=D)uf8gc^fI9E??4PiV$(hB)J;Rt%k+<-mTwO9C7AjST$9SE42j>E0r{;eL^6oKM7>>=xJ_ewa_X zmV`k2ws<%Gp44RIJi1|`CwE=ttQ?4!8>8fzF9|JWUU3ZVo;s7g^Ah~JOX=kNY$eZW zE_8&e8lcLNPC*{>fCgESlj^y&mJdbsMpJR$__Reh(Fp$Q-7RdG+`MoH2IJI^`V%TCBQvH59`}yC}u4>`|Kdn4c?|odV9^V75 z-$ZxM-5TCkc>JoQCioLDiC4Eu$76jXbSw&ITg?2C?ejsN`C3vW@{WlNW4xL2@Fl_D zh>E81D^;oAfJ_V#`3#GtYxs?(jtJV2N)79@*^wc3@b8{WTB>FIZb1UsAhIY%OKhdGXx7)aMeKfu!+U1@gwb3R!u0H^NdQ<$GB z*DzujU%sAHm^-T}>Wkvad|A&qrkwzT4Qk-`qLd2;=fk*bJ2dpKW8dFJqvu#dw5;68 zOT^rcK5B&ur+1RSy*;{~oGH)zl5L~$A~=_NH%(R+Hi~TH^-MaH7|bHH`{I~$zU;&N zt4PG5W9mp*qOEYA6NkKaB1h0phk9*_!YrYk4xSy$k6#pwKHE;XHPVxruO)bGSx)08 z`}20i<8V>z`P~PdlVYnoV74NZhJ@Gg^1w9QfA*7JrI_=s4(r4_usKehS;;yVi=NG9 zN^&d^dwy*cSPuhP&v~&k26~b0q1o{^D}Fy7okpgRBiwk-7|0~&9=PIo)y+Q8MK+K<|K@lyNVcxo5H1zB#Zha{luj~xv`|OZOLXZ7! zA$Qt3Fdw-3ttHbtMOAZ*+|lD;0-g0<&t40?^o?;kx$X1i+Gnz0@k96r@;k8AFRUo% zK_0vEVH?jE-r!Z0+Gr>k!kda+F?oSGoJU17TeGn+o~_Bs7JzL1aIEx3y>8)?UaIn1SdH`vw|(E!a0Jf}|ZwPxtR)&E!V@T~yofg!@5ghwxm4Tu z+vyL6)pqSDZL>9g{wvXb<-pKf?&<9wKc$&sMFGeuLJ0b>tng!&_n2%F`~cV zU#IP#UV|~MYZSe1v6QXo1bF(zliuq{-d=qu)SHx${w;-cs-Xso1ctgq;f2je!TUNb z#Fc09QkspZV;^W#+7EU%Qslf`ib&hvi|g;s#8{DMY|z^;T?p<$c}2TeyO4NJD`MdA z(GVwseE6aa!DZcME%Ir}Y|2rF9%akOtu%^HQyqrlotZS=wu3abb1gmy_K|7%8S-6| zg5#y%XxXwEJV-o0_r&va_k9d&S1!1}N4Lo{Kebs5f|eTM(|_NTS5!qlYhfpxo4beU zwRgwMrmM&y=YvwOj|<9LM#~z0;rC?d9B-he8v`qCd<)TUzoFP;92g*3a zmxz|ICezJvwdkG{e0(k~FV>MY{C2meL)|cw`VZc$TxchOImXi5?LqA1ASb-ENT-V* zLio6VEa(>qKVRPslD6pY!^v#sGhVMh2y6BhQ?r7jfZP?y~BDZGZQ{Wv6(+cGy1V72XGL0OcHfJse?V#(FOGzWk_@7+~V6N&& zY_HEVwUQB1*a8`fEo{2ca_pbb6q6E9@m-=*VEqHZLV0f}MTe`SS#=kA<~Mg3kNTbY zbaAQZR@lq%sW6j#^4-~{5YchgkVkcm>Ab@?@f|Tp4cbxB%C)(|m)=zPOg7(RDq14P z(a!*FBX;sCwG2#(vB9{dKcv#n_Bi%oI?WY~vLBs>!{OdK>h2V;eDzI2s!k@YUbcj- zNpL`nM!vk~PwttB17T|N-PV0|JXT+Bj=NuV=tb*jSlYLeJvsMu6Y!>YM_e7?$;7`N zRqK{g{Cj`?CTA$79v3V!t14+w3rpb(SS8Q=?I%l-Hd!BPv+ViyH3j%x*a`!+qF99F z0yE7j>indF`}U27m&g|V>qF^qCI*WIGx^l*TTCZm3ex(dQRoLR{&H1cG$e-6u`R01 z(#j4~wG(7*$82IcX7v3jIO&DT^~19<{E9AiwA#j~e3{U_e#(2k`qOB^E;7LEvIh$H zf*8?<-VWQRcA;JM6VW9mg=UY~Tb0zp4Xc;Lk>`+1R^{Xb^R!f%tMF@cws=O=uxg+s zle|08*7w=Wy|IkHIVEnOMmi!(=EoN>T9u3X{(La z`!x7c0Ynby(gSVT36>bM5~gYfa>jPcMi0FDvXTN4@;02MvbTV@>w?g$*5wuaNir zv}nN(FK>ksQ6WOTh&^^rQ`9w5{ zNTHBWZC;e&ih%Se`uW$9l?@U(#IIkd?pk1_waC+ji~D%}p7X41Od_U~>!QT#5HC&_ zog?GS5Zdjobfd{Uirpb}(;iX$kcto5Bb20;DN1PNfeU8fjC-6dobG~rck%7Ea1DQ( zzaDjmRj|8fk<`6T@D(*QQ9MwKHqMX3z$$H|FG=Rn-lE6W$y_|=3O3(d@FwSQik!NO z_dMW?W^?Dz%dvSpN;g& zw1kgYDEjEXX``}chH~u7VmPepg?EEKvk7V94lBM(ZM#+S!0#?-@p!JxQrNrE4j)WH zWR`+fonVIdETQ`9)ykOVsrcmcl^&fv#%6Zti=4z#I#`*?mpzNen}Ft+ayd=mCv?|I z<67d-6eIEvkAZ(D3p9qu@F#xG7*rZWkDOvz-?Jj`lN%||`Sya-UT>C4ov$5`3`&Kk zesqRB=bwoVxFOS3v9H#jo3G8na={!kP>Eq%9RtuQ?ybzvQOSwG?+8;|vNlzQL=1*? zL^$y&DkOcFfVB<<)MJ9g-w6Jvy2umVGuL6OtZZTDx?W}}>=CSt_kw+Sw3j{)Z7;GF zVa9MAxr=QWwj9e>YT=0fDSjy(v$d~gSO)c7}yZCUDotqXH$ zOGq%EF8Y$bjucwNk7kOFK^yTj&QfGet>|}%_;v_tDf{immn7g!x+PSPc(Og>)?b*h zNWRrh`tFA2>9M3t+a*;_x5VP-D{1zQI!+rzx6AD>)MQ{AK2AJKC(ig|+@G^7{(%eH z{H>(cRy%oy(8IqrGl1`OC=$gV)@qoIQ#1l^$|TLX&0R^+G92a zXw)kz+mvBccs)HxUrf80U`l*^LjSrBY4KaZP4dC#&?=_>rJG=q7s!752f=ZuOKv8! zkyG~+A*sR!i@%*>aKzFjMMw?DhV5!Yg8(3#HNS<}CS7QJI=%+&&39pHiU9=D>pdgfEiP!)0OnGtg4YAepNJ0xg@@+I}FBB=OVh6<0AP-*1$yQ`)gmSV4cWT z82?d);iPrEjo9-CROsW@{@%>stCh&F@1=Qz_wyyX5#sqV5ggbj%8qKTIIK69YEr7>LTrf~R5Ci!OTYlrvUF zEE;}YTgn|MmdT>etCR3IX2vp6ODF#97E-WT6i;UTapPMe?YwCwxlXJ_*%{HdIO+^7 zyq$t}Yd+IIALfa#>yRpVcecyBu_KeLk-xS~_UGutM`QBJmNF-EugEUF5zqIY;d|JV z&Li+cOlN0YBFVlVzWLvwK| zeNS4=wNi?(T(1dqr<6$%LKkX(Lk(VrniM5+{mFUF(9I{A?-k!H3k6qaN~VI{PU5UJY zi)9Ueg~R%}G@m7ch8_%n0XNyC4-)@ai42p_siLJyyLR0kDywAv0@ zN0!So|8nOH?6~}dMzq|ed?k9or)PYkv0aX_4KMnL9+?u-j!of*?FC0&WMG4;Qx*Oc zjhT~L;MM>mTG>?Sy{*g;eOB!Dd-_4+#dL~&7R~Ac6lj|pK|apI`KmnOSv5@|n>Gif zVPAS6T#+ubk-KLli9c&qd@&x+cYMi0^G?Rt(<6pSX9Mug?TyUOVef@^_oxZNVX8du zuE39_bI7xGJv-Pi9=B|ADRzY`?{4FQzDrW*la(&hOSgrw;8*|i=eWm-&Oy=bvU)-b zekeE@?!~&e^IuYEi9e&W$azwKmfFh^zlw6GW5*1>;X?w#-v6b4U5C$wwp^|do~4Yt?Abo?PVZ`l zI`boZ+vjzNHnzd8LrG4?ydNP?w<@{K1eU#Jy^P;-Y8>A^NjoW8YO*6?SwNW+*RpXo|s8$Lr{uqeg5?^ww) zrW@>v(M>B!bJk8iyf9iklOh`;{5d7#ML&pNM@&2Xke!dt!OPK{)_jQKo0l<6-7Vhf z!A;q+YFk8T#?qP%rF==H;FlizL_3=1EBgw*Ut(*~u{)}e9Ur?K3s*MCdd{)k!Y7>C z66pF+u|oJKU3RuZ)3;q|$(%uGp&mwR^EXw^T;`2r*LW&1&0(`$oiL(2iC#VE&r7Cy zqGSAKs`R)nZQI?Ms^?|PdXANpfLXSpcUA26-7S;hyTSx!3!>Oe=8qm-e$&6ZZOh{l z_Eyc6HT;Wnw&25#7u4s$0y0=8^v~vx>F&#geB0c&@NDaibBoJ)AvWcPNZSmiZ2v%><{x4*~cqwO6be9xqRsJELb0Fjiit(Qt9_WwD-$Hkw=Uc zxkcfH6WvMb-mW|=(+6gaE66!#9_u?+LYdPKaD#wrX$I_}WU`F?Un(hkg8mR|IOd8zas0iSk8X31~5w zPTtAq3E{xmHqkU>>F}zw2?fX&-uuw@DpZ{+?or}r@@I!P_sg#V-{LFJ{BEkfXx7eh znTLPAROH)PVn(UPQeGzlgfdi{T~LTrjh1I1TY@Av zuexGjY9)IdI8|f;lgVb34tGuvIfZTE^2|RX-XrnsBUSzltbA!DZW$t1<7|J1O}Qla zJO}hp&`sQeg|@I_atFjcd?vj)vyfc2H<$T2+rEsz=6#V=q?)a47^V=u=m@%2Ig9Dd zbH!eZRI=(GDm2nZ(Die{py~C}zkZ7B7HW9tp-I~J;_&xMQ!JRC%%A?Q$M-I)(YYXx z>2B$WnXRhG+G`h|E&LM29cBoIYOYkj#Q?iY2a=Z4Gk$Y^I_{}Frq<=1_{MnAtF`PK zbyF{3l>xmWc^1nWevfFuC0NxItFKH`YN@27OOZJy*4}5>F0>b=U@8iK_5J0pSoeH3 zO*!;OvTD)?wVjsBU59oC;-6pqh&Jr6P{tLeVod5MQWhO!t@_!E-o}!DUTA(RC?4e^ zmwoR~s$#+^q2Y(>3+>yG^1KC`_qQote~jc;PCKHH_B0CV8O^L-hz_s32wHG*INx)? z2@kZB$)x)MX`@C@oPD1r&-?*K!e9DU6%J>{^Xh)t&@(W`uz(mAIbs}s2fU$w{k9#1 zm*(_E6KqH@Rc<~ax*)~OKbv3AHg%YY$Psz;)#&%nBD*?BXoFw3 z@Xx}hH*K~m1`ln)hdR8$ym_-RC#D&-_`V#$@tT;@`4q2>ibh?~|7ZTFwqhsUXer-q z8N87j8%x%`Un^@py`gtwJr&0KilC_z?o7+23X4pxo1TcyhZ^bB(r9H+xyTlc(?Qpc zm)UH==YQ>Gir#KV_??mK&|jq+tQ>wyQ{wt!!-@&Ap3~qk8JAV_=(yWD<=I)znA zXGcuB?!)fhCoG;hSN7q1_8Nz#kJpp^`!kYVoh4o*FO_G0QM**E3w%#n!_0V9MLG^X z*FaXmQnobD6)h4ElN;^i&5L4DGO{Ivl})+hdM=XY*`iqb$f`>7vFz?KS`rn@3!NQt z(JX|z%~fMtA@+yY(X{qrDQ~qX4SP~Ql0`Y#Cgps0VbJg(6Ug+)=OO~R@&PU9y$o@%mQrrP; z%RP|dw}}$$uSu)!cA^#jnX*6gZr6Bxt8apb#>04V>tw9%Y>drTQOxGPKSo{uN&ozr z1H_!%HGDP&dVEm4y1WG;+0Q7r?Lt!No`Hr_wX{IFh&L0r?}+&usFl)`xu83=y5`9m zeo|6A^aeLYz+O$B|7e5gZtjlrJ5RE;KSHo>N(=dJI|J_cJ#GQ5%I(Y4(_Jy%VJ*G6 znZpCChCxSJNFP>wIC^zb7EaIkMSa()Q(&LIc+|awMh=_Ly;o$T;janBHW4WSJlZC*rck4cj8np#{s z*$-3ARPpYTGY&{wX+>)fKJ7<}=nU7zh1}lEFuXH1wckybr2X9FYlQI38q0Yr-mb`RTCE^L!7vMm~T z_47R2utUuJ(YmmxsN^5IrHWoxQ`rA^Uuvzhh&=ad%lw>gPY1xcaV0&Tn5MjV!xhKH zjq+dK>i%v8T+_uK>lwz|`8*Q*D<|A6Y|*1rk!y4PbG~Wxr>MSI^ixR%XurC^#+)K(udA(f6BjP4}{`Ej>xJ%S3Yu= zQ2r;M7B%)~OMCXl@U4Ziw&VCZ4jW!*$uoa>cs5py?I3PZPg(NG2n=^@jlJT#dy<1M zzMou5Ru7x7kq&*(Sh85Y+uqyb2XpbvT;H%tStWSjo2I=Z*6bL2z1$vFi#N)9{@Ke3 zuo7GmTlI9sM&U~d((DNBi`^)%T@?KH8Dqt$NUr;%AKI^c3|%>1433QiRn&-4+T z>4;}gbfdg&yH9#EUGQyAi0+=m8h)^4GX5+1OX(fQ^R*}5V9lf%qD$sFb3Qc=>Er*S ze;p`&21eri-qvylim$hXp#NsjoICYwDNRI%dp6lLDEK<@-#vOgp1j&MXQz|xaL7D^ z7OR(X|NdJL9&d!cMqPPm&n(d|V}RyiI~m`#0xe#v%X@y#-Y5hpOki}$Kss%yfp;bC zWgmV(@EH6mPN(apjY^N3t_Yo(L`SzWR;KO*+YTagVY8067TLW)>W!pt8KbO9*n+R( z8*^Xt_smvsd%WMa#P!fU{8eBgexCw)e_KyxDR}pZg7X|>{ONR+eZQP5`n!+P zk(1GUfyi`3?q5z05o)aBn;kZ2MN?m?jQ0r=dCX4l>D#b;C3`NuNsnn@t8odtV6{SM zjGts}r+!N;23fU0>9dE5m9eqtESQIvdUqj}3JDe0XVBq^Syh&k6iD+8qeE(GOcJ~0 z;{yrw>Xa|P`P~cdd7G$y#0_cxXDjO4u#PPfOy*9V#Ls-67H;kx%DcWuLZ1pF_#cjB z6WawK%=Cx6=l_gxf^W(s+Wh`MMbO7Buanaw+2ltz46yflbuCx>hx&4 z+-c~)Ee3UF`iQ*i#hE3zMPP^k)^_^GxM)`c6i=B8O^c^^krodW$JH zY@z$*26=1~x_YA6Jv?UdgJCJizN#X!MjhGE_FZ98Un0-;k5gl??Yf?vrS0=*9aI#8 zr`oHET?-9B@!Tj{maWBmT1l92HH?;T?#CLt4TeheRvH)3u5w#>s?fPrab(w7rgdJt zuSYh)^I!Y8&6!kW956w{oClINUnH0n&E$RFEN391tCmxbBWcRH_TC8l6isW!E@3xS z-SDA*8l|g8@L3w}f@ipas^1KhP6&==i=HajFj13^xW~irrWOW{PUh{+-k?}#1@@Zf zvBp82;B)SXyw5NCAfb&komScwO1TXY{nUH1-n}?ddh#X z?(chHZ$my!DA>dorzOJPrzwJO%~GyvR*Vtvtgf#r(~kw(4|7M&{NiQ8QeAT)$E z|NWA-9qxm@31XM2-O3{^yztaLgI2Z`u3TpYRz&2|6}=Ev5M_^Uzc$dmF)94HG9GEc zS{Sr7RdK^K7n)feuso<6O%&M&!_mely&cJS*$HpS{V7y=G>)0}W~iDTM%rP1e3XYX zvM0q;Yuy9V`;R?w;%qXN)z|Q;9aGSzyXbTd4&;~4zk&1kX~<2z&eHcf;dIFf+Ml$Y zcNaYW^SfHh8LJy3`eV}2MfBD42Ro#eg&v14(DArXei{9cdo7k8PS<8m*F;9PCQY90 z>1&hF(D64Zw(9dO206m_VF-iiyIJVf74WQ4L*>Pj{PLj~>=ymn4=RnM>mxOAuGT`< z?GFa~VopX3&6)C6Ik}4qx@?ap#UTajJH`b!BD3l9%}kzBlL(`jpJeD4t(^W~3oJc4 zK+*a=n;!?AHn#*mM{DZh1dg@MSR6+|?{^Y!|4sc$SMEYrj2usDAB zQapNxo8#PX!Tnq6g$B$cyWJDG^U(m5T4j)v{u!ys9ZOgbT1ZVy>x8${7n@>AX!_}D zrITj1$RIR<{{^8P9d(7ptONA(bOnFjN8ErCTi}Ojoi##Ao#5giRtlzF*~Pw0@2%y(~T=EHnt_q)k3(h)fkMIrl|wgP?n zitlKl+h>aGSV?S4d|CTgarCax0N=F6rHqc0UM4bzzB8!ke0Eh+@vIh)3Hi5Iu*u^2 zX;6zNi(bC`+)!^Ebl*sCr{0ik#d|KpHABA7-k%pQ*jk#R7knrmD7fF9bj3dNA&OOP z3&5(~-{^tpD;Xs*bjg}VtLi=|<}{Y!#mGAPwRbVuT=KxUYiacQaR(kzD`xVo0_t$b zl=*$@j?nsSDiOC`%YXOZwpxf^tjUiQXCP;m83OC~uo}D7m~~7K)q_v-7rPzs!Y_bw zQo1tJU^gT=hEo9*a^+4RsP9=vPuDy@>bfLTbSizOSS`^dS#Cd#cQXw`d zOkp+ejx@AlFs-(^%ldVQ=D+Vm2_A53Xjdt?N&g^>a7m(^)d{TA69sMzUPBWr*YcD1 zhQV!B9-aTAko>;ZpmLAsDia!xikbj&^dqK$|Xz1Y_0ouQXnAmlfCrN;i(tDGEML;d$vXH@Hlp>zz1il z7f{EK@%+kaLhqMhG;6AXv`gm$0v_6m{?}V{TyPrW+rFWMXEXSZ>J&7&`Ip|W@5q$1 zx+3Z5CVA%nT^ftjN<9Rf_@J2*BF2jspxvV;}6UK%grpuy>_Hjoa1bQx@fa9Abt&;|@ zf8j}N-BTWVdkpTCZJ=9EJ}E7I33C$iMV58|Grike{Eiop@q`k7L;Rllr)$Fb#5ARM zLk`w8?EsUQ=PX+_3b%h4p>^U`ZuMR4@J$!esb<@FsDYUCC(`Nh_aJ3t7dO#gP)KIV zFoxbjTNclu_SFW;pM}75K6~k;YFwEZzOo69IFRW$)#cf+RFP{6&_k<9NP<@T)gB zLesgi>~lM@KkPU`M{2h7GdH8LMsP}Z=eALn?jMZt*30STH0c)^1?zM3esAz-&{PE6YD(|UufVEeHNlBG z$!A3tz@@+zfA;r~RL*E%*TlB6R^O(zm=Ee{6gfbJw@7wIoidg(Yh9U#niH(sX3{?f z=C#H|WX$+Z+ZEBuLEgETe$D{c{g91mFS-%C>mpfYC%L;Vt=O-;XsI72RNy1#g zf_R~)M?ZzuVYf;bS}WpsywH%1UYlXQy&H>e=7E{xXHwvialFXM6+SjA==Bnj-I(4H z!xQJz_^dh}zR(xJ-8NCy?P{gv$zr@-qlfshF@pQyiq6;fQSwZ zYIPu|>XMc_id(OxdB4}OQT<(D?Gq<6F!$GaVcftCbgAUJ)Jmf(?W|kJx+`|@_G{uX zajW3r#0=%{wnN>uax6;f&Ug6{e%mn1q=PT;+^nut)KaT1`7t! zgR34`yFqYSKeu6#Ha4i1)O&t<(Vz3tc3$*yNymi>z)(qFq>}3N6uSWMRf_moP);he|_S2n|(mA#nP z&@NaWQBE=K_Va+^NTi4y(431;lo+DG?H9$=g6vqMT2oQIExy_ zl(I{2o#D52Jq@n+;;U4$5Fk7!{+sqmUs~GI)Pk)t8)tIYSm^iFmG}7(T{1-nUuO*1 zoX(~!@qtF(TgJdHW@z(=$RB)dRjM?~RNV`9BkUOW(nMs7--od^B18r_I;a z*<)|;dWZspOS|(qJie$bb9% zVBN*!`MQbB#tF6u8b^b79g6FPbwB3Z3dtIp-g>+GsZX{qlsnP`GpB0D?P*z6|+s1{ay{lHN_ID zXrW3k$BaXT@Zhagcjn0=w^XT&k^Pox!f!e3OR~(j*E^qtNUiVW8KKX!coEJw8sk>< zAr=|E5+_=zqH^m=9yBHf#-azd=`lm;X0-+q657a|oPlTkk=sY;Z=e4v`;Bu(b)OhI zzR;DuKhzH&mt@Gfs;6^Pux`#zG94GIv~Rx|uD8sgB6Osf2coBP3-geT4q=*xv{}(-0|YYRLXe~z(3}@ zqUOJ)^k30d=|WIPys(%{c4O*ztl9wd)Za)co$o5WcZyEBg5UJx)I!!{j{@Dg?V~W` zo!o41ENTjLkU5N$qaO<&g^H={!_i2Ziu%i9Zx{Y*?<_}L8nu9a8LF|NgY7Z>YPihF zd1~#AfZv65$8MzZrQuuH3693GH){0EZzUS}TY1jw3uZ{oa9vreX<8PKnYE@kcGa35 zp92oQm@IflIaM9c1A#kNQ_$lKMqga9-YAY6G;3Vke5JNntN{ zm-0B91Wf9w0eg|%&hkrwuizfLhD5N+se*+s?gIaAvM*LD1jlGR9q9Q^Q5#%}9gYvk z_u~R;ad90cJ+GE|Xo1;|Sf7$kFML|EvN<;JiC!Yi;!esOojM;52 zLXSSU8jWXk(7WLjk2y38CvU})W5^gb{h1qjTZYQ}e0gg(*j`Pfs%bSxD+F7t?9@v- z_u(hoXKar~#{!x^eGWf1sRlM~!x8Ra#AX~HO!^hKY?G(_AjSFZ77n&53l z(*daKbGk%l+&Ji_JfLaP8b z)TkuUj(!EK+|>oQmSxhSUtWBV$dKwb3QtAtZVBgY#a*k6t=3B9+4o|xxtBbLI-<8}b7BAI}vGBuo<`psyafWM2 z^mA~{Qea>BYD%8z!jcCL$EC-ml>DeeWt6zd_Ivk(7L}i3X2(Pa*2-p>d#jR%`={Yp zq{#XS*75Q#!L(#~6IsIv3>M#*VAF9*ZYUtF0bi6baD-~FG%D~08)<6?hn!p*^sR(< zt&c}lH+6V^o~8_Fk%)m_`pCLKQsJXn`D_SJurMPJho#(|`wDZ8j zZIj7z@;E-l+7)TD7SkKetI9QSc&lE{ zapO@_?65z3rb3^O>1T!SUa|BnaU(zG;|IgCN~+p6R{q^ecv?F6V8dAzvaDE)g-_qm zuae`uu}>ycz6*|7?qiwz#8e!#HNlWCJ?O8N$RfFf(d5X|x~P^iOi75$6V+`Dv%e4 z$ot{!*g}Pd)4rYPq-YczrA})6=CmxhORZtIV+*qnTaIl%wH5mOC87V^Z52kNA}kp* zCd4mWL?h0w;sLEe7a?A zFSXKcz})!*(ecS&TJyvnskIgKsS^B)xPLX=94qovIqb`qp6KkgMKSZ^q(o>}87OYD zUza#y+>VjtvbK~@)AYoph*(9B)x~fU9gb;qc*aWhvb!T5J%MrOS)gD;-8R<%*Lt*(n^0P@#v*KV49(o2!B@uFA#c}AIxyOT*_i}k=J<`Y>}>a% zZo{(SB6^x0mKzJwyEvTvbVxwWFj37ljtIRSCX5gm<%BE>@Ja zgy+lxZYh`sqe=`>bl!>Gn_`ZWI{OrRzKh%fJqpD)z9?U+k1@iv4y4%g+i&r~!lHcA zjDIG-dR*weLZf@Q&X@fsxZ?(|N)?K$y7Tz zBJP@8q33ipPeQ|bL(F|=Dt}=R3g5q3B7g0`C*;X6OEZP8UlD%GG_fNXWzs{nDt%MBpdTyf7aHg0E zee(JWid*waZhFKC&0iA<5fYo>?1Z~gKAoy5#686Mq9x^lUHR3|Gz2Rj9pn)jL0T;4vMrJM za5?p@tL6{h6~LzXCAIvsMksu5;nd$7UDv44>NktAy5(!S9DAH!&Q6C`dtK})ejwvs z;@i5_5Q~h>$ajo0ns>i#y9?d-CVe{&Vz&}%9<*gt?zTvUva=B8+xmcguthGJ0WM>-yMh8M;S#b&pu z6z-uUS%+|EjUZU zFZ%EHYCby)NiAC8&y+2!c>Qub`mTlcZ;tcCQBF8O?AAYVB^TT zC!zH;1K8|y;s`kNKH%|+4kqH)Inq4Fp4L#rgriX24|nyYw5g(sTr1y5tn z$hs7L2KBOJa_w8j)VA8=m|ZRR;=Sm61FdS@(Nq%mudW$){um4AL zGIe|RMi&HyNIQ%o4q3@IG0mlW3MJZe2Fklz)4kGsng$<^+F zq}p>3_Uubh?C_s=t;37qTCn`GnBN&H^o@P3QE8OMiW|kAaJ-fb47c(h-BVyC-XIhA zw3i22m7?G0BUJe;h8rCbzSbp)R8y(T*gXpb$PjHyG@GrmD4JjuBW$Y#S6xx-s0 zWQ+XQ-r*AKF7kJ8nse#?sX}fqdPpv?4BE7TiY5Q zd{;1jMIWWVL8H_n&=zSUhf&vJ;cFGXT!%$T)P6yleEoTbndM33GI=hu8|j2$=W@xw zI-36s$VQJYpB1ycXkj^cxFL>}cP7Ui;h}n@iN?xQZn!cF-Nv?4?Cp``+%Tr+SQ)TfH%IkWHne$-(EPC=ahn+YeG#0@D$fzF51CH9^s9HAt-E~Cz zy~vF8W764&RaN|3MJBADsbKJf;oNht$YSWX#h?ip%=}|0Lf8lT$H2K@>4ZPmhSTx; zZ)DnIH)B!Ho0KZD>6a}&5X>}5^QmP7TcCQiwZ^O&FFyHGfs3`_d68(uOz(v2d&L8aV5tO7&2 z2sX%>JGIf@s&JDj!}@?eZC4W<-|=ON*&ckX2>-f3X1l9#62_Xf zR`};V){9@C>qFU#MzHaN83O0crrpnC`GVsPC~PCxQ(C>GH1`HfZPicow*IBVqUUbG zjn&l213c_hBTBD_pgAL(jTHH#=HnX`x7U+?NjNj1HI}}AEO!ZE_%Cb(ywf|2 zKg<(sN&mY4#5YS-^kT=JEoS9A>@mMCo4zHw^4?1tuyl_T+&o*b?Joz>+?e%>+v}GD zq8Ci;2BG^scz>ar4gT3yOPTkG9hV@%~9W(^~4-;AUdwqn@bhUzeR&z#l8+Fh^=WpNSN77R9^sy1l zPH$x?^HyW7{Vp2*jtN~0sJS(dq`wZVwyz6X85dLLD&v~c57|iS`-Sd3JkE@2Eur4A ziq;rU;ZJ3v6C}Si4xPO%4Hz+>4xDbG@KRbg0TX;f=&*09{Nzk`d@5N?0Ya%Sj+ddW z*x?&Bmvfb99~9}8lU3JXk#{S@d$CLBSLun}TJW5!)$uDqFcL3{j>6t;@n)18v;1X_ z7hCrz<~((`!h_$Q^l@Z?WS3|JD`N+RR&!vB&`)Nj(S{%Qu}&4aKx?5j0n)fZZ3Yu;uq>Df~89lZBUTSRze4e^B~7 zXApdnlWF&#``l%9K5iF$r=FuD`04dx2fnF_Hz$@bZ3`#ZOsb(;wXM9bTQUSd1wW^@ zlb=lY!s66$h2JK2TPZ#bI!vxTW4YyJXR+^#u05$W8*68YD}||w9X{77AKF)izTMr3 zzn)xz-&eGe^L#tA9kUdN2mGXeci4JQ!5v*=sPNlt?W!iY#D)sL&6Uo9@bXWfnfl-4 z`CFav;Zqz1-IOu=9!%^TdE(Ah%%A9pY~3)y1{strpEFN%UI;(N>x&oJ0G~Vz3T=%` zvkvj%!NS*wy4w_N{g>-%~K%@neF9?h~A3*XCx z96F*C&4*NrcV)mwvUSv!Ih2%wSL@)^3RALgnTB)bnwb9}m4^wx?w1-UCy9x@a+N7Cz2nMvUTj5wk76%6x9o-2(-y-^wc2WxJ-#1mRYrIb#Gv>cU0%=US+}RuP$uEwy-$?E8wf8iQRjS^LiBr9L^a=?N|0?wsINP?wd~4 z<4gI_BLt25M8(YC_FxrCM~hzF+v;>}j}5Blms0e^nY`WR`&jwg3z|_zY;1r(DgC^t z$V|2FDHue?VviCx*_uh#7&d1JZ9gBxw!L)0^~v*S{g(tDSLz52t2nw}*h}*Kdmp=7 z_krx}A9`oti1l4piyM$LSE+BrKM%*`fNZ8)(+h4@)%09{FE0=?|Dx#I`WE|GzT=mK z=_Y}S-Tp%>;G@WsUAyL6mzd><$^GJ}>U$9z;O&5-{aJMJxhp@@vI0?&!h@tPmmb|7 zOdbvE6#cU^#7v&_vL$vc^x$W;MX%7qeki}Sid`@tg647K=x=ly&k?_8)UT;zSgj}Z zicog$QD%vG&z?|DMIKT&J|z3BDcoJ;Qco*ypd*p@r5Pfxux*SH(fKx!yuI_}<<>*6qs0<> z+c2N$if^uy=vAy~Ucq;E_rtrn<)pu6q?FhzAMw`T=!0@gG7$Q9rM@zJqq4cz?_xBI zJHj}b8@p%F1Cj2#spi}cK3#a)4O@6ntJHj{F5d{@qwN(l|NCMOd={)=t<(4ATWx_w zY6aw}@6BAzEkwt6p~64!BHqRC%Kp+ntw!6b5Z=rPy-e=04_}fXJ!l1MBeC0CL}F)g z9I4&wz`|ErV{p!RdK9&p2c8Xw@4i)(zamk-HP`_WhqLH{>3r5U*%s}4mMLzsw~l6@ zyU1I&bjg*;I#-~eZD;6q8c4tQC*ktyR=A>{z)kIBxY{LvGM=We&ie_^B4;V|`RHdd zv_BV5F1-&(%XSO`8=Xv-Yz5t~As73!n`lK*82>gX2Sc=5Aa?yy#^*SpTvkK!{#*Ii ziX^m6Y=yR~Oy$k`!_fEo1ai#$&Fqp(QJ%u-$=?{>@Y@z&Ca$1vW}0mLD+}DvPoNbs*|DzC)EiT!edEyv5c(^_eRWsGV0P{Enjmx8>hYAlMzprPu`m) zzPHNQ((erGJwvcZhKW67!)_kdJ_{?|OfawPjTC*sR`e_kp$q?Q;~O8%K!E5q+Z|XY z*Acg{BMl;pQ5ePU`Z}TMi147USj1BWU;WdV_mt|aEqjwK`17-saFOZKCs`Uc^lS;U zTd7>c-n@MVeLApd8`@CO2QR0|Hv1AEbLQG zB`q7|whP`u9_t3PcgI=Tk3l$@FFG7G*YUw3-#7KR28?ASPraOn>>(Y{aPJ}OA++vJ z>T_uPS&6^M_reF!gL9@%kLew?!ZG7T3je&BVBZx-7L)0?K>6UJd}zcqk@2~;%r40W z*H&(z9AxqLq8IOSwH7XqeJEo-$>^fd3i|!J(<-HT5a2Jm*!ytZ?X8Y@;5?Z$rf0E! zFD0B;jwk0RAD&WThZ7&t>7nuw$?9MA(u z=B)QX7nH}(BBj-7ZsVQK&NDMY!V*zfim7_f;A59b*I0DLF~w17i>u`f@@-Gx`ETlx%*&`Z&LveT^qgrElQ5!{ zzM_lp+yW1@jSC^C3+s6IYm&&E30{z;Pu=7(j<}l_Ls!=pvD5<&=$DyEjwWur$4);O zs0CrTc9pl+C38B^%ut3tW8U|kOS zwuD-iM6;V~oG~yfk%o7P;{$I6LT&U~apdYU-yt~FNLfiHy9-blrq z*W7F)y0jKi)ybVwH!)B8v=`b->jpk!M;>Naf1)F<;k;&lHq@6ZV{wNiEUl~H9%vt= zNYAa@zqRNddZ4G6^CgRi!F>NXnp5$cZCo%8`}|Vq*+fUawcZxSpQ7pE&X#Omf+fCv zOrq6yH}IDAUN{s~O&?~Sm7jl*g^uDr5-@u`Gj&{s?t-EBZ@2%16uW(0L7-rz3Xh-I?VbDDVAX(yH21CzJAB+5`)-$zx7AwyMDT)Me|<|z-BaY< zMURYXloCo!&akFY85rL}Q=!j)6Fqd7651lN<9liTC_8K&=pk4x+xfSrzL=o2j3(A3 z$*+dUFmhoGy`K@qifly}^ZQI19~#ZoReYhobTifK);n1VE~|ma9h{z^OBaLEutG-z zS$k6Xm*QVbQJX4<=LF%utJ(Nk1TeNL?9>gQ7ND^VR~H<Km` z8ke`spt^Gk*3^#I@q(F3tET^7Z!sT81OBh?eicSvn zW5oi*X0d4oL2C;XGT8{4;6l~P}*d=wl4LREgoJP zM^~q%v#U`IUmnI%^idxkWh=VacBE6+IY*_W>)lA+E{UyjtmKIo#hv=|A7b5x^Czns z@$mN~T)8H=bDjI+ckMnJ+kG`}JJJfL?>dt_^pQ+2v8A(;Sr24&J4PLEgyC9h359jF z=nHEo5g74P0@mh_F?{5^ly?ThqnhBQm zKQF!ByZi85;Q=QzBi26LpAJqwr_gf-&re3qPd!XAm+=o_*7(%yLjGfeSn)F$uw;0&^p`6jyUDHoK`O_V%ujp z;K|K&g`V@`y9+`lt|e3TDbmL~7Ifxhg(5%IJSq)2!VjEO?7^i@SqM^XqtJ8ah7N_^ zr7>hbJ%g92*`u&exah3ck-R#t!WiqNDzGn9Rm*66Y%RYL znTEezHBfx0tJ{Mpf7}PTZ)a=lh#W&nT?R1EV1}hh*|fEd zLCp+x88&TQNp5>%Smr59EM2*l7HUrBF@bAPnA;8}7LC%O!W$GGJD!I1d(H2PZrq04 zVbt^`NzS$g!LLOe8M=uZ;N&IcP=w1=`=sT76>~mrdbU3+#EXsHA^}2TGYUoDE-HWAtos41m*HWR?Uo`W9 znpqmHAM-^1)!GFOk+~E)YbYzJwnQK0d|G?AlAp2{zVR`?=y~#F`O;@qDF4$HjRs9@ zw|6?e+Z*8Zj_urgxGUzh4xsc>6&4g`15>3jEqJd5`={;cf$&;C9Hyt3^9S-JgrD@L zoAIfv`jrbh4VX^*3WE8|Gcw%rT|rj!_e-zF4;CKt1iJ0jz;#;YBC^9Wx8{>}D2=F9Lmyon5akMSwnGEtmrgzj5R zr3t&#uxhTJqFeUX_CRstUO_G1e3k3Gv%>Wqb0~0$LJQwG@|p`HaBoX2t*bL(y*;fk{PJuvn_SH^H+f;*lp-p59W4J6DD@1topcmW+YaB+??3%T8dY`;8 zr_Fr2GOLUkw;_zV8bi%C!?=mQBidXOnKgrBlEr8<%5Raxz9($*SmIx&!k zw=Y9=M`QS`%Vg``kHezy*YvM{&_np2-`9IkKa!RWcA-rStXrw$ zk?V26$+5zJjA;H(b9S)E9nn=YX_s0B7h?kp1I3=u?oO>&i`9r}^@_A+tJCB)f|Zw6 zL~rgyaj(|}n7g_Kel0&KUH;-vEqk3+|e=IKB-JkArW zX%>yDOy*09BCuX~t&`7qOM&_y@VU1I9PKo*Y_B6m=$F#{tKgeo3yrb266BNmGo6h> zuj*Z?*x~)slTmwLFrfUN$UpeWpm|^jc{`TzJ9%E1G;1ym8at|Pv)mCMuP&j;!Xjpy z>3}_R(`e^JS02Azc< zLX3S8RW*i&_R8WfKidm_%Q(96Lr2>9s{#8mjInRqF?#6jiXJ<1DM`0I&l5dI3-e3p z>aWYvjq1KQdB22q=hpHQ2h!nZA>Nq#o8{3p`IufVI>KxYFmH7?Y<=fXlh}KCW1}^? zR)o;EeFK>O6lWNE3Xh-6sAhJR3^|o$^!-x|J6dUl8x0ktbb2y3otG~d&w6-Va#z}) zdV_+~!zgIiE8h1F!|P>3Y5J&S`BHahEM7R3oYqfgnVSeMf@{$uK87bR@I~$SQc`a< zLUQdd`aUAwQJ(~L+EC(%=la#;p)PS7!N020(S~n|J?mrN6F1d%D75;l5rQ+&i|Dsj zfmGpbjQvwB72JcteSPupLz=>4V>8bY-8+k(XnR+7;GXctZ^~2LWFsRp;rQq$eL65% z9`UFEfAw0yciA1*Mr0Z8$LV46hRuB5*ba>9GyVZ9u-G>GFZi-0!_BE*U0J zsMZvDk{#jV#w=QRa|s)$C793gB{X?i9`7PJ7TE%{&Kd+&1oZTNe7BNoD6?s zJq7n*-){*oV!Ww+eJazu;);by)2S|D1b2zB!R*R;w36+V*3TY{A-m!gbKZ7VE;}V z;L#$Lgucjs?6pIWqYG)%Kuz{O&k8?<-}Rrb^4=uj8|?g+X02(>w}_eWOU#5`(t7rO z?J}qf?&3ec&4Ux^LVGblj|>y3SNTRypfy4Zl82$7V9H&1pQv8(2EZ9`CyR|(|b@w z{VYy7b(mEmZiDK$7hyt21-mtWy_(=5rtwZeCAeYS35!$%SoKFQ47LuU+Jx~u{fHF~ zE()fOJ=RLjgUxY6b+lsUmne-yX2}{_korWPv@g3HZ;kO?D-`?uH@^&2<%svf@&?(|DMd(X(*d6+ zSkaLt3EkFs(zS1eb(h4>6FokJmOG}iU5^V7>`%~48dKR3M$hBQlFmtLd$_iwBg{HOe z$4k^JFOWqI^1y`=)9KdAB);g1BMMqX(}Q0gBikZK^t6=ZD>7wEB6S=krL+WQwO5L%NR|I-u#qJrjuQs^u z(^6Yxxy_}5zj@4MsuN}er_mBqcm6V2_;{<=DE4{7^g&c8U&&T`r1IO<=~(bi4Q^*W zxx=Fj*o#}tS&I~w-7f(DogYJ^&2zZKGm&fT;nRBV6C`*kQm-JOoYTvW&QJafh8JHsgW!8>`206R?D z6GA!H2C-;&V9(1;IyKO+Mq1^D4@u>8zi$#7)o6vIE6Wvg{(EW#<~Nz*&GvUv&%HP3 z`K7URd+sY9|6KUzH+oUp>tuQL9v7^znnKZCX0nvCz#H-IHt7`0yEO=2#MU%Akm4d~ z4=KUv2Te5VgEj?=_h6{g26{77#uFNaufDbwE+siL)8w8wcxRhp&Rc%A!@fA81trCj zo3EJjI|eHB`Lii57_>fy=2+j7@Az$xbm4uP7p!%_qPESzgb4J0}n~RpAW{RoLG7q+Q8o!nsP_CtE$1#~Cl5%-*tVBC-`&b5h`jTyy*ff$5&eUmg77&cl){r$Xuax6 zoYvk)H;Q8Uuidsd=02NpdbDJDhs9kxSMdEps`%q9PqbcHLH$P6%Poa2y%%7u=86;#O7O*A{nFXHkuv zE%WT@f+_M$g@69D@=z3MuBSHBncPrl=?+VNQj4N9Oc@zS@ljLE`8dHhbAS>4n!lBv z{ItWS0!FcYxAVsZV=#7*(B$K?C5+GB%g1AQM=oaopn0Yd|N1PvY%seaCo~BV(+=LvxB@*9~D61MdP`#=q);48%XUA zuayS7nB%{Uk&13{emf99O3G;Jy9e@9rGk0>HkYpFwPD9*THsmZN-7Uo$3tV&F`>8x zyk(H*_sl?l>sI(>a-D^z568MTqp4QKhF9$k!7h^+%3ff~jP_VT<0l)ER=8H&sPXe zxK1;T=|7w|jwnIvv#n5?p3VmC3d4p$FDU)S8E(AP7w(UPX}G7d6qQ(wdi&#Kx<_OH z?uKG+NG=^Uu;Mos$O&T z5I$dJF$nvtDmq(_@ea1$7``BY`j$Dc1s?vugreEC$u%R9LKz;jKg%9WY(_}mqUWLDgPvl{3C0u&oO6G-SeD@pCY5OCb-WCk2 zi#uwI+|wc-r=8FCt&+j;K&pai)@u1Md{)~)<7Us5oW>2JSDnk)k@qP)e_p!iMri?) zexCgM?+l!5-5R^~Q`qIxp(x%xkxZM5`Rb82qPH=K);4KMJ;!S~+Xq^s*!L6No>ze2 z>YKFh?NmN(q63zGEue+Pmn0XdA6ycONM&6uzw|c)k5$z1r{_=k%3)$IO*g=t3p?58 z@S(V}WjF;N`X=8qX&91@&!(vt-I&P!AwXz-Np1!;I@jDV&U6hGc1>c-zFFaH_cau; zbTao=St~O5rh;?*P8#3#CY|*QRm}Vo353A$9%Pu5EI06Fc+e({E~ialPWxS8=nx}b zt#SPLC2=$rJ7J~1BpE&~f%TX#w9QM0G_E;7&t*OJ-0Z~fEo{VA9)|SpC9H6NPsnn& zlF6GLe1wu6-0GdEWP6cxX_7H&lKYd1%@f`f=mP2YGSaELDZlMvj|r<16`83WRbr2g z%vQ|&ruUh+o${4tR7{rt=vF9hQ#y*7e=}TkBIoMhS;!VXej(vofE!tc{*{gi2Jhds zfmHBxGoRmL2=rFRDY!Rt0-SKNE}0fQp3iolwnK&BdhP3xZ+z`1pSnP`Sb%ajGiP|YDe}-V}^;n zW3K4yDQ@7?9C8Ks?>YVBSa!ISgP%iw(*A`@*wS^9=>FKF*zJd?r9y6~1JnQ7$w!_K zLdc^K!LLxEX7^PX-g_^#jgR9+L3SAE5=GL&maN9q8e0WREq_53H!k*Ts>(XeHvG&(&}=R2 zjy%Y>3VtAOFhKvbMyZdDJ%;GZXoQ1c%SZ|k?)4KbhuzDKBK2I0#V^t&urt$O#xtMUl2m>QL+0{Pc z?K9J#dK69I#dX$b-&OS5>|QI~*=dfj%wUE0(tpSZeA!$^6RaQ0t0Qc2!cgSzR883K zA(pToxRRDXUdJCbreXRW6^!Uag4Zf`Gc$cW_k+?oexSz>vaFGU{w zDGd}qJGTO-(USSq{Qgv5{8cHW?2e=5t)59Zsai}6&iS&YQfu5BxSE{iWN?G=`M7Xd z3r25W$}TR-LXY6qSmGks^WEI=%V7wuO)aY{5gj50;X%}UcslF*fW*cUO)evcakDxn zOejgFX$HroL>+UA&5cv&IZ~S7PKdste>d6XK3O=|QXRV8;+WyjFtm?-M&oMF@QegU zyqn5MFZz|twthPn8=s-iXBN?@NfD@X$fr+Z?D+C#35Axagzm=dr|5c%JdsAH_MG9V zBHy>t{VN$esPkSwDzLNM1nDN6?OPOs-=h2D-^}m4$q(QD1d`KC#$uHi#@-l1vZzv? zx5gdIN@B>N;X&=Y%MyB(Ui8Bp_RiH>W9L)I-J%87xTIsA~QZ|xMH{0i_>wQ`_USa zhnr~Xz(VAVz9ITDrtyQ1?2)FEPwdb|DPE&LqK+5R4XZldew1L6cT>ZjF+b(!va?Vs z*wO!H{6U>H&kcsO= zwoWh`Em9UK*u~D`s$a@6z8o=JNr7~wemXhIw<;rD{|1&z9n9s zv1jjUdJ2w#;A#rpzSnX)%p2}R>6*pTi6h1$Yt>(&=Y%X0-tUgfh+ViTfAZTAzx9&o zq^2wT@lxpa!?OtfmHbSvEcmqjO8+`azTPUp8w(w@3%Si4JEvj5a~-ViyOm3Mz_nsG zniH^uCRkTh|KRRU?%&J}zR5MJ{8_SaHi9lFJ_+6q#1T zZ`8FhSJtXXWSxA}@iVj?b+t@IP?I(~Xe4r3wj*xMWAy5M5_9h3j+{<{V;nG&&$;J> zzFG6g;Nf0rrjG@h+Q!hg_y%q|HW$PHKBLyJLisL(Tx4|rNnfrkVdZKPI{)0Q$V?sj zmV#Q5+5Fct-l5nN8b^oH&)H3EshdCEG|i^RH3Rse*$((KeKvLZtH}&9tZ;5`tio>} zxy=hdgZ@ABLv-Kb+5jKC*r!g9U6-SF`FpDCdW^f=%7DW*ee8d1BF!7BF4*}Riu_c> zYj?E!Ii8gNJd+>T;|9H^rBv+e#%vyo48_273j0~g$K(yg&6aV@W*eF!Mtpa4!r{v9VMqe2P3eygy!Wxk{>)_ zha~Y%-1pIhsok}}(!f%h!`AWlq9e?wi|`CDCi$W7=}6AfMMwQ>Y`BSxe!=@mXt&%>8y`sX2o6^>o9-j^T>_LAP)_%zPC|%A?FA z%_+Yye3T_jMNa!xpd(^-lQEQT>u=z%t)|2CxcGNCeQBM=774yhbE%tS39AvBt$eTO+Sc{tu4%rQ8MlsZ zE6tNusanvLl_d%d-``4b7X?euy2z84yBEXqcU#O|n9JV(61^KvfwbK(hnr28;k(Gx zJE`kS$2YtZTyA3+n4Y7#Gs1DPe+8}YJ(#zi=q9|ZWwg-io+SUTA07+s>z{_dR#mWx zc8Gjv;dgnjZp8?=)fSEIYFLtiH=Nvu(i+h}KIN@F{`3l@fNO)l@Fb1bhi|_ zrs$$Nb|Z)u2S%{R4xY#mb8P%)!E6ur5qX7N>UeFq)UV%43|9F}zy9jdXL0*j`MH9= zw~+C0o`d>!8j4%3jdL%k_1P@?7sSl(CbG=4?P$e_VrkkQV-$zC>V-oCu8aK(J1+Y6$~XUl4-`&Xx2wV zFwFbqk-@M$Zf~89Nsm9%Bdt7H=*@JL?NY|m<~FpeXBwg&Xdxsskw=JK&ZgRm4$g^V zUQKRzv0)tbKQMyprP^W2&#AO$%r5Df@DZi;T}quVHSilpMAz_)wIo?|;(LDPB4yck z%Bx$-ay~PB{IH8Iblk?Dz7YN9S(@mn(N5lP!w@LV5q{~BUs?2Cf2baxPAaDd@L7WO zH(YdXQDu#wuTTCeOWkE-MG5Dnq&22rIU(vKc<04NQ)Mkxj+PMcb z{`yn$jmLcL!XRiX7tyu42Xbxkj;pg0c_MDYAhU$_fD(nav*=Pf`ui!P)d7-+=oZ0p zRvWB(_n2LuK3y%t8mnp+h@VGOc66*YcDae~yV&zrejb7auQI9QLUWH3@Bu9`II{HbC(9GxRXSzc)QS<&SQ!d}&+n z$~x;d4tSs9Ps&yqEO03>y=Wc{OdG~)>aFo>vFJ(;uazj$jOf;K#mqPRn+4~~pXhW` z0N-;_WZwkGW1n$6tM4}+CyzX)A0}sc%3P5rtM;J0@EitTS-;lDAx3mRjF5AQoJ&VD5 z2W33x$9N}^VX@(sl-9NfD^VGO{lVj@S5M*5g)6j87Lo40d$k*L9btYUp5lwk*}i56 z(2E?}?=+idXspJb05$w4c3Q7)0rY0nQH8d1;%6F$kI)AD&3L;=Tg25{(~Z(#R#NJQ zy(`9&t>7DSr+K$E76h!)ILapkFeB5<6JZkMqpXOBXKVj3MYMe;(M=z}l*(^iPqfyk_rI;Bw zF!TvaQq24eM;FZYDW*eq6Q#Womb7bFi6Ub){CFmoby5{sYcIaDqF8jzi;kg;TxLEh z5XtibXi=wJ?w2lh_(nhK-lQ#E(rd(KOJgK9pQjIR!ce5Uh72Qb`s z|Fm0Hp}5uhoN2^F<d>oLJp?@~#Z zb5gjkdI=grOz^5(cWI*Vyj=EBRdCM+JsX0{-eHRV!M`!Uyvo_sayPNaPZC~jPf)NC z!lwla#_T%Ev3HlBtvCm_Z`15R!(YaN8iO}{#G)*vlv(QXt`NBETi`)_>@#AeQV0qh(2LD(s`Aa>p zrPNoU=frGx$3?v~%J_XzK2zp_xQiuZIH@~(;A)8`!NzwpTgRhYi{8dDO7J^M@*g|X zMXo^$-Je}yPFj=UC>ZZ^+PL#8FUMj;+Z_XuedMUR8fKzJ5BImmNgxH8i2M>eQ4Cv z%DU@a9HIVH%>3IK?1wsFq%)g3UG))+VrzsBTuR?A)krrD%*o$o89Vc+l1s(e*uUT- zxhDWSH?N>at6m2s>#cRU>WKT^zjgXj>1dj-+EDh+Aw3r*+6R;FSXKSo#mN^yT4 zr|%~g@(IFExV&Eq4UKNglDZATw>HTNJ?HS=0xUN8LCxE>xt-`RjT^3tW1gE>^!*s@ zF;GJ9F~_)TybV4Lupk@do~)Cy7j91rqvL1(`JE(0FPTX+u+_7d#apcg(C-wVZUQIS8u2fDu+wR zT-OXbJ}U>e){EkAyLoi@*HY|dd7`X}e3ES9g*WH8f?HP}O{ip?&t3M=JXMmTVKRba zcZ_hj?hxy+48gOXDk16P96Ef!6kqPlfiXjOxc6&jvkvHd;obK2glxRvAcF7r{pMpL zShvNOCAh9-JQPd1;7Sz-NN)SZAE-9Pw}vk8P-iZ=c${e$Whw00Dsz4kyZcLP6@u)d z1agDj=AMc&hFDi5Ren~2yHN_$W1e%%w4Z>@6CcL=?V|SRjO`2UVSj%v@5}zo4EAR_ zpA8}9{Z`o9uoi|tNuYu97C7Z}B3NcJ*?o5<9=r4ro{t^_39;-mTwe|2=UUK>Ej=hD z>4)(lr6lNwIwth&0qZ|U=;~_$cq`ur+}HiXjeE=Zk*TV}-F|PS7k1EOF#qzN|Hr@r zU9Tp>!gMQgGsOV8bs11(xRdG!I%j2OFJ4-(!ak}+HCaMkt& zU^3H>4%i#vkGe33|IUghCh0TpbPP!Ee@;dI6yTFJuVC!jU^;DbFTS5|hkb3g$i`rzj;5%}Y0tg*!R4?N5Z64KeiQH7nF8D}paG&s!`$up2*JmckHeWf=bS5ZboO zqsguPwD3$B#;u)=wreuYtWRbtE|(YF`oD%c-LdDOspIcL-c2BERunCXQvfMY*;XGDSKP zA5RO0s;jm%DK89PEZPXM9W%(>4nrL4AHsYiduaK9BPOlSgyUh}yu7{utriu+QuH88 zYK?K_>oUmK%BKJJGHza(7@jETuxyad#W2PWx_eOr0u?>cNMs(|=-b)oxXcRYYxw~G zwSY+cLi_>D|5M>Y*Eh{W<)KXYy|ab0*H8s<(@ny=Z9BXB&%DhtZVy6yPZpwF+zYt#m)&iHOtITc59)_HEl;eJ7QDPGi+TTCffnyz{MwKX#KwS1Fg^VA z=FN0E zArAke0}!f8K5lcs>urJH1$ERunss1xEdkL}4;z%-I1FcfB{$RR7`Mk9E!A>>imawz zidnz;ql573Z5mfq?E_DrUn0vhQ>n?9bmZPj2xtD8ujV-Mv;p*{29Rq}j=1H)0vKeP zPm-Ah25Covnwc6m-%U)AyvhIzn_1xHmpL}?%MtGOdw1BNXwFWUwxgTdP^E>%EtUWG z=dgG4uX2(IkKXX=w>ey~))->qD(EuBMR-*_7NRGuY5d^BdITmc7S8-HWsEuRnGBzY z?5RW|+kt;qg2>KQ+&)D;c<5Fn^ydui&qn|HVR-I@1FerL!;`8k4{|e~TsL8!rj7pa zNxYJ_rWv4pn+=$Mkl<3cOcWGr7z^k4_EEvek#exvqeGvCnBWMOp-cUAi)$O2%{mnF zAVs;6##ChC4eue=jsAEd~)FCPq++pq#W&y|GUd&S4T z_+n2oJed8F4@xk^i2Myur*A|o z$2xL*q9ra{lLHp%1@xM09v`oEN66l1e>WtWWDBFy3E`GYm@yz?aDh|l=)ZVU4!7Nk0F`wOK{xp z1UP=Am?o^U!Fw)e{A0%LyH+RM^R<%muzkj8ObzPh3@?~r z-)&t8?>S5t&0!kRUKc1WTF38x;Dw>}2_R~)ja*10_+@G$w3Tn9quqVbgK2*0*MSZR%2$zE`c<(G8~j42m+FA6PelE7O48#BWO5${wm-yL8oGeg-)rLWMCfEb2 zq7OA*|7gb8*N#H3j#39>1#Djd50<&n&pRD(hmStkqQW}DHo zf!}>^>N>6$4+^|ddCX(7oaNV|-ko82hkbPX2vhXanghw9otCS*jRoIW$DyGW>x2%i zz^&sNp!-`4eJf#tA)>Lc`0*HW;i@j)yp$}Q`N zT`2);3m04I@_rpmuukAKn?0c6A*v(PqB&H7+ynkSTNe3q5oo41QW!%?2tw67tm}9PA z1@ygn&h@uwp-Vx9P{Y4pnt>`l61Y;UlXo#BXf?tRnh#e{!69eN^auj`FN`MI;(-tq z4}VJ7zLdf|JpZzt_J}>b5aNOp{#JnB{MB5(mLBMJ6bQ4l$&4={mNyI)Szlz;<{ljN zDFW3Wy&~pq3vuohA6UDif@Vh>V(Tnx_!A?^eLgx_Fr&a2lg5hSl$3?&{JdPK;a_ZI z+*g+O%pHH5Gnt@+9};tgJ>yY3vr+c(AXGm8&HHWbLE0CA<)PzY{e%Eq8|ezqCyGrH3L;xs`XbyN?{T(JzO#V8nqr4L56*{ga;wRYcpLmywhF%FC(_y|JM3AL z3hIZPxK}%?G4pBv&DGT!Pz`d~lzA;$zS9=8$B{5RH) zcq4o*%$8opFHvS~tIy*>`tk;HHIYN($vLe5qL3OkyI}g_eV}~Y-SV4n0e)a!j!&ZU z@Zc`f7_W@L;)M|=HL&ZU4R2pxivJw=2?4J6$qttJnzd;=obL*uA$to^=MU@XncByB zuzWy&bIA_xN=W|hHwlw}(VnvRwcE{KNE4ZT-NoTN3@q^6- zv~JaK?{}$UNtwOSdtc1nBP4xOL0P$lZ>};&_t;DrYdw{0urWYM(?X$c|D-YxzkC{o zfs<_cTT?30diG>I^s|e6{JsDUC0$|SBTL%-!3xh0xWT#%Nz!J;bc{s-!rea3KN#c2 zmB43Q!k1jPL{2sv^u9TfQ1~I>Cg;M*LLiJQPTFKrM$9!H3L&F-l*4wHuOFV{L{IQG1 zjxIvWmd~KA7O}?-i|YgN zjztlqJUU0F+MD6<&CKUNc_qy~XN5PxcFj_pyamjV62 z7>4=%>g-wIN$hf+@uE!tOnaD4PkS0-rf zyH?xdvEw^n!1W_1qob_E?X!3|@-EdYza>72@USwXwJ34Uch-Iqre zVEgAH$eJ^ou2eO}gS*n9+WI#4##ILu19F6OKE$FNKZGz|EoMF?G^|M2-N zbIL5&pe3e7e8mO0+dmO3+-1&-eKo^L0~uhg8b>4-7-JmcN&Yw6a|ZHpg{CNm+CAce zN4LQjB~PIzN9U^(`fC!%T9V73>@~vUv#el3TOiq7Z;yEitKm{YGOfSEGEfUP!PYF` zQpLS7YC#P+@3~0U7FwXSNCnVM7Br3JDOPM5h8seR$&3>kIKp$MaG!UZu@FVxdqDN< zGu$<{&%gGaDb#RUd_&QFdn(lG{N&HG-ar}lcYPmkMtV0G;-9V*Av2*)B@dNXcZ2n~ zC|-kcx>TnOf$O_FWJVx+AAc`_Co~SxXlVmn`AH3ySM_q`=UEJm;tVOvl=W$zM!VZ ztTD)}0Os{gq=v3`=y0VTM#pK9qTO?GFuVo|)M{x_O$MGd9f490<@m)}4yZI}4oyMd z$?mD1%sat&FJumNe$03{HuE7YNsRb^U^$fNwQ&9CF52bffMI)zVX4MdzNOWY^m}BWp3QL5hxk-Q#j{sjIHrdu#0fc|M_W*1-tyA zc7+jH=V*n^$5=LMSsDF(KL}epc7WV-7rt$#Ek2yP9VDNo6LmEMyrWPH%bP-Ic6bqH zE*XQJZ~C~k0jy_mm^PFc9icf!fbTUNVdUEN{1q|Arv4EL{cUT>2*#lrFp3ApU7{gN zn1>2;pjPdSg_TbU22A@35xx^(&L8#;QaAtu&5SMPn1>HHN}*<}6-oTyiA|XTxNv3( ztu!-aeq9cfG`DjR4+@B>t&V`%&#BdATl9vHbPD~}WX-4?1xDble zchYFKFY(5I!0rt4K5Tw=unb+S_;XUR!X5uu0et+eN3#swQB^7sf)0!)I>|sah|41gZsyLH2)@xvNrUb%I=Fl5Tx%jDl03M%vVHtTM8&?lX zV5p}WMCDoHkr6tqQ?Iab>?Ttrlda(IluVM(G}8Ayk-|A|JkAQ0G84e&>ov~$qY9)? zS}WA;Cr@+2$r8IDHEt4pE?0*qoyK7OiF^{T%Hi2fr{IJ0KKf=H%ZWE@vOD5i%KFgFzmHro=Z`n)o zOA}D3@fTcFZld<>%xm;Q4WzHCk{|Yfww8`U?`2(4DC^`(frWkp4NqhV*5BInTZrW{Dxzgv+7QCkq_;BLi3rmTF8fM^&3r zI6C7w7qMO&pL#K`6zeEiox!@3J`6{wk<$Q`9e6+ zrcGNbO|bTADlA%ji(A>CgWv74g}Ti)=CRjZ#Ih~+fA|##nU7sD3~!2#hsKl6XxwT6 zGxz-D_X0r&H3tZNZAkoXTH~@~iNY*xU$+A;Phwi=+Eg-%d5?2#i$J}7F%_}TL)BM< za4Pyfx6`E!f)m|^y3OE1E1VL{?hw^!{P7_+GlMwRmF!QF*Rf8t=S$)J$3*&&y({%y zkA;l^$hCKPW1m|!%+k9=emu6o;YZ7abAI!OI-Dv#77v|rCcQ5-&|6}M@IJdEhxuAt zRiJxo5x0`PcNwxB`M(`L)sW@le=UV*^QU~4h9T~}wL-YVH`*9smcll;aeF6?@^{9e zuRCGZb`{>CiLnqD55RvryjC3ZlTTuKpNa!i@{a+|uvdncNgp|R6~;@y3GjUJ0eU#W z5uc>20J{fE`4}1IHx7@5h&$^@og9Znmop&pasfTt?27!8-EdLf!}8a@Iy}-k8q2%1 z;WX22lI+AW>})c1MAi%MFb5QsGKk-N<`XRSggNsAX&hrcN$B~&;_HXF{9FT6I=3AB z1uv+Trwe{$y+0RUO`{T$fG1@upy;kLx%F)>hR9S2cX)ICOl&(Qj%!Cu0@zLUBka?&KCai?_OLkFDX)i3Tu7FgRdwlK+D;(mhK)F7EWPdeg zT=zOyu{x6`IalJkKNIjBs&Lo8jlf?mU&)QJZ|OVM)$)|_r~dQaNU&VPs9-->pJGg= zhg+c$#KSVLGFrXD8K=e+!?KMWfAED3nlG#YlTGPlik<;#?5l>B7?u~C^c=^Vd*Z8a z`o!#*IgZZO0J$*sj#dEJe83L=99_@9W8W!>86hAQxPm;KE5K2`TVSOACYo#q2y8aK zesszrTd@QUeEXoSPX?^m{a3%DA3VacsQ0ZBOj_C_mePrD4VYKW z98}NMa-(LeVTG!-aJF}K3()=5R(SI42LA~;+`l{n=1NQ>(VGo%j7>i5|65O0|72s% z>R({{3i<0RDsabz_ytjoIRt@&Lu{;q}c+T1OIZh_l>YL$w$bpf5cc8 zb<7VrFVctK-e!iUzotTywF61{#_opFMX)J6n{H;$CI!7eP^kFAvUYwBRxFgj$XjYK zeZD2COKHK$RfUaLSjV?g5P;{fOfse33LP?7w{?;$&3J2uH~rSZMfVHbNe^`}?^{dG zO7EewHs<5WS6%QQ>+*GH9*X4rgtihp`k&)vce9y4 zgJqO*_L06j3Am;Ahj7kcT5f>>#+oqqj26+j>4etvy}-+Q2YoWp9v5F)0$)pCG#E=5 zW3)BvSFNugB8OR?#V#GZGuch{xHa0Xt_HziJl7E80wudo5cLYiakb6F{0-tbYz;>P zlZ>(SUlqvN>rIZx2cfZZ1nW;JqRVBB@WXa*h@U)*yO=2@Xn0|WBN?kMi17y9G+EZw z80lfgPe>spa6jWYH|&Wvt~M)$6)q>~q&miJz9Wts8asLCYk;#=br>_Vk}hP={Tn`3 zU@l_cXv*028{7QghH@d_1^|0u<)Y2)y4cpf?L>wzNT98l?8x`XX|f0HdhH&l}Qct~ELz_|A5rzKHG zAq;IN6ocLHxwQWu0Uq6#4Rc%`bMyLjaOv1A;hg_fm4h)kzaeAgAKt372esTo@x;4v zP#ewq-LwqAwdWIWHo+C!PxwI91#1$(p6`71MyMY@_I# z($XU7$F234Hke=%^zw?|VT`>i{t{+2`4&J1XrdWf7F#TdvQrBJopg1&jdd^q5WE?fy|o~ns4 z*Xtno@DUog*%iO8HHF??d$~uslhJgK9EeJE(6%O~@6jdj_+&eOyxSO;l`>ZO14|;o z=4a2kB%#NCaJv&@4%frcyUM&Q;~gz~^c!Tq+##nJ1Mo0E96Qe)qQllZVP3frq;DTV zF4dUg{uB=G9z8&36#|~^3I-|}!nfXLov_n3z>C@Ii0QX^tRuS+jtHvh1|?6_y|V}Y zo$YOz@Uxh8h>N1D+DyndVSOCMVkkXq8@=XfgT<3{;oGMy60?3D`X6-zDceB$J=_T0 z`aEIT@WWioeFF@!Ukc&gFR1OXV%$9DG3d94(39_taEntu=va zCbpgt6VCaKudFb9w+^i7>m}Z|eDH}{AY`=9r50@FSH5?H8Qo$;GQkM1c`O(1^KNH+ zu;qCLNFBb<4=~@$aNi2}uIW$o0*$a?ehu6hkwMQH6`)!)N>7x2wH7Aa zNFq;HBT9UWg_OQndh#dY(XvdiGCE_iaMcccxK#xG8WmvfNv3a4`VDGwS=2|r5aX#7 z)+ySNRV{8A2-yN~Z_1(yY@gpL z`wLX1**?#7gW0X@)>EqtXQP6!e2)!`9($RDt)v^AC{hk-!TjSgGR z=2+u8&^~^N8+}n74!?~S@{P^?^0CS5EzEcEqDo8haE#l}#?V15i2ZC!l=nth zbGU>`j#`dZHtC??F5YNjZGx|)S3+fcCHXg*b;yRNL5FKJ-D+ZsJ!7ij#N7mLlD9Wp zd38pZt7;pag)(B|I8L8XF2)$&NGrjsRo+B4X#qBcEQDf(BI*-rgf?cL;I21|yS8DJ zK+((yJ8fp5;#LlIr>28zF;XL0W4tJn51%eS;kJF$#-!)P!kg?(l8w^vGpIz*?8OnFCnLpVLS6?cI+Ue0; zcby^Ve#j;72Q%oXe;D7==O-l8I#3DrS(=?Q9Fv!%kl=4_`0p`O_&va$`v!==qiw+Y z#yD=a)l5Nh72{bqOW~edp;)%Q0Mu^Gq3o=QoM{FG%Rk`CP3Pd2M;XGI@0pN`J?DQx zQB6PJ>QjfaC&;4Q=qu#4zb*RO>caSCANgm0IDDvW1%2}j$rcwIEc~$*UfWMRpTRN| z%et9|wqgtMWSORTodP&o$$U87#n{rra&1yixi3La!T4Vnp*}w~QGhy6wPE!2RDNBU zA#M&fg%RQYMXb~-L65ZnVLalZ#+? z-(&u9fhqoJTm^I16Jn%kgsO5$LJi03C*!v)u7~r(RCw9Txwvc2Z+JCuhitcJ`ok+l zVgFS80aL7^mclu|(i3np4FYl~n1A^LaI;q|n9bfuPI_BmQBf9L%PFD1uCTqaWG}=t z`dAvsu@8>12(DFEfG8=JBqEpCw*2(C|xkF#o0y-muJriZ! z!N%Yq_xYs({=0jLaLyNq7bCaj5fnFv(5+96aM$ZRn7)5HiHOld=K~c&-NxN46Azn< zp-+PxFXqd*)|+(T`}&XMjswdXu{+n|B3){J!~nNixx z-!q=l;;+rTwjSUs`!eXRpHJ2*Fn;($_MUYooeCZo;OR&y-1vDK7s>k4N7(lWcl*+W zdHCR~6CCk=&(C`1guAttKuww>@tbFZBf2)hn)T&$#cO+%8O(v;8>aj{u){CbtUqpS z26@8nCNq^Qg}eRtVMSQMN#V-zpE%P13p`P$%zQORD6`SvuP6bOx31>{nT9M8?FXJ+ z%SasSkBD(x2RUChP_;UL++AA<_k!=GY-{LN0U5-C$gGy1GnV-#tw}~^u_{LgBp8JtcqI>=QOLxaMtasB9RK_7SXhHmo@G+t$>t@c0z`-m~K}p73;d7R@v@L6ag6c(PBC^Y9)c zkX&noH|Neoe`9uEo1Vt9#sYe*#Tb8R=D`f_R!$ve2jbyYFSwn-%6L*JlBL zH;m#M(}xQ*cgmuf+&g$~7=}By=fldQx^#4?2bx|ehPW|Z+@_Q{IJ7rin4b-2KEMv0 zpP)8rfd9U)2m8k?z~c_%;2yg{Bs$FjE*nRisnS(p6Pv&A3dwg~ygX|FBu zkVYyD-P%md<<0Qdk9;upT0+x8s#qWE2z)u~4L5M^DLl1w7S8#|G6BnHXu_MuRNnTD z3GOy9gU}^GWINNDZ?uGgxoi@xOfkU^>5Nn4Zo$RW5In@5-8Sxr$np!8%o|?>;*}OO zyt4{D4vxS_%Wa9tQ%;{ITH~N-IUIRrV|jT&G1?v*gbGOoI6FEAGarlLVyjfTVlTVz|Cj~q?r$R! z&Muf8;|!0#2GL^HRpb%CvYb;6a2rM&qT5h7*iC;yr!t1#ytnN4n>UT_(>1}dzPYe{ zxjac^9(YNgGNFbuTr~@ih>2o>+caM0g%uv`QiqVdUedh62W_IfVI-ML!NvqfM!JFP zlMy7(*cde{Bf*s0O(RCz<9g+6ICJhYU(jWPcl*j==hg)z{H!T<>ej$T)hxQMryXCm zIWd-d6xTLf0@qLKB9nJ@()lc7;VU~2`eQ!urJqgldxJaV?lLAf_gQ0^%to-jT}IRX zdgGfNCD5|phHoga#W`>vE0XAcV?8D(*=|2Ao~oy@e?xyRI5u6hxHfAS8tM$g zfv+=x26Fg}`82vDOsUb-e2jM*ffM#vk?ulwyd-Y`N0@)iV3-k3EHeNl+wEL`zZ#0h zvFAIR`BlNzxbs8|EI4|TuVuMNPtz3PZr@a9gl8JELDzK$z2ncA$&z0{avSoB!wc}4 zssx@&YbE!JZP4WC5pJRnc!OX9N|_8sQGEe{jSV`{;nrnAoHlNT2m<8 z=OgqPukW%5UeD^}m&ze3eOCe9O_lVW71Qf>xPfY2P~${#f>rD01L-LtT4xYv`L2T> zIrg-Y`PE-Bj?;@fA)E~J)z6)lNggz%(P!;BxU};N3=s#qae6LpUnh>59;rm*iU&?n zHiYhBxzw9whg)x&Lu~PAu1HlyaE;xh_co0|d5s|a=WrGba~$rqN`dwnE!>%= zIXGrznsCm4G-FvslkecAIKV4e=i>YdaoiYrm^fXt!P-AeBMt8571%90{|>tqp4K8C zyx2{42FpgD8Gk;q&l1y5Zi9Kbo5|)MX6QXLA1+K-N)s>Dpx2KPY<9il{3f@1N1z7U7l#6d>`JUO6 zg!{bFTo06&T*~~M?Dw+K60c8KA5GJuYMrSX5Z!0W2Zs>`%jz=+nuy~jG&E2h2xAp#lR-^*NN9W_lOT#hECWET? zTOyr13yy`R5_$GMJLjPzEHw$H#&h&hbc#L9jNZ?!*kXvWSHfUr{?52cV%K$Uk9m5y{ljf)O23wrpe^`=NmT|h^}nA~1W zP%L&O9LO%Bf;3OeheFt>ZpGh^1kAWw2vOgY$$plpS-htl5{50L2X%8%!9xtcWWMD# zG+E%7jS9j!uiNK@SKaNQ>vkgVl4g!=C){A>tnpz@8uT7N zYvC)sAGPa5u_#%Ebyjhhr@9?B)|pV-zszrGB8n5#2uXeFg<=o%LArejJ$zH2^)t?a zIeImm%TG0Q{AdO{hjq~WKUR28ZyhWfbCd5}WXZDsNdUQ1$r~3V95y-&-aV+NZ8o`R zVDTA-Vg>w1gVgcIHPV~hDq+22FY{OrM=t#wo`*KGzQPQVmzFXoS^t8x2#VcQ zh8(8h%dzVUGlZZhvZBFPgo#!)Dco#BH4(2JYVhD&^I5m!Bnm`l%pf<21dp$BX{f zAj5hAh8OrVM)4Y`7}TLD&+SpqJq~sqmLvO)vz`dX&S`eLNoC&^Vy0z>(0lWd1q;KF zMs^~?W6T@b=UGOM_}bvJuJ!O>vJ;hiV~(je6JhObKd$(oJ`9e?5VCQ8Ud=_jDPQ0) z=ScMjbMT>(7=HYlLUIG<A=n*NParQD!1LnR^9Nn#;r*0sNJ>v7X|m>+eJ&SP_b#EQ zZC~IbmP5D@sz}CqwL{f7M`3<;DdXh(O;m$Wn$9;p0@T=I0b+%ViT@Y}ym2uYV*8V5 zxuGRipIZh#2U+}ofd$@INP>)S`$$!nC7$ib2LrI65wTS`r9lk;>z|dMs)c?Zsz5yN z2%W+1>~#;cVgA!yT;J9Jnp8oYvoi zVu^NG^e_%8y$W!N{s;_|&ZOtxEI`}!=J0k(4QblpidVin!W#7uDoEGILwD>zwQ)c9 zSjC9t^1`4+^(F0F6oi823V5!lMi(#-?cDBcxKt-kM0q`29a{pKM{201Sr%@t7=}HQ zr}39%5Y^?CK{ zUCZwAo;|>_fkn`sKc8$FGQ!1Hpvgi?n9r+wF)CN zHZNn{cA+%uP7a=EV!gn5om|ai_8Is)9o$D8r6P_?FfKC`=0z3r*;D6X$)6xlVD}@r zO#*!7w+aTe~6onP(h6kgo-s-zLQal(?&vkm z5zL~-lLn?IJVr-&F=sFB9?AN(N3Mp#Z;rfmk~{hu=D}o#5c1X80@GDUu+ zrMDX~A53>K9Y4|hgHLkYm`rj??vw+)}O5@1#{QyqrVL6RJy&5u3ZN>^@aj`IHyCdTo>Tp zWOHz=uAm(|t#H~+mdDI)ZTNeXWkTb^Ax5lLvA)#nK}9g0Y~dE| z@`ZU-CxjhUI~nJvIbQ@dqmcHOti-f#TL}M>L8Qld;Gl^k*!E}A$YTaL6k-b<6BM{5 zr4t3K>sc4tQB{nbi75Ip8Fc1Z(NC_%*zcbSJK7#|V~6YDXvV?&&yy1xmW7&%L-3!T zlc>ZvF#a>)iG3xV6%vA;!+b$Ob9tlR7jrx|-v#y=7Lj?YY%p@zTFCk_kAD7XhCN5) z;Y5rt_iT|7*zL_A{Vf@EOcCQqEcyiU`yHr>QV}**vHYicPcBHs>YMeSjl_j_uXZi6Nw z%CLA-IxoA8!=^}MNG)4LGFu(d?L-hrOKzhMJI%58&0?s1&T+S+&2iK41h~?(msqm@ z{^r9xp`If%rVvwfzk{ZRDftRZD7R;YEEX*q54WDZp_ACn zclk3{SbO&_@8)cT#jJbirlL6+gT`2s9SfIZchb)%tWfoFA)GFl&evox-Wu}*FFbaK zEWNJJ-mU6k;rIYrHE4n2Gp9k;&!1e!FEiB8*Mq4B2kDElFx!vn>Sesa}H%=Th9=TW_shiK?l~= zrUL&qX81lFX-W$|X<&12cnmYvRW=!WzM_Hpp-AqWf>Lq@*br={^4hp}M z=^)eUGlC<)>K{3>ljStKT0(?-zQZQA!$;f(!MX|blC=Q0Z7X2^9$(_m^y;;@N+7N~ zjegje%Q`bfu*7f*x7AGoUwvs8>N)0m{^&U90wa8W^KIu%ajvxk41F*nh2uR@J z#_V9diVLx5BkM4|=f*#{Zh`(RgRpHzBJurggrDR~p|v-ZdacRB9de?W`}7^RVS^=R z9+89nc$9J>p7>>(Jy;$~;a8N-!$~!P&{wdD#D25IrvuS2G(VnJvUm1gr6lmZd(vXr z$NhMH*Dy@^sscvy@-b!b6SP%l(Rk)>S!OT{M~oySqst5XTV})B;w5yz)&N%z*8-iu z8jiP9$L0P;!ae`FbtuZ@rNfu^UHsRx#^|jV3kB5^NuCJv*z_~)kuekQu)EKmjlIB^ z3;5{#T-0?H5$^eqN}Q2vRRfnRI#fL+nq~DO!0Cw^$tpC#>0w{R8=2b^Lk|&%NT}FB8Fjgv??sjaKtfz zD&Q(!-ME3>jyr#83-^4dIC~5sevGB;N&B6Qaq075=mgvfZO)hz@G0~XU35ipY-tH!8Jk+|CdT3zTNT+{FEdq8Wf@S?QhVbcaZ#f zXn;B|>mhu53LR7DgLP(eVEl0O+Cy-(TRPJi z8_0?wmYX}52+qUSQtu>JoWMHJbp}(o;WOt$>49V9>XU6$z_NZ)VZ(6F7^Fi}UC`57 z9X52VAYQehcx|K)%r-BfpBxNPevLJdbqZX<?I>=|qk zs^}ru|Dlw-Bl--o#@Y$@{Nc`a`1zC~?5N4$-J}iiIMsspqy5N>AP4L>^as_?N%R$C z9OVWqf-^&w+yL`q%zC{QoR#;H!$TaJUC4#J#}-to&>V|DRIvVGs(JCEUK-vbcWBSomh%Nmq*iX3lkiHTRl%y#XWiJg@-f>@X)oX2y7J{{~oM zwUZ|9_P{l3s^MQ3bzUyd2FJ~)hkc{7$=UG+C}U73ocZI~-6zRw0xT~6#4TnVlFE`f z!kPbxaXfx~c7lwKK)yHB3SYAuL?$0gF23fl{bM{d%qXDWo&)le@}OJ?Eu9|jL6bcr zar%L|AR?ZFX=;Pu7Mem|uv@m|k?F9@ErYCh?~aR_tzqxfg;arg;Azye@~zDK{ol+l9+r*brUT$(KaF=q zCtSEt8RCckBzJGQp=J&9jEQU0zd5$}@tPNmxG;`1^%>)r#X&-5LRtjtRLV{RDcOH{ z36@LE|H$-A3vV*r+6=2}%HYz4O#1A{GgM}uty8&C-0>I*^s{aymuV-Jm2$-s0SFn3 zdU*M1rns!x20CUM5w}tYoT#`4dVVn9nv)GazMTxm78>$f7}H}t>%zd{@x*NxV?_8D zgO7eF{qZ#iho%ofh-@cU#d1bVbY($j#Zelj=Y*3^aI70Tk@>9=rG;@j!){KC(P||qT?!P`u8?}o$2A}%NS4i z*d((5j1i6+p9a73>Z!DI9$p&i7Vh~w_#AxDI0*5c_sJM&q|&RccC z<%lRz{bYix>TIBM+g@5aF&rQ^ zALL%HwY<8Nd5yjdG0j8`6z@7>Mx7$)$yYZ%E@!{T4O+0FA&n?*vd8np2VzV-Y2*ka z>`x1T?Jv)AO6;A-*gc4>kFTernhVf)PaDKFdQrVctou@>4?MUeBD;AmE(@;tZ?C33 zea^U<{XY?l{#s68xwh5;3!oFnu-o~3Xo?Hy8M2Djdpgu7tqqK=Syt0d84b2Qq6@XiK6Y<4cc+_qoc1IwPJ=H2^o= zayr}C6N65NLi@@O4Th&o851KIzMZHfhgnB??5eG>vTYST`hvqbN;%*n7Q@~*eIfq+ zQDOghw;$^xZW)5WCk&rmW{F-SWnoiA0BIKW#>Jm(Vb|$w`tYR%u72VGf-odW)6;$K^SRD-y{~W_aUmV9z0~K)yUp-}O9Ir) zI3rB&9FIHBEr%KD%{*dg5$_i-xM2})oX?ZuZi=sOv1;uQ11Y-XQ!`tE3}T&$60k1(u~zCq>gxPMMzv$CfvQP zgeJV7bmm_=WP=lwJVAcnHF4Web9C<&20iy$v)!LbpLbda(>`tBx_9kyxnBtsbQ>x5 z>EVdm#acMrBcB~}GRCeCYhb5IFqfej$R>`4f=x2aney7ZG{?cZob9}ERyZb{m<=)d zsiLhsd4n%Zg;h53EXTkWRj2%)36oe4sIs5{jywU$lj$4LRY4X%4IU3Kcju$Zra!Rj zdpgg_K|F0V49Y9B*!x|+_`cQwU$#D-Du$>j^%@^mWZ zJokaRr_r_~`C&O$TWmdo19Ou=9LHFj3{IfiD$Tnoc+nxW32S`sYiOU7I*Iq1` zIx)w(mBHMWY`*DeKE@sU13h&W1*=`XP_N+z``16-O~V75q6P5telO~j3ApE)6TAtu zV)Fh@=vX`(US6-H&H{UEoVpxhd`-l1!3xiR$%07-Q`m!CQ*1t4BF$JC+ZJG?{crHM zejxg{@I>#-~WYdpl+{1 zbc%Tk`=e|{)xDJGqTU((Pghy+6?YtTdo&y_8pn}#%X1qv;lC9f!ZCWM4-2=2(hHk; zoti7gzl?|41KwiYP!qh+F$b=XL*_vYfhmQn;A?t0&l&H7aUENs$CFx#=Hmjq6Z8kZ zFVKSer*xzFr2`j6ZE7Bs23YuQJjh`IOKx()#mjwQgtHGHB5R62PfdcdU5A8Io?1{| zA0}mB{ytcOhqv4T>(hSx7-hG2wbO22WXM{`-&v^;rH!%Jm?lf?w1GKzAO^1wFOXyV28Aqb{FN{ilaMVtb}nt z(kCaq8Vd3g!&y?NKX#|Nl=wEEXY>m}v&Yk6sv!#5OxZ>`*%U`j*26z>ws=7{4Q70{ z<9EhTPvVvg*zxC5N)vRS+W2hheL=42sxN@Z#)_Czi65N>*DE#=(4DLo|uv7jyeASsE zJlF3%Xufjgj{*y^56xs@b_UaH55x4raqw4M&396l!KOMLXjmpE3_}l_lT(8*+shDn z!c+{uoesl04fyRHwz$?X4L-Qv6uOyBz;Oli-$FBgpRpqzc32NakGG2@qf4+`|88h> zXgB+`&KW(AjfCB*pT*{>=BU3^2jaRJu%nKM61^yB)*aCF#7w|i)uj*^w}fq=Y(k1l zHmppF;b~?L*qm4cyZsA<-*yjSNFw>AGv9JMdnfXikAPU^9PtV9SSBvjf)=G9HshNc z&L_5^WAAi6U^VSaae;78!$P=3-&6MS^TD^Rj;$m=aMqbTXgVX|kW|la zbTz}11LjI+ezA=|7V#<=c2rj!H_-v-B(H-W26^n*JnBHnSPP%-2Jr|r+U?^9!jNv? zg#+*DU3N(qE^OY;4>YdDnT7QbXm&s>Hy7|p%4Eo^n#VGeY;Z|H3JgtO#VHoS4@N`u=8#LP&y;=c|#7FX}`;9Ow z$O=@nNYC$QhKg?jq%+?$Efkf>n{At`!Jl~%5B7N`thzgr?IgBs?SNwV1~b`w44279WT{&#Mh3r+aw+rZx3Kt zmX`yn`o64#n8WnCf;s>04&@K9G|C2N%#Ri}-0Fqazph9?%sMl`M*Aq{nzL5Wnu4=#Ox zraf%%Xx9lW+*-hUy%b<~zC zn@CS{TbTq8#_q9B>dr91GzWS%9b|*E0R25Hp)$vUm-VT|$Y=5xuxJu{8RL(!2Q^^9 zv6=i7u_FD)sDqx&I)Po%#%;mlq`Q6Xt7*hx%Yfh?@5TPTEwC8dQ``;D0Zep!HmJkeB-<)Y2XN z?rQ*>x0`vOq7&}4o=KTs4>5uKw>r;bp{)tn)HQCnWn?K#D6Hh~?t7p`#YV_gtdU5F zUDoB(FX?VymJxsnt29Aq-q<{_n*#;*jDTB~umH-wDSanqPJth{FgHaRD}U*nUp<8K zh$92p_JOs01ZhpvZj^#*@nGI#rVXwk-j{;YST;q=5Y7Iqfw~b@ob7Q&gXhD*=SG{P zk6{4u5W->dGCl4~H>PUS9$ADbFJ|vaS!#d07Gds*a1(lo{6RQ~)T2 zve_4mvDITO=yj~*DX(3zU&RP8sWxZxhTGt?l5tX|eGGZADn8kQ*nas)>k|{qzu^ae z$Ck79arC<|Eg5#aTfo~%aFN(jZZva_@L@(E+=m@f?&ZDD`FPH!1B~|oucqB#Q1c+^ zJ|Ak~kK<1voN~?QZ)Td{ss+|?UQJcl5u$9fYa;DNK6*H-A2IaoQ=pfh9bdA-0%c7y zq&`e})p6(^oGZ;(?UL6oP$YcA7Cc;alEN)0sF3UgZj!_;)~Z-xN=}HG$;b=;X~c@c5zbgW$s}|yp>f5XWK@K-*p_&_;fX_ ze45KV4;!P2eYJF+o9H0M`6wp}tDCmro#hD2grMW7Y0gJ^jZF|BLhPHQ`x>vW_WF15qw@cg@3(Ri^j(Cxb0q7_BvO<_T>Y>q-7VE zQL{mHt`A$P7K&qtcM*5NLOR<^?%QJbi4pLrelc(QM69;4iy$_7kM+nTd+Z;Y53`y@ zCi}ApU#@)x_KCT?XTy3tX5JS&>I2yRo&MPO>S#Fjd?r8N!xMFeTfiEP{lc}I+W7F1 zK9s(D$|Kh~pmS;zJV`q*TAZic=+byFE+4{@W|?7<)e5O@^Hgsl{%EO%_k((i$F~+> zhH*Pw+kcH^2YX?B%SZ@VGJ%hIYKp0Z!?DhvYJbc{?etHJ*c54$%_VtFTDF=mVdg?G~il0=gKPpVbT|Y{o zWAtD?j&dcvV~U`g+8B1=sS)1lUIiB-tGV_VqSc-m3fuX2iA(iFENG+qMUMe+YXR-U ztAj!Im@Y5=VvJgUyx{Pn-t4lPG42`_1KKOkaSlE>*R>p$#~&BHDj5!xDTloVDwkU2gx(ke=z{M z-3(#ZDm?MoIt#csFPnR6*kj&3XSj4yUpTZv*=DScp>)niy|csAFUer@%bt4}TH*1p z>9DQGJt5qE91c;;k?J;)Lke*Agr87!zO7phe?A)U zRtFbcHGes5?D0TwS~CG(%B6tP!e&0Gw*yX5t%ea(w~1Oe3-Ek$J1jM6U{mOO*1ui_ z64Sqm{bXG5{0SrYZ<4@9E}+l;0DrhKQLgC|Wd}?R;$hp)1xz>08e7k0z^^?q++vdh z4ydYzCMXaNAAAT6x(Iz;-|~4k?eS`FMToV?5nXTNm-(=)TB+_Njg%e&er#s*q z@t3RW3$R?T9RjQ~cr!6H#Lt6Z;i4?|`;;e+Yq5Z4m&v@(bQAn`!~)C;wh2**)S2?$ z7e0kQ=G}KrMn4(4`R>r-nG(wI&dP)o%Tes0y$L?JQUG?v>$rOgX~hO@uv>GuxY*wX zGv_OVx865)>x~2U?>Yf&=a1p5m@&rYn?r?6cQ*GJWsSiPx+K=~M`8BpYL^0r3yz8g zfy7fMtZ^n!hq#%kOk2?$EsF}_#l9*0 zNK-X-P40y^CBKB%_XUjpBM%3^?&6*q#7RJ1c-y*AylHEUPoA5={pv7ww~He&T_YeV zHkmJo1AL{K0MFL!wH}x2fqj0LK&aVi7E4~xK+o0i__G-gLgFV3qMnfvPHbT#d60gM z1eHxO{F_L6?QS(tsar36j?uyAq}%^o_Kcf^gk#5zWPqbDL}ReTMJ93JdzN}S=skFe zSR()Ws(c^YVOmusXn4qodr}H;RL&3h$GQw9K2_m+buhVX#Z!sTP~kHY^rG5@-o$%( z@X8A8hiu^dHj%^gfr4hY>O z8gSCwmpR>C&#UNtH{pFL^eP(4Wp0?^ps+&N9XW;>QcumwHI1XB?}!G&6CqJy0bfdYw>R}^@buv<;k`l#biJ`%+E?XFTKx>i zAE2}a_&LfH8)y!KeyvlP5aEezswwywXYbJQ0!!P~pjt3so2OXdB|l$?xGUGBaNPpSx6TI1$py^k5Zxe((!u3!4F64? zP-cx4aP?!ZFyr$>Fka529aSGw!*RQ#CSs&}#POB_X87$#DW}0DOpF%1#e<9e68;g%mu9Dtl zHNLvyq02)cXGxuK$XpqR*ULzE`^J~ytNE?3fW1~`!t&l!1-ox8DlBb- z@>`lPkvQZ}l)r(2PdYcJKYym5JUG^5vUT!a7`)wBI_DLyk{2l62nJo)BIq44!>$d=K4p);|9Nt+m6%2T49y z{7eOgz52sGs5)WBC4JDaQ0I-dX1GQ)1@W&8`=VivR~kJ*F{7S4(yR^}z66#(Ix6x# zgwStE2d#E*<~~D$i!w@J;HW%4?|LC#di?|DONI(weP!`p@_$l&{=`pv%17%$7wsqF z!rl_x`q>JsbS>BjSvMTGHVPi}t>(`As7qw#QmJlpI8ngmUg@yeDUHpd?-U$Z2<=~{ z@{q|DxN%80{PXdv5IUSXR%Z5rX#;n2joFTPwMGy2d|x82-DZri&Im@l4`Xl7*i&Ct zI6SCc${Q6B{ktxJ@NWC8Fa4$r`_N3-^7#jd3!R7ZoSf6V? zxIIHf$~4|Zx}s;0KC}$oDRd`p_Gv9`>27~{n;&{EryiD~d*YYxPB^VwGF+LX#+)g4 zKe#FdTqV@0`3{!jue0lIe%M24IPBCm;iYGcadqi1=#+04 zTD{5BMc(_5J-6^VbcyA-t6hSF!UGu(&)@YkO8vKXnGTXD%!CUSI!*2%g@sv~6 zad88ynghamcTE^2=fmzDsO7y*c;oJM#NlZk%2Cb&KVK~XCy6@i%rU|_N6R6#ri%Ce z6^RG?Xu+Z=%5NU@L#M^Q(%GI~1gNwn5PlC-V6fR3PYKhY-{y0CL!cwBDai#T*#jbt zT9ofB1smTmw(Btc`Q6sSi>_Jx`ZWtID(nSM-)OOwaW)w5t3~{=3VwumL6i5pf^+oK zBSufnF}B?k=2=v-ehX<2FG_-Y=7~I8%MD-sD1e~z%Y_wdLZEx%HYwjyHKGXZrnJHB zVYb{aKL~HnQH3EBmoSaRUO39p7!M@cbtSXzM#pu&GqGkzG3$&nf7k9R2%% zcT1t;uoG`cG)1R|6xh{vT`=o89*^_2YYYs5|2|) z%|@SZaFudQ3Fv|GhC|_=QJc7**t}}V>Tvy<5gCywap*iCPDC*g^7u6 z!X6I^j_Vu+@lg%@$7J%=D>^~q&l%#76k=H2@Pwn!V%aoK{wrBxPxW8Lw_Dre_b%Cx zJityeuCo@WXZ?a5Dte&&Q$WA4^`Je#h$pS1H}d!aaAs&eQ@G)W!8=S~5&bFVGl(r2 zLKz3stwQHEGfd5x2+ds{^IXp;%)U?vF2Q?W68jNhjT7_;(bD(f|mfbrX_`0F4~ykDLMJ|Kwa2fN{D&wL1+ znZs7wQ4dkSLNNIq$=#FJ;^!>tnA`VDuy$oQ_na(PkJ`2yyFyqE;bgPW{P6X<*7$_g-ZKEM>|Gj(tDQ`q|`mupal z=+FQs)Z1LmMlJWoZCQ$tc0Y>O>)N9?F@JBf?Lu6F4yw0n0M~uSt-epefWM1DuI-h0 zhd$Tg#5p;uKbjQ`F~ib;WcagXJ+F9XkF6HvFnYa=xU#YsC30=BQQ;Qb;o^_Q5@jg% zGU09`1!9Dbf@$}t~BYmQTUQft0^Ck7LK)O0Xzy z1^hai&*MhYy|T7UI_I0u6ry~`SNO-S_oNSl{Cx~+zmd-^P% zJaQUY<>0lan(uxz3riz(pu6Tk!TqK`u8#Hw-8H&=nGk`wvzNlqsbkqc=9Sv{sgQc; z9B=C8f+-JkA%qnJZ1s3W-jDy@66C0Q((J6tWeh(3{@6e zq#Y$cMipZHgD)_BG;+&KC)^xGx8lI*OtRY_zt@;RFa3NzhJ52D7p)*|jh66ni?WSP zxE=;|=%Rh96V47=4A0*<@mU)v-*<2sY$M5?{uK16Z>dJMzz3`^da!Ame zBg7S&K~mQgX)l%PTk<~jdI}W--S`EsR{ZkC5x4!i&*Gf?@Wl!x$^jMdJJU$xwHyU4 z1$~8~6P#_P^sz@}e|@a<2*MGI=0V#HEk1;DOtao4fN}UOVZmHOY`=}_KaK5-D<(p(Qu%P2}`8!#PoGDpe12glfrjb z4BwFqdyCUq)<9yE-Ci!$ZPMRJu>a6v_!f~V%$@uQHW^tjOKlRtXga${6>itJH5(=i!YP+le_4`%FCU zK;BMW7kIqOoHd=Yz}TnJpgXCaPa(Z=OKvH&{?ZYbthdDbg#{2gcm>NTA)dyy3hA7W zqdVX^Ia%P7e+ro{5^NkZ3ho9p@Ulh3v7A6mfa=-eK22BrRWKEfr>8RGN?ROavH;47 zt#|%C;sC1*sNO>oP+>K$jQIkdff{hchJ4r4KTCb}lSjB?U8Djud@o{YAHDEI(#0zJw7y?e$elc&+759V^o2ZW#-(5;Q^;ZpHN|+2w3N^>f zs)^ElzS}f<2Zg1=`_j{*M}rqCm=(k2b<^2>gMa&c5hxtaT2>aj zZxE%vdN$t?r(f5Ax2aFX0`eZnFE*vjlsSuWcf**L$kKJ03C>P4~Fq zffG6K#yy+Kq*`KAdmfBF8o>`}dtpZE4(NNUUf6nw;p%{%Fe_#^A5>369^z*VHSSyZo?(&b)RqKjI#W!iTw$PV45%-2Vu2Cl zb8}cO?IP@?_ph7RI_Vv@^&EBD*8GA~pT~k}<3wyw8vvba*EVmRMqN&BBcZ!o9^30m z{OZfDu+S=$i|Y)rb)_AgRoy4NKTT{L=ZR9?M$_2?wOjMy{iDHr;dM{qv8;vl_sv<3 zhcUj3Tm4TP=T)R*NY?ZQ8;38FFaLSqE4r2JRvrkeF%sYDhrrEYCcH4&2m9}ihI&&q zHekd*7U*Q@%vUNY#U*wZLFcb5m(8%oLDca#a>FF%>0m}&@p3qHKAm^}Xo0(&y1|9> zTI_Hl;>&xZU_?qeH(4Bxmx=;FX2p*qvnpxVs`P}CyVdNws|~7^&jG{T^SLE?61?Ut zf%Ppjg~Km{z-7Zm=}mUQ@&X)~_z{A80q;_cXtT8!EVB$}=@tGcH_H(Abkxa9y2LL!qRPw!@cQe>``$Ojk<|74Z|1j89*?

    k*aezp z-0Fnc0!9#B2T&6F4XnEX}L0$&13(61vH4 zQs$SOX{P6r4c&dlGyXjUx5mF@diuqj?~TN`8-pNv;8U+5faj)4z&)Z~cstAlmz)fONwp&Pwe};PZ65J{kBEP=tk7RjWLhTzI5v&!hcKam0D@n{R0q_66&s!q-%3 zJr{j_a8Aer_OS0R!C<2@uI_zN+N-C1r7ZWS;m}8+SsdEK4E@KC11~gZ?*b_g8E+$< ztB-Q`L}!^~*j1)3PM_s~Th-G6&Sx`5d5o^RS3+g)aDJ9DdowQFVLGpRu-f5>?{EBK zw;if@bRTE5-Z=txe~%GU*P39LlVf3g-&mH~>W@!#BjKsi7VbcEj2G*pVcb_sN!M@_ zY)qL2vYNH*XTTcF33&kPT(fzfPfqCFd7bU}n#;O+`QnY5p0KPSk}oZ%UF|{zNHo|l zWDtMD`?faZ7qoGuSyS-TwArAOt~DvA zo-2`SQeYp(5C>_UHN4zi!7Yw^qfUDW+~X2)+b^o;$3x+8+9I~22eB~*FNWzwG2FDT z173?I&i}wNVdhL5oOtIVvo1f(6{#Osb4w1gEz`x+^@uuVL!fGOJbT^Yhh=lDp)cKc z42ZI#jF~O0`nk{Qt3*b46(ygv0P9hW`R*3b z^CNj`{_N%r3@5g>7E0^639h9lS>7D80l}^}hN_U!zx^tT!ws<$bflbYcWKIeJ zn8JI(3XNQ@cisV$x~WLL9xp!VTaP=WhKq`Aa4Ka~-V6swuUS3}|nC(REUt!8R*&j2H-B zql(y`JM>xXZ4F^bfn4u}38p*{VCP47A({5sS6+omIlv|!F(~i07T#qH=K*~!@o7aC z9B$WUfA5ClNzG^MRNvM7!*EaXg7tvP{=)! zR?jlUF7XVibGFcIma@k>v!Gz49eDMy*3)QOfq9@$ToLpHA?S~-u(2&<=^MQ z$Q7f-lM@jab}R;CyA@1siWLf#S#TsfoOcYP9MRoocD!dV_GulRbiDk^!Zua$u;~uC z>6jACX^IjT)S9524*A`vo@;f6qPg2-_?WewCyfwrL|iy1-#3@6r+ww`;fc^{U&|UZ zOR=s`D>(niTx4Y8^AN%)! zvhfpm+&1DWJn0J!LuA=b4=c=lF;3c_FCzzsQ;GvPnVk@y(%i$mDjFKk`mjgjxZlvR z5T;9VcwbkB9V@b7=d9C`Ye|n_RKg^7*Q$n}`sI#Y3%f$)uNUIG7z;f0t}n=i8?oKA zzgtmh39o5BTt|F>qAvCjtfwQc=fv__n*h#*E7^s6h(oV0h8ahu@Q>Bx$l&R4O znub0$#b?;rONaU0`Q)K{BL@jAQ?#dS+s9{vq5WGTJKxufa@`iNK`Wh~`D2BTqOC!G z(tfKqb{5#!KL`R{4zSfvL$RLrq^oax@Ud=GhbcQf@5pDthO%MLp5A7gFHPaab^ho( zPYyD!o)AX(k&kn3S1A*+eXb z@qWbozRmKZw$|l+74XvQ53Gw(4x4T3hq05@;mMCs{(!hc7hb8soy4QU);LYLL|)~8 zb9EV~DE!`>1`+b3xU8i!{@0QQvwuxwb;No0u*`x}bPKFL+XX)dTxNCQ-z9Omp6Jpz z5?0r1@Xy4(Niroi#^RpruRq;NY!zTYMI+z*W-@M!%z!uZu86bhOwik#e!tV**}Ku! z=V7gck3ZJ|33Sa?;sGkvT{JZhO=tm0}Ze?hsmn1+$CV%y`|l+DDDsnUatyb7i_ z*$o42e859}8NYkP1g}2#g{YHpLI?3tYTJvXIYwJUSDc?y40-)~@ce6$n02L{1zIj= ziyTAnr4LCKZshZrrydyYHWDW8F%%k=!mK~+w!^UNN!T~m1E2Z$fzoML9&(xdZaV(( z`B;;%5VB`^Wx$M_yXCK?bZ;eCryBs}F~V zLpS$L?BiH39NA$3Q!;({oMmQsVJ2w+uv?t}$O7HuGGR@62#eblhDRz|SgJxd zzH|cd_w+xq*+}Z`@Zl_gD;b*b|6Levbyecom<1-wb!z zjsg9lX2Pi&Q=Iz83KmsvVPPe%cyDq79M-Ypyv-D|t|mg+`BvfSLw&lxNP+ap2Y8=m z54=);jk##;5Gq`has2L6Y_ZxC9(l?EtyPp@$C_JW_ht5IGfy8%HaM_@o|c%m2c)%q zZ68Gauah8k$q;d=vlXt(p9_uGQkm^dOPqL|*v_ZJ_}gy5IO^v;cEPYO6AmJ-qW$mZ zeO27Z*a1(`9Dt4i#F%D!JttG%UM-egpl6WhE>UoXZ{tH=3aFPH4kg7F5@X7GdBiV* z@1^HhzqS%wKeibjoyg+nPdXBN@FF|fBbRCZ@I^PuHdGFa;_ZK3u#cY#oIz2TnoIor zeVR~ltc~v&=ZY7}iI!JBm=9MrM%|u1aD@$Fg>@FhcbYA&?JFJ!;mVmCA^OFOx{mSy zT+v+~P7j^Pubni%TJu zX{NE|stvZ7L_(4J3Fh;$6tC|)4>sk6oWz<`f0n~xcrDy^^T*lauQOAHseEfZG3)yO zVYL?z2=o6Nj~6Hd_RrHap1Aae+J@lictu=$$_U*glqtQ`kCmEP;9FgP>FgzGxHDE+ zroyC~-Nl{_=7uV~e}7c4@zsRuo3x~J znBujOxT|J4R7R@u@4sBI$ILWnan)x((G)NKNQLXB8+gAkSFA`r&#EGRNcJ^T=Alj% zb~R{n?ZX!6tvedNFX_WNuA1YlP%Ci%*~p`myfIa1vF-?iX!s;yu@INZ9OvJOGVW~1|YcMRR=1((0O@H2hLX*Jjb z78+j>c1<(FKB-f{S?d^oEKga@Z+Vb=eWQ4Oodd4Bc8bZkl=C>^jl8V>!IbN~>b8ya z#2xcgKuu-~TQuUkNtx~K5xrUf*#`%Ag*TQ^0Zmr?;_xhV0z zvz<}tKmjB#He)gO!!bAgF0*-C!aZc|@b$Y-WCMIF(Fzl+WZ+yk`Y7*KFfm_8<=V8w%G? z4iU}inO*ZwV{e%OmxE8C4=BW z(`0c%u?dd5J`#?m#IQom5S-OJ6yCIK<=r~XvF|WnXrFH^X{~WV2jbgIS$ds?6s@6| z?Ja2iyONhs_V4gs87aR#DkBz8KBU*)f42p8nX)?O8qyj*bYBn-iVcPVPOALjd1DOF z^nh-8L)c~Vmu>V*lk2lm6Zx}9s`ExYq04Mp_UOD7 z&ikMN*$O-PC-S~!-zS#z!{fB$1ML4P7{;f1vPQ5+KcgiOu%v+ZSQd!Nv)4nxjt3I{ zL>`~NUCv@Gp7J44zNkp|XsfQi6Lq>-;(WE9;8A15dYgG+z9Jbt^2>SHCR;qU$`*#M z)f2yJyQ2QnIH-M*#q`nvdppgA?6tAn_OltDxSUE#`g~z_DmjSLPO`BPM|dDPgSw6T z%gi;?#r-#FKYLOYQr4!kaeqB=UYik&ew)U z%M>p~;L5n0?8^~Lnin}>L&XQC@>Gr`>|zMneLyW|kM#a)hl&<#_>Zp59~q;1qcN;M zC1Hme>3L-MT(B|U#K&k!aAnt7u;opzM5o0PKR-wZHI19>=d1u!S$vtzZP-@#f_z3p z=D%X0WqEA>I$xA~q5`ZlgnytM*Mtq~(D9*0$Os#xi;K z`MEhxyJZgdpEvTmZ@iEtCP3ELTJg27Ic`>q2e-$bEFejO7k*_xeQXxLPd9OH>@2I7 zw_ukh*yFFC?^x@uQeJFCyVov*p)KoSEgvkwk{ufKS}kL-lmmb8(hc6tT*hlJnxR3v z7d(A2RoMC`68eA7XZ4e__*Yjq>N5*r`SW2(FLxj=kR>W znIEPsnUmXiVWDcc^)`Y05GAwGX{INpgm}V;L^p0v9M_?a9^iZJ8a?b7p+jIS=mj3* z4%dix*F6suS-Gh8*8x+n*D>8y|AS=J~0xQ+^!N?jMd?r<>Ro zzY^|yZ9ke{@dmT76v6%sWpCsrfMw|r?pkSxQELprXJ)-HhrB#>gFNYX$N5WQZ-(2a z!z`C7F)0dgf4?l4J1dg)9vg{`2XC?NvaQap0b^v^q5A2BVM?m0~a3-tT}Mg z46RR@LF2PTrbtIWf*+Qq3G?D{|o^5|-S-_V2+qmu57+jmY9C}_h5WBlr5$8AoY7$e~FfS|g zGE0Zk0+%Vc&` z-Vf93yy21NCjLlbfmMZGV4YC{O>{p#s`C`H-nJTZx;4SvpIQ7;lMnhn`^CKT zCvl5Uk!WwF0g0hag6aS(JbGjl9DC5lhxTyA-us*&N_#M0d&nK_^xogYRHW7O&bOBVgx9eAqTsq& zCVQ4jU(bM9kft8PKNHhWmwx_Rm*)$+nr*QbkFu1~BmCl4J-0av8kGU_`w!#5*~7&?;(<1^RvWgtecl*su@lan+gsz%R6bD-i?9 zVER({eEGHTtt1SKdtPQoFV5sO#H;+g`3d`SdZ!ThV>}*}d}sgqa0T~ZOs_YGj3W=k z_5Dq7pR*y{Eb7mCs9WNP6J9W^X9ZtkIStLG6Z5TXn7G2-7E7F0!l2bT?B1eq)NQ%U z)K*$>!$LbeS^9znF6hBF{$QBb*%L-r@8ORx+T!6^nh+}ID9)kmS=7ht#Fh=I+QhJa#`+%8|Tz9Uu844{f9li z##hYKsEm)$@Wz6EL&5*kliK#aE|_+10?Z)Kn(1(N+(|h=`>h_Xw2Yi^Y3jAMf5Vve`zzH|1 znXi61H=W>&w|h`NM8><$L6Mlr1ABpeTnSTnEbP8$EhH*i;U9@PC@F4d?>D>R2EQ0sxZRff(&y~#HL1i5{3Coj zWPny*7D(&1-2+do^R8z`XLkr1S}Nq&J;wg|ueT4R`@y2Y(A>90T-juddyXoDa-s<< z-ED>68q8s|>~{VpJOIlhX2F#hO|gygw3XN6U||1c>@j6=J8aS+Z+UdGjK9R?kSxqx*u; zMc0M*`r~j%Z9P6dc7sKYs5p3x10H{uHl$% zTLz9vZ|YVPr|6DMC+l7|k)I&msrJvFAo1?W-b6{zeT*86owJi4k*DXu7FT#xbxz!M z+!#G~xkzjHM7r_Gc|HeDZph`G)(pK*XF#9rrzB1XdgA^IbEVwf&71x4Lg6>2Hsm9D zk%Dkx2=V7tz1cy!HC9PCfcC5{d?+!>E>NCoxRJhCU1CLUJ5QK9eKDIc195)pOyCpZ z`06#}L3_OfdXLQ$ye8P;v)@(h?yV#I*SkRMH2ulmw`Gd0nt}MoRta!Q8k-R2i)rii zq2pc#52Y+$gO4S=DL!a5+SMAz-tvbnOh>&AA0grF^#QxnD8A$9f>hoy0WPM(ILo+>}S@xi1pvE$2 zp3o)H9W0k`;f=4oh?7bF>$IMt7WI~Ed#{9kJeLhPFcpUuUthJ+Uxh6bJ}|^ZKae{L}rl+l~6WCvPWo8sGeJ1N@VYm zEqm|%-hTf;pZ7)QIrnw0>w9Uw>dl!OJ~Yxt86WJ?Wr}G${|OiBIsXa# zW9=$Fnn=&b4aJ3-zZ%smfmV79`Nwz%Hy3_;?dOIMJhEAjbXSV3h{R^wEMX+?!x^c* zRGKZSKOI56s@CB)P-LD>o^+(K4q`tiL1AV%XHfit7rU0T?_(V)%)AeN7-A@ldKP8B zpXUd*^`A~FxF6uiId7bN(vQhM_p{ytR4u9)&aQ#V37eRm#FI+5ynuv0flY^$Icun!48BxZ4cB-0(e=PFIAme~lmDDZv%ZeU z7K>Z~dt0EVqZ?d^Sj6_uk0$4jh4{5jjd{H1p7}wGaOyx~2sj>1*>$b3a@=aRem?gx ze(HjY_6-vzHhWNZ!U&WM*I@lEIY;Q+Xz4uP++j&^o*sBDjj;)(j0#;2(GK zd2TT2X>*U+u>w{fYEAB4HKjh5HQl}G*A*9>y7eGjX>cbs!x+4?#h%T0X+cd>sV-L%BOQqERQoQUi8Er9Ku6+fLbC`>S#>CX3| z7PUj*uG9yaPMy8$oIeiG?kwrHf*q`r2mHCN0sR?K!MLd8yl=|C}xVB z)${Pa4{qOSC3%`CA27I%Ot^ni$ev+GvzKaOTepX-rqG9WcXz?NbJSSyRu?km{m5l^hQZ69He?l+ zfLqjfPe(eREz0@QJW-5o9ChUf%tl2kw(*QTz5LM&11;pB;*x}>6lme3O*@&z5D&7e zu*YEso5j1|IUl>H3)Y=-gnimXF2_@(+ITpB6M^kgeCT{pGU<;D{c4{q^_)j3hSEO8 z50J6ygZNX^mKwFY;@~VZz@(QDXE*nAjy>{JO)FPFTsK(Y{$w zWX5mAJ&jTGd6{ZNII4Aiv^j`IdEmm?O;hhd%dfy^e%=4xK za6-8fT{wJ-cT9A8VT%4%raH%)uCL6(LapB7sMBtA_*((08WuxNWi(y)ZH6&%w(MGv zGv_|tg{60TfiL%|R^9A@SN`l}7fl?=)>;RHhq{QFckF2KL^E7a#@EGAiV zKPJ~zHVfmZllx9j9hYa%Mz_=SS;lzE_Bm*1g;0;b@8Ix}B9>Uq-*-oQW5RSp!G3py zy>Eay&%jJ2gB3yap{pkbfAVA2!!4=txC@T|bU}#cH-%p2(b9R|dc=d)cr3vYpUcI= zBV6gi-%1!aZxbuH<3;&fIw5mYP*eR7-qGyX6Z2$N1C#fs`=z6>YG(kOpJsvMemH}e zzlbH}MN#_Jd~A3)fN7=(w9hmLyVQ&V<+BlFbyb7|ek<9QN8Z^wFdoRMKIY&;oChZKEq!t*BR734+HAESBqoFmhpB%!?WL}V_V!eSj$8vS{? zbSKxp7)2VHjj*DjTB!T2L33L6NN0F)VmwVZ)WVdMPvXT-?zH3fFz$cwfLgxaetXSt zo#xw^mO=!@-c8}};t^tNGSQLpWW2R>Avn(g%KEqfA1sPt3)lLRsX-NNJlzZaGj*U- zXRpD3`BiL*c>w8`E8wrdG%^2zFa4Tfh!1Y(fTT8(I_7eolErrRi~An?ySw3bEpy4u zUN)3II~F6Six6~k4Vi3h$0w@_Sm3Q2bmp=Js&^g8b)sMzz!_W#Ph*+x&j8B*qksW_ zPY4Z%?I^CNI(8U5WXs0{Q;W4bs+ejq)nR5NnP!i5n^fTEKs(aDH9@M4pQ-aBtr6Ut zwDE3Jz?WE>r}-UzHe0gkclq4D)&;SwH;m<3xka)XxbM_XHg%9I{W@cZ#rs6@;#*64 zoal^>_0G_z)P=K{)3M8qV$S2Wr;VF(v7^sPiNX?DO8*%zWpG(;9!D1CuffFflQ_DM z9oG#1fUS!;2t315ERMwd*3E2cCg;9Bvp`X0w0N;ipshAuSny~btUKmJa3c+;TuWvj z9j(Ykdp7|@OVc1^q7P|mL}OdpIyOU2pds@UFyz}(NrH%^ z>Xw7{>ux~531MWox(=$^b~G*G`StH-Zb4J!3JBmmBiHj4(8x8Ma|mszZKxWy9y=;5 z+^>%tj%!JGa;@DybUP**Bf2TGh9B`{Gjj=sUUG&thCIsIWxIGj$Y~4!RDbo zglB)fsrOwuEO@QM>IMF;f6<@!63W6BHCw9wGzOpKonwK+eF(2c;a~BHxbZ_Ig>sEu zvHxsH2}c^;D+i}tDPTW$2GZHKYOqlfAUDv347T5dr&!8X|K~^xKK4M@UsoI7Z{bYc z2kN*@y9|OPe)Q~=BPMt(U}evFj!)NJ%2d2MB@VS;7f5$xeExSiJd$?Jeh&_1#jFS4J^p|kzMC>uu!{Gyf7{cLls`?NOBvn_7&tMR`_|ev(&qyHf94=c4@$6 z_kG!jfM8m7uNZm%38ZL5Q{%#;aI$?ByH+@!te&%- zvsd1M?Tc)|cz-bUbvMF?#aa!kB>bM6YluUJCqd*nH`=Q*4u5}~&enbPpw96#@kIy! zef;@^^ItWkewF%~8hR10iqjr`5@U7}Wv5@3&hybSp)~QE5{_D4$TGP{B8GoQesqxt zyDJ&A%&0r*+T2CD0A$!3W$K5W^_zL&;vc;9sV zoM0?o>S;^oIiq7ezjx1lB_Z|k*?6-oiam@>An$d@VEGLdP~x}lX1l8pwzi5*;-0$s zp?y&4+e9&A7m|CfCe}@w3e9|0yg0*m&a!Q+Y7X~)Jn=;P{??NBIX0wh5sP;oiQsZ< z4auH8gC$c7*ng^5XqnGgl;5F(ro#j1{nAeOn;FgC@jt64H@o5UceO$-=QvF<94OVv zzsYhog2Wv)PHVBIrDgf6sv`3e!AshRImkb`k>=tVINPrKWiqw@4bqRX%fij zO*T4DYL?szktNBKNNGQ*=D=|jbhi_RF5utjB|II@zxQ+i#Sx$}DSAdpHww{oe}bjzrQAty(y-Y6`2-^r!SG_h5_RA)(lR6#ahn z2>x}|>7C(k|L8#&o75)W+ipiAwvEP{PAbqt#*Tcax!|3#TbLf#RV*gX#X4nKZX^;Y zC}SSq-xkB0*O4^9r51uuTQk>zE~Iz#G8~8Aa9)8ZDxBXboGY2{Sr=-G8HB|-?qZpV zC1tNO#NrSE25Ux;%IqW@RbIgo=9bbl^P^bU@0q06KVEKk&f@NK9S(jTMdE1ghf)R$SImfbJbA9Zf7p^|CPwadgOXreA{WxMxB|*yrOcOevAo^7;pD;B8hcz7XrZGT9vx8z$t$@>wB8ACcH}bq zLQk^%5{gmRvW5Q|WAXOM#ZvCph{jlw&0dR-H}q!nKF#50Z8EpBx zj15WQDU$3y=xAXk7;W&gpQfizGCkvIN@fsk-r|IJ7x}S_wPvKY9ME(7Ss^gSg8ohl zE;SecDlffY<2lPg?m)=wph`|8xE*e z%~;$Vd-8mqh%3CdioV9?NwZM zwjl}^^>kxXd7q2@h+7EJli`Odk}|8(+eE1l`-HgoK?T9Hk7X-f51 z>@d+#1ujI{(cAQB?9SPzVLQU8;Bql$FMHZF;Nuy3uRjFue@(|i^YIin{spLwv|uL= z^Y`6X71UDL#mXkP8Ny$4*r0%%WWVxEs(DI=wX%jW~SEZPcMfe7S6O2 zgLm)_zE^g5{K*tJ*2RfFyh}ud>66&PN4%4?dmiTZ*&s|Sa3;S~8$j*SA*P?|PumEz`LZ3 zhUy%_?tNFVkMYiA(>oW>?E5Rcs^oj)rAnAJbqZVjZagi%{T#fH92ZW9k0O1UdvGU^ z>niu%D1D$dPKZ7u{>bKi5Kg> zLl1ucy#%jIRzWT22WtMuJCX{++0_iB1t(N-do>fvj_9My6E*lWtDHHU@T9?d!RUTS zfz2;5;|$CojBnM1t6nzrLS+VipSO{@Z3rXfls!-TNeR7~tlNR7Xl_IvzsD%z@ zYv9^0)nK=cXR)`Qlg{%uE#v4)XJ1@U{HpPJojW-*ZT!-*9e#69bw;xTip%ntTdq0H zyDY)d=@W#E-m$o$Vj-j~Sh#Ayg-#X>Lmt)#@r@df8ssd@q3R-W!IkeS+A!KUU;W zXn?Qle1zv^X1u$`4$?2?u~*mQsq^7tJR70OPE~Th(3EBP@u@vbPL3qk@=DmdVkL7< z@g(Q9m%)9nsvyVnS^uro!Lr?2Y>8k_rGxb_cVx40`j-_oWf00dWGt+&1KC$3;O4Te z;)_~K3f!KKR~mxgP*N@BalYB6yZ~lwoJ5up?_r!nC>%N!L>UqK7*eCzU~FMQ)?M|b zKErvRdGA$dFh25|#h{V*r#y+nrus!fyId!}<2R9ix6YZR2kG(IzPKXbt2p;{Bc&EO z;1QdMH$|6qhISo2^QmU;4Wtt!};gQ z3uofJ>fgdtMKk(+Ek!!Rf7{2<%A6$E8QJ5pljf3xC0_LH;S@e+E`ry>2&$i2jK_JWq3!2W^gekYD%SVK#L56-tFOVT z=4d9zbLi79et~~`xZGJgO1`Uzm2D5$D!wZY0t3YqgC)ZUE zL(9{fn9H6B(wJV129uvRnK-pm`gRR$bex7m-NI@2?+!5Z9LxSOYJQ}?2fftZz`hG) zmY|GoBX_Y4*6#H4jya}V9TRqM^(A(su<8xmS~&qOZVctjZ9R-t$Y&S$UBfqH1kTjkZ`XgfH7$q-ykxN-3RKJJ zpm80~;+3#*1Fh(X?-Z#{ej+%UzFpc0J4U24&lX>b9dQZv+^iMGuNp;PqHjsPD|ywN z9qp(t^&hry-bm0@o)O^rpowTlflBsxV89jzAEHQqP!4W)Q4+N$22jw?0(1yi10h)v zbbJ4H*pgwz2JM(Y>Z7=(Iz|(kLWoXp|0JE~tk#uWoz-!Qo`<;oHP3f^A1d`9c3&M% zO_8yf@_sYh%)7i@)BS3_^w@)D-XC#?_q6`*1Lb>ocdC^E zp5A$mIb|XpNOeZvL6xH4=wMRlItRyLd&GQBuFFLXA z9CWKFXZMGWBm42PSlRTl@xH7FDJf{8<(us=>^#3mkFv#|_1VmFuLb?~v6FgN_L{}v z(hYgi{k*~^g|=VYfJ{Y$y)$ni-S;ZEQSBk<^Z$lvrPrb0_7WDf&5^P%eFL4IhC=BV zUrO+?m1cqhJ^;ZWMb?bEOmIYoyxvWBFkE zIp;d09*S(5RuDpKBW2L>{dUmp5lA*XhxKosf9AKsgP-)I^E{)!86Mth4ZFPZn8BEd z^!?Q$yr8MYs*L=2FD>uWyl4kg8)E49-CfYHVKrOn;7MQ0&%&X(s>0sAKD1-qAdD)} zV)}9BG<~hEbe@0anXFriz?p%^*p3!gN)DfdNy0Ai*&cIh)=R;Cg9D)WbS>Rf?~VH& z2XIY>|ID{%LD(jN|JJ+G6ccssO;u_D4bEuN8HNsSlVN+6H%;sxgolmiur)mA_}McE zN1DtRdiH#Z+HC_cKmP@bSjd0olU{hJ`Lj4^$9Vdw{|FR!=E0lM5j5Oe4&VMLVn0WE zQ^hpS3;p9E$o=HLtP*1!(4!KrjNnYa>T&3H+Kt5?vY|_F$Dz91Lm`5D2#ZD}<62h5 zV(-L|_;nXV4zCp+xoc8$K$(=C_<0HUl=^hX>xb@$_NtC#!&Gtqa|h@jZbyr*8DRXo zt!#uR=hsd5!rL+$Vt?Mj;aQT3=PQaJ>@m{O_PMyodpv8lY^A%rkEZXMY?w=qWLbO? zE?QQzet*W1=Sx}iS~^2Kf69lR?jM9|FBd?f2G`BfY%wUQlr^rirMVMGI?oMwPrB#g zFg)Cy!Gd`cXz0+@*u36{*`=MPUD^Zjc%wW%xfw)Tov%Z#Of37!yS#U-{sebCYK6(G z?MRV#hyBZVPHA87MV|#=1JApDTDxrz?E;hB?kD5Ad zvDB(nG-&0O9EPOvBJXhSrG zJ-7u&H~tV6&kAJ7^C>eHS;F$`0raMR5aw(zX9^?jNycm>ZWg%S!t)oa-dNy~-D%)> z%aMHAW6`8Ni7C9YrG-i97?xEmDED{?oBCUEU;0z$<8&;p8i%iVPQlac$H3|?^U_D?|dLrDzc)k3aMD? z_F5QnJDN(LRlw*S=`2XupDyQ~g{_Yc3d=J`(N6!Xa2_790M2u$O;N>uJ5PzO{2Otl zb|{vwQiA5i66#sP<8*RcS)(J*yj+S#@%67J!zH|rJ2VZe+j61Vp6e|#o1sw7nk};l zp~U5vU}<+{7*@-(`ODsd*|JLZl6#>g7uE6lZXZ#ukath_8-tN&ydb$goaWj^&?gWKKN6D|xInbQ07B0({_Ewxb6iWlXZ-rlfc{gPxXNl;w!}@Il1&<0p+N+?Ax87;95%oOxXFUXq zqnZVc5^K^fv_toy$C%}9S29YPh>F8@iSMe+>0b0C%z5q)`s-@R?nzg?x;B9OnZ2oh z#%Z|T3~>EzAiXXajJfwT8eZS!J*N^KynQwqQWbn?O^iQ|o-~IQ>?cy!i^k;|i-mZ( zr}&}=pMhLsX?k&xbZ&LSqBUQ|2bW?g^l1mExh;hC+Cik;)*WNV=d-dczI4l13$;DG zg~I**yhp|w7hS7|Q=vSc#X>Nn(Vg9zXGiHH$KkE-kAx-lW;BAcs&?}|`RUfvWvk zyR~ujwYUWD$9l7`?x$%lX92--c?>KGqSW|y_{U(ecuDkk?@M@cuvW;|l2FN3IjK(G zKiQFb%8bN;`}#3I?vc)DwcuPbRhSsYJvm2%(0)=m+mqo(#*cW%gi=S-h^uF)@3nrM zuab_BOeT@b`Fr3tR>J%*#M0i~vS_hH2UIrzy$P1b^YeGH$n{P{ybGo*zd>{?wV<*H z-c1(k2t9T<($X<8825E4Tl7YlDEyO93oLh#9`V`Df&`+?ypsooODb@kqS9(Erz1r~CqkQdKQUu{{) zs+?VEEx+}v4ym{E-2+tdi1Qy7*McOtjBYnqV?$gCv&?cL|GK&Oh=bf$O^T)nuTtou zp3dHhK9m=B5~|ME2!r{4uD{@dbe>yt*3;+poQqZ4F6Knq(7|;&II*WPEbJ;!sEr`) ztysc)z{MBg=vnf!srz-VEw4>R{b9KI56n4 zaP5a4ZhEO8^|6?=#!`2=IDC6_5bN4%L2{RT@R6A|_{a$4ZJv%X8k<@1`a1e``!`e$ ziWJ^(U+68l?s&x7knQejOV1KzaY2(De0AV`9KukP`FoD#&YDCO;v^j7eo<6=~`bNMFNfaD~F}orBL$T zmr6#NWA=t@cJ+l7>F8Rc_Mk)|J9+}Xys`kk<>#|KhvFzhyM$}_{n?mLS+rtt6_~MN z7?l}KW4*6{+W8V@^CN)o8(k2(S_o0S6YMMa-7|de9QqmRN0LRH$#BV&-SIJ_Qwz=T z%2vaFhmX zy6sCp)fb|orX8fth^6Vt8{taZ8m8mGztO@)*e9-n+dK(n`3%E{2Gb#GsSl;`8{fyaIc)JGGYY8m!cCf)Lf+a= zto*1fWt$tX%A)IzRnVBRPwbY^KnA@`@Yk?Au;Ao4?yu{P>TXNeW3HiT)hJ`0vy5+%-P4RiHJ)vHY)eBvBD z#|#`@Gls1@lS%q)4`ke|f>fS~9{j8YUjH|q>CZ~ zLw!f%%PIYt>201p9Bqa}Y&lcwvn`D{8h{&H%h{zSKXNF@LmS$R z*1b{m?(8}6J#Wf>7e!L-jPAIgUK_5p0P(9UN8zDGlh}N&eLbH# z2|JpX3B4*^$auy=xKvTcdNumcfo29#I~Rzbxu15g*)y>EkpdY#LnxxJCf;vf#4^J; z-$P=EZ|x4*b>sKw6eNby>otF2 zUV{M}Qej7PIrHJ4X8w!68TURNg5yokGfEGqBW0mjRsWw@n`A-5&v;_&EDz3k6X@sG zDR}eMVzy~%CbgW~1r~1O;nx;->M7pi`(m z`;%9jDfZZ~fE5nl3_$K(*Q{75+{ll|(KoZDz0a*nVk!RcGIZUg%&OjJ(r%^QFjc1* zI;Vxxr4^?kdhl{KH`be6k9~wJ?Xkj((LogO*c@Y1d>QQIUEV=srJA|%dP{mZ*ju`j zck)hz+qpB)DPf(My1+qy*kM^G`E(=lp@@9Zx`S)@oRi#hF^~)p4YD zFq1Qu@cf+)YPSXmYW3#m9c3!r$rIO?k;;Vw_^QL7HHa2e&wH%;O&SKFVR2OVWi4z8 zUdzUR4JYHiXTZB7$Z{Q&g_iz^nq zcU2R6OiYHl**O@tkh}PS05YU7L7T z{YE;jj*VefMVWN{>@N6qTNh0Hd2VG`9b|m2X13h_ut<;h*Vw0sW>XyL*LHclXOsah z5JI{;Ezx3AIXn4n9BCVbpw=#b$>2AfrKS~#;U>pm#h&%#x3L+^hc98l7cwd8=Pv0C z5AP8{BL|*=E)I#TPZ{qX-T594&TA41i1Wv0$w+r{?cHvatuP8T!jxIsBMUmY$PD+& z4S*>H654q>5M@*=SoHgNvc6M{>mxrjogC9n)pKOf=}kI1-%O;Gch?}HyB&+>Z1(K$ z&mpS2Jm~Qr*hiUt5L$MzcohdyO4rBypNGYqbQ@CXV};9oU10_1(bYM`;;z6FwpW*P z8$zeyiiO7|x~FBRVB{FsHRdt998*pExRz2m&6$-nhfvI(Z*bV$2Lc41;jJEkcM>+U za3gneU22F|ew&Ili>=8c&J2SBXTWmaS#X*25*vRevmrb9Ota2J1MgBn<+cl@zL^j6 zSsl9^;zwuw8eni~ju5em8( z(c`#QskgjM$Cn=S8NQ>-MKRpZoc{J3h&FfRL6tKAGvlnV;m8(-zeC7Wl7?y~eZ_9P zAH3K33FxPv1I-0dWR$fGtUp?_2w5M>pd&ELtuJ)pZxchVZ?ALR$0E4qQ2U`D@9Odt zJ7g^>Ia^(t_tfXRbk#v`T;x{D`#t#%Fx?wBITT8|-WTXrNeaqbxB}6mGf8b$1)MiL z)>No>oh&&*X?<619KikjX9jAcE|U_Jt2kXESmGDV)f?&Hehom zJv~+-o#(HsT*;18tF24cEUyo{}W7CJk5A#O&&YF zDu}{&`{4IW3k3)MXFPvOmUKU_ut*?z$K@DvSA~^6$|T)a74WcMF|<97CAD5>;J}NO zY}~aVvYGw`Iwn~Pmw1-v+r=@`o&4236KZ;4gkGCY3wwHU{?!!^v|LcnwDvhup36*> zU$a5HKHrt-@$&tcLu1}h-4DdLVj;p+QfShpGmWCl>`G*z7NEr4zOXh)qH zTvrSa5FXW-;eS>9cZ6%^gL${$UE?$?040{l`$3MHC19AfK9~)Rrq~|<6a z#n(53!Kguk%#yA4vROP+H@kqYo(rZe?P~a|K!**VVna@0TG;gIq_Bx+wLS^v(%HV{ zP5@osGYJn~s}l7%JLS>h8JIsh9v+2dQI6FX>1_9#?@ez{9)>V2fL_kdG)cQJ8og6! zn0}T2Jw^<|=uheJw8e*Z_Hf5-Tj#LH_NLUd%o(3X%oZH>KgA11iqg!!;fYN8d%XfY z&sB<}w{ZrPRy~+oOo0XbP2qp%H+*g^V*NcG>0W&w?9xC&Ot~v90s{=G+z&_c0(m!+ zH*O#A&OVp;Q4gI&oPYF}5Rzq1Nsq>(scSX6C6~onsT)Bls7(-hY0)?_A3oVWVGA|J z(MppqoGsBQYQD6i;>PY+VQL4DDwc;H3 z{tBq`>ttlI(d@#8OsYIt1~V_}!l5`Px>#Qc_d2WDddmrP+pa5a6tl(EJdZqcLm%`} znFX^0gE=E~EJihLVm8Tk6anTq_^P?&A2YcyiT}U!XR!ZiDZjNH!}BkT*rxNDv}8#c z)E=+meF{+&+Ik$unrfyIh;EasaN zPdVM7VMeQ`^5MxcJ9>t;7i=~2&s3y(q zU*C&lZ<+y@(&fm_xqiSxz*9kETu-TsT=(TgblzRrgTOB>d8v=6y+jb~n9 zUy$kJK;pr|ttjm>=@>;`sdeb;ZC){#Pfkn))r`fXuv2UwBd_HB%`xXQe zS)~4W1H9nO)%SZQQOu+6*rUyY4OQd)gO|HVXShGt{a#$t#8I=)v&?~yN{h&=o8(&WomZbb^hlv5?i_OW}h?p}{i`Hk*56 z#5%0S<1AZqoeE zm2l4ka2&Y-7DNTo$e#VN|It9UX_yV&o1l*C6nzDcFBUk+cntKqxsXkj52tM*Y3Od! zpDp`rL1SLV;5!%ww>@L1-M0W#tyi=C>70+WyaA$A1_?t7x7o{Z4$)IdA=$_K(a0}~ zoRzB0POq?`-Ms(e-wdBpZA1Hxo8YiZ>3rk?z--cuFS;4(`e% zVc!O*+M~j@2!0glcL*$35j?hVp^MLDacaI|!yB1e3MyEMI-@(Ge1$J{9CE=?adVl0 zqA3mD;edKKX9*2II`PVPd5pAp&aPNyQAdwba8lYQmaIKTuX~tcVd4jP#aTdpBR_z{ z+5&chbMKYDDqyLWm!Rb0L|005@!6KWQ0^DRH&ajS^4*=SE8~01CRenu=n%e?bDob& zH1@ErW{1kN$aCu&zEigeo_bo8I3*9V1D-IWx8W42_Yq{xpNq@%?db2kF8JQx7Mc(8 z+mRX4GYT8mw;!p_8k|VBbCEEHZ<4-;^0+ z`e{?i4&p4+dY%#HH&E5oQW`m_3DZJ~So-xOI=t^B$gZ2gPJZ^Ig$tj;z%j>#Z@Sz! zvWj;nI=N2J9$Yz2imbL1^fPLZ^AXF zX!Gh<@Oefm-cgRBI~q+qOJ&B^k94EIg&mOdrymq?-_D1A-7)3iE}qMFqzSEqQA6vf zIHtyyrY;zZ_M_dv6*>FpOEj+OyP9>F+mToQc&V;(HA0s5%o+mnJ$c8FMGd{0po(v8 zUD!$9kK^+C7PuY(n728I_jV~_@A;cqUab>p$_>Hq$Hs^Ux&Kx_U^IFR%mC~2ZZv$( zINpt(%B*rZTlnq-OgAhRu7vPgMqloG9azt53~DH6oGK2|y(=yrhoszi2{z77gb*v< zlW47kvGR-9ro|I!TZ%2tR=aGsgfo;njNLKP@)X3yPN6>w7ocrz6tk`3In$hp(w+RG z7(;)YbD^u#G&T`9_kKV%lrK3X$a)%4+?^)S6(6y_Z-Z!jZzZfRxh8)4;!ka@BQWdY zFv#cq(Hg}j(yY*If%8-yCgVcce&U4jyc6os1Z-7V2xE6eaeqjTbSH1Ij-$A_BAmFX z4w?22Wc%tWykD@7U0&izrhEEeo`bijHQj|9eRQzrZ!b9RA4Q+n`Qe&DTUf#$8@ik0 zhO^QOCHr**O1YYVixyvoNyhbbx9c^q&XW^2B%h^+rlWAt8C7hU8boO~p2NSa5Ntvk zx~dy4>dJ&%7w$K)mXY>5Pu%ZI3mP5Ka-|YW+F?qs))AJyR)?u)ZK$Hw9{OIu}f;ilQ*2{qH8doGmM1HuYnZgvH<7yU(1$%IYHLyop5sL0XX*4jePuf z!_1>)tZt|`RbGDp-?Z*Ep3NpYY}8#k+xu-AM{`FQqr{=5Rd5 zESm{Q7kN*5Z)Z}TJcTp=|BA_Otu*|?GwApFAy{+opY_HgASWqihdKK~@4y3?muD=@ zxx%xV+*i40pBMYYIk8h6M&YK4bHc%8R&?y4GY+b%XC_;`$?NVMyq&sPEH`qai#?Me zg8Q;AC52M&I#1QgDCs9 zB8JQ#!sc-eA@Jfr^wK{i6v^09M}RT!SUJWnbO$oK;e}DU<)Xqn51Pz7JsaO2X!-< zTeKy$mOA0Ib@K$b(5L8^)>o>xI1i|&z(-fX&+LcjuH8zTUg)Di(R0wu52xnbchEz( zhz&jOMdKIB;goysJg3H)S`iw!qIEm$9TG@Rzg)0Kr5k&+-IOBvzddK$8-nfwbJ}_# zLb{X3_0gg$=W?Vv`CXX^x~%vf?3|yA{+vTK=jR`|Zek0E-tnHYS3p zyKnG9JzLBj;YF>ga=3ZJe25JR;qTVbXdc2@c1MD#E|t%dKi-m;!)$4MrJGbI|1*?( zU7ly*$W}X+qi~MCA9)82y%f>fI+A>*9RVZ9B=$=5r*)4yLI2Tl!K#nI`vJS)&+!kL ziw5s@pEL}A_V3TWezl^)@uP8Blp2KczKnK%ca&(9v+une>C*2M)c$z3>F?n))bi&w zXpc_E(mdYD72N>oPG)Sap$lCzxdr={%0tx+q~?Zhc*kHj+sXH(#0p)kQWeFb40pPG zSHM4CLt*<@ANrydgHW)V4e|`4Lvt1&>Ryu^GI)j!le&USRx@*-R!be5l#msP5jT1uhAg9BPUhD}*+qhJA zLBX94PDsbJs0~6yFE#k=g$2yUWmFko3p`LLsr)Z=tA*5@gR&nj(b?b~SFCFa8R&L~pNoyBwHHY}ERgKGYF7@lcrKuCcD z&3bkOBfkV zOJ}`-r)lpSFHAzZx#cg<50$}^XA|jKz7=}eE@RhNJh{aNq5p>E!d3eTc)BrN+E4L* ziwixQn})}#x-jjHr|Ht;2hh2z6YeaFB$v~*Q0`L9l1F;bV)dJFu*Ya2;D$fxwhYG! z%e+`psyTgHV1NUZs+SnQ`)z4j~jw8Qm zRbam%rpetonEbvzhKLE%tJ8sO_97b^Fj)m>n)wR-pP8X?PXlPs$z#*G zmtgE*&Zh3{&MfC8QlDu{aG9Gg{1-W%>g?yjlH03U*K-kc%BU7*>FEeH+~*&BvoHP_ zIhd)2@OvfCf=%9dO6bQKdanIPW7mPr?Cw6GCs#Q`X-T@{JHGBuaH(h>E0CWRHllvse5s&+i}bN)dB>>HS*PJj)3zuf6g{^Ky@8g z&XOHZ3O5BDbhTMnEtt{e{h?U8;1tW^v$5Xd5gck90i90<({P7{QV&IgbpZ|PW`T3$@W$D*p9n^ojx+!>!Lj}{TV3Q!BfdR=r&DH#+4>TCvF;n3<)&v zMA~yIALhM_V<}gB$hhD>DDmE|8~5baF8U5Hty}m^_Ml-sINNZtDr?BKpx%o|A-1c5 z9(UA!G<1}9KhGTJ-#gCO@qE=${^@rWP3gP^yAIAkW&MdXeOW%FIT*9YTZ5@D_w9<; z2LZn-r`^uKLDMgnE%WCN(1#j`cB1HJ&)Kje^w3Aa4t#Eh(GT5NoWZm78n))NeqRXQ zICxIdn9znLT3>|&r!TVTgwrIs+6O}-oLI~P?g4ao4kN>Tp-+4~Yisaj3yOO-66@B?hsQDQ^x88Jf9uU*hp(GZ;)ph_U=0-&~;)26tTmi`N9ugDY}UA85aclj!bp1NGft?0fydc|89v+}B6#6WMG~O)$xLMoahSQ#VU^M=S#I zP%`v#i=YonW`MhuHFFM}Oe*(IgT@MV(Co0IiFGxQ^Erm{%nD=#*w z`_YH=`>-%Sn9b+Dg)=cTZxb6;dzoA&)x%!D z0_Y=huU3!!@M&fSTh%+5XN{hKY-W4eNN1vNl3(zTwN<%0n9@u~VGCQsf{QFTe|RMJ zJ2yq>JuU*z^_>pSos!w6&S;YFz825b_hUwXuF`@>x1h(1R_MQaBC(ZukYK!p)#$p@ z%#bFSQDq=}*yu;Y9CT1?uqRVi<-MdeI{0$#bzvOOijUE-mCo~-b@rs9J{2>T?-oCG zccIO<{h|Br{cP5zFpB(f9QqVRl^fanQbEx@&=LNF>ks^?C0Gu_?)kG^?!vR3uZQyn z%@PLvF~w=2y3!8OaRU#Urxk?SD|)jDdmSm;aylL;H-Zagp(M8_7F?%oW$8^3^hW(8 zboSI1TzRgqf;(`7yfv9eu!Q1Xt6TA>oT0BPI3FjN~%d7jEm2= z!8X|l+S#ierajrjltXhEewUpRgWe;f*q)FIG8h2y!&9ZWUgq^W<$d-cYseP_aN|YSCP9ePIAj)0}czsFAMPIWOK=v zNPk+IFabxm-G)EYCsSSD6qL{8|CjoSv{)e*`W&CiBs_o8_4F-JICoJv|3yM`nm@w7 zzGq`C_g${%cT5*m*(L)kx}r5w>i0~rlTfj*J%0V2#m;VuA-#hs_;JODat+IBzMrfC zn};(n-FgD;PCWwa=NYk=fqwK~&t}-tT@Cuh691BX1=Gk}R;=Sp&pDgLvwOLC(t%8k{GzgPy`#oZ#eLeXUZJK<=1EXAyk1LJ#3SnkS6 z^sC}1OnS-$_ucyBcCbLoC)XLt`vS+iVeRxfafg!?t#9m$FKm?Iy$k1rXpiBJk8IY& z{m!4}1)%!O9%6hn&z8IkL0g9;*xDzOHXMlr(|T+6^ww267&{O<)~tgay?CcAuu?j! ztBXUZOSBx`(GL^v@$KQ?!OGa6Xb0ndc~jtLYfSC6o6$+`jp`)nIlSyYN4hV>p^?`E zn18dF(tJwb#8G)se&AJd=YFEtW&JROXPYf7xr0U$%A$;kJL$f_R$@Zvi_s{`c7uK{ z*-V!+7&G~PRnD^qJUu2hE`vu!Bee*)_4$z*w9Wn}rN3{K`p3w5Jh?21}< zk)@uTZH&WA0+kLJg_bN^Lm-v>4%oUx0Wu;4diYHlH@ViceQo} zF7yhwq#(ZYcm8vZg~mCNs@_yI4cRM>n(IQ+*iqJS|wTJCwc}hCz+XR-OYarGm!_Skfz1SQO|_@4oiLK^B_Kk>A-_>#3lEN{x_w z)tb_ubI0Y#i!AsP(aZ$S*V6t^yj{vW(ajU_Xmlv7dsa+&(IucgDTJlVRnZzZHGKZ` z9F$Jv-|?b9;M7~WG>e}f7TT!cEvuza$+X8` zf+|+X9EFN#ADZlIgI{(#vIokx^kauJUi;i8wAY$ZXn6qIA3ViwR@YHea6Qb`(Sb#N zL+G<=ymU{#`%69*b~i!?8%x&pqAe}o{!Kc=7gY$9Yu67wz8zxk?zvN#zQxlTs-Z_J8UvO>WE~&ojm^ zqAJ@w(30LS(#2?v0idiYp~L)+?^9D2`qxVH)pXW8@zvfj_`=4r9HjF#EDksvX z1xH|GzA-bn=}*DF&5)}w0Gv5bBPfOUOmF5gwt@3J{|>|%@nvEh?=NqhYl2-?1%eVz zq#JpYksaY&xMUm3jh}$g`DKzP@x7`4z^*Xq)pIuRQz2#4b;Zh;&g^ob2N}6ugZo_^ zz;YvZk(7J|{oCm*RpLZvpZ3S_oN=PQA@5**8jj5q=Rs?zH}ywkgO*@ z{I*sY@WzD}>jHcZFJ{+2o}t9lZkX-)RGe)eMJY*-z;4+(aJ?BoS$8;>X=O5V9nGEB zgSF7G?2?V+E2NouqovvM)RGzGI%Y18m=ng@_l>6}?iZ-L_+0ohAcpK82SdLL3t6*& z6)kw7gird7f#@)O(qDQ^dJf+c<3-W;WpG?toj5+0e@-mrrL$cN1$yH%5^EM@GyP+B zlxiOJw*w(QOv3WMS5m@3{_m%zK>8+oYIeH_T|@Gj zm(fJZozWXrHinBUc!#%DT^^wcU`4VwX(n3WneDsShg5$4S3;btwn4HKt?8+HFpl7U zwYO>KNwVi8EcmD(j;pGsyidwF#jGD{L)-0BR z6Uy1_O1mSy`(-Gd?IjaT=tHSF>iil6^LFtUvlYRZ&v)0?|CE!`gF>j!h!GaTOgiEA z3fgro*;(#0n)CM!T)(FPw+;wo6sw5yX4JFW&z-36y>V#ba7t{cv>+>M8|=8^4uAN& zeBs7uwD#D*JbzrG^liluoRtT*b6siJ=%J@Ec1 z#QTNN{=^ZO*FBlZy>q4GspIj1$}-^>->+aq2*}wjV^*`m>3rx)l>gY5?Mb~!Kf@{^ zE%F^`oQa@*!3V+HU>ncw^8WSgYtlPVqlNx-po#Zo_&m?zJxA>mS~&G@t+12#<4RG2 z^)|)qE8kc2FrSD~=IP=Z&YM~+2Vky~#T334(xsbSaa>_ZxfS0x#$37yZt({ptU^jm_(Fo-)jOVSC0};Z8v?b>To)-O0mQLLE`p>&m$H{dHmcP#zYVrHi&9 z7g?DR=ltBT$L-+<#HFXWr;oqS9!U;>tUl+dY3NA^DF|gE?`n-)tAs}T&p~dv3vDd; z3F|&7myYLmH!rzkeZJumxYUc^jlQ=){IG=0d}%>Z+zHiEvqDgx+J-ZR^pu{%Q|UZC z@;M1v9)HAp8rSIZn||2H-hkoINYaaX2)*WPW)~_sBWRHf)`hzXw*T_jsY+P4>oDZ= zuIno$OQ~<7$3Y7^t!9HBvmOfJoVS@{=qH`$%OdKCT`Gevm$hMK@DN(PW1=*>QlfQ| zjJW$rIoOKXc5@(a-42+!#}0PM@?H$jK>p*F8wlQ1PiFXby{6b|V?iTcTH^6;OCgba z1VRr)U{XmGJ6KsyUFMa;)W{TY;T=Ft1@3B#Dr9vv+(A6F27VgO5Kq3cB^%FoFlqc; z2=WV{r#?e5G&Ga#Z*ZiK5B0J3iy(Q-uZYt5oiXV0?aa zIKF>701Ei|-*o^=8Hr^Lwv?D1j@hSc%Abw7Mzy|YK}~fw&bl~(ns^Vx?UE7qP52Yg zby!uc24D4UY5v_e@b_^pJAU7V*01T02O>qWcB>h6kJd!f*S6pm#yzC}-GqM(^B4sevg-dCqW;^- zn4cesuLt95iM4pOAAcV8;?KU&`S9Sj4-L%m#X0Q>tg?=K0KmS1-voX00Q^x zQ}WFmDZ`w}`;k8H-N+AU6u0aO<9XxZxZw9_a5*cXvC29a_~btp!*@77z3kEX*{||J ze4jb^nhweY;E*nLQ1+^XQqyzb z+AIaJkoOAvbh!@SK8LbgewBJK=M|)BF=0-3J#3r*Rrtrb{fqYGducSj372K>>`bZu zS5w@PsSeLGC8YE{NSZ|~Hn~7?2FKy1O`P!e_8i*u;{}X;XwAOVPbQgGIaD1u8j^T6 za^Nj_4B1l88hC$g=gZM}qHn&acF}^4Cs?B6R(CMFX-`|mMBwuF^=!$E3i>3U505(Y zAfm#RJ{4?)E&VdtkqX|U>{$oh2fivBxxtV3k7Q8s(s2l!7eMui8d$V>HH*D0q4^p* zsJk>?DA1aWtzBZ^mo3jM8BM0YoMn1xsoge;b2SxkkcGB{ICEbsEnkF590NIjkt&hhS^wlW6(2^AuhE%3YEF!FmuIu z`Zn+|->rqQ)d|ZeRpS&~>^cp$I=Rr@u+N~mUb!@g`)JnP=#L?PR>7JBKBOLFhJFc4 znU9Mj8Ou9yhf%8V;b|KdWp$VG$@P1c(!;HXVUp)x@vg%%TKDTD4025eKbvq0!zS3U zfx8Sgc~I%bACRErD%?>9TK+>G<+kL&kM#HMyUp4a0Tt(Htvw&CZFgo4o_|QU@3i40JED4<0edVNr*@ zsHD&suYDUTR?F~wR109&iAkU`%8{BbPQncbC$ke5d)od@Xoat{^We@+C(g=V3j>Z9 zvVKn9)N<_-oSV_)2`Z5OL~XhSb=`Qw-sWs-tdy-6^8A*kiFvU5LpXX=b%;#?r+71RJZDun7M1FXBJ{<)3$i1zUJt<=z2l{;+m?AUQ|;f#g-UMKk^!T=h;K z|Lhq6dg}$cE;B-U_DN$uvHfE=QSFu+jZ=$3^I@Ao=Xx}~87jcnKN7a#Y$6?A znhTGwjE1UF4rEty7ABSFvz5Pm$yMVg98>TYbKR`yctua#oefZQ)|-B$8DnbVE_U#T zKds32#m~1hBr7><;_@lp`Ese}%!Tt*^=uz(Q|>E%OHHJU6LZ0%<{ZSY2%y{tJo{7; z%1)vi&HwZPY@byN@^yOXTK!QNEtkbKn;q%6`e>Z2B**UeH6b5WW2~CTvoxIB*-JGL zEgJW;?38kPqQ4*NK2H`*l)~xm^;$5SIhH+(cBD$f*I+b71=1z~{h1|)azE;sx3V40 zexi$B=TC?+rq(3tTH;-GFX)JMq8xrdUa%*PP3@?lkLwP?yJ`6_nY-Tdoz{U$cqX%{ z4WLTxN+`VkqHM|V5HdO=gWF6_!q)x)l%cJTYP6a=$oRcpgBD)hFkPs;HVI7vCc?FC zYnW)2L7h7aaOMrp4Hd83U7lQ?HXqZ9sdSA3iu$meWde6lo5=y%r?owp8_X2=iR zcjtHdt|(rUWvjd;q; zG_`%_o;XVz_Kx2d>-G2pmv;KYD_@}dQ{=FISPmOEh5KtZn@RKG)ve|<=ZPt!eYa1i?9JCt?pn>~A{066heRU!0vE7GmT3&*@g6U#JK7U{S@e+Fd zo(oIH1(1q`IvQ$bGJhQx+MzNQm&%aj!+M|rv$<27F2d5t3ACVKA%+$^u#$RypUas* z8r5=`w}yZlNg-&wW&P7tARG96hKbFVw^Q2oc@m40W;;sv-x|t zzfa{RIK9z?xOcXssP+;b#~))j!;9MG)v$7Dg{XbPjP5!NLA`snQ2ob`rX2IZCz-q0 zU?&qAoau^X&k7|E>U-0)jN5`ZtCdA9PNd_O*>I^&o+)rPd-u#zSXk}^0a*cbT=yIN z%cW>?29e#PzEZEmojcaF`iln6&RGcEd5=t6(-o`F%wr)1#x#96_rVpc74$oKRzZF! zBuh$I`k_Rc5s(cxbTY*W0X0;5(hLW8{Q|)^f~8KSbiK9gwXqY$T5+~O)ft=B{COmD zFIAX$20~N(s6^QlH#1xIWtubXw+=^#Reyx#z2Yb+*F-wEv#%x6lNs4idFhTYp+TR@ z$7V=#hOcFUh_UamtbykYRc+`*a1T_p?+5k|fjk1W@Z-XREN!$eJrmur+N+lsqb<<+ z+rB6pl?<9AC)1o9BT%;!*v++x^wBmOs`iYAr`$cX&HR*fZm0SC(%zs?VD9QCK2+j6 z;f;M!t#h+zb@>U!td+Wy%L&_X0SUGT}ge+XiSfj zX8~QpX_Zqj%E?LK$POU=+5VWcD~r9pdx1uc+zDsi#R;haE_N9cSJ4o4Ioto%&!msO zx25}&1@ew0H@p=(l~q9V2GHE!z0k?~CNt@2$65L#@XF>B;!VyhZ3{I+gBPA~{gX3= zHil#3#*HjfqmowAUQqKr3BGIG=3lU5CQXk6Fywq_=;yU z;+KDgf47?t_0^Lj}oOGxTW~1QDHUnD&S;!o&dFH@+XEt7fz>-xZ%+9uCJj zW4FV{7KCbbCyG31iy#fVT_)U%UNXHWO7;)j$P9;1+xcjI7hvUG?((!r<5}9 zZiUquf5pS2IS=7@HhdqE4kLv)8hec2O<&*6zM64QALrV&uW%K%o#DN(C-U6cd>jfn zuME!_;*nhrtT|yky|`t7$B*9@G`^aX`ENH&RyfU`Eg3>x>g}XEljd8eXhX#iw0~pG zIyxLE@4!=dV`&eM8iAa-n_gy04r^1lqY+`lahz^{(Wj>c`Q;elWVI!bqUb`Ov?k)Q z4YBM=zh1VPt9kDDS{_UWXS&^e3H18Rt>nCSZ<$pLKQB%fXRhVBg58hc^sc#}*E^6_ ziv2NVM<)Bq`$V&+jKlr@Zj#S+Ks$O^O6U2Z@qu(cemX9D1T1jt6|z>_COwCLv5Tbr zUTL8FDV~{6@Fnf$Vo-j5Q7D}+(A=~;(sQ`|R)3nbMHSDE9K^OTQ~L3Pa~JQcz|~d> z-Iq0&?!XW5Ue)`G2)-Y?Ri3I?ON9!%U~}X=%o{t2zMNVQ1slh+@tpCyIPxqkaZurT z2|Loi@(_maI>zd6#nASJoOwI(j+n)>*+&m)qJ6tNtPc$*SG_W*hz&pyDBKtezp7i{^lfu^1+#8kv@5cv`t==bCFd&7!zh+O>O|m$4`DvRROM5!&G91(U zodr9YX*4)L0^96^*to*!^y<$_+_0uU2y>^CYVByaH)}at$Dc=GiTj{><{jZwi$1^8 z-zA;rK9hoJ?c&c6u69T4dxH1n2X(<(PbHXJ0JLV^Q0!)MkkKJO8f4~%GJ3LN$UDyR z>h#8#`eg1!okFXA=t6osFqzy$+PP;R)E*iQqq)a(u*nH1{+iGB&GF+*k9Sb-=`S99 z<3wg%`(WQV57>G$kYbM+VdbfPtZ|zqEjKX6A+y#=CUXwV*vZjY>e>pQZj}<*t%HPy zzTyl1-SnjK4%EZm;cddMvHMw9Ef@M4 zq{|t?eOPr0-y@liLp|Lg&>ZGW4W41RhaF~J4qqg;Bn_V4pDH}{b+H@reIe%(%Gth~ zK7$lGZh)$}1=Bw4NXqk`fW=%DIIE6iyR8QvSaXvJKX}(kbvSA{=ZPnH&vBrV8_w81 z6&x?P&^O-m^7y@x9nQNYY}8>}8u0Eu zEU(Rkk?KKodvkxZ^G{-Te_2xK%|Tdb8!M#Wj>MzQ!4SA5nGGqLK$p_z;1U-FRynYi znyS;mVpKao-$^71PldJ*TUh0yaI$Q_2v<8LLW2j-1ZJw>@;;s{=@9R&l#aphsCMB; zwH3JpkH^ft#cb8DSQ_zW8Qv&3E!MiY(T_zcaM}0(D}S0u>&o^)g74~brvZ0qtAzv| zm2~m+)d2dru>)SK2Qc>&&a`-KAKdXfTqsQE@8vQBAUS6ZE1ku=yx3HrJ z`2kpzuMZ*IM{rz!5Gb3a@utr*I`nlP44h#hSJQjdkb=z;fi)me(;7r_g{pq1Lvy~*t4)@bg@?kq@J4! zWl-BavSkaT>8rr}TU4>blNG~`) zbMWiKkg}BbqvOY-n~Vc;^_Io{?)ENd71BTGc zJ66&iOQOYTN>Lujv%WTL?^{O->;Dik)E(ep7o>Sb-SGCj95!sT9qB#O#1+x~#Xb$D zw3z$TPq!q%*%dA{eOD;|oy4+^f+~8}I~APhcR@!-u1u;^A8jr5s` ze@pDym!KMiD!8u{Aj`ELeNaTB;;lAyCnBU_~(7IOAMjY zk5w^y-w>9<`6RCwX<_^AVIUbQ(DT_Q=-QISVog2hgJ(GQFS}K4w5OKdc5DFWUz~00 zK8aLUu7Uc!;F_P-*QeGaA>ZR61K z%M{pLI+0>ID`vVGX9s;6Pebc%arl5jNqd(Tyyv+~kn}5K29uVN@0)b^W23&JAMv>{Wx%RBF@GxFi2%VKEm45TSFZ$P;< znQdO;K>CY%Vn>%kn4?p2Ff!6N-2r@1A#acIO^62*$HZ4_#P+O#* zrbAG3`$0Biq9e^p<=mC7f6IB{oq~C%e$k6$xG*S|*g18WbQIZM+v{Yc@d1oqr$Ro@ zUaq}!7|OH?*e=feY))^30dM`pKh=)>JJ<_*YPiGe?>v)y%s@KZOI*3XUf&QkHP%U% zsYqz2raLAstA~n!a`H%82B$tKidfl5t3G~*DKhHl;~G!u&Q)ODJcrF}G^#4 z*B-Xn;e}9VKM*VO!f5Z%Rot<#iLK^rx0WYmaK#XWTHaIhTBwX!T%y+NwH5VzJOB$n z+!VIUSW|e-ID})xY_*;fy_X3>AKD{&&UGV06Iqz;et^Yk7jsA09XKYImn+m%lVIV+;Lg+Z!i5bx)r4m~BiE z2N7HL429;R$)q-PkaWi~=rtqteNQ2`WP<=l3n+6Dp}kiUvsWX^Skev0tgjKuXL85N zt3eq1`y$hh_M@?Pop845iE<)A;t zgUROFbtGRCA~csu<4$tBHZsFvb8a$FF1`&jTH^GsVunYXmR1c65C33;y*w zV-BpPs6D38(yc^PsHmc(##eCRXgmCsnL^D!FM^u=HfA}5yI(b)gS?@eu<@c3-;>B< z{;?DAiu)I4^Ig{ccqg`s`^`f&$71>PyTa@Y3)<%4gi}LKv(sWT{hYN0*13#<;fse* z3kT4KT0)4eeQts zd|-xioRT2If#)<#gK=2U6jnXEiZYXvLC0w&WOs9+iSF^RJpBwiax|2prxwGMtOa7Q z1j(YTQJPoDI}}LvBm3cmwoH~g-i73rj6mTKN@BSGWr)`Q=lS`TAnK_+6<3TPrhWYy zbzEKx`pXsYS4KRY>bC(JYZtM+y?*47a2iH_#M#5XmG5u6PSpn7fuJ`J_jZk-pkqm3 zG{%G}hD6d%1rhpf(S!#_?P%@FW=O0%#^P!NNyfe(?pMAhdOGmCfJK_Ptj!yCcLdTK zQ#ZU5w1-*Tx1?fz*XHxCSW=z(6ulzW3mcAVkLC5 z2_Uzc=O8mNi?v*Fr?<;xrStsiW1>rExQ9+*1*lqkbJr4K^xt{x(DLzAI{@(M>$QSn z0`G3*{t(i3mauL)=cs;bE$0J07xSyC=?CMDC$9Big z>_Qvclbi#_{RRIV&8@-N^ku*_~V-?2f5y@t$Xoi%45{DglzTgd{xm#E_Y`l@X9ly{JO?K8*oah>Ih_S;gu zkr#$)uLHxPSPB@`7kcu)ufn)W3cC9cepDxe#W#LFpY$K7j4NPO{CWL$Lkq0A?kB!r zQKYOh0IN^N!SVM&l;JfN!<;kNLkmapT55sj%eP8agg8^STL8X0`vCTjFQ-wX;~@Q} zqByc=Ek&O4>g!h%S4y1o>tMc0o_e&$Yl zw#nk`Dba%URdf7&q#xJ>B(r_DeCU^p9ezH{---4blZB2To#F5^n&v$2BV}jp8FzuU z4Q~dwXB&i__TcP_mDIL5txW zxUJ1QO^*6F=gKN}ZGRXg#kgZHon1opg?3zY|2zE4iqC$&j>i1d1DkW_MXP ztGe1#*6gqt%*)sS%;1uiSunMbvhx%fV?ka4id)_^`n zq=HB1GxoSHpJv`Q!^wdL%=42qCCvE(PL0aI5tbDHhI9Cn4>Gysj#Tl*6vtlqQ$DSg zy9s*w;rqBW*m7w)MQL`2z02&``u7zS*-{T9Y}SCsR7cX8o&keW3Ygm~U%Hm@092Ry ziQ8oy>4S3@9IxsIs%L_!{QW2#SC+vZ>2ZY#p4RDxXEuK-CmjxLUN}I4oCglVOb+5~QxA;(G>V5e1Di`X$a{gga zAB>4x%}$0}k%?|U>5e5~Q7D=^I)g$h_cedCr}Ixd(O|(ZF-Rtq664~)kMHM`&QGF) z5qvlQKoAb`Zcfc_Ih<JalAEstQ&(#SBsgbi)7O5g5&mV7iB)W zk>1Ydg6rV}>{~`LVf|$&7$KG~-ce2aw1(mhhe3Gwh9Bi@cnA+}`7$iv{WZ>Vzak$k ztU7LvhO$ah{-GlGD#l;4!m3rh*eZSwoWyhEeS?kRSrX6uD9M0x9?z84h;%!acfp$1 z3;jn;pefETzg41aYw zYg$(iFYjH>cE7Qp{mG+nTi|jb)}|e;{(gqZrERQgWD3QFtAX{mv*P2eH)+!J$8fIO z7dW&piYjtW!=Wx)SlKvtQcb@FFNQk{zMPrky5Tqc`F48XkP=GC z>z_b|Wia$K=M{wF@36`AF!Q|bOiQ;7#{X0Xi48L?XseeV=G|HhOJBK?gMlB0HpHZBWFtuEr#gu_!206okW{o#o@fiPRuau3hl^ohaWk;u|+dYMD-VL;oOE8wGN3$x7kC$Al{*!9^!X4S)$URe&oug^z-btIqR z{`z=q^8t1?-Rx% z-h=4X*d2E)z9hcN5@@rd3I-&(!Ya;+$+NQK{Qo_yC6aq#cH82UA0?85#n15M=#`H=R-MBvh*If|db6NoTdftVx3$oY{w+Zw&UmpL9uoYES@x0|2 zReaK(2(~r6L(vD&_Ub~me4Z1PuJgo|6+49)rtTEp=Y~*Wd7i0DifOCrd3f^bxftHH zn%w1hZfE-k$a4rJH@SOIZAk0I3!e$R)@hR@E7qLjzK=mxSpRzoWIdlo23_6? zH$*%BU8|r`c2^*#ItkX*I8xW4yWnbV0SlS!OGP7Y!}2y?alt@)>R9j-Hg$D@?A%~# ztkA{TdotMG-S(8rIjfo~TO^U&`JL%5cO2<(7h<$U`gRwfc7>9-qP>>lzt_Rw?Ea`T zJ)Fj?k2>}&S1(=F~~U8sRCk8#W68%vs6#B&jx z)f30(L+?%Y|9FFJ{qYLAHNyd##>NZZLt{uYBp>ddF=AW7eJNAHI(nsUCv zF|7tx-_waI#|^@m6$Rop6>};Xp@TQmTwvtfi4^7)gVP-MF$Mm&^Sj{!olj4}aLyvQ z!|!-AaX;&l%IB@-VQ7qbUG^>9kCN4z;hx-a*m^&hJeTpT!oW4mxSgm1`{UgCvxP^s zQE0ov9X6dwW;x;9S$4n={X)93M726n_~Z?u`)go6F|;is7J5BOXLgOQb|I5*(2fyd zw%zgqNQ3j*XT0!avv|jL)k~hiUfd+~;!Gib&rw*_R?OD>@$=Y7C+Q4Nb8)8=nm2?+ zFAlKMJH^CKod@GUvHa(=Dl+~w0Kc6ai24@(wCNM?)A4ioCH`I(@Z%TkIU6c${b_+L zqOWw95~S!z1xJk0F{2xESszT#tRk?n1K>_&H1%w36}-mmVh$=7DWppUbS_L2w%<8T zXFE;t-s)ub=%_DsS=SRA3myv2kplHd?Z>?pm)JReK5siW4l_3XCkp*6D0iQLbxOW4 z{9+0T-+IArLTaY=cujY!_}(_)zA}-QpV|uuWRSiU2BKx7ylI1Wi&YSMPvp}uv zc}(DZ#VNO)ad<|$AjfmIl_$>$3s0VBdsIruX5&eyZfg}&_FN^MZ7TSVGuAHT2hxo2 zCNN1zX0yIHQ|arUaOOgh&5I2_RMcUKqq`tG;cQ7-gC(dd^Get$#?#-}CShgX3bx9& zo~|6@IX9ja_yh*@XV401f3tE`0jD~ws6qIiM9J&rLOW9K(THud>i6Kh8MQNh+ZdI zv@ZAGwba3t6kk!CZ%+yCU!cO?1<*5?947F*hfM}s%-J&99^voB3FJ}tYbLZIx ze&=V%sD14ic8`4=_^TLC7&v_=_ zu`l~D!jziIhN1VWK|r3|4`oVtuPK8)S;**K^%w|JjTIV7uG1yA3V3gshRM4k=+u-$ zko-lTZROmpW7>^yPH8BlaaW!4)DGBe-@sf`ooLW$HB4+O5I?C|a@UMDF5l+{d7N)^ zJtzv(CvZ!^HzcbxY*W9k$=Da_7&T4>kr4z8b zB$)C&df}>$B(~p#=UrE8V&{X^!j-B>Obl^``G422@@4LHpvW7|y}Gio0dW)ii2InC*DJW52Yr8z$dzV>h&TFET_4 z6$joH#`m(J#JjqfH=u;=*^IPwojr!-Y!_QrxKrEWbHYz~?#2F9Ou7jtVg4+!ynaa) zJ?-8PKlt$(&fhUVzG#4Tvi@w(M=!eHz}cr$rwIMkEit^Nk93ABS2>W?N<;kP(~Vtt zHlB+2m}88$CaC>4nfeW@6*P)>v9D7vkm|;BFyhMwL9M-j%DWk$wp|i?yvu{Oh05Rz zn>*Z1&wXCs74d$-C3ec&feZ&2;?N!0Vh;ri`gX?}v+wzU)$=5>KlVmYYEWke_7#-t za2{e_6~Y6~ijVGp7h+Y0mad6GdT8|l>`WHGCI3)*@Jt&gTC8Rty1UXfyYcww%z9yC zYCATDzJtRVZA?73hU#?Q3F4PCVwcFP6sLXxaspn%GR-K;NX~)ay_;F;XfOKo?mGPA zV$Jx*voZR=A;vHt2E_8c!5A%!{_4y|HJXxluoh03e@FOsg};M2*+r)-WVuBPLJls2EuOBlK*16c(~8&| z-r?#sP6jvJzA6q(jiNPs?nAy#8qDDts<$ECu-o$tc4LGy%^B7o^?QJ1^>z=M?QMe2 zd}lEvFq+2a#$ZXZE9;SRg>sJ$gVM6zXi_(Y?3Zxv$eg+C`-Iz^(LE4@#yY@CEB@6} zFOhOo2Cd;8x4YeO{NlmPYc9X@>LZ6YKn?nH9>V`PIuC~&+bE2;RVXBp2GUTZXh^-! zxldbrPlQU@dwnWt$lg&1rL2`;k$eP0iw6lxvz6wziSKXk-%H0 zsquE!$-CZ_xXa!aQq545-0TMTH8xAuaL7Hb=gV$BgxTCfP?*2PU+b_9cxNbje*Ei!=hTCFz)Nu0YUM#E` z?t!C^n36X`*3fo23miRmCTTpmi<7r?#mnaDoW5=)4M?s)zwPJXcjZf7-lPeCcq)*Y zil3q4>RjxSZ-+5UchaZHPWV9YI}G#zEg$5HTRT0ZS&4Uby1GE#-3ua6({JaVh6_uLsE@8Mp1W}!b~mVlT^!;+ z<+mW=cZ>duWuLt(qsV^KLOye;8QwC{B>yEkLNUvEHSY2uajy^2_FMJ1_M;k%zMKy* z+XWBDn2Ton-#I1N63l{e9=1Y%mOFUVd>tgba^T;Kxp?r$AoAsO68-m<-BTD-eL;OR z7r8T#EO{V+iovl|SDpPiPOil2i#R=#as$2ZYQgF6Z^4mczTc~Mu<7+)dirrC?wct^ zwAD^?SzS&xt)Hr~K{D8S%y4hUMHeF_Ixci`GW$KnvZ%cU_qoT+tDm=EA~|GV&e+$8 zdFIw6r0)eYTFUKEGew8qZ6Wx`;thPxY2wzgtj(VtL&Y-fXKTZGZ{C1)o75^BzFH$Z zd+hS@!pmIyS!t_VWXo6jKsLLHijA>N%|u z1I`t}yAf|-!Gwia_A4FgR1eZP=3CfX*9Z!`UAeRAj9(okM%L^rhWIppR4UgbPkNo` zede1|GZ;sdJsxn!6=!0|1WPjgV*y=1=^A=-L*dj+bvQU!9q%{|g7f(=sBlp+8VY~F zMF9F&)fJbxU4{N!C)g`%jcJ;_V4ZoEK78PZHzul+IUBY35P8N(@tQ!I#>ar1qbIJ~ z=t07wR?rJ&wK!a3F#LWI1s5JTp_-8)7>SqA{w<7uzWfqUwY~hsLlx-HxV1G`d%&Kt z{$3^ggG)Lm7!S|^FI5gFJ_1f)bdF`F{0zu?rW^l0ybNbXEhVqkd(&e#Yw*wlIY`_g zOU&j(;4*1@F#W|k$e0f#`%ezI^}phhDdX5oE`ljnyJ&lvFYZzn6Y1pPX^0^{Ly2Ln z8WepIU{HY;+5hh(o%G2Si|)CIe2E`|L-F+&gc<2(wA?Bh*Y3=LTGm08GuRG~J}rad z!`bwFj2HI)`wb2A>-eot7~8~DiJX@617Fs4sQGd_Ikw<1onJW%m&ZDi^vm^vqFZu! zC(nWlpULu@qbqP__6ZQ1?oPwhqw%zCHsj>4f^F=k8T*ZgF~up=&6#O9{okPCgc;AB zV9ZZ_CDM8~0k|EWII?xR$cv~k-2zu8nu}(8U8E~2vis?M+e&)mYz0PWrNP8&FZqp( zIiJvf5t8InV5wCw7Oc4rr>1PD8~4n@nu#A^&*%~>%}uU&ic=|)(Dm>{ zvY&N1O)cbbn^`w}%uoVWJBl`GgGo$R294o*1{h2E1xK`J}OS`0@U0I8`q#1d%b3680athC7VTG0kik zVJ!t1)|CSK>JfD1GEbCqs}arig}-&lbnOOFmhcnRAELa%JJhX?r$j#%2Y3c1cTx%;0(l0Kyxa(;W# z=@RQoOgWnd-bGi0>a(LzX4^#=ar6pYV7uG`wl@y=$>%YT-{#^ku+=A&>wY|g{Ir)5 z&G2~E0jfE3GP$fMP3tF`;O)3+B*md`D*Vw&oBvh`;Syh-)I55;aQXSbY&eyzco5>gP;yBU%- zoUuX70CrfGP^RPu$g^LL}xo z2yPbJ;*RTjqT)yDbKD>@tDi%p?=4+F8d)1Ul4eoqkYD~}Qz#&S)HJ+xqGB}$1OfO!v;>9_@C;b>b0R!h%W~>r{y?Mu$Kx=@maYCkpqbp8I|r`Fb2&4L(FWOFY=QQBKfSFZyd=FGoqKKvtI1nXP~u3 z8D!5AoTw{Dmg$_KE47^QYM=r6`&gW}wKK!SH|(x`f!)MwmSTx~A{TCDN1MnX>#8Gn zAZ=a=e4p!xdDUCt*{?jR{oNCAVVG z+~jCNY;;cu7M$?JL&sgnrh*q>p1U2F98cvgX157fJ*vY6TaLrdY(?U9XaP!89t2@X z1f9QtWgq;7FiEPFdw*P)%z0DI4Rix-Wc=;M(W6N9!r|12{odi@7(e{k7&slw;rbgE zB;6^Ex`r`s#@cRfp2=G7$f9|;%;x|!T$n<$MlWD|uPH{sM zWhGKoSj=a|nW5+BG2{m8mioc_pm?@B={b9t9_y&Zc{3k#10HhU(=P1q8V3(mPtxy8 zqVVU2GcdbhkWlW4KdzDg4fSU6G*Z(QPsolSD+;4Ii4nnMbkhvDdnJ}CF}~30y{y|P zS%Q{VUc>1DPq`ZvoiP7&IGU|D0i(}{Y3R==+;{s7v~Tq1LO(g#{7ooDy_Z4OpZEEq z+3X*X7wASETOv?qkT!`pBo6740<2!4N#yE2(s6PkZ#JLgSKM;NEcXbmU}y$4 zNvK5KxrYGXUlB@eVIKa3Gq8zev5uYd#g^$;;mZuBvFvfhYlGjzfM3NoawfT4ECo45 z+vvML-gxNdG;(O=5E^pG0+(x>lEODyP`xY++k<08dw8aKHM(Y`z#OAJT%W~q{I%pB z9NTG3pSHN6RqO}2sNcbDXIX}`8yGK+&G48{HrVZ`Et=tn*Um&6aWlpW@PW;7F?dRH zAD7~P6g&)?%k0zIgZlTr( zXW-mCR;th$#kHirCaSV8;FL-)?Ws#--M&Y-FF_@|mPHHhaZHD6dGBFjZwP|;0k|`K zFTF99Y0f6s;Q2g1t}D_DGxNWIonbL77W2bo*8jQ-aLq*I5ukYE^OBjeJ$PY;W-pns3vcW$i zFAW5FHl;!0Zvv=|uGc)EuNnG^QHUBo}*}^z|8xn==OH*RtJvy^LsX&%I-V z_kAXi4wGNP-_2&oRZb-_Q)1v>`%;wRd^u?+JL(@+kI#1;fVRkOkiN$ewW2n{9+iCB zZRLgI49ei7ofmI8-W~_nK7*!xPB4x2QI=(lBn^qFbjuN2=6jhy4sP2gFgfUiEkbK@ zp!qTI4oMhsYz;ShdyBAqbsgqt?1!QNMKUfc1g&=Ogl(Q-w5iGq4UU(=eA_l|>S@M$ zd0xq#mpDNyS%%s^SCJI`7)tHj&9F&Rh2+Yr!tvG2FEnHZd8=@eUaYUd-*$OiiP=)_ z<(&EGlC}%B1{uMDJdO=6Es`ZOVKwKyVm9%tFoXB&w$gv>v++aKo(LaF&^wj& z=)(5HmOD zOXXLEL@OG%-8=zfm99e7`Pn$hz1-8l* z^&2oq^&prymw~esyIcKN3A=j7RQl_)G5xOtjx1aYo*h1j8ySPhI+`{!c67$1F~t0P z6qix_npmD;@0%a5=vt$AOtf0c)!r)LThrRGVCPX7vHBAn_neC_%Xff{H2eCC=Heoi z8px~)RdRv)c(%Y;=h4_3bdt+XJWB+mn`tWi)zdE&4q?zzy6w!;_p*=ExAnw=SVc z?E85B-ceZCw1>a)q7hF&nM{@~`Uz*e{7~(2pJ;|_TG?US(LqG6-clf3=ZNX!SXXsq z14NZZqJ!rg5^>y(PENUo|0NyZ8dl4b*guO=?!tI5ys)0>=h2u}dKBE=z2cT{2i#qL zMx>Juug}AMwYKDKa5OEdn2CF=#6-ODwS5GuZmF|QkaW6Ck7YR(eaOnAJ;EUGaGav4 z4iD95Q1|#~>vgI2Uyz~iI11ofl<_c`f0WkZf$+ax-d$tlu>jTYDY1nKu3=pLOeGN{YIbPwU!XUY`aD)Bh>l z_Ra#=|C>sp^tQsJl%=ROX&e`)WJeXpHJ}yCb`9%d?SzjU(Jgryy!6PY7UzOccTPE2 z9}nW!MKE8D*8`D$qQ2N46DKK&x|NSq*y1CzaiST%kMWa>_5ryQ$~v6>ZNr0gX58q} zEy5)Y&FJdC1ISw?X4##Ozrqs1z+@q9VmS-D!G*9ovyJOh)+KRGW!yl|@{rkX*vptj z`q~QgxRDu_gp4HHS#I2@g~ON=CL)iDb8#KowI_1tla_Pmx6i|OO$nmiTWY%pu4%{v zR}EFhm9R#MrT1W#({1Xv$_ph~kM^iXW&A47+4x}TbP~)oG`Q!7opYRt(c@%h-DH1e zR3hi=avA0^f1~9AIXHSDjS9_UP%H2VT+NXc?(AyCiJ?=8thg?@5yEnXD(_&$lsJ0b z#vQFvhLX2Zv0RLHFgdhw8k{&0OJ`NN;+4Y;KOq!A*@p)|ZF*u&mZ=SX<~q4FZF4ONTPi>HEU@UJ&5o zb*f~tLYE8v`LF|iVI3b~GE!9bo*5b`O(Aub zf>hP!m=2(?wKLCG!gAkn;sYZ|c(8-F!`(rzPKy4Vv>9e)Y#`473Z&g^qI zSCUMttD%{>jyQaU7K!3BdGjfzs2*!T%<^3!%pnHb#!u!9jFl-%u;TcPBv@fn4l`VW zP<&W9B=@OR-mW1iX?z#P4_*i1%&+3Ja0HooCx%LS*y8YKn&jiGZCp;nYm&h|5oswq z4YuLYv!>juXC?fYPc=ABF#)DFJO}C7bI|K`9Q+O0O;cI_b>Gk{AQm}?Gw=36ht+Rj z$b?b|eeQ>oT1ODw%31Wob8k%BKbd^;_{{~2TjGAkp&czKq!B~v@MCBqSM8w&VM<+0 z4@luQT4mAm)5`Gk(++qfW=(7Fwz4}ZyX}s<4t|^sR`=b5U*YGdSXdBBOk=mmo7()P z*l^5wIg@A?9fL$x{5<2Eok&ZWQB{L;ViULl-gxS7XKdai2S;9)&_u~HG(O(}d&jl% zwyq7hx^)tvi@wA6F@E@^@hv1=IYE`rvY%6#LBw9mN}&438JCRHAy1w+!wDlFjC$xu zH2tjTjBT|zRxXkID<($<)kb2=Q#Batxt4xia|cVDf5Q|*8~D8&P!O6Sn&E$RE@M~; zlAHhjqZToa*!NwQ6i7?}BNaqHqE6%m>2&Q+2Mll)kXuJvg|FQsQ1ZoCxKd<6Q~a)B zY3gejxOFBA>`_(mJV;08P@Swi96HB_{0Pye`=af!Fm(`#koSUTIf3}d&X~l^JVwXr zT40vVRI;wVMDVM$mst0E3$nec=^G6p_Fr8DAuGJ7#s*iMxZpe-|C2%!J}^zpsT<1I zTJY~`1gLW754@eR5f1wLU_|>Q5Zrox zC5ym4=rw=ApUo@P7vQh*1rENMgZ@v7VOz!y8ZYaLD&yqH@aI*K+3SVwg?c14g3x;_ zP0&nRkGw4F;`(xzqfGRD!I}10+8@<{a*MV>!l0QTUuB3dp4f_Z?@b{EXu+7Gaqh-6 z%)H;0nO>>SMqGT8ACG1ax!U@Z<{m(r?a*#b$ zY^uW-8`pxVQzDF9G7CN5FM#7U`IMewS;GE8aNH8i*FCetW9D~7H%+$-ez;@5A{n&l z7~SE<{Ovc@$-evh1k;!|rr&Zpk%n8am~l&(X;X_nM^?kfRV=$Qavp|l zhyp${jQX)`;8@p7qKwbsA|29lx=?h}+`Z5nS>YW~-9DUdW4DH#6GpPubv3YF3m6wU zjj+r+-F+q=OPl)y3vXy}7jov~UYi&Qi8Z9pS#}2Am4QSFg9MLbY-(}~M()2&Z?aoV z!FvT_kY34uxNeQ(Zj2?%1AM{m<^s%|?M*62ouo&$*WlAYV~)FZ34HBcP&T@stFBIC z9KSM5tZakG>Gr~&*=)A+#Jpc}KtZK>e6FntR;^m43()sryk}bXN#TRGJR0 zF7fosJ$H1=MZ(odQj^STtk`M9WXhu7t^e7o(E_}-AI&)}aI+|E*sh~n1XKZ6R)84Vi`B8lXlHI>F3_QXB6JHe;=A(wTY;EE10vQDO!(tHP;UZF|6Z=T_WpH0x{ zlpc9x>k12J#h^lFk6>VK>ke*0`N~c3<9j*$JQ0Xhegz=AK&`Sz!5aI<+=SN$)ck;nVlC(62dlLPc%#D8l`XR6AEu#ed+x%Y8Ho1tGk!iq(mK)%7 zTrXIz3PwprEpE`XNBh|)!`&b*A5y)8)ctN*AD^QHKG>WBW{svx%j@l6T) z`km6LrySExy={qK!$VX+8E2-_( z^y#7m)=i)c$2^tjf7~^UZn^`>PpaS9DE!63I@F5C$F=Pu(0ny zZ>@(}i+nKo2g{!*Y@o5ptc!EZ6k>X04`=v*WrEH)2<&%NQD?&hT6toBR@b~)Es=z?t?v^J7~_!K>XVK9O}YqtpZJ4@J^#NnJQDo?)pBsX1*>-(Xghi zjK3N=Uxzp)cXOAntilJLiv$KSarBjL19IaRz*9p5P%SaUq1!D*8J}d0B9v`ZAX)v> zsE)Tgrd;oUjT+;iVKL%}RV;t8n9XwuroBsO5O-}c{wDM4^B1R*=&A&W*t`NCjEfM| zZ*-u>r|K}kHUzXLCBor_v#@(g0N57i(^cKUc-}o1Cguh6&l>IV^_?4_`q>Gr*ZJb( zj=>@=CDL{lN|ib4HMK^+i}X z<3E_!wv3w0Ux*c_OQ6EPi*u1+{({w)xzj3Xw7lOB{T>V<5pR@ek(UKVT^cT$=MU`> zzeE_5TZX6Tu+P`A`+A)~1vhY;AI!%I%T~k5R6{EG5{jFOia;`04>tSR;B%7}_*HP5 zdgXgF?xH;T$CvX#_dIdo=ZS>B7!Fqy{P9n?9T`-gOpng1!590g1l^Y|!FHyt&EQ^g zc1*XK_kv}_)?b6krS?MKBX!u5u154jHAxJc4>?Iapf@3ru|VCi;?p3}9v+fBmmK+S z2%Fci@7*ZY5iB$#!O+h?4XDA@+p7c}1Nm5s2)vRe0o!|$>G9t!_-FKENVUDpO;d2T zIsW}LniU3F4`&^$mTw*dlsnVig0FX9DG`H8AiVjrm;~jXmzt4 zJ~z(iivE}rO_h(_08`~T+ut06#*x};8G4}842>V_k~GQj?BC;$N$=eS)^GOG#rx_o zaastB+Odxtdub6C3(6tz#T4q{8_v3ZKER1NAGnrog43_`gR*WdJ*VV|YwXp@Ael^l zI_qvWd#}s92kx+~awWF;MhZ$96C)~zx**FthZ;v1b)3$Iom%Sz(Q|>|T_*Yb6d;+@5ZxKX|D&m!6Z?JpB z5(u34nE~+^VO08mK*SDH*BSHh5}yyle+O|b#2bgcdkh1xBozPQ?HhDZKvJw;@ z9o8%QM1y48H$ne@Hn@*Aist#y!5+A4jtu!*rp~(rS!3JBQAFxm9LPQMM(4GJXj-qL zQETf_Z1W(&{mHS=>gIyqZ?|(FCzjGVEoC@=EQO+Ht$d7C6Bc``k$ne#!kK^wfnxNW~RYTzmBLp<}6BeR@m(zFM)*vGxH>a>s}G962B zVa_-1?fMPW_f#vUs@w&OLIJEB!hRPU9)>Z;yC_{Y8(%-^g5kV66~+m$9lk*Fi_!3) z5V1&a6bW6OPA8=aaN8Hg{8?Wk3{ZQB69XSw4Sl|q^wlrMYVHdcxzvg(O=LQJWg|RV zxDzCXJKznERCw_vhuX+{W5TQZkm^;(e^;}|#G(Hf$H^1SRan;Pm7ZuPm!8VuFyF~! zf={I&@qru~?pL=Q@Tk~k3GwA%gxBA_=<;bbXngP*?0?JNaoz6hUd(O>dB^D1ZA{nF zx(gc(%=z_XcHV{Yrl%}(kKY!W zmer$*t1~FP8AjTbBe8w-Qdm>8ly-&bkhw}1MH&3sGRA6FmnQ$(73e!VD?DM#`l&NC zfLW;V`o<|DZT#HNI(+2NWm($3oXeiY?xfQfLhuVidMBU(r6-RW@C`zS&<6cSG{6k` zJMUInpG4i0UZT;OS3KEDggiK?viyJ#fFl z<%yr9s!ru76H^5(Dh|T_>{=|HJ&O3GXplXxd{IC10mPPWrE1Ddw_&{r-8;5&S?fYb z^Ww=c@mU;|VOiHXcc&4t>|Z=GT{O(`9XET-Q7Zp{qL@Jq^qHLD-i&p&Iq7&Df8+*P z|32=6RvsN7@yUhmW7(NYqkqGO&#WDzT#3{Q*-pL#@mz}`iHkhMGXerm=w50$ zO79E}aph6E6yfiM8ewzPb}5YQ8z? zk$uAr^lygWW**u$4dU22h^|nw!r~{BNb6c{F!N?NT($LR|x$zhgcf`{4ze3)yq784a@fPXfO8wzj z|8)_x3J=gjEE^s*D;pM6261k?eOPlt2h2EH0u7Auo{~F=>{((@XYT~;Z&V_)OS-t! zE=x=;m_!236;eqd)9qKju)J-l3I5~NvFOt&PUF}Mnp|0q8$MQn&1M_AwTLkmaz~Su zUA55KZG*uU4Ioy2jz;eG!u9WDh|y6^{-zYcjd~-A!Q`#*FW&=QVysB;L3YzLXvJe$ zZ!G_dPJozd7fe`wgHza5N{9EBp~u)N(CcsI7ggQBH_4hrt3izXkn}^ND-W30=mb?! zo`qWrFIaLY_zD1z4|QMv^|o&=%IYeEQ&Lc<4F?K+PIc>y*i& z>U5edWNgfh_QY*dmoT&SA-=c#ZCT|SM~tGEpkv8WI#{;iljfW7J^lbV`a0l| z@D$*tT%!M2ztwq}4hV|7#y7Kk!RQzLpuWljhVKo)@1t~yp=K&=wnLn?pZS^ndBL(@ zav1fbt7?E@o86g+{^_4Mt2ZO5{;3-DldFRJvnpWScz2ZFmIAw#j?sOLGBop38<qtaQnZv(B02iWZD6EDNBnS7`B-z?g>O6S0s;>&TyyG+|m28zR+7Bq&*vxFgX4z z*RF7$f9v`LEic~%@RKI_HS;l>I}75SyXd{=v#~e+A$)&z%}UzE2{oht04P>~Yn>M+ zAJQZ}-9W!qnc{@a<4O3B5-(StMZ8U?)8Xvv zAJ^W(a`&3xRKRivC7)n`TYGhwJ1(zdJLDZnev97>_8!q9D_pj~qCZP9>aMlWA>5As zWDJLmozq~*p9GM6It#T2TZ7Z!0xBstoBcm$h<5VeM=m%xxfw#gdBES(w)kqnH>k4S zL!WJ&gZw33@#&y`0I}HklE0SGW;V6N# z!RqWHdQ_(q`=MsM|VC?rGNDiG!gUqkt;jhCN_;= zy&GOUD^9ZJ7V~0;ERP>MoLm{|1)G`Q?0&EXQByoXixcY5d_jg#KACCbEbI49Sk4XP zHkMqM526sVICXQ-;Vtq8M@9E$Ct(@TIJfdo* z50D&Budz&xan)2(VEl`Ze^Q5ob25ZKS%2p}qeYCfbesF2b(9Xxzk=>F%Av9A3^#tf zvrYA(WQ2?$YsX4IoECN$2C|&*Z(6e(@fR30w1cZ30_c)8jL1E%puw@$=yz)}DV90R zr_FcAKhgTat1K_Da}tk69+RPGOO5dQwnup7=WU1((<2&oA-Fm+6O3HvP`SCT*sFXU zEcY$oBEOoGZE-!^kxdD7S%5p{|5g*R$IDpPlAiTAa&MOgye#s^Nq)w{!=v`m`>a#r zgR(JXeqlX^A0lx}QZ`()oI-E3dEuX!n~;3<5jU4{pXSW@1m`!_(#0c#QT~ZGah+Yr zE9cHYkI@s!2XRl39i51~+Jl5o4b-TdX*~wUnZO$7Qi$GNgkwKTkufK?R(cp#;C(3z z@{4;5Z*Kcwn!hyJ6cm|wX{Smk^c`g(eAEaRiyxFJl7MN!jL#>S$CR9lhy^ppu>;&t`zCD~Y-R|Z( z&8<*dpi4UM6jE>Z7Q7)fjBk820pzKw>1LtN3V`T`eOS4!o5Sg!EtMQEMZ#*@qdyzu81$U3n5{<2aknY?e@`V4*$iwyZ24wk>DEccj5YwMXlU>uM!c}S3`_MFuly6C=FxWQxsnS3slUT(5v{zjJbx?Cp6ZAk+c6Zgyxsm;1Gj+2n(!$i;Tyjvhg6uH>c7)nI1TMStCqWH|Gz#b2w>GFANLa z2tq$!lwPSpzMR=WH|x4FPl5?qviKM`rq3ONLJEWlNkY0wavM7J-r>$zp5?deG~tKe zB~Zd{;%nm~@xaAQAd>s3)%{?6BDe#~JL|0Oux=o;%irO`$8z}ZMgTTRjVH@&?C6yn zrs&(PL4t+d+;!>2xb13#P$nyit_oqZrBRJ}P4!^TXG8oxTLTvBKBuJ}g_zC%1*cup z=msS5~7q^ZxBxt;%0@HpgAe`#Rt)G(NTz<$p8@ z2kx6{>9r_5O$~5O0vyz5ck_Q{kZD^$-;XH5QpJBzSXszZ88^YlX+Q`*IC&3zy^^Q`dpmsa{|lcxw{VWE z*ClYWj%W|Rd(syFyKO);cl_XMKh$Gwf&o8eL^n(^j>I3U%DD6Y9ic1puHp>V)x4-M zlPj6%Y!mThA8t4tWF4yJiy6Wem_}S_9J?iTFMkWOCGK&xO987UDUbtWE9vL@PF&K0jNaMBxlKx>vO}0}d8;Y`eK~4B&jh{F)k)0?4KPg)#Y1*A!v23p z=vkdwdBx>)7Gm7r46s%;pzo)8;+xNnp!w|qXUE=v1?um>F}0SyV*F3>KcmQ7 zzq95a#;wvqeRABRu z=_GvhTL`)DkH@s7NYdvmRAq%D?qWLm-K_20=zurm?8O$*PJS;x5%uT45N@<6;pIEJ zaPo8$xDg~p=>AB28}9|@JPy$t1<`1bQwTq{ZQzba`(n)4R=6oBg|8h1U*sC4qG;Q?7x+W*8m!sj1=3NBNwVkQ+}4qzAB)hS@qahn+;Ws zyCF!*5j%8tz^AlJ^k5Llrf6|<$Y z4$amw!MO%Gd|6v4n(g|F;xTn$A!njJf_~jvgBPXFg2~tlraif#b^dPAY&SaQft~-= zz*#YK9+__{EawG0+4dhapZCF!k5oxi{(7p&-sX?4uzr=T`#57a4}8!)h~M>0NORsL z;->ZzZnFAWepYJ;E;UJkMTd9NC6@jeklzT5nQb+J^TfH9zd(k&0(WZy(D#8lNm8++ z3bkhVWw5%af3x}iGF&ieEZ-LzOT8G==68tm-of0 zYk%QncM8jPIpEk;!%6(O1A=d_S+?l9F*)Pb32L|tN939ER{L%Xwb$3;E>#&QU<|m{ zNs%~4+YVaKETzhGqfx~@2QrTT;Np{X$(cVVM1B=*)j+JiAx;(yQKlOi5A$-NJo%(Q z4z_mzzUgGVzTIh5m+ZpZxu*P5F+JvW2*o9DSv6?XRJvmaV`4AOf#njGaFq4M8!Rt_ zA@ApU8jx$*YF6;WLLMerduR_--1B+qa$+&GYBWs?ka{3nE;y zxcyU{Z6-|FiG%k9S?5If;hWbD;JwI=4$mVvdPNURS>4WAodE3IKA221sHD-eZ7}nR zF0ovDnE!8t2fnBp#D8f$Ll1AFXiz8tXKvIA>6{z*{(T|p32hcXH2lpe5`0E4?P^l^e$z7O~z6B z`$#<+3uK|^^L|bvD;%X+7tfSS`qaSQlX07CMe}^;4Me4emymj)mU17Ru`_-o@xF4F zf8Jw;&nKx9>0CD$e(*nZU9ZItl2W2;Zq%YtfDGFiieXGg6rTH%4PB9@mB-FiU={P< z-pqQ-Jet9XyCq5XT*i}J?t%3UD#TM_FZaFX4cULBNyNyq?%Imn`boTsTs|+&JlM6S zGGMm&1q602LZjpMAkaKaQ7alp>E^)Im+LuK)=777VuNU&_bPa^&endIzsZiy+{mF- zkvz#4>*PjUwL*dM1d=kmi0(11!^*RlZcNjd3v4{|zH%xrt!%)(1EeOs6_mgmt^QC*fr@rnCaj?l}o+oj3SJX;G+nJsbF<*O4CW!+2%(jURYVUC#8Yrr_|MzkiC>B%Nrc!}AvWbFRU zXj+=hRlbj>kMxIHvn>w#6ShKl2*JMFaiU#)Pgw|F%eo1po@r9;$$*BZo`dW6F|aiv3@*Be6bV*iqg5I!#JwdDP#R`_zSSH z;6Y`EBmSMV9ZVZ8(e|Brcyom|akw{;9xd}m^=W@#v`Yw7Y+&70YsQj&nMddX_I94Z zI-?DKUKjNH$>E;pcS7;-=QJfhnlX6}a+?*0Qa|Nd+^=*3f=*R{<~Vnh@ks*b_o*~* zz9)V=%tLmXIiEEGu-5A-wPGro4Sw`gB*W;Xfs|SwUVZw9% zJaxL6faRL0TtRszAD!KV`JU-;;rAz4*cXDo+zvwY$(?jfnjbC?sDZCiSFKbFTygl~ z53HM`3UZYKFqZXsIS1O(TXq)6v-_G>aab$n|psk50Jhv7vgmrOe+3)83HYb+f91pp51@x|DH12lKg1ezn zypftG7WwipUd|Vy0{qZ)+b<}fsdR0&CnnrbCYNne1ll9)Sa-G#>0jOs8|Uppcga<} z)YaRyXyp8|;DF^1?w6w;c{({&lmiOT3&Q$e ze?hfSnF=*5vAR&2EVEVz%DA1s9!(Hw=322$xJLOhKgeq>=UC}!Gxqu_vSO*C^^=Bh zywzg{{5oU$lVvn!&&h&m88cz2mL00EEQI^h?$T@S0l4Z`KMc(Iu26flyE>GtSsnli zp8hByYet+xlPPajhtBaA`D1K{_TTA>>A3<`?uj3QfnbyhBMQJeO~V zcXQ@oNpvF^v%X8sdRNSd`v6xhqdA{jbBUFiCde7YQQ=q*{Q7<>8R92N&!4G9O{t5# zkKa?+Q6GWlk0){|Mn~ud*J><2e+)7vWpRC0&NeNL2{?9dkoC%`{^G7ki zTabCrXmBT&@e}Z#fgGt^R7nSm+2V>qZIXQVFyAxZ0|N|9_z8-cw6;4AY0nW(X8Shb z3C9+6UU&v1T-AuG=>p7eJ_Iu*=h0Ky!5HzW9`fW@bDNyZNx;l@ZlH5HWH#e<>yIQO zcF9tQa72EK7P)?E5|np`VOWnHKhXQOBBd5J&UJA&YWH%6Hq2kwlnj0W`t(j&DDJdx zgCUdqIFm`%%#YUv4`0_(S1C92Hc=uq0q6N|=H_VlLRGZ4$B)>I-XjC~XC6w_q_P%G z+Pb)DKZ_uDV-%);$%Gf9Oe;4HyN=(57G#^dIGKMp5ZhA!La+2zI{ULVs=EvpbxfpB zXWGlXYw%v;6@A^d1GC+h^BX%V`FRiOabIK)*D<*lbbf{-8EOtUPadF#Qqg#gea`=s zuIHYvY{BxsGl_z+5&3b&7d7twgpV&AsIt^NEE+bB?68u8VUhxrY}O>7rxww>L3Mb} zwVp3Kpau?G)zPg;Lp0|#JGbGN9v2vMcPRbL=CJ>Y(=e)VBfQeF!-cmmL-~K_sY3Ds zH1v=loVNj=#;zab+C#`h*F`I!6QQWa22a$;kqKEDG>B!*JdzAZ{pj05wY10BJo6~&!-lC6m7_a3mwpdC6&A`@$Me+Fd^_%*9?d!So#&GmG@)iqGTcx7^gl=E;g@q8 z#o>~Oh-4=zqq0|0dVc3VrJ=n;iKKz(C8;Rwv=u5@6^bG$C8_6kqrGK@gvx9nd%w5m zA9&x-Cr_vQIp_PmF8E^SghM1_!TU%wT{q1R1KY}BVaRoD$qaKGcDTjw`6^V#!o`t^_~G9e=SWEpRR%9X?AQ@EG9E+ z57QUNs*#)A#z!8y#27kesCfvur19zWX?q#U4vvL0xvPXfjt5}vzzNvr)&TQ;wqR3r zGd${yr=t#=VPHZJ%$=~0^Y?cmM{dePT4xA7n$O$;N$kDt{DP<>@&PZWQ!gc;-R5E!bwpcUn+3aLK;5o~z8o2Pcea_I>B_X(9?LV%qE?g+j{=cvA zAZ*z^o+PZ;fPm^qH_(IWKq49LqP#lJAFe__)W+6C^cE1yo~wFfvXcqu{F z{tANiOYKnU!vf;bx|3=uv3qOlS6=*Q5cID%!_57PoZ6eKG`YSE?T&>(<*!!W<-b7G z+nWY*la9lwziaUA0HfUwPG??DV|?q_4VsE5xWV{Q=dwnUtAiV1L5c}xb*m6#m!;IN zhh_h2zVnVO2R2oV^}j6Dxuj$MG%{hB&Pl23;9(K~vx*5?J@F9TOe+R<;C8$PEhTg5 z-#bQldY}`$m8L^uh%RE)5Tamviax5?h6na8=48q^+Jv?Eet9em%#4SsONJOeumiGW zF49Tg3sC<3M6%=WO#0=;O0<<~2i#x|2Yu|=oM*n~ajCRvgf0fvDv~X_RIpLClk}O5 z<^MT@`r86=)3PPZb3T&hG*sj2pZg(ph7fw>OtGVX7kJtnp@C5jxOsCKTz4Y;B<5N& zU2_jMe)I>v#|F0y8bjvC?WRv)Ij(dYPn?fMb89DA;ta)T-Yb)*HXDP{Kwq8vpq|ca zc~-K!TO{1w(gSHFPADrD0T1eS~nPKbG7% zw32Ew|EwL$GSv^ffb z96Rqgui>Fj{~oTy!rB<_>c(*Rb=eq;?4)5#FmnsC{YIF3DkM||@GqHPb;;NQn4xA3 zli%B6>(_o*EP0gHv5fkef}x@gk%NOC8ck9Xz1yX2VwuDG3ZGPTN9e?MGIEz=xSBv2 z(yzZ2&%c`nl7(LMEqg<%&HoJ6x~m{oeik{^6fa^YjvM5FM*CRSOnE$2X1s1cg+b)@ zN=4vT=wNc(R8p>#P7iC<;p@*5^!TlvoKp~ECFLr>_m7L{g@j7Ha^o$WZchY>V|r*% za1O@D+@n4*Yw&#g2Z)@<^CQIEu$W&#Prkv%A8C*j&H!jN|E4Y?nHyY86AwS!=%5y+>F=D ziQVBQQT{xlfn{-9Mv|%GQuMt2GOT#Oc=Cmckf^vGLoE;TEyE7e%Z%gkWJ@gP?s|ah zQ*y=DyHW5+Wi}O$x5nNhMR0!n6E66%4(>bC22R_mXrq(`CZCfbd38Dbte}+`>pG3B zOk4-D@Au-}Wm&xA135aguMSfa61e)ZQZO|s!Sg+j;DuXQ+05QroEtfZIX(Ztl*@KF zsHh(b#_ppthB{!#;_+nU=fj+JXD`uQcLU^Y-_UK(_Tx77LjLlKQoikc6&{F><(3|M z2|Bs1I51HG9&AXW8sRJ>x{GxWjcU34TGlCOQzbF`)QI4d4bH9Th3b#`^uVYs7#%W= z82%jwpUw%e>(*o<8CyhmM^vNpf;ahyl`F8xP~ z&sH%OlQX~(ihW3|5c-x(jYp-aX1+p?S+-{ zYMivjUi$r70|q$6!mm48u$*-VG$y%;-sgwIc42+_EeMI4PglyAU7xgAfIsB-@m0ew8F3Xk88gv~uMFq^rgeYF1r+;NfC zk0`|WzY|EN%q)5=Ko1`!J_g};bI6Lf$Cz7kB>H|T?J76Lv+q@iL`j`s!I@4X{4|e$ z7f?=5jts*IpMMFymdH}8u{CHRw+G5L3ZeY6DYj1A0`qSiq5B`M#W~qU;By)H?281u zgtuVE<2@k#gLPgQ^Kgo}4>dZZg|aE*$V)DkJ9pL+<$5ys@3Sb~sSt^Sy~Mds=Gpwy zKDHBE?+XdPdq6i}3pVeF0Ha|^v`N7U{Z^O2;Fub1Cofy{(0m04iW#%@lO38^jwX|S z=uoN28Ytg1h7?D1bIPk(rpW&)|FklMeln}X>RkfvQ@sjIShD~h>9%vH_IA_4-z8YQ zr4*AOF1r;+i?V!+dE z8=B6z!jCA?qhMaaG7{Ph#1#fDBTVqQsuw)84Mo?I*LbQTnM0@oOEe`DS*3TTfm-j9u8tl7(5@XU{S5~Bz4p-qs zHk)bx)dcueVt+MOei6!RY@cllT#9KtgN}26R$>e#schGj91sKW%Pa`ek_GdKJx|w}Oglcv-=Q8r*q^ z-BVnDfxNK;&N$e|@?0U*mECc)dxn!Qr{cJqmc69QS14lMJ{cR0y4!E_U0v7sT6UAt z@Z-1_D_+71bvLX`84doIljwyR&FGl<7XCb}<=(PhhBlqPNz>@ zZ|P&>9!X+h{FdVy1bAWgMA1AiDXu|<1{M0=kNL32ydklmAUL`tmu}LI#FOn);pK#p z)azLjPHydF_qcjc6W7PwmUNgXnL~S7eqQ=XH{8`z<}0NEe}4G|%UXjV(82~ME>|V< z?f#>N?Unc{XckSG90;cv8|tq3eu1}VDSbO49DSqZq5Z@mz9p*}mB)9%scnBCUeOU9 z))v5W?+iNYjsps--hiB(g+Pnt9>uo|CCPdXaO$)r#tqCQE0UMfAMAe7cR+<6gkfaH z?(O(MD@AZvZV&Z&Q-gVHw!lI|4e&leP-&XAXs^EP?+#2qbrTL{%%v+@*&WvQJ~XK* zL&*i^o?a?poRTpxaI*^U;^5(O3<(3b3K98=*A zdOu=eWkjz!wbXkeOQ!W==L!*`5eo+S-ZgN&*hMFz!a};cY?m-M`+L> zM|5?|hiTcYa#BTbkz<2swr?C}gQqQ|$!={Qx}``9zyBB`n(cmrtuXlfRbDKZ(vjE0 z(C=WBVEu;Ed;5YPaH&g4W3-FRl zE%z@2v+Z>WyVumfHT`9@C9Vdqj#nh)KpM2M9PF~}X3=bq^DxGBS(3zHK#UJO$KjO; z^Nt8nS9GYK1NKL} zf+Dl=^eAIH_{t3;e}B#dSH_(i|7;>LeRh&M7dGRd>*{pVE`Ls1ZVN8ylY|wyOX=W)Sx7&I6hftuIeva-Cy@W1P7D5)<2}9A5Y=cTR8DKak7n&Ky=6L?eQF)n6E9Mxz(frYnU zb2U#1{@wW-W;pF$}^Zd7s1V`+eK$d2#hI4oPFuCCouRnYY-5Ao0>Z9)qcE1zC<~vuh@lOqG z-yU9ec6&X3+NeaHGS=$L2$s1r>x8PzK-%-n7`;D9l5c@AT*=;E@}BVu{xQtg?~KHp z|9bgoixM6-R$xa|z2IAK7v#L#jGx;i;qdUoRD5qUI&XUlXO!wV=>qn>tYr$h0-QPH5|Y zdqJDB92x&se5`2HcD}{&n_6=*)v}2Affh;ic)%2AjI_zMxYUShktsb z8Rso*gQAc>5Ol~9XE7(C=CurZSHcM`r@RDb87skPt+lvj%}8Pz*#=y$Exunki`a=X zS6x#xmJHFS{ftxkqkJ>on15ZnZK@CTtFA%ouQrgUtN~-+5L`BA71)mKqSxszd~d{y z-shTsjdA15JJ9!lG29JTvK-@Y@GCq;6RkJ1*{DvkKJ^PnYUUE9kJEXDH>==#%{C0s zxv2eb-?D@Cm{hM@KutjmEYDemd#+hRZPi7(Dd;kWnMo5DPKBymb-+mZE^waU4pxKh zamAP6q*Ei6HUt=<+EN9gHmh2&t?d~Zle&%%9$H4{4i3jd)AY4R)vQ9GvO_DiPkNr>BYbXQ%BIyYhJJ^Hwl#Q0VFR4L7)cFg7NbL= zG_grn7F5}-#!VYLAahYQaJH*)=_1Cb6<C$jmn|FQ!w_^ORT%9}3?-cwv@bFYooyfYvf*@}iT6v@89>VdMqYk=%Wk zYcMRLJz}LOX~Tny#Z|sZzY&jaWUMFFf!`*y$D5VRHRgPjp8l?nQ-_F&yh0k81}Nph zT&O;6kmMbU#oLF`hJic6fg?3|v^rV)^o`LZJ$)-Wq<-R3KY7ubtDUF=Z{XKdC!o11 zq6jkoiefidSC+#7;Zo0~Es@B8y;6Knc z%^tME*5cPeYGkimD&3G$i+vaM=#x!_Ff7lUWtrr)Pp-_MKZ1m4b!8=(SQra$O@+wGx#HntFdl0>qQ*(UaM2|$PukobHQB2 zhVH7hK*^K$p|#)@_m5ltE$|y``%*?teU0!`8gtyMr}3MYS>dWV?E6t-7Byd0iE&1U zwEtYG6TVwli>iOj;p5JUr0lONI-K-`&wE^`k=+J_2N%Ggd^hK@bUB%|Rw&w;o2Qzi zVUi?qGnS$fp6q_X{tlJs7Mp(sgV$=G_ zYL6087Tr236eG`w(F=bHcpHf-RK9;mTjtISaAX;beQ!Q0Bk;@D;c)rV2pYn=iY2#d;qVssBYsE4L8T-Cc$8?c!t- z>ou(@u*Aa)mB}~1<+QHp1&-Xak#5tQM(iCtakS$i?S?15)M08hUN~n8@yFG{u8gpK zjy`DI?W6+{ThQ`S5y)$)P*+nk)R4Uks(CZPmwjK}k@OQLNS>lW8?(`*Aed06*?j2n z^TcPG8vp2kF(lpg#QnvKwC8>i(B$J4=r3aoLt3L@+(_mVd14M`lk=%c`(>;>IGpq( zsZb^6h&lA73npo9hL@^#2o1xCR$2;umTrK5-6oTHRuzItOS;G=3xD2hkdW#O3B%ui zmJ6R;l%;#_ROs0c3^qmB zU|69f8NJ_!Mli0j(F{4V!8MWNw5;&drI-AgGD-vMLoqFPx$xqGQ~Y?@TWD5F;5B@Q zmP|M7wA;YEvhx3SD2%8-}d zZ#ds3UmWvgC>?d5xyD$hrne+k*sH1rk3AM(qW>w;?j<0;6t@Q!!Ja!B^t@j+&bE>x zDw#(>*vgo7<&`kjIg6et&Bdf!kY$hO;vc{iI7-{( zSE16d-_ReOBuf$?KtmrJ7=1( zlfJkzLTAV`DYEEpG^i)dBKiitB93BIlOwJ!ZilMz6KD`y2~BZ$2aZ;XV7g=_ioG36 zO3gCpQ-eCRdFn`~f7{7b_-@6L$&a{yzUCo+D{*)_g&QN1z%o=HZPpxugUjzz{~E^o zx^zc0&z)}Tq4UdcU^~hlELnDU!ahafurP^k+t-4ZFS*d1gsb4o?trT1@ zcx;MT2n%EoQSjf2-v`f z(BIxB7&=d$sP7Y_bL|@N@wD~yhs-M&I@}%=TP6tqSjN(^Sryozp$_k7XLFi9#=4VU z>tUNO>;5ls!cp(efZPUKYQY@n7EfA1z56vc)sC@_@go$DE2mpEjc`}MB%<7VgwHLs z!kVS8_?KU@=<#*cSU)UIxcE_naQF8b+@Ylj*2)u!&;3m}>WCApGTcbd=rW>wX%_hU z`*2-XHA&2wQc*^IyPPd{NDm=ytM{kyw} zl?rmi{OcNs$@0StPboU;t1QiCJb_Jqu|iT@41Z=_Lpp}>#jPUBb}xE_)t{9}{?}o| z(8C_{Egrz`UHfR@94maRF_=glPvEr8dP(rw%cAc8nq}cwJyw>QnicWIfmK+#HC8xy z<4ZXGaw~2LdBp7|$#nY0yLcg`8TQsUb5brfsKog8a;IjK2zy(cMed1q=`Cyr^_qS6 z{9X2uyW7s;lXli2T2xGDl-6Oaq$gdZ$a1!>3ivR}NcgXFl+Q8%<;I;{h=DZ4(UrLB zU{#DW!MXDh*m29Q`P~cj88&rWI9dAcf^Iu+Q93C zg}`gs8g%y`Ldp#ufHUKXjp>_4Oz&w^@b1Qh-bgynQIRZLx)o>K&lLV+CvLQ;#`w`H zF#4uCG%}xv`+rMB^W0ow8)o$8!pB#tbX~O-{#e3(R@2p>_#*2s4;m27^D@|hc7aRD zN#Pgaw?*g4gQ^FMSJxiapd;Om7KjJdwkRhgz`nji!k>&h-6fMXMrU$c| z@R#2VzM^^o7)@D#Ptp^(fBakP+EQF)nhT=_FQ+FAs_`Ua_YLtn0@sH!hod6}5|Bmn ztxVC__ZI{Vi1V^XJ#fnWdBpyGIwV=_MET$`)b#r*TDzkflZ&VFn@&Z5G~2AIU}r}NlOZ%}0oY%&Spc7-?*$wny=|Mm^rQCv-$Ot!lWqSHJY z(D;)Ny*>LCIJ+{&)RR2n?uT)7s~+oiwJU;bem0jbwH^oSr$d>%9W^g>!QV5Uz=_?z zIG|>`3Epwp-!sZ-00Xg=}i0P=%&h3d~VlFLaZx#EJ`w zV5KyU>|5f2dXH@2$N^Vc>wg~u88h~Hc@JmPq)9S%6^UkbF3Tnz-zq^~FC0P7Yii-; z?BS#&P8p)=T~O=lFgkr%Dpi%K!R*C~{DY`O?(BIN9DCUUjz3eS?LY3}qvnaE6xPE6 zC-%LYtv0TNR@1}B%rQX!FLZo4$2(W+px$6vGP-ju+zRl+;1%QP!!B8xm|ulBc`9#r zrx@0*x`v4rx!}4fqRjHZJ(LNZNG|>vLSAM%;z`5%@E$|yuPc@;s~|=+G!wW*AA8Bu zEtf=lm1eg{d=REg|Ls+FeQm%+)28#S@B3iB%@(wI%yU}YValm=;bqNR;4tk8*Uwes zmV<2na8!+qWbBUf(k-A>qEFYZus}aa=DB5nH2#=MGk)qS zf`OyIVbe@16z@WU3n4mCj3LL)(AoHgsa{e^!WqEnAn<2qeMGQo?ZtCo9W zkMs~exXhQ{Y-M-e=+Q95NF8RD5d4s!3ezuk(jL}5AFO{0;#z0XgF)6fxu+IxXQ_eE zLl<|mj?b84<{Ug{hH4oT$W_fd!YwA}$@<++{2v`-kg(o{!>ot#^VV~8O)BHA$H>4e zzZeJ+8X??V2ouxtsn5A0Jl6Fc8q`#2cDpI^dKKWNy&9%R*`N*M==NwPQ)LNP%xY&2 z?wqHB5Vtqv+w7zKAB~$-yEhc~FPqLEI3!E=?yF@vkP)yWlZPyO_Omiy0-NHFQrGAr zJaXwPNOqp!Ri-py3yYz4X-cwFmkoYd_ZKRhedxmk9c-4CA%>-iTms|sG)7C))ROD8 zr#cL07|h`JZ#m6>)~!cVWf^F~0g&w9g5ryeV82QdRm};+67h@R9@3@#{HrZC28t2g zIHXZjfOn&YlM%yuxe=Lr8J}tvHF>|E?&GVN>t{FLE2##yWC3!fyG1*b2P>|jlwk%~ zZCg&`FR`5Ykc-gyO$W}5&_kuhQpnw&MWf|hu$T1%d`^$z=MP$ow`VJoyUocklHI8t zmrtce`3CfseKq#!`10*Z5#YGb6onc6 zy*Hh9XQa*o#ZR!lJqE1TsSxdxuH1uj$Eoz>4Jc=J2R3Ry_b^amxd#(lg-W2Ceb24b22F3eM%#}0ARJeXYGq!jaz?SPX zNn4dW4*X_(p1xR`1s3S(Pzly{K^(CClh#j3(fj%BadW(XXoASsS(xXJbsnR6FZmR@ zCAk7u{WlEc#%FU%aqDsSnlxA(ZAXvDZN!_i@4=q~Ke%agb(nYf4GbwPr*e5lsPJ8m zoEe?QFC1cx;37@m>SojUu3+4nH;vEn2^ae2R^qqC!$Bo=9Fa3}$9@?D2sp8c#{FVW zme@S-`yIpm-m5{X#q&6conf@_sVy3KiHT-!{Z~yitR71CE?0(`KDAi&!k>>xNaEV& zyW#^*4>o*Nqkigv=unskYeo!)%F8R!#;+80e~oZ=h!NFd{LlOcuV71iC%2h(V?W-ICeH(lX)dIa&&>wBvFdw4 z?sNrQ@uEU_DD(y0o*jxtCrh|s-C^{|sA_EY$%Vpm%o`MEfW}=>@L*Cd?Uu5{d6TMO zV7~%?BM5NH-xs3$qx(cFY<8I>>fMue3oKqRh##lSa-I$mcz$acS28G>@1N6vPaj`| zM?K$RT#F+n_@#<=)aS3-qq=(oq_r3e&aGUJ`{ag@-_xEz(zrD!yKgGlo5s9$F>Lq(_%`zrm08E~X-#?Hf2W7{6F0+Q+)W5|S`C`_>~Ys| zaiYFIm0HJb$11h?#CqVh;NY*9#4;$0Unsav7taX8_;F6W!5vwerc#A2L*8)OJIWv; z-W)5%RYYB$i-Q7Dac4GUE?&onJ6*$G#$;H;-tN|)>@jxfZ}>UUpT1?DFP(eCiI;jJ z*S@kFHFq2!*1PF{azWK zot_G^KQ!sw(SeM0mJP$abl~_YJ(hnff_0CxXu>CBe53ph{@oVOkJMw%j*%qCYCptp ztYi?GZ2n(Qr>e^o-Pd??&y0%c6zeklek}#m_FUsN-UOhNb2dbH1w+80wRq!o4IG?=^oJ&Vu3IFf8;-Jg#U z$((ClFs%q0sZ)NX3oOE87(YveJbvaV+CR^pTEMutN@QUCPMXhtM+$d5gJ+|r!C?08 zy|8`+nffuE#t%v*b2hE!3mumU+*n?;F*J@-*rq`vG%6WWRt>_$ls(vjyDVH`s_cU=8W6M7vtQLW|xJZYW{M<2#;Lk?(==g-fI=ItuYwRq*p zU+DfSLr;FzMCcRT(+ z^@ThgU4_@%v-vG6iy_Le41EeyV1-O%narmE4ED%|-o|t|J7pVQXm5iVPh)9b<9f_l zB0-u@q;ghI`iP8nF05PjhH4filL--ad;!-e9Lje1iSx7h`>gM+@8^jMG?trmD4A+m zcVqU|5|CWb!DTXs(Hr?}Skd(W8l2W*;?)}XxY3y2mtKWsr9CiArI%xfUbJ32jCBc$ zX{&lF*?-YRG?Tv*1$_2Lp8x0Q`7kvUS9C{mW(88zavS3-s;5EGhYH}b4DhmZkZ2~4 zbzO@#*DBz#{|w$Xhw-=PJQ2<0iTReedh%Gd|M8?JHIm7caA&^j4{*V+El~ELC4YWl z8C_Nr$@~#9oKft#h+!TL<{nC&ESk@}DRUcr$Y7nA9-g~z zikH$DlXBQhu$P`a8;Xza#PVfE zvNT|OB?ju1b36EJu#)vwzRsN@ViGJXW=gn(4d;d%lyLABgr}lX1(-#=} z+>eI7)5T)UeEoQ0xI_}N zBT~rtSPywq;zAc|(YaMHmFKrh##a8^5;Ck6#3p2t#i3 z$L54X(F8O6x?hj$@+qbT%)|I_Q5;-zzQ%{t2cXL0bSPjq>)k6HaF+Q^cpT5XtL7HC z)wCbxd!-28El(kb#(MC-{JYC9Copcw>HGXBe_0~D=a08`d2!iR`)F)rGfqEw6!uIv zg0;OWWJ0jDXl`3IJ7b}8Ehy_urg9;s*f^mFLg*YY4O@w8T84@C75cwYh=a~%(cIpe z;fY@wHgYecm(jS%b@(?S1){$kf>+jzeQgl{b-nCuY*>I5(-g>tos(%Oy9?ji^9p>! z9YE}|J>JrtAo8qThZG{O=)s>YiQpVYSYklwdOnDGgi|hFN58zQoZA^Q;rh6TSk`e0 z1b60>pC8xbZ>f03Ti#FI{haX8yecp=h~k#NawO5kzqmOz!Bl^>4IX2j#1B&>DgQm0 zd@OY5%_DNTmE+uTi6v-R~~eXcpygDq(gL14CfuENxXKQ5#_Y!Jy?srYkokT$tb#v<(-`S z2a$$z$}sK<`)nJz^W6`t`P0_*_+@_^@6&gXQ#kL2#szaha?l(qJ1h_r)}%x8a|w9M zd@)70*gJ4$4YlZGH}||x;Lw!E=S8kYY@0yppX`Kn9m(Wulsi9o)I$D>eHHpFzQa$A zDhBt4GF);b4#v7gmPJGbVrx!1ELO|_^_H#ZE!N7or?GTzA?vIi?Sp^0J_nUP;?Mpb z{o{mtze^?~PP_ABM;e6TNSV67QwO z!i>HTFzu!}#s>#N-IP>%+S3j_noA+u$w)9Pf^jV*UctXCU$~zmDr}l4n%nK6$;3a} zn~yKK#Tgp!!Xt}P`Q1~4=^Zvho>v{?KKm{OA6dkm|4E5DHPJF#(N^vN*juX5Sz&Ci z@~{L}=*$Kk8(l0kcnl+5GwJax6ZA40N$%F%5;mnK6UoqB{JPXdP=0J1s%$*WH)k+i zs!bL8x2JLMzQn-#Mq}m+9tG~6m#8&!D+@Z(M04APxrXyL7eGs}J+$qx$HfUBAbxl% z-D{_Zic_UXiPLq#T=s7o?diw+X8Y5zP9gZz;VgfmV-$TDTY;#T58VN1ta=2ZzB}^GvCMh>elFvX3?i%D?C_@AJNU;57yoXKUmwYccvja|B$H*j zzI^3UDVn=B8oMtQ@NXP)`6(*Z_&F-XdDdYs~aPpd`+RWbT@ zgBm=IT7aJ=#kos~-L!>yf|iAbLi%1UIy5^FeUBf38`aEXI$0kbf8~IQVm3X!#tD_A zzCp6r2);gv!=jgiNL_I#v}z@jV)PZw?d zlZkMUpXlvvKA{>PD~VB`f>C7Ms_po2<^s{JFkiC~6Mf@h>|+Da)K?+%SFI9pW#^|C zV)4pJlXo<)A9-WMi3 z-v|R0o_J#Dd~W9HWi&Id4!bVLLapOrkY#tw*ZMo);;1&NDtj42vL_LP5AxLagf8w< ze+1j6*g*Ha)y!W%mT{_*slunci#}fl`{v8na_THP*x_b&5K0OUwWL(_R+!t zs|R>RB^mMt%_HX78?aMtKlp|1ryifyW8v)UP^uiwMJ`=WOn!ai{=LI}x*Z3Ha|cfh?*KY`JO zQPe}p829a$CV$!&!io3Eq<6a?AG5HAPaRT^Zh3=fU&%qPL}Lri;FKZb_&mD%KRwji zk^_76YiP_H8~h&J2OIh>@Xr@Hv0KSR@^Xwn?2=0+d&PWtf7J#2(!@%ntN!rGcZy)i zfpQE!5en74k!9O&S7QjgV;sw$@HcS_7V6c(YTX#RP~8g82D}yRL#hw-l12MYL2>pg zdi`}W>2~%L&F~o^)oAV}Mq`h^g3+yR2PNW86Ezt#t|*f7qD+ zcOM*C6M`>lIIhS_iq6Wc!NZ0zaAy+hZN?hn9m^e1+LTMnZ5{B%l5$|+AHJlV;IY5= z!6habOuz;+>t)FqB`?||mqNDW_=)EE$XZLxE!fY${8dJ+1|o63vpzSbB83nBP=Rl* z?T1yb-@^n6bKEo8A8Hd)XdCNj->>1J`j0Rqls>e8T8^ws_$=%O1O~px0NX z5St%DM-sgCyXfsTn{kp`9Gssp zi>@DUgU^1l`|V3L2-~8ICw@Hy7sdvkPB!BwjcH^`U!Sm%{jHxi%8zdlE`r&6wqet; zG(J9(qumEt_Wt?-?mKhcjT&Ww!`F_48)q)jX$2*CcK8#3d$Z~HRx|9_T>yW+u7+!8 z**r{SUii7Gv@drh4xccTq!dtrU2QUnmkH+;cKFj5^?}$ZPx*h{$ug5_47E1rOhd{+ z$hcMeH%r2SGe>E@!d1L>?G7Z}&)_XcJ!(x=B`R|y$htYUICki3_?P|2&1BidOX8&Y z19NBJIZQH_h4I42Lut;IC^XsG#BWf~;iVamSA3@#_kL$DqzvDTUc<+M#ES#;`8wvd z?YIp+1~UXZUf1K#991G*r%86Ooz=T0<|m>$^m(m5UcDhr#Es^e40Z0m47O79dO zA5@L!{l?MPMQZSO^8%dURwDSfKWUv5iIV&0K=YNs)SUGnpO5N<__u8Lu}&X{be(}w zhS@ZRy_1&GQ2vKLmPFQ19&hL|H#929S!F7BKEcI~2E9xb%z~BV6@4JL64-=AP@>gJ@ zY=qy&Ns(n5k05tuGEoW&<8SnImKXeehD*1pQKC7W$X@nB{o_9bJAQf7O@o-*TpdO4 z@Rtt?Q7LCE*)ew)J$=#u0}WWl_53WD$FqL-uEC;rxSU%u=_v{0Z9|s|jMrxq&jUY% zS_fU=;je8t<@Pth&x0ED+V5&yw0|EQSa%TSQA51`$PI?9Y@KnThB#nZ@@qO!I1mKj?VPl zh!yJPqCNJ)L|vTw6bey>jtpUTHz&Bt5(_mc_2 zMge2MPBY=2`;R3#Q{C}SiyV7zZ=ze>waDKOM@4hHl(C_v?0yGddPdOOaY|ntFZw=kWL`6(> zNa{jHQtv~0=sH-EOkBGTI&LKsx$)tmxA(~3wRmOq1Ul!!Pb*)gMa78ChaqQx}9Ej^|dl_LA#f>EK=UiaJeCAuUefyy=HV z;iGQWM~E0tU$Z=@=`asmmNp<5e*GYwNutpuVFAnwir~Pa1wXp?gRH_LB0s|s<$qs+ zWz8mZ;VE0(8uc2^9sI#vzD#g!xj0#>dxb7MnL?Ht#PFL}zY{!sH3jd-h4BBJ4mo$j zPt)BC$C_Th4ZLGj!Q?|nR z3-6(e?KWp#+yw9QlIhtk%-uY)5PtWY34rZVmcHzU7w7N5=8N_?fA}a-#>3)62Ws^- z(T4N##OH@6UNf)eU5@%uyJze>+7oHc+j%K`y@XgB^ol!^)kUwp*o-ZSA@JK{7FD=i zhZ=#?$?HRzV0T#;=RLS3+MjU0H)FVjJbCtCzi{ZgJYqOAli!_a2H?9LW4mhk#MMCe z&Z@%7vqL$DyD>0tt_gZ~4sdOSmuSAQ1lNvefU`}r>8z)wIIt%h#@@FFRr}RA=DOQMJ`*D%CIe*QvSl#~csV z3~(iLj#4e{5`4bB7E*?0@VcMt@%#^E5`0*KSkAY`+3io^prSYJy^dII{TEUS4sb5) zO|t7q9Dng)5+CPO_DpFc|R3jf>yUK6^}ANZ$Ak#efL*x?t&CzeJ4)z4xg~P1|3}H z((WCzAy8`pX5FzA{Oi;hABw<_Z{$IB-eBeit-*Z$5$p;`gMtJ4*t#4Xb8+;?_@oPINqbipTC%2gYx-vsZ)3)_*j|aUGx)}L|&nb zw1nvO)Df2Il=E_{nlLK<8KfC9$E~L$-WDr>qbp9(`I&1m{KhM&$vGjgR5r(sJyPV> z-lrg=n~3>(`|0ec$HGefB@T`?pvyc|$nO(du}(H#V0y=k7JRJ2T{7;>M}XjwqC&=5 zYKU%&(0CaSIFBahTzu%BuLk(#+Z|BsoCQN;SE5I-xahWM-}wyhblj$zo%=b{iX4*K zJch5)@&G@zZJ6{YUeMXUjN1RIMn_!_h_ycmpZ_oEyyJTMzc?OQWt1JVl@a=)jP$wZ zo~R^gDD8owC^E__v=otcDw0Aek&%$kJs<5MG^9vFWn^TAtlztS|M;_q_7 zi3G$-CfGkGOOVk_BE?Dh7*y9TGB+|22X3rDw=KKigxU=LZiOXUEZYjpO#P_TYXkBb zH^F#8FsHh~f$vlQp6g~+4J=uWgZKeGd-#SM4S25V5vf`Ifl$j$*eqWxjQw% z!SlDG=^82A@V^d>>E{VolFVsSpa~9;yV&E|oB4Vf^63xZO1qedc}M^G%krFlf?!)7 z#h==JOsLm-Crr#dgr~zBgm8U-vD3XgoZ#Fp8uxqzujl8Ao&#hd`lJi}{!)%!E1Kcn zzh-Xh9u0n(II3r!KU!&nH~ing{ekjS;k*=&e(!_ zeee_Fc~f{HwG)l&H_)s{LnzR#7g9BrXo-qQ1W4;UDB?fXZQAk) zl5+b(ygZ`omcQ`!;7wAgYsOHidU~{f0gU;oh+0!3gl-?m%N>5Gt~f>1?E@*xV*A5E zOOT(O2leCiP@HNCQFGI2?RP7bt4xPiY14%I$$A)hpaQaf27vl9Gi(i%?V0VX6n^7* zolfdBNP_=Xvs{u%p`d!`F6p@ip}d@;=;x-BLc#ESEb=!4%ikYCd5AH4pS6MepJHeV z^G%gDu)ZlBV^PUxbG(tz1Orw+hTAtyF`=(4-#STy#wXWf+RR#N96grrf6^T%E^QT3 zw|J3@bqRi5Ybq+)zZgu55YK+7;4*Ht(6dv{xG$AyL>@}C$gULgmrUT(zMTc>fy+@Y zxr{N5&eE!IOFYwOFn>7exp>a;OkQ_)hTxNJ%*xuBZ^5BeFp=l!l8ED&0LFA}h-_>k-)@GQ*JH&wBhJqsAese*6KF$tSo>*4flnyoR{5xzzifA0AGV zqRd^%LX9Hxf1d2nH1Gco+^t;k*^ZxFpI2ctsN^;dD3^etowCR@q7-YtDf0I}EaoTJ zT411hBm7fZMz#uu%v;O6^OjODNNyXZoNyxxJs%27D#nTr%cwq7h24!*(N)7tvwJ81 z7b?cGp)25R$Wn5QD8fv|hj4cqKM zpNy@B39nUvvX`Uk$v@D2-*g!A4CSxXQT+yg?%euxe!bmv;m4lMATD>qje((>-M7w$ zIfYm~!x&U@!eFYN9%GCc!7QPc?oGOmuS=P?zj_=6=-c7qLjoxIn&8Zca^ZMj5+$`o?oinh zOnW-)@v3hIRCfh&+7E2`+{#w2yC2!W!VuG0c6Dz?FIx7x89Tk3X#HX4A=~SWDg9c6 z6IY^XNe6r0o&2a-B%8{4IJw|8^&Oy>Y)@Y`YB2GS5`XxWE0|1NjwNeK;j4^59S2r3 z#(rP^y<@zfebNlG(Uh+4Nu_$1W9T|jhNjzwifcdTq0ih8n#R3H@_PGRaZlt=Zby&{ zjca>=GqP%+rt1Y4X|{y_9($sv_rdy~6^?n|3~Q&zQA~*lhh6*%J3FVr+9qqvI%q|k zr-W0#^QE}BO`EFKBDl~WTkyodpPb~$T$02*z-Gr9I6u`KiZ*^stTj1$^)Va?vaoCV1b zFxR~X20HZSZ@#d{@;wsCDU}EJO!V;cJ0lolkxqr7*7$N_T94kcz(*fFKUF|MP#|HnuFfYXd1ROi}ipH;+vnOiNfM7@QX(y7`=H6SxV+OF+-NGU!qC;*yos%{fyMz z#_}KRx8c3KH^M8W{q!Fe;;7#rHHVy2hlpE<2D|R}?CozyZ^pI{J3!-*GGz!wXq!Kl zr`j{{WD@IcFe_ytcg8k3wH<%tjN`Wr=oAl|@(n+p{6cjn!}wiAtn+b3yRg8Or-7&P zarW;In(KEQWu20%@aEuJE_muy+8cQr_eM+LjpuB-__zXZM@`|aUOt1xf6dS>uO39@ zQ6wL_9Q!-{fo@h+^#d8Syd+Pf&bQITvtC%VPlh@U4#{@hwdB*@i3sHgnIbBWS71ZETXh3Df>5 ziB|P3#3yyb`ENJXc;^cisA63QZN|%JTlEU;oc0Iql>Xp;8L&*soPD(7^&u**D#462 zYpRKx4afGYqQ$=lce^W4TH(8oSjL63(eKtA$2*EdJZw{)X9f zYaQXUC^fiZEeI87@-R|X0*f6B;qG@^RLD6G+cXmB{xcgK8u=WeCY=%O8^Zi`lcaem zjV9O-cmf+TqN&>VsaU+X0B3z*8t^JPzO``+v*->KH;#0tVCK8Xc&5SnsSs)|PUo-3 zOzYX(t+hPyzXo=H>6lJws)iU?{}8eyvq5R+a*RIn9b(U&q3Z>;xFWoTx@7#g>$d6q z8b6Jm**-YM6~iJ1io5TjgO29o^_@$4yn=z}^>FZ4ZEzl0N6~k#^;1tG*e&ck9Rh3=gMKlWTEr+Y2f`B7uhICTQT(CdgMM(fRLw_&9Bx*xqlj zSUac?rz`GgI->hFm(>|Z#ymFZ@M1sne7S*HmtknIrN<@ zPbu@)qRGF0{Hfs@@FvL``$cY~cfG=Co?l`Ed#-N+evs8Y+(2e>o0 z6eh@;L+@A}oV+3unr0PKksZ51e`bC0_vL7MFXq!wkmendox!nb7hXSdh(5D?LXLM4 z=1sJu^yqBp+AiR^>kA-9EhuN-v2_@+DHS5~{7KTZ3NwStp||r<7CU~=e~XHO`K_;L zo@ppH`!iqp)B@qkf`>TIe;q~CeS-1rn^Ebwthhcjk}j3xMPkOpkJ_lf3x{tsTYD`M)r zn?1XF^aOvLc`;6Ws8E*Dsu*u-KvNj?;a~vDkm(Nkrr2Pw`UQm%eI*HdLiynvwqlIqAnMj$#B*5( zYoe4e;ptI$Jg7UDa)ss)`<>{V*J?n(UftpmCkhRL%Enyq!l-iT6GKXvGFkBcu)=~GG4v$@XMU> z(0Kahc^hpmrNjA#vqJEeD(v%WG%xjG06*)JCH_#ahE2=%5sh1kw|@TUnc=H`nxQD! zl^z_-qq%H9PoFY@Y7Zm}r?!G3;QI^0;IEP4}I zh98#>INx__G_(eYJ{Yv4Z?ItjStvKsO zCVNyYA~E9*RqmMz&R(I+`>Tgf-)X=C>pI$5aUGrJ_u`M6Dw6IAD_lREW#V?Z!k7Jw z6{gsSw>6BQ(#>_Ku;U}m&AA7+znfry`X6EGyCk};Q-I%%h6&Nf)`+cH-shR@4DeuV zBU2|gR2Hn^vJC4fi>g7jIb->v+0tOJWgTys_l)ai5AGdih8INAJw6r>wHBPI{fmN4 zdhxL%HevcDS#qd|Vm&y8*zsqW;G&hvX)@2@l#eDbX_*x%CqKsO17mnC1y?9|w;XGK z5v;f%P*^a_a$foelcY}xEt45*^pPtK{+UVzsmJk4-&xd_5hmVoKNpYelNW|eWjQE^ zEm%;J$F(~-lk$rfI7+$_)|UU^{-$W~Qxp&P=q;LR4mc{3-8!6y(NZ}MKTK{1uRcm} zcdrfpsM<*(vEel5PYDWJcTiQ83qL`JV4RKfGrrU;jG* zx6O&9(81ZlqPG>uf7wsm;BWBxgEOkL|ng_K}%V<9gUe`x3 zxGqCWvCrv<`JDMH@r;ccDE&<*H!T}H7!(JV`;`QhgO2#3=_xe#ItklZmcJmi zH{Wn-JGnn=MEkq{sQ(i7S#@U~{)m2L6(y#_vyS1JOY%Zc^eN%k+hUXpQ~X4%Hs2W9w>HK&;ebUFHb%Ym_T zl4$8v8VPOGMem<%g@fHq5;FH`CtL-z1k>z7jj^pj4{r;9K-!;iX-KRchK}_5-gWa z7Oc#?aVd8No9l-1hc9vIcfu*9^ETrpCczh1Wswc*QSzR21xCJn32oVy zxZ3FfxaLTTeklE`r)i5@! zMqU}H+>H|rIcJBD75nklS3AJnIRF(?;^^M|GVz<-ZMgWsKw;G2U3A>N2;;NmK~r`a z4DX!Iw*?OCVN9)A;fZm!X&_ZMoy_e`@!gsd82{lvSW&wiA1J+t`m!@5J>e||>kg3g znjgXinxyj&AKUlr)tVbzF}_Ad=*~s9tz&!j!6C5LE)?dl=V_Mle=z1i9nGC|14pa< z1l{9`jG=9SKbdB^Kh6%ibk^dy;l228qa#T7LnEe^^^*LHECL(9H8^v&Ecw_b(~&1f z88>pWFsOBec#}gRPW~*%o);{8eB1?JN%UdCwPO^$$QzSqUI9Uf8(?#XwcPoO{}x0zt0{~rh&n;;BdyB5Fi-a}5aFH-U0JXGoD zC|tWbg1@1*74vE@absq0p&_qZasKrpF!w0(3095agP zX!sf|3@e85>(hnN8p}~*(>t)zw1#MH4>XiPjiyEfvN&1ax0ERaOZ>)Uy+0A4&e#>IBM;~OXh_OE!duJS9*%2;ie{=9fuXAuIb}lI%VZVFk zWth0YAKG&n-)a3rc>3ui*$!Qa7u>(VKZAUcvXcz@{86Uv?n|AWg?MjpqM(v`7dDS) z`Bu9_oc#MZx|(nYk6E7t!wRNR_G1E1DnbY$mkblH#IuRZ*}V zEOhgrk~;huS3H^Pw_ln>PuP3wi!)#}BN|G~SO)F0Kl56q(C=-Qc=~4%+ z!1~HMntkD?_YSPFiJ*liR+0(xGgm5_3Ez*cIg>Y*{yr?G60Xfw^eB#qj5EmMN#QqOmz01U3l%n~XAEv@u zsi&O#9LAn{$qU{4aO)w)()9Ywy_}3-v}6WfyjG^iL!wi;8P`0H2dzI7DTQT4-Su*z z{hcZd%UzC+Zmd^}=@|E$nlL_ffaIP`5Z9m>#XmW;Mlc??3ZAyOqRkKx9Pciqns(+v zI`Wa5*e4XGG4`GN6eZTHTt_qBd!bTY3i#(f6IAyZ;EkVmA!ec-sK;C4r_XG+G>D>Q z&JDO|Mt{i>okG|>stE1F5(NVvGqHM2AugZzm5V*cx>9spuzd#yaz4jMHO31S5>r6N zIF391#*RPJyPVUJ@u9LYX1MA?7j)0qZ5mDJyKI1@W!*oh9$1R=za|My!RcJkyG=O8 zLIhU_*-?0d7w&nO0@uzBgeWC#bTG<-_AG&x$D5#5_IJ3eoFMFIXWrB}U%GecB28ev z=r7@>LjBCRyLT9y<>$rItgmSVZz}7Jb!PG0wflSNN@y!8#@&Hy$GbR%d<{P8#qORN zJH7K7Rz^?bgO9qt-f?| z&wGApYH*L=@4(Y4v=F2ub4ulD@PTN)+`~-Redh|-G|&a}zAhCEog(OBb{;-m`H^!5 zfs=Y&hfXiAg7o_({EET$Slu@gd=w4IxRiB*^p(JT{L1yx)j~JlR(PSDP1b{+<3C$j ziDk1YR51-9#C*SCkR?mkl=9Kpw3_Q1$hrWFR^oA$3Gl@A67AdTg)SXQP#-Q50>;E@ar8Z zcs$Q%y|IWx!7lR$g%R+0Mra^zAL_srWf4i@-xZWna( zK-7M{z=gMlNakfv;5X<*@fyn=1gGp%!o^*M*kycA2(ML#Yx@x&k2mPqd-JC{qg%lO z(EK)yDp)4YDLkoX_U;bUM&G?xp}X%U`kX$lRCxK=&oVn3j)%_zy$=HtA%ZWJFf zZk;fawh0$Z^D%7uJz>T2qu_3`8i%=BaOXX)k$i9tKFJCNl}U5S?x+_Ayg3WQruc(a zm*FxHG)bss8OEjO6Jc&dGMsMNf{(N-p}{?nk^@+O>k}!y z*RS*3x8aPTDg@Dq)O>oeHHy!?;wWVL-4^e$%Ex3;sbHo27M5(-hQZG6+}WEEwCZ*a z`m^WzhmX@mBUyfJ{zcY9#5xF#7!UvZ-aNSKpiQ9>E79w~Yw+0C#hn;ukFV;E)1K4Y z$>41iKWeL!@Op(5H(Om52Y9Lp-CmL9vH^II^xx)fuKS^N9wRlln zYc-l!_m{LRnj*}ziQ-2@I0|c8Yq{;=J8^K+J|X4HZrb>Pb=DUaazBnBTt7FHum2~- z{n?N}b*`Ss$Diuihh^@YqFSaHv{(+S_1AJ-H~a+@3TJ3e?`G7Olap+m9>f(g&;POy zj>4a^Rgn17jqyV~1na|#=)7kEs;w^M9!(2_Xj+N-v&X`eaZhP3>(fIrG0+Ite>nas`DgLAc2Gm=JPt6Sr>4CLEEg3QlNC zVeET4vN{oN-5dz@mfE=O?G>2&SfJNxCTPTeg7pQbg%h^sD0v@5+lQx7DDy&pnCd80 z*vH;2)h$HHlKX#bLI|9c&&sjT&jUTb>yzc zmMNu>`EoeLM=_7q{dTalo(D?o^SRqKxW^yDjgIEmUUll3+gEi{d51L_VyXVeKyH~U z{#fqDDgK^IPtD74L}DD=KDLJK-?}I>oALgQN+@C3HGK4H0e&c|Ihu8pW#pCHmGwN!>h}*BHK0Fps>#&3506 zmv(O#LRLhQ!Q}!RbGVS}tt8Hf|MZohZknDhv4Shgb4T*IVIhUDgfc&5`iE4L#*XOU&yg@vXqxeLlMP z%y#Evj58DYPVnic4yzs_`p=lsb5B%w;)=D?XTfUi8MJq|HztYW;hEP;D1D}l@pCT0 zzNbl4kY|h&m%W3noz>#VTOZI+X}rY$?{R+GBsLqvw+m56w+S7s`PlLIz0l{5gZ4)V4tB=U#SsQrcJ(FXeJ&K8 z-Y$dX2N%*Xvo>O7l>Dc2y9B6J60R;U#Pj|?*iLm9jySTv&!MT@rt$HNdy|9XTm9hN z%4Ff|7H{m^5et7mB}0>k9ro=bfqym!Dd8Mrtu(Su)ODvgPTL&y--ghemVEjh#C*k3 z9)i)O+v3RZ`&g_lMdNyZgU6n(7?8ZU$1C!F8SBV6;}3EhXNaP|cq4n$g@s#Q!S5+H z7~ER`eR&;{`tE`&-}mOtj>*Hf@q4iO_BqnraF_yEHp(E_L#Tf9PjpO66|ZDi_w3%| z*=}sv&#*^}&WmK-LpArH`Bf!od|iR3C+&i*15#5+uA<>9wfPVJ^ zVd#2y+!Ax9N8cFziDemhPoY?CCD+3Kk6Jzbgxy)UXfpUBZPe$U9r6(l?`Pd!mBFxn zTnSj;WnEOZUeNqJg8E#u!eRM$!Hz#IDpP)pGyMij#(Pc?KC(PZ^k`2Z?Q9(v;O&N! zpF|4Lh1h-;4Sho~C~G?wH;y9HcH!C1;;9Oioedqs%YD z4G(QJ{8ta%T?yjRFEDxRD2ZNO5T`mUn&)=2pYLS=N3*x$hxjOA*Q~{qrl*e;YI1P< z!c!XA#5!B!V&O;3GvSrlYW$^e4YHc-;FpRyj;Q-xa}@KGA%# zgQqa0?v=17G86|c$r7}NjuT%U#8|Sf@mxLYDNIS*#`w20;IBa_>j-8$j6xh^!o_j& zh7SDBQ}?)TUf-}PD@=O*6-I3xKqC}duquC)WSmnk{(4jte?QGbcsL?g$eR;@@gFV- z_h+x?I*gssJC(78tn6rPfH$uC8w;iH2Ey^<+Gy&Z20OkA^xNe!nyD@0L!b1fIcLmK zYWfK}vnGw6pJ2JLvmS!~%hJ`!-Y&guELpiZQv6z4`e6Up#0QuYV`}JydBZ}vyr=n zCwW$)j%lg9Q*Nbr^}AqD{kjDYi57EyG?xPAmE!JgA@JJR1a>;Fz=xhYVav4=D)+vI zPOSTH!De|{2n|&Tr#$ z8aEZ7oP03TEPuePANDwZU=Zk>^P~B%)?v=?T-a}LlAHASJ#RNUpht`DmmP!ygR*F0 z*B#-`u_#{tl!p*|HoDkjxhEjWT0UG+naRsIl?x9{a{tS)+pJD3!fZujF za7SRzJRg!^h#G3wnb-F-ckzuD1}i=7ndjFBw_t~Olw|T9HSjqf#pmXG2!Eegk&nqC zH{#?~BP3U3LSgTPDBiNrL&)I!(V78Aaa5lSAyFevIQzE%@5IJ& z8jHU`s+}>O^BxXo|HP0m=K$Vyj04TN+eDcMAK)O-eBRkjpMMx*hjx>G!qdrGw7K95 zYCV}O8R0*RfAKq#ue!2JsMv8zDDq;y`c=P#JGU0Wg9C_`qel1a>O*|Dpz|xGo_ytq ziXv6H3Cg)O=i~F_e;i-vI_M zMGw7p(dNtXB+s4~*H7()@ny-v+vIZe(Eb3Q|Mg*CbH<;XbsJQ@574tG#<=%ID_~a~ z2hq#}JTHnqY8FtNPZZxV&97&k=N-$(fyzUvyUUE9vkBimmEsO1g^<*PyV%gQ3sj%Y z5UG59gocWrLC2QkO-9?`(tFv^?~6A1vz|(iwzuGZyf5pB+=VNoFH)tkKN*gR;^&w6 z3bpu8l(kJ2eL{SM?%SgFY+qCuKa`8PBSouN&S>w+L(ug-1}d1>=-+Y|uw9i(MT{M7 znotw4_`pNcjgK1~~AJ#d6x z2RW9b;u|@E2-X-@zb# z#*NgxB1lFoqR#39EIDGs{n!`=W!v@f`3Gr8D0xbtev|S2svuc)0*(2v7#B`uy*o2% zA;{7K^?xxQ=Hf^ixbqdJsZ5e6`aNJ;d=x*}!cVZ@^-9o?3&I0mi-pLKL&Zx57Ncx0 zd+u8FB>q&*M!axsBz*mTl-4>r@Ov$Cdgl50ax2`J`T-g&2hi`^EjZ!ic!_FRFaEDv z6u)n{pKzf4o-qD*G4696LFO50oMrZAbYG|d2TwcDf1k8*@v`%9N{d*o#1t?4z5+ev zGlJ1ab1dB!MahXQe|<5EPt)}iR0qV}b!=q3p!VKeO7$ihA76|KqkSRb{xdG)>k>Z3 z)0_)9?@yOAui=LOM)G!VooVl7Jv{L18Ei?P3rmApj`Bkc!JKfC%V5j_6@Q`ERBMq| zUK-z~{#*Q5k?q75jFWs@8}ndV|q3HCeL|{<8-$krtLZnF6)?A zGwUoInw3l$UWP0K(g4GDRf?ZCcHk0u70I5w5Pr-s#xv=6q-XbbWqm-=i>J}MOUGcg ztszd&I4hDhXPvgy0eIPR3g~V6A$;{J!?6onAikg)mLIUe1FqNMabqmuL&oOSY=G`w zn@_7`u)tosXI58lW?8U4!NN-yWuf>+5x%)RgPLE8p;^`hTmFWMAUdAn-0otctph~r zpA(Fxu>OdrEs&|#m*4JUi}LTT!I>^^ni{qiJ4CGjP6^yx#!iWt8c&l03&?BWQGB-T z5b5tp7s^YF!7oR|f)_SmgED*A~lu7+k0S*&SE>{yq2OFek1S)#!pmXj7oQmIWN>%yKSd2Ce#wv4N0`7c;- zOL{FlAL55!oSqBwq6dl9%Zl*!TN%!B{UqMW(-{|Rlx8^#R#?@(9sY(NqIs?B@eI?%7T2HTa&4OUbr-in@9j@XdHzw!i_$BTuG=S+W7 zsw8ozG{0VJGrBYs2;I4x;hPI^sqO&I<~eaAo>gPly zfCiVdLAcikV(XS+AG1fGt9y$&!dsB;PL~YQQ-?D4-shkYCKyIqlcD}0Tx9>YXZOC& zz9Sz>6GTsHb3wXGA7>73ofMcp=IPKJ)%#OF9MVkx_!KaXz+ik)r+6KEZ%g6WnXw z&h2eDNq?r_MsG*GLkX#BVPOdFZZJ7nweO$xSnsq`iM7tPbVRqgn~YL29--!%TF zF7r*@+(a`i_EGr863qFhLHA=9!xZL$$xoFLb>AqNFn}*rdPDNS>13OfkB!4C!1%{0 zs7lts)5fR3*Cd&KH(9Yeaw{~wV!4}ykGQ~YzQmqC!GDt7iqDmt$z2~9N3IwTEL=)^ z<{gKrXIM9`hOEf(#C5tP3BdFE!{OGFA41ZSa{QK52SG<_VAeESd~q`asj~rL zEnwY?dkaJv#xkfk#h^z^`L=NnD$96KinT0#Dtm~x1sz&*x&Y?QHbJ$!_cgnBZ{0?J zylf>0i!W~y)X$aU=7J}n^sx_rPsJ8bd0ztC)85o*Y=mDkp1|3gvD|~*7U+8AELqGd zq^f~|sJ|$HgrXEdi{;9XCv$YJ=mP{eZNa^(+cYmP4WmwPF;=;+f|G7DMbT}gsM=Z$ zTXGlkpCfFs@xdinqpVAmxE7n$8=zxzA5i(|i8r?2q8AMTOqXlIVuj~q-vLmtTNUN2 zQiN`{Nz!J2O!^}wa`@Dn;xdcSWxF{{{l_?W^?Hn5vj+C2r&6S?HO?BD4p$mwgbO3| z(Gn{`+wCZfdbSfy7_(vaKYiMp(u8uSp3~8=7`S-H1chTILPOkbda=(JUDW?-*5CFK zG%E_x_0U>~wk?6m6l;|1-3SGmrzj}j9*6l~hQK?CqKa>In0tSUq_3{BaN|uqE`M7` zKl~^0bGN$V;BRe0dG#)mzg>uLB2hGUr55N_sqnVzZi@ofCXz<>4*Z&a0NSQ2(XCa? z>$P7%uUm& zHaP@;+&D(x>chpceOvL#C@cE8cMiYaaSPfSv}qQaIn&a$#i%&V0$%TU#zl=-!u!tG z;>y4I(eO*xQDf2|{)NnDa(HHdb0R6xaGJ~3 z%-~;SDhcWHL*eUPSL}ECrREnSRhsl9pFJN!i)iK#2fM)4fM+B->j(~ib)S^-a)fz7 z&6u;df$GYnc_rJ;m_EI!M-O*;UV!hJ>;2Ix33pDh2#YG#LU)%<$(MCFVWb-jJ7P@t z8Y@uw@>Je$mkp`_M?>g$ONA`WBRO(_c76fNj(E5Ot>yeP@Ey^4VEOk4 zJv+JF8y#FYnQ7yJ$uuU#1a%djLi*9i;!guU;w`-el9z8n__SAUsC#)csm=rPHY>vO z7dV!YJq9Bm8RDI7rJAX?uT$d405p!0gQBiZ;XiLXEcDNShYRAVklia2-_%0Mr&7`X E08NVAUjP6A literal 0 HcmV?d00001 diff --git a/nebula_tests/data/velodyne/vls128/1614315746471294674/1614315746471294674_0.db3 b/nebula_tests/data/velodyne/vls128/1614315746471294674/1614315746471294674_0.db3 index e9de912740a926494dc6a2834286990199d2ee40..2d95339b1dcc7abefdc52e2d8d8b25a0472c46e0 100644 GIT binary patch delta 11158 zcmYk>cX%A-*~MY)YSd*(mTk%1W6QQoF&<1aeF4$i(oHjCSgI*wdS^`Ui~(avfGi0u zK$3OD@>fS;kurC-W~7r+gTYz7(bc|<2!TF zwA}Tp+z;kCFVuCuFgUvFiO%MYa*cKKb{;kAhL^XV*U?Z{SC{MjF8k-Yo!B zrnHO@2_~7+aza@!*_7@eR0LB@X%!(BOf{t^35j5uDXk%-0@sw@CDa7dP3dz$)ydmc zXCOvC+r3NBhZqD`FcUEdo?sSo5DJ3X$U!Iy`jLa+3+5mPArP#E9E4D?HgXUm!8*u6 zC=1p_4njpR7dZ&AU_Im@B!YR!K}ZE2au8~Q^^pTmb?R-7`N&bv9D)sygW%R@kHUtC z!O_$8jSz!S5NwPXgrZ;*#31;B1&Bci1e+oTArx$e7=%c$IbsmXf-Mk(P!Vj27=&1` z6=Dz)!PbaDNCgGNAk+lgAO@i7I5x(%h~Y4XU^~PhxPk%XAb5i9k%Lfh7U$~g>UKa4 z&P5&A5j69VG~{U=Nfa zB!WFrf{+S|C_$(R_Cg6j)oHLL_C|>YmJsZN5)IkgbQ=!K_S_dCc)-(v{SbmsXvp^5 zA00Rrb^QQzAozlXC_xAW2ciTa6dZ&Wgh+5OS`f;DL(qay5gdvZgjlc$EeMI=Fti|~ z0v|01HNj%E092hu+v0GvXk-h)5okeh1tr8Fc!DDlgHRA0g&c&U;ArF^_=01QgAfRg zMGitJI1V`okzfgO5Xyq%k%LeXoPZpJSa2e85E8*j$U#U20df#(f~Cj-s5(tH$H~ai z#2kWCkb~d~PDKuaCpZl`2nE6E$U!Iy&Oi==FQ`KfLeP{wPG_0m)TXG-IAPQAPWBh; z*(SJ{5DCsP!HtBn;9L{jNvH_UGr@y|Sa7}xo@rX%W*U;FCA{ecCK%?4R3}0cyho@B zmYLuSK-FosZ{tD}IL+Dn>JnUJg0TcwaIpzy61?UU9DH#uF~Nq-*SDF*Li2I_LoYSK z01p)Pipxx}FTodFZh{ga5L|&8givrLY7ip9Rj5HI3$8{DLPc;5Y7k<0K$MhZej@EB4MV!`7`K}h&MpFjwX zsjkNeku7@AjlH)1ljfP5dpB(|4YjtXo3o!=Pnn^w+ZHrco%UxqKW&DZ+ZQz92Z-Pq zGc=yy3Z6AXa|oW`IWx3?P!K$ChIS$p+n;OB*A1DWg&cidf58kLLkI-FHA80-Lcxn> z=yF0Nc*zXiOehO}XNK-2R0J=Zp@#{v;1x48L`VdQ8G5rl+dXZ!yRR`rAMr#@CtgJi zK-C##W4wkKqZmUlj2HxW)U(ZaaDI;#oIM?Q9W4k2!5e5nC<@+04T3Lt3pEIV;18%l z2nBDW1|bss5j6;9!JklrP!aqYH3+fb9n>Hsf)q6fso-7IAk+kZK@C9F>995aiW(iP zA$Sip2(I9LhLLm4UIS8TP6XYO7g1;jN zp)B|mIS3WOKahhE3qC^*LL#Uk2O$-FjvR!V;Gf6=s5+fC$G?!HlQ{%mAP2z}{2Mt4 zp5RO5AQS{&AqSx-_!>C~ekUKWZ%~7Cpab8c1|jUszFXg+1;;$=Jo%e1jmZ5 z{}&|)vEX}@AS4!Ybtpkd1v!);)C75y092hWmdMqkMAv3b_;K3xRQ5w8=b%Jamd4eI z29zLpf<}}e6uPoKb4>`rxrhV!V&%;93%l^(IDQw_%(Wl`F9&*kD>4v5K^sC4B0)Ps z5Xyp4NI|FwI*@`83p$a4kO;bvf{+SEBL$%*=tc@a)fsJ5j6sUgd?*BCk%Hg~#vuj4 z6Z9Yjp&;l*3qnya9uEb<7fe77LLiuk9E4CX2{{OnU@~$L%7Q7#L8u6(A_pNBOhXPr zB5;v|kP4b~xkd(H0~o4+7u7GB(YXWO9T`?+r1peegceQs%8`=c$V=a#Noc0_L4 z10S#NWOsUNn0Ly4QCFusm)7$YPx2MnZ}Wb5#j%S@ zlkF=G#`o>!?)LiZ6?5^5{QrAJ_A9?1Uh#hYNj?92MQLeMdwnzB{?-RnBW zDR(Dr*%x%48NQ!T5qM_!Q9>+O-weM7eoky=h7TSy z*D($Lm{<5NHaEjdcp%U#wlKrz5JJJ0X80;XB-jcy2xY<6s6nU*3aCMd1>2woArWkg z8iZ7^9cmD2f&tV3RGqQ5#`dT&mNf)Bpa#Je?1&l!Pp}he5DJ2wQG-wv?1CHwU$853 z5CXw&$Uz9lzS@@0?T#26BVFGEF$iVBo`^xH2#Sb7hy{Bg1|bpbjTnSfun%I4%|4~t zSo+#yK8TZX#jp@_j3M0&v@#2}Ofham=`BJdG|5DOL~25*|^riUX2 zPoz3=1Y!_sf)Zi?s!orMaU^2&WQ%n5yplcRN1;Ve7RS|rqtSxk_3%q@3{r3|=)kc^ z(UZk0;y^xk976EAuj@+?f)EIfM+!nHH~}dLk>Et6;F~J<*t#bn1y59TB0vg4ELe&Z zghX&MQV>$XDM&%6^<)p@sR)6$U2W*KAMt4j(aWcz*OoaQB?zwI43r>vf-{kVP!ODj z6ojJSY{Ve=f^!gq5D3mij0_fT*mqak%7$|9+7X^Nm;OeYJCC zW8AxT_Ve=s1vSjn8i0Wygz+*Tvbj z^CiY}$FJ#J+2D;|C%gNl#P zY|pu9=bN!TXW!1ZV0+GioqvSwIfoP0 z<-b163nw716WPnRVtHOJ+xa#u&$(jf+p#?7*v>z}@|+Vpm$5wO)XsNcdCoOE{}jt( zUg1pS@;|G36S=${@5J()T|3`}A0IvE$j%R7d(LG${{q`{uGsmP*q(E2=U-ua&dJ2}^0^9j=aky3tFSxgT6Xo< z*c{UeXA(Cbta_8Uxg8(G=A2zSSFt%~&(05FbIt`j8*I+GXy=EqIcML_k6?4oft`PY z%{hm5eiWN?jwWT_=+#(!QuZAyPvUp%F)Yr@l}UK(k7Mmg{Ju}(H{uDb&8vyMS&YRw zr*?i4i*v5o`6;Z9d4)5Xt3O@!CUbQ=K7-XcyLNsSt8@13{2W&2T(I-=Secqq>!$37^Mv2vEVZ^@;o6C)Xc~mgjDc3Y7lCIf1(DU>P)jW{)HOTSVQmy zY7pFMd>8*l49=boe2Ex@g5WE}AQS~(BL=}2e1jN-K=3VM5JJIsh(U-1BZxsL3;u%| zgo@z5s6mJY-=hX0v5>Dr4MHl&p$4HQ$fE|J>bR_tuSX4+H3SZ75L`h6au7U0BXST5 zf+pl36a~%5LGT4F$Uz7Mt;j(L1#QSdhy?A(K`0AGAqSx%=s*rPd%j|q&sV+^Id~$` zi7w>eiBu;>BL`2^bfOzM+{Wf=IbMIi@qmblYbva!hY*#{cBiiE+rm6W;Xf zY03AX2Iqoa(Tf^{qF_8~5PbWJ35dZt(1D4FK?v=ENoc`2vh!r5;9Q>mZBsr!1tB!1W7;w{%j2##f4pNkYTvPYmY!#)D*Aq7vw zIx!C^2#LT$3PLJaA1Mem!F;3uRGmJ4z#E`MA4~MvG#jD>!4+(T5*ZvlzweP8e$m{w zbz}A{ZEOa1=zFXM|4Ag+#0>1;x4H$tQS2-5!~!#LRNvz*rZMQ-im<5}IGra#o!HC_ zTuO)po11}~2xY+*X5el@rEi-?JdazNfrmK9I6FCT}poknZvrnZq(|#&@AqP%W zomn==-pDbFIRyJ42f-EWiyQ<`upe>|3WEKSgHRM4fE)y0un;+BWsgrV%RWyBA_q@| zI&lzk5F)|B$U!Iz4nYn=MQ|u`5Mse1yJVSLQ!xuN)UX(F(^R@1jnKTAru^k z5`;*w1SJS%!SN_Ts0dC#2|_G55hV!8Z0>myLU2xXAV3I0jf*Tr2aHvx-*z||9s1d! zKkIM`I`p$czwK};I`n6sr`K;k&(lzXFDU2^r=tX+C^!Qp2)^J>mArf4L9E7sqYUChP1lJ%3 zAr@SV9CNZyGMQsP$?K4VCsLh=kb_VYEJqGN)mh8txE?vyVh#)VH~4`bf(!UR_fQp< delta 389012 zcmZU*2Y3|K`uLxnnVp&4opa`FoijVLJG-eQAz=w6p@*s{Vx-tmZUl0jAHyWWIvQga(03N?CmN{t(_1hH>t`vNy??hE}p z+ZVZEOJ5k+*}lvTTl+$7XZz+ko}F_0diGhgv;86WYDeEyytDmjH|**Q^_}gnxnXx- zNOra#biARCyu6;BsQO`>lx%R0HG_bFvx%SyCY~AnBnmLH)+7~ggK}`e zKr;sw;DUh`4l2O~1FanN2Nw*qb5I2?80g@j8eA~Y#le7F`)dqzbC3ZY4D@g?5Ogrm z%Rvq30MIFkeL4n#4w32LU@+(q-RB@B_B{tfKnE+4;U$KG4hHHus0AGiG;mM{Iv8l= zU>N9NpqYc=po4)H4n}|u23k272|5^P=U^1*V4#D8(V&BYE)K?k4hFh8s0SSk^l&g1 zbTH7%!8p(Xpi`3ibc_cb64SxK1kk}iii3%ugMkbOlR$@bmM7<}mo~5_d<^JdB^r2% zV?l@HDs7bdluia6tVFZqHqPTf2D{$EuOAOG*!5Qa4O2h{1MM7~05TZp;9x4qV4#bG z6F~+8-5fN43Q)9?Ik-BvY6Ao999)xIbw2|g94yMM+RZ?hvLXP(Wj43!6&82%0xh{!|6!nq zgT=X3-!jn4!IIpnKLB(}YTs>Ln_Cr7-POAG;?qZxL}}#gImD`1Fam~1}+$A=U^$g zV4#D8W#EE=E)JH13SOi15p1xyofp^y zHW=ve-41oK8C(?*!rF;NZF3NP~eC2hZn5mNAgw;Dy}C zS_bMl*pnN13Xc&Ai0RxsjJK(89sq+{halXyxFQ z+{iWt+Bw*l8+i`{9UQ!x8<}IEi-Xs4BVS~on}gSLBj079M;oTVUna_}Fp!9Y6)AA$`AIyg80HW=vQ;2_vwpqqn_zyV2*2575C%wDS^wf(}-qgO~UVbg&X#yu{z2 zgMn@i@}Pr(o<0DJ+L2!}(93}bbO7j-2-D#aKnGzu$Z$pQh#-T7DSll784P4N@PZ5m z>N$`>260nuAS_jn0y0>MMqWY%8N^MsnXptnK9IpmwD1yskikGJ2LX`5KsyH-$Y7v@ z0|YV{=;8o_3^ppk=qpo4*C4$46X11%g>fDQ&)Ij963F1Y{kkOoutu26poMnO;iT;};u zcK~*9IH<~H_A}7KL3J+k83Vl>49I1E2GA*mt0lpc$z`Ol`voN2_l*N{nFs?Z4r+3l zVg@oC49aB&Gf>aL;9O<`0}UJu$z^6R(8$5iTxK2v%^cL`GM9wk2;{si0K@`MT`qGS zE6~ad49jI!G0@Jz@Lc9j20Azxk;^>FKoD;N@4vtUE6~cn;%qR%KsyKL zfC>gWI5-znFwn*B>O2s^!ft;3d=SAv4+jfC1OvSsTmU8jbV^2_iDociFcTbH2qp~o zHd6+xj*CD9E0Ey@E(R40)N^nNs9>OhgN2}ifkqB41r-c5b8s2BV4#JA%fST$t$m=N z09-K84#1CKdEk+X3Z$YPi%rRSXvc*frNAeD_-VucJ7w?`6qJ2*!|eNdU#D%YJ327y@P22uwjH;Zs%XmW&VKXT(99=EjZ|K5#zdAzu7 zf8OZdDbc>-OWOA96fP4UU)#3dapM$^uWQ>sz>PEX4INs_^=+n;sg79QWywtu-BxAOSbw*6b&xShTUx!netyHN+f zx)d^Z<1QXAgWTP?o5#x`cQ@|gaVzBR#=SgV0l8Di-R#T#cF5g?%Y?@(A$K=U@pu*F z?#3A&uZHB^xSq#rAbB@#;Bgxy@5YThUJJ>)aWjwCLGo_g!sGRjyc@UjcmpKw#_c@b z2?1b#yIK|^fA$vE@@VFDQcjI~D!QgqA&e7A^ikgCOm!%(s$z&kM~3RZk*xq z+mOB+*Yo%tNZ*Ycc>FG;@5YTheh<=j<7OVe59zyc3y(j5^xe3X$Nz!!-MF2{A42+W z+`;1mkiHvt@%SL5@5bFc{s_`{;~pOOK>CU5+`T(Odlit7kW_cr_&BE?NgPo+rDR|H zNlsOhN1y=V;M1H+8Ax&PSx)W8K!$_Qb7~y}^&EVWQ;%h!frBq|>ZuGga`077{TBnx z9DJQqFK3`7=~dxD|0bv2#Nt+7;M<(KmH{~AV>f;%r{0_VUCDVnk|G1&<2q`8>~b!^orUL+Uwn9#!DM(&Q z@d6UqUV4#(Q0N7xlodXSQ zFwnsP0vil;rQGLBz#xOg-MoMfG8pLTD?q>ni+g#2Ah-a~DWzpq5JF%g%}k{G)P&)| zU?9b=M?eG%GyHlKM5Nv4q(04_6Cnm7ScwK+!T=ErG;%;e1p7!c|A+}9Scw*1A`T*0 ziB?|10ucx5e@7BbFwo6`111>g;UEPn80h674JrV1 zN`-y77lMpJCWC__kikHTgJRIZK!$@7(7`}G2c@8+(7n-y!oC|V10AeHBQMbpbTH7& zK{@DPpoN19(7`|}2bG|MeQ7)Y(*B@>mFOsBk3kjKU~w1!L^ar8pqqmMV1t1k4l-ba zfnE*MH?D3bh{t833BQA`pZcSW*ZzI~JD; z&O^HgN^DK=D_c~!Z#ezmnqa{Tr&so^2`+-RSXcD8r?5a60;>@5e-;t$TTuV^fxGus zl>EO%MCMN8u7FbDxeET^&|KHBqIwyIucD`X&>(7aU6WbdQ1qnFeNgIhU8gb7SoE|{ z5QgQt&SqgVzdk(Ibp-=09E`|y-ONBM2P1P`>lkR~U{tPad(l`Ky6mFe>~D%H>-w63UJl0Px_$@HDHZqK_xN0wuh>nDa4;d)WipWB zU}CPToPi7nlfVT7^&A`nG8ky!;8>8sKqCi}K?eiP92^Ha7--?(c+kN>D+g0R2LtUK zoB%o)=-^-~=wP6WgA+jq1Kk`nfDQ(Firq>%31qOamtUU-G5~Z+C4DlcgNza;gM%3$ zgMkzWGeHIe84gYc84T2Oa04IQSR1V4#tMvq1&} z%^aKqG8ky#;9QWwKr095feZ%PIXE9=Fwnul0+7K#7Y7%Bj8Zq%?$W+gn?VLE(Zfqz z2r^hMy*!tTKn9fPl*;;KTnsYGm<#}da0$pLV=~HEr7i>)EY9%qmx2oh>N&U!TrkkU z!R6qBfkqCl02d52b8scNV4#JAtH1>VtsGnpE*NO%;2LnjKnDklzy$+c9Av=-1Kk|7 zfC~nCI9LoW80h6-3Ag~zDfR1faV@y$$C?QT*MSWNQXE_lIvB`sa0BRIpq_&pK?eg3 z9NYvt7-;0+X3)VvGY7YT4hC8{xD|9T(8|GWpo4*S4wixr20A!c209q%>gV>I(n?<={vtCl2;Bh5z@caiW(X5dGy;zC2MiR(8bdwfzl zUbp62Qa<3l5SwEtJ}0XUzY3N176m@Wk>}#-Z(4~)5);jW*(iK2GV_P$7Hm|#Aw7J4 zT=`k63K8WDDwSaEQRKY?9Wy70ZnpgA;kZZxrE&j36uXq_i}lKGOa0XE-KIzWF!VNU z^e-_iSp~E7#1dPqKx0$H8epo2H0${ozB#K4`2%wc&Wr>;ailwN;(Y3VM=&424xxCg zHuQqD+&?LA!scq~->X^Ykl3eG=tlN&3AqssuL%Yov&8<$^iluqVlogj7uf1*RK3{p zLzP^I!!a6Jpw$(}?EJpD1$U#&yK(Cz3w?*97DYrfN9&R7IaGNWjb4_Np-vXzm_z+- z+K|U$#$u{@NdKoT6{=(lRq}@YEH=(A6jvyLBP8ihNWY?FCzW2L{>yOWyu#G6T1|fU z+=4@e-aS5bA@QF~y3f>CqD0o83|M+_ zf~^Uf_adCEqM`G(x)xMrq>KKY3E%|nw`rHUwao^V{BE_ZC_2^xe_KDvslVFOf8?=%4#iEnq zf*tZda72Q-+fuZyGi_< zPdOhth=QgrZOAI3E}#;Kc{1U<9AzsGm~dxJziIUs8`@t~TaQWxrlcwo?rSC&;M5@_ zc#$>&s^tC@$>Wq_Ya)st)uDYVkE7UGG2C?XNn-8RzK(42n(5Gy-CD3g^;VI>E92^) zTKTmkpwQ51*f$~WdlZfOB&57=sVlJdje+)NE$?qA4wbS>FJ58E2mM}~$c0qiq}9C` zi?7l>^L0bA^`U6u)kLa-=TLLLiiNUn72R5Jg)Lp{cn@M566h9UTX8Z>_3_%|(GI8^ z-`>ZyijVZd_o%!FC9X?(E<(dmP`N|$jK}>)QvVHE(JG1s{%s3Sqsm>babp+OLNt1b zHc*Qx`F*z*Jc_E1#_0+RR_2mTbu7ky#K9YNts51A0jLW2;}25bX07gMEOx7of6`0# zSb87-!!WD-^Cm<+F*hR`UOE}e(rU^p;_%5l51~V+r-&r44&GW?ip`f6)iNYq?d`CRHG+ zAHjxU3Ud_lU@(!LpOkM!HEX3oPg2s3L&un&lie!WQm`wf?(zBN>)IM=%620HPl!8g@ zO$*&A#h^-tQt>GiT&S1i4?hA`l9dZd*?P;rMY1Z0&!C2l{R{QPv#9>vVB|H+yIva7 zk3z+$1=zS!H#+r_r!C(XercUF;u`9^R~vI67J@3dNVopB$Rspwtu(5c>IEo$Bo=Pb zrTl?M3bsbP+Y`z@42CCn3-oH7iqg<=+N{xOcyzNyJC1FZM!c`3-Y59Jlyo;rM$_IU zXowtF*GePq!$m`==OQtEg+|S)^qy(rfek9w~ShWrkZRG2w5M zYEzVGV)zprZPASvQD#~Keq1E3lEz+3eRpd^evCzK(#cSQX2aWQ_b|8 zp#)zD(n$$_C#q|cjyu7Wufo<4Q#?%@nBVns^=&g;*k0JBV zq;wN1YlzEhrO6&Nq{Rq~H?_NvvnnlorbmZb%64h+`MBn9!?;=-cBO7Vo)R>@=xR%E zm$G%g>jr55K#N|Yn}J*Y+mq2hWJ;>Q6P5`?b;E#Edpw7)U~S%Rd#JvQ8RX zMx)}!*zza?0Uaq`17nx>84kaCBP`!U@tjqTBjt{_zt zsoaUods4y;sCGbHTO|#<6FZ+;!cx&*q^FK1cW_3%x)@)DYG604^*()0?dKCF%XJ*M5H3%}^q!;( zNfSm$=f0HOipn1+zV*^*6%C_Qy}`_?orpqHgIXDFc^{C*o`(~?Mrg4%;#xg0q(qGB z#bfQj7U_5?7(+Dhg%-UAI-0{DxYdG4db{P@B#rx+1O`#kqQmnzijoOGbVCZ6o}LB?ZPA5VQZYJ=Ct^!&c;2L*4T>NS=bN`%%( zqx(|~Q{_569H+`_Xnbh`ny9!&nmEYx?$m}P40Rz@zR)Y;tV&kEbe)E8#&jvIT%eGG z5Jd@j1sbwJO7D*cVE9`==QX)A)ul;jE)~wkMmp;VZK(ed z;%|q&XEZKG{HV~s3njjAylFkT%T^wgCZC7xgNA;+Hex|6wx?J=Pj~v+-gas9Ts<^~ zqTMLGHx|ktK3uR>mA$0+N?UH1M!iPl8%+h~J1|DPgGSGfpkFQMPpU7WzNcwmI8FkO z==Leug!gN=PQu60&|})bkP)&>shq@~Nukrwi+tBdewm>ykQ`oXQH9hJ{c#@rTAP$>j)+uu>Boq zxM9ivj-$J9VjxY-*M{eJA1+8Zz88FQwvmKe;_Bzx=o|@rQ>YHddel+wKovK~$x4d^ zQ0=FNKV)jpprlbGuhNSSTI4|~v=qm`HWIgLb+^Ythl=H--mk*;m!Nc%7=Idpqnhvj zSh(YVI}^#95yC|2eO8`0p6ab-rr zdnYdKPn9;&x-pi1#DQ*O%sMLoRdhE-85&-$4ZY4?V0t_~s8X`cpKNU{#+#{z#8_H) zimCh=I^(aTI|o>e>3PssYeS}yfzML?dwtMW*1;_b`lr%p15Tes)g?+cFf3%>Z~N{; zgUc-a!?@at(?<;F9Boj3x5v|x3_=|>6013`eWi^&6?#ll9f+;8Bi@I~+T!S13&+ri zavH2GBCn#vaQJDMZdtY>YRdK4fdOZ^HtfzAc_igMO^+EiDnpfb>$HHX520`l+W+Bf z)N_~WjgXQ#HmN{EFDJeX4c(1litqUxjXD&J6x)FfIJgCR3`!Q`*!M=@GreqoT0G?U z{)+@|r`q${z-tIO)%19Y`JaS17me#8;gE@rXn3I!sxV<%7WHgSD1}LXiSCgD~i?l2{;GL;%LcsxcYP<5%IT^Mq%vjdya@Jb8b8IV?E+oa|K zZD@XX)U!URzU)&bkoehgtyddxED1GHS;z6?9PbWPz9Al3Y7rX^{>})%O7j4+Mms9Z ze?PTUuO?rIt-PVH*6Oy$;E|d)SC3qqwS)ap**&^3i;5p<+GjD6KV0tF25Wv&Ji?ay zqmhdVOqJ1tn9MNI_h{5h!RTmP-i#BSRB5KhJ{&r~5PhpV`wC&a_m0qgJE{DVHev(O z8%?E{gbyZ^v(eOU5_*Tq9%P+rkcB46A1L>{n@~tn$ZjRxb1ed^mrHSa6b+rL&3Mdl zC)@$u9AtU(n(?V#HqSJlL&+hI)Pc&LimOvC@eXVZqDrgiJQ_2`6^ieoF&#F{vWyR~ zKA0xgYPAo?to*)mPcN!2vuQ9vKElCXDh0*pZ#W*O`Y)*Qc6a(GW?>z&i3)qQL3JdU zF;M}j@Uk9mmkIq`({!8~N!4XaV1CFs-|@eIhQq80_#@ahX#7IACoA`Smlj{}dFx5y z)VTi_ZP<^*D5im-Sh?4ccA?aZarGT543B=^Ac;b?7bVYk)LnY%8^QeFTS>nBK4S)SGDm_5juscTC!+)m=)AF*F-E zjzoGB;w9*q*G-r|H08C*dkk%R9HwNWJnYqj~^qddK7;YFW!0*O5u zcb9(_krI?lz{dWpBR_@8{)&_LEO&pv7lgN7)BtwQc6HcD)v%W5!K2>~`QNkEwP^4< z$+Lrow_^%x=Zp2SP1&UHOTU~WR=ebXU8@;P^vg{7JDqwQp#_~hH7IVD0wOB9(U2c^ ztK=k4BB^*&KAnUoTH1agbThV}HMM4KW}p<5H2HOMqV2B8G3f_$lOIvMxlni<4Mdju zCR^Xes5VE8z8NFeriCw2{X1E<=7$f|QUBfA;5Xc@vXeYsT)ia{{lgY}aI{T2IV{Gm z(5*7+E5Ng_E_9pCW*k{3^?zL(SWT+$P6htd%PP`tmH6Ync4=rAwg*vdmV#!5=tRf! z0UA2RQa4B?x4C0W{0ePIe)mb9iyZHZF#gw(#J%j!1`s_=jfpt^TuOWiIfa(?h85c? z`NmNBL(BUYN-uPjbM%ofTB@X}>m}zO)OUwA;{6z$bc(0z@mkwI8I^628eo?SAwmt9 zk~P8DB8#M?B%zE!W7kNP3e`WxFgP~(@W|6b=owqe-ic!Cq`{9<|E)MwZ+b4%tG`ML zP$e@-82DRS?RpYvHf5PaqmFhxnpzlFH%av&=iRaohaHR?pJ)RZsUBEi5Z8)?} z8uPYRoh1>=6ckbfV&K0-9B-1wzl#e?sRCW@<)I{T{BNS+OOvpotIDpxj!wxnZco)5NLk9q$`@@giFg zG~a4zq>o0oYhyo(!Foe9NxxI=@JVREda0>~hX2yyGmYS%|I?8@EH*+%mc7EWUG@I0 zS4>Wd6VRlU(y&8R9jGgksS{jxX+*s|A>4)P)=CZc#r?29+e~36FFoDyedG7eCy@=( zgb%d-&*}CxrawUJH7Wls=-7vdvRRrKLPc@v&zPzFfh#K+K0Mtn57*Q63sZR zQsYu>T0HAMwnmw5onfKP(y=13gEaa%3cXPxzJmJ0V+%{5HPQ@+O3OuODN*+niQl4$ zJq~mV#%gKsag;oy4SvV%$*%B3aVC?9hZDgkaA>vEWQaz&9{A9O(fEz7VeL&GgE;>x_+hY zg^p~MG^vu3`?X*$Asp!~c zQuPXo{)vNkQ$2#~284op?7(BFq)i%hKD25axRBB&y?l|Q!g{}%#MVnSJzDKCr0QE! zDk0_!M_7qw>?VOt(qIFX!v4UTN*Z|8^yCjL_2iOSWxs=xdTN%f_PBd97G!#rHrL(o zDKHYcc{Cw!mZm>J^gb#WqKPb5%;va6~brSuFNbgzFBy3-u0>j3IcGl~4d$XFU zH28=%QZ)2SYV--jUTEv5qy8Hu2WDAEHR}quTDE%bRpp=bQg70G3Tn7r3L0>JgpGyN zOyh}G2>+N6H=1!mr#!(A9D8m)ZcCga%V}FiD3Tya~-b zOtOK8<7xz@<3w6!`tt|2dR|D%-#OxLoh-JZ9|?2`PJC(5CECpE$GO`uv-S8FmT#Lh zZU}KoXkRwD2byI@{ffHg3RDDGffU4L%w} z`F&eGXgoA4{XxVzSureu`4dBC2I$GmA1G=wgMXEWxRUl&lc*LfbEEzT0qY0*&s{M%_)k zPuKX0h>>xm*{J{3MAJ>#i&AeI>bBedJ1x6s)Ewx|Iz9KRFs-jxmyl+mW8WsEKMhU6 z+UZoS#3SsGdbjO;7*$?n`rG5^MI5iDYIeR})SmQz@AsZUqWj{~cUtvVx-V=BQ%N-D zsGHF7**JP9E<+=kNom$J@&`ISN0Yw7lzOjjTx{Y02&JoW>PsVat#-=z6uk9gl<3K? zEgVFChm?J1_}@YCg{k1jsGnl{Z%8N`aLG0rxLKq-bvvArvm!1|C)|CR^_ZMXgU@I+ z{Yf~#uhUbBtH&pdrxRGxqt$RkCB{C(@i{bFg=Z~gomMwC{WktVtEnJx0O6ZS{ID#9 zD%u>^mRr#-T)Ny8Q;PO#$SQGs@1o%=Ep%;Cz84qWLnABQR@3P@)5)qZ2`D1*RTeHm z)l&&Bh7JnHK62!*kbP1}Dzzgf8uq0gEV1N9Y%WR#{?_fO3E88m%W>>NN_J~wFC_Bg z1C;?JRp12Xqka>0`7Mf~sCbv*&mVrNuhrCCp76~WRz zccPlDrus%a(1MM_MqsvHeoNB-h2J}aM5owr?pYHc+ND$$f{7AGyB{6DA`TVkw^4GK zi5uLW>?M!l$e*XZ#l(Qt0SA~ZIQ_X1S*A@Xs&n0*rWeDaEQx#{>P1oNdk;lUN_)OV zmF0F;#R=^J9BrrSIx%&c9-=7`VP{Ly9hRQOu@h+YIj!F*#K`Y^$uk^R9ZE!BOelX~ zVp%aH;?FRxqk+MAVtJvvj{FSArdiU@T6KgZFE@pL!N?HSYIer;<8AF3ocaL@E80(? zgyjT2Lc{O3v*P?D{stGmXyP_^lldjjsg43u<&h+gZM_1GN)mDmMOmD<(~*Bb$8kc`UX?^cx;|Wb@(mw)QIwB0_Lo-ji$e!B|$@+X^GeB zWvxl2*Ds$+qBq6iOtfZIP@PT#zMylmXDBu{T(5E8%~~N##X>l%qUO=hY4n(twHT$ZR5izaJ;2w2i+-iv z^`iL?U3XHFjH90>VS!-$fJ1Yr_Oh0#Bd~kD5KhKd4qJBTJCF7$w7NP$4^}=f$1-50* zB#{Z0_?K4n2T4t%+RC8a;3zqC+&gjqlDJxg;;l4vvI+aky`B@CtaoNgc}GwGZK1c_ z)r|iN>R+p!bgt{pfSuOywvQs;A|jn_njfO@w6t&(RljO0PQnMz9^BMAF%BnR)69!dGU-nRyaZ3NynhJh>ln5>ywmWMMNZb;wfqYQ zVFdVFGvdU$nCgdvv18o@uJ~14{@QZ?2)rM1i-O9+@j3@V6}@Duo+PY0n#w3@cYCs4 z&k{#^(I*Wc_E)wvgq;i?HKa$eeuv|gaZz#Df0ym8K_lQZM=i1pTTZpAlk|s>Kh)8k z?sBl{C2i;k;(IisL`drIq_hZ?bdV^VhdQXRfWm4<67Ex#AN7ivX>lQ%`VZpSAjuPP zz@g|gT=`i)WZMD8Ek< zPR9dDGWMtAE6o!4>yjcS?!$>0l$?pDNo-#RR=8u?vhZs?VVdC|g7LA1uxBM&mcF0u zz`*JMjS8v@JI@t)e?-F%+US9VyHaJIj@lZk;iN>vyv_FmLMS9@W zv^Rhg*GB?-ZBmy-b?c?FxfZ$shxBTwK=NWz_G#(^*xD!!>DGo`Pn0J!=%{W!mQt=m z<=Y8N`>BJ>g9aSKP~jd`5lFd{5*DK~&IrP>WabqdET{50c)<5zWr`#Jg2u<H(N3d5&I7~yEw3)MO-6}axPdC~^7{T^zaeZUd_Lc_}) z@y4XOT8iF4={@e^g$nSF53DZ>h-D`N zV2kx~9RImWb_hI!J{Vl!rH)O~@$YIwj|)osGJ1qqKP9D`QNP6mR$Hn5C~n5}@BXJF z8`|9j9a*Jtzv@*<#gvry7IgA6L|7>e6?CLfvJjWAie!}{2cFaZ!{aaupRy8DlPa1% z@LWeabWIAF6jQ|S8Vvm*U=+U!n#dNEv_GB8AV0Kb1M{xgeA`2(@>RqUQt<-df zm|Un^v#KQpS03xG7mZhO^mb|L`&woWDb4Sz6t2O=3zFuqjvCVwmso-+nlEDdF7+?L zWB*_~Vo4nzV`&>CbeQ-FRjm;0Rl4&6cv0e8%UCBR;k~DY3Yr$Sx*YEjG`!2n3V$b* zl~Q~Z4L;;J{L8Xv61+hG2V=cB{JRlu#i_SL!OI-)Yp6UMSK6iG`*5t+Kq0;EQ%Cs0FV7&c z$1P>6)c+7MbsAq7jGdlV-$dg#Mzr--Y_;UHQhdmQj%gxhiY#ia3_i~7&PZud}%)1HL?FWcXMCU2Aqi>$z-*!rf*H;IJqP0C19 z|BdNJDcPfqNRY(zjCTNWOh;RbYTHR{U0fcRMafzk$RD2W4ldQCGUIsGpc9@Xo+b`rX{JAxNG(%Y!IpCzAS1)jlC4^^W2fM?RuPk!ZC5`NwCZj%bnBVpL_JtgRe z-^Uz8V=s@WlkMOdDRO{@La>#8V7i;gx|H`9J$|mOz%k5b?8y!_ecQEZ#}9$6U&BWX z_g4gMwl9g`DAo5cjj1TIze+B0m+)w6!nY9(dN?j^anJenk}@TUGw&qbKJX~kTP^y9 zRwD*Ue&2NAAzav-G!Hqxa-B9>C?-Z9#rFFK>BLoY$HO{S?5{^IgAF*8^~8zW%N2x! zpR-=>7t0&BBYUy&4~oxI^nZrwy0n+#+LsGGLlg4dxN0hm!9i_)_jKW`TJKZt0Au`- z5T~KhCBZ74hA+al$j|xLSmH(=|ds40jI}PYln8`1w-6! z$svVrCj=WQGl`X_K^qlTR?C&R-{lGaf<)j2H2TrFyh%(i(gRb<)M7j&SLjyJUu<{3 zSIflR&TPK$26nzoCbK^{>VtaZY)jYOsk8lw5qk?)*VVZLPKmB%tw04TE+y9YMzA0p zS-=*a=i5ruhPMw&o2arv(UwGlyHdV5u3h0s!xHjsIMhJnPq_omeBq2*@p+#dCG>LJ zcP2W<3PuVkX>?zV^THYYri7Zk%l6MgCte#A+AVnXH@&wivXG>1OR9cNc^%X4xcrSa z^r#Veqe}Ax?PAA!FRGeOBD>@2a76o4Ie+*nVY{lH6eLd-dhbLh+zop#7MxhpW-5M% zeLEt0iQ|16Ro!C=PbA>wmgHP%bY(*QKyWtV=#|uZOqDDwV>4;txOPdQcXm>J2&XTj{+G0({O+rSId#J0K6MB&u1_fcMA;K& z1yLy_C*sIogXQr!xh>&+&X(q)Hbr}? zFbeh`?7;H9|6*dC9haw|WRxDvK~|G}ZJXrNA4DxqGzHC_lRcjB&*B4M3GQ66XX;J`Kj6OZk39wf9GSr`z&) zl-ft#^RxVcWkPGM_pOxIN1W3V{sV%!8OLDZ_k=cWNS%6TMj#~mWkOCMxjcxTp}s-j ztW2DUO9#RHGUiq6y!q7Ur%NG~{?_4Ln=b~|D(4F>A$2L54 z$782AAy0F>XQRnq!TD%GQwvT(Pj)8JA4sZLQ+;}Ttp%GTLw+#S3Dx?7U>atz@PvTe|jsYX!Ap5cf&G--F-x6wj9IB+h!Pp$icVSS+^ zNI2bXNoOX+L)a*DkISP+QsS?E^%!E5+UgKg9S_Ri8~Vmz^dZOp8yb0i#J9lKs^NVc zDjWwdxgXdj2t(x`s(cYr_E-{L#jv+wchUQA?WD3g`Kin?RV1FB;y_O(pG8XHLLIWM zE|pHgr4>m97X7ay`$9{7P;_c_!&|CA-A!U|aprY>k`?|_OO+BBY_gayQpsC=$ zbb5;IA)@;}?xoasSf_P$ZWaAYxBsxvXjBP&FU7Bh)SfE$6^&bLIs1gIy~P%?s}=wK zk?3nx+7MhjE9otB5S$0V2VT*jinh5!=i@${AaU4Cy9kZ>nZTUFGs5jt2c3eG{gZyx z!55-Q!MJ?4B;SN%gR12@q^!8m3$5liY~ILzbO0wkXICpbgC#dR%G0Rd^~A_7VF#iM zDQuPPf}TwIEm)?e#HUgH=W*|^miwrmPRUieyv*^x>v;b_cKQt|psz5FA1+ueFo7_aTiVE zg}U~Zg~y_7^(IL)DV`b$gsR0~0oA}U z)obuRLMVQ~5j8yInTRGhzFK5#l!h*{vaox(R~S?$9jel9(~Zm1>Omp39mC{z(yQ9Z zWSIO|Cg>qWsv|i_T}_IBmmurrQt<+um<8=024p)%Wh^>(jR;8 zwa5l3@-e)Ay>GAZ1ndu|!m$)OM|Vz03X*7Skd6_vl)OaH4YknqiRb9r2Ns@)2DM2; zA~bR&s^(cw_H|Nz-^L$feX}&WMe%uJ;eA82V{lDTQvX*%e;M0rrE&Y+#mio|N_P8D ze`0Jd60Sj``?-g;BMNlAXP|r~j$f4Y4{!oY(DZ-D1DmBGo3Z7~mMY`mheZzjtDLZq zR}716mBtJw@+H+;btu%~_+CX7uoVwKGHR2Wey6^J|I?HGT6jM6WCx)q3mgmuwmb66 zXyQ=I_pudNE;SuP#TH%pS5#T!2(TEBJIdwmtUj59*Xe@#5yyMfFT)_1{ih>MK|^3o zF@r|RLZ(0Ep?J(j7!lfj(DTTfi%v~6+o&1J2qoAPT zkqpvFNqb65BlQ8|zqlLQje2H=~E`H8kE*c^D z{mYpaoaC3oZ-w&v4hqSj|I$<>o>KqR>F16Yi)Nd2%2`yH9Mtl)ZclcRu1~amQ_%=G z$84mkKkDgt|6Ju}@iJ8^qv*j-q5iApwNB8m}r6%fpr zWlSh4C>aGs6flbs#mhy}YZlR~*MJIQR#a4i3Woho@B4ng`~GS3+jYC2I^j9zIj7!B z{&d0S|FF zxd;8p;;)p^jV$^|T5NUH+4O{?ZEdC4^HvsnprEY;UhPPhP6`GzzJV4F{gk_*n%ZcZ zuQ=#kTD~0G^GOf_ci!S#&2Han`dd!bMQ_o=SB3)Pk`y3mk43IC$mp>4vV)?`9p#8~ zQgx`Jxvd~2GJQ4$X4ArBr?|ox+Gl~-JR+vvZs{Wyx1`yCPm=PDDRdBpH|ckeUFq7k zTll$|{9V;Rta*1<*db)!@tM|P@97i1ZzeZ41+yF!OE^Q-b=bba=s}1J*Y2Z2# z*zI9B7JA#%PW7{KG|k}9JUy1SE)-j?j|J-yNvZk4<(D-1GO7QCxgESq9K;}NsPPph%w9l8urL{NHXC~9ovUKd zyu|2U8UJ8K3pM$DI^^+?(3v#miKiY7_CMPoYeRZCCx%(^YiP!#BDacWA4pU!>xecH z%p}LnE0fv@w9g`unlKw=@q-uVi|jBdrCyjML#TI`sJ(0}UE46)4Ylc-KAILvUTOa3!0?{wtvXv2{FB=vcoZm)hft$T9lJln1uTN4aVn53kQ^5tP`-%$s8PcuSww4T;5r zCnx2Jw11ZoJ~U;pr>2ZwnLE}d z-{}LpHeduE3(VvUF5i$5m(n2tQ@Gg{uV%UDo5c;x+yfmzM_Wk8ooK5dH(kQ)ck<{# z!v#?dII_M*WQ`5#-SGWJ@{=M|KK@x_gb;xPoE8* zERODzu@H;_CHs^PUm6nUC-FN>J2|G!F~}KVcAtw{n0zHfUB#O{eKmw0&AayUEtOw#A_wCY@80rt`4wggzDO zsjV!vFhRHLV-LM7Gqg!Lh{t<7Qh`cKcpB>NN6^%WGJb{Ge|D#2|A7QlxYaw{CaV$1 z_)z&F0merE- zF26P7zfI?}3cboSr)0$2=^G_Hi38jh@+L z1x@o}N6b+P3Kh2`#6>g_Yec`WNXj9vX2h>)wk?TPAxAOdnY^^8TiyoFY!268f(l-6 zyWw?ht^y?Tj8^jyR|ZD@PF4vcUVoj%>M?z35D)T+Ec(+3u7I{6ZTp#<+hW?jsBlZc zuh+bnmY+`2Z&~oogmk5(^BPVTr9rIakF+w)HG3O!ZyR_l1Q`ECAP3-Qn8uq9NQVaB zmr&N)`U5NjO3k>T^a=}CIr0N^)Gc;kK?>KOW%l-*TH(%47a2MzIP|A%vp@?~&sy_q%M5ogfmyy-t*7*Ynd<6~IgwlvzF(mUwLzZ1s&B3R96^lnA$ zT_fl5>_J)ab0M>n*_S1>z4}4_u80>m8LQ0{@YoWS>pTr9WGCgb8u5CAk8$LwS#&YW zmtp?oeiZ$gX#?}ZtA^R)^F_cY_>67#rXI|Ec5NPw-ZAC5?Mg$9XL#&G7a)o})7>%r zPe=~5`)mdTqaf~|LHl)bzms@fgv=`V*0eTl=NzgS7EB!6C}|H=P^mzUWo?JKqT&jO z^AUBJrlnTbhS6wY1^-hqzcKYoe4X{M7ZURLq)+#+s-U+GWrm{-a@42k@O5bs>Y(ua z#hli`qk0B1XZds^`Gc*u(t+^YDDu&k`;_B%1<&KrX-P7Xmf(5UuE_{E|Dcf7P}BaV z{fC9f^GRHPf%$rBU^BDAk#DN<5axAc=3GduyouX8SaGVANN$A zHnY8RxJ>06Ayc+B*gw!YvI4>lV~axyuJ{|%Vak6k@;_t$irB)|~*6UTes|g$<#mjAHH2 zr{6J&Ct+3^$gRJVFu78k zFLrMEKc4Kv@fUz6n}^oQgoZh*=@Hid`jGfbl08bJ^Tp&%1|AjB%$hopwZLm^Pb)ha zUnDy3Mx;NQ(LNQ*TAVxRCR)iPtfiv!Q3Piiffg3WrRBJbFQCn%>$ZBgIJ9fqJam#L zb`+F4cR<>)Lr6vpdzuYnlF?H=ba*p8%Ca7CP>m{=b9<)^4cF>%p2$r7T30T(1hZ%| zDLsG^0MVhIXqy`EE=x~0OqlCAln$6Hf)sNeKtz6Q$FEfN1P|8Iih;uQPks7c6T@Q9 z*$`d8B}MK}t8*#rW4D%xg*h=i51Q6J&e`7J^h8eeidsu(G3i6 z)f)`!Xuk!`yEe>213m2pCHk!u+UMXmXxl_vc*_RnJ+Yr>d~A@zUGWbGy-tUP9aMI- z`XcerMLBh%>3gB5P9_`SOHybAZC)(qo+|2NEhv(ArdjP=9{x0i&!FkWVn^4m)#!0q zUJwZmt!Y^{`2LXiZj$}R_)^iDXON@eEBBNqvNE*6o=F=ZhF>B^{uz~)H_PD2uH_PR z66e$2X&;hM{r)I^t1Qi7FbO2@aLAR=H?zqqv1iw|)o8G%FDT$X+?wX7KL`zH7~xaw z#I0f&-hO^_sL66(aRh*5I?vu=Tl2--C{MfHRIX~3imnRf4jBD=93|jP^(^8wrrOpG zNiQIIN%n?raldx^#|V z-kcVXp>0b=zO!H)5|T$OF6LR|1a4oPBvYt;vk2;#_2@}ix;|nYQ6y#7zmOt7BpE1y zR*2*lgG{YS?^eZ5*78N#-I|vBLbw#gSuye7&2_m;m2NR{yCdF8n@1&r_t|V=O#Gru z?q}&)X>iG8Hsp}DHYUZowyj6=%VcCBQ0MVZNBLH8_8O7JHVm$+qday?GhJau*TeD% zsx0Bj3zK+>$WHP|#!}|A%8On3NS0ZY6`w-c*O_>#hpU!8zP0Y>WK|yiB_)lc13u#5 z$=3Ux?AK=Lpqk##)Rtr<3z_>_Vnk9vVezMKNCxrO(Pr+zo3ut8^m zL2jtYCl!^GSmWk2xfjaWM(Wd~&<6x_E%+~$OtBcuf89y@oRQFS-DT80>mG5~Zge@3AYIf=^ibGFRA#4s@%~M^QH~XFp z9K)I_@S@nNjJ98h{>l=QZCwsy<+1`maRfKsbcNNl4-AMNYdd=y$vaiwkxg{u6CJ$= z%<0(r2C-N_(-Ns7i<@8X{oV_>}(dB(c?DsT3h4wnj9I&on;1F~^ zNI%wiG7nvnlqXSRWXa;tPzW{lgUOu{A}5U1`&s4Kk=E9bQ9|nD?Kw zdTSbJZ6cWzhsXWA`O9{7gEVfVvxS$zo|ydX`6r)bx< z9q5EI{vjva#-nFDdo-vCW}mO zl?S=%5>}e-1Rh4I&zU>N1KPfNS^mB1d%1p&Tz4eZ2(Gu4Ig)Zs zS=yV^14d?>8@SLlZZWJScA`pQa%l&;z|&t*LgxjIF)sd&wp|cHhbNUyta`p@er!m~ z!}{m0`U4$$rK9ak!=z;T=A6DZ2vxC$xGw)-gm$C?oe+7=;%^0`XFWvMmIA|AZYqz? zNrFU~eG5ZHyY`|dWEnODTvSkpu-=o>;wO#_ZH(^|`g}NtHF9K)oX;A*PAfxP4O9oU zBpMQj16llAB^O%ksT_Wk_Ie^=J!C7Vxq(lssHee8j&f}VEvLgrC-E^Ut!vv}bdx96 zYkB++?tI}$4ailw^@<%X(o-(-*o#fU4OZ$ESF2H2XXL^p%5+-0#*+Y+J-wwvUHLSY zz21>tK+dPkS)D^YLb%%QTgpDenw=G=(*E=KAzhpIq7O~@yyk;dVHJ-D93_pCzc8o8 z7I7HPQ5f=XbgCI1?sJape|Tt}9o$=z?ybVhARw~mJBr3KJ(BV)NxirclY(%z5g$HK zS(8z6oX)qc-W24Qd(oAi_L5?52^ye_-$nb52$AE`^i7tW>6xDz3O-vP~vsftMkh5IEIM3MTz&QS} zLZB?O%H+#)UWZbdBz|g=2P;xXHMoc;KFIK9Wb9_ydIAGR zPgH!bwb2ar&I;>j)1}<}+NQ0IJNVLkIV}@4SS>;IN2pI z7IY)LHig+TNnGq{|5D6Ch(c#|KRswvh%8Sl@6}oSCQtd)5GO^@*)^c*!=R9LXj`bBM)V)9cmW*{F!dn?BNEm}mOw@7F6H4}DRKr4y^{nvrY$}q%V);q zHw$!3}v zye$!NlgbHhU~~olWk69)8I=_tq=TWw(U}4%hAmdg(x^QC4>vz{$bKO)#jtnVkrq1U zv9kDcQ)sZ2_}*2Ts63CS#w8=?(ahbR(qyTt+F_Tkeljaf$^>3S=`NOh(34N8hsl$E z^D8QFYimlmg7&$R!!VgGZZ)M^Mf#|yt>%%}GFBeN1cOb0g-4JncSEwyv`QKAS(;kJ zgV);ZsS?U}Kflr?gB)5g7?cpNlhnIC0=I@7&aEwNb8tzo^#F z#!Cz=RdBslz-K_I$PvEDXd%w}+VY?{`pgsmP)SeA*zSri&}vURvCTF>Pq*E}HkUqh zluA~3lD2PlVDCAMVAjMN%J}M>xP{ZN9eJM+9dD!#*m@s2;i9rCG>6t&#X~YuFDg&t z&Z$Y-Nqax+Ln5EnF4g;Fpp{vvriINY@f}P2mP0p${aPqMBJ=Q1DR~wh@Pj{oQS%{r z!ox=twO_dYZbqq~XwERHO{K8-wCAT^Su4K45niRSH9UN`tydb+Bi+xTI_Nm+78WZf z)mf63FO%Cnw2_-*+(7*{SDS2@X3{*!$D}6S@3EH^YgbtQvdUD}|BaBaHA&xQ;Riek zJlXF}4m4PJ)(lO}dN~&P$799j(F8^R{}cfgwh`m)Fl?QSf9h zyD%)OA8cy_;*gt&f2+{Zk+lr4scPO%{=;UcyMfa@66ew+SN`0etR4)F2PpV=Z5tv! z;^~j)6tLgV9buo4I^VGGPMHVQ>G5OA>fb%hiB|aNjMAsOHxu@E2J~F-DQ%WAx-WU5 zs-DBVC(`U)1o}&Bw+|6~Zm5z(C9bVb!)n6;`~8~#5b+~Z+E$MBFY3E^sHdwnq3{4B zak6b|VKl_^yJ81f@re#}1!HG(^AVd`^+r6{^Q)OK(=^VZU$fw#q;iv_HI(rqIi-)O z<=wzaSD9u+o08!peTaqt*b1+ z;QT|q*fS+Om*uYU+X%8~7_By1Vvr$T@YTFDlO+Z^(($g=$Iw5qrG9Z?pvS&gZ3+ zq4ebA%jBn?*5MW~au6=bS8)4=BtDyFSPAuo_}@%cR^dqWde9YLM{#7>pXbo*F#gi# zCQ*>0J)DLeZT(L&VM1oCxZRZBD~C@gDDU%FryD3Dw-47Q+Xg^#sMj6;r&#gReBEN= zL2m7_gSAF-DA@L(vUt=`9?D4M*@waAaM^#F(qt>}1Oiw<-VqbcsB}P^>lX@DO z$~@sYcpmL}LPGg1Phrj3ma?{rSr2j?b?_{jKi!6=@>Fp>uoo|Qb_w6f8lF$%VGau# z)>AfFZs5^g=#sp+lqDM+&>gF@4fA-LfFnE7W1>b-F!);mBwxMf*w(D1db&H}I4>0A z@U=SYQVz_gb%7&o0*l@@ReaUcp3X_4r5$J^U4n~w?8%gNI32&YjBpdbJp`v7w^I2G z?mU`g7tp>Rc(~P);M0Ss2CTONhZ}_?!+k7=XZ8rXsA*DTi3}pjP!1mzQ~bQ8GLM`kou6if#$Lsze@);KPebmJRtWDQ!=} z>bb=3A~-U9X^os)gmKUMpy$%^_bC~g=O>o&?l^hBS#oq3Sc&Y+lchc+?74#SNJiLS zmY-(Ud6onM;<>auE=f8U{Wm4sa_N=e$YzR9%4Cukda(p@*z`dTIm}W1WZbp&+YM=g z7Yyg6wJdp}gS9NK8L9qh)F0yiXs~~c7(soui$9}1!LfXt#EowIX&y~*>90tS&m8&R zv|q(xg)}soXZqTwM|1K#OFwgQlZbNP8sTe`^c6KQBPA}Z%t79`OlIBd> z>%1cBXF)>SHnyr?#~NUQdo!|shGU&W*Vlbd2F1zfBvXqz>I&NShCd=RQ~c7DE-0(f z0{;#~YA$LzqcJRrfsCL%?PHB~&clCd=>;Xr( zUQ%-v@wS})wnaM@AKl>^{dnw^6b!P0)yxz>Eu#9rmEcb?)K!29)j^3A{x+#@0d80n zzc6sICLO2-;rSPEcrtV!3twEsU&sCTZ_vpxod204D{1Qu3D_;5F31R%HsVj1vBlIk zWYIj@a)BTJ7l@BSO6Ku+S%Tq2C>fpRC{cs`%a(69@adjX-g zHO0{xo*K}kLQuci1vzXD)|wF)?RCi6o|)j}i%8&eCkVBPToyI@DcJ(}llaV>Rtth> zD=H|n(};{n>Er1M&lZJf$(j@5t9lb~WVdts#w5Rr=6*VD&>)L6*QEM!Recs~4LEo+ zvi7j#*EwNs7>&3L^3JGZn%fJ)y|n*xe*9k`er1v~$}Crqvu32(MI~6E#;vtBqhay9 zZma2S>E}DrZfeixb}32M715>LL8sKJeC}$Ov&`KYakiv9?Flz}$~i&p_I9;C+$BSK zL3fl+I=pMc0&!tcd_#$>jiDRo8hu#5@6&QRqk~4C zRpjsdHgrQ;m%?Uvb^}>WTc1rRU*@%2GQy@RF%11Jlj~V17kQV1mU!11uoBrQvtt`^ z$fyT@PfHhrD8i5tj3XJiURHj}DYn7KIdDOSJkDTu!nA!HUE+y?CS4GuFS@XpvuRui z;w$Ot1}^qO4p;7Mk$-pe9kg#UOAkuPUE9`(4;RJTbL#6srL|q*DE6HZeINz8-s6@Q z#V?D}>QL4!(O$H!%;(OP$0M*SwK%ZPO9oxvz|R1;SChp%~HR2L&7eDN^JBq z9vSTf9;JO(_>im-e>6$ovW^R?Vuq)12i&|$NDGH z+9K2kmchTl{|9~ETWPIlq*GXI3A6@ZnEu}x_DFpt@MEODsAmr5T&7SRmq8yVfRcyzN2V9 z7z!>Zp;jub=joS|>U>%@8v{cuBG-i5s(dl4eU*V6Ao_Q=RQ2Yt2m}{kx{GsImHaeq zUBcb2&CiJ6nvzvk@6D@WGqT>r15kLSk$%%QlyDu*>&9u8C0z@$K^FOe2Y*Z|6AID- z&+iBHZkOMwT8mlc!ZeyKNfQe4Q#s>bAv~bHQ_p}T*j|$golE<6ZFojJu^_#rn9z7# zS&$E5EqWS<9r+f6k1qsv8u-Zy9$C;wvzAgu*x?!`H%FDwcd-BP-U=@2(!*wWk)u3K zn_q_RdqICO(=o3iK{W@2rm#ixVcK-2PcYvU*U9paCF7n(=@%me#jI;#SjSL)vGtV( zndcdIOE(m5Y7_^G&f-L2EtkhT)JN9zt2@?hbSGv*@Yd18y!xhK1>C&7_U0Z}Y^4Bvf<; zHI>K!3s0#Kx1`+7YOiI)O(@u(hpsCH=7q)a6>yKy&76(Rpyz1&M?SxNQ`}`rv&zc5 z^}LWbBa>aB7pRtb?0uW@FeZ(DMx3>*t&W13A(-)zY4M#RTGQ?29&VTJshQWY#m4jNItp=VD`%!dS& zM2SBQ`}i!mkRJ9x#dy3J3PjX>&A1PhxAS=1-`db}amPUiTV$VyBP9@$l}uN73k9p3 z9#RV27RK9sS{RL(+MRWmyhM9l1%ou3KNEj8$sHbjDlhai!-A{!M)n^@;%6In4~fr~ zefDyb6?x5(8Dp>T*ytobKL_Uo5<+xBU-`SLeiLhi&Cl0M@jUi0RWhLf;tV84p(q`Z=t!))5|a^`H?y zxQutifxY3pF7>w}OEcnYw8^m9=z=~WBi-)F$8mC~Md2`Pq~60R`LX}w$S%8n7C5qf zkU2|3JPatk&JE3#MmgHihW?7J+-1~pyiBk2$QPVVcX2HvpKHW%QZnM`K~D#arbo!= z42<9PUJ)W6Ct)fn@UX{|T*|aaJFAAk+BT<^Nonw8`@}=Mzzi_Kh;mgkD2rmS%IC%c zx{QuID;Id8NMDI)y_>~$D)qB0&0%Y3bwNjRh*c+-dg8we+TE|ApsX00Q0lQb zj3#ws_ldhr@_-jQ*;5ZOS;YrxZD@AItD_G^pG`&%hp3VtM386?Gt(dLusM0u(-jWW@r64Td zC(i4zwkYN)o`_56Qq~A^I}nXeF!#T8;i_Ujh+)&3<%#Y*H_hbcK zy3e$saq|{!KG>#r71+s{z+f+QG{=8g@}~~^7cCwO6_Z^Geo9u#o-(rTDMy*~SXY|h z(12l_o0P$9f@SmeoIKG~?{I}bT;)8Y@sy-YCLK<;HlN=*h1fI6#Qr-drJwA^FmjZ#JMbgUYb1O;-cYR z+9>{D5VNdp%EQ+E+)J)-wyR~0hSMwB);JK{P)R3CE&jVJ{D-z4Wh<)+=8TMRxECJ9 zL2AjqsKdrBnjZuy)2<}`hb*1wsV92MHdEQ)l9i5hAG6L*N&v~Lo^?eIGEn`7R%0vl zuQ&xE4vGt#JPB*$7JmzxT425PlnEkTC|YCBH4*Q6<@8+;_A&Gx8$;)2w(VXB|O1YK5UZWq3^x0_= z38Syd;QG)*exBDAt%(k*$cFyU#$k0vQQtNy-1my_)ty_L>_|6e*gS)` zl*O%a@kB4|>G(-2_?C-5qRsUeZS}qazd9ov@9|?fP6ajSg}g;eXF6oulK-Y;-~W9* zc(NwAd5)w!G}Y72^;6Z(u^E*bP;^895&Y+QIed;qZ)s(xxVVi+<|ZW)N2iwsS;PN{ z34xl@lU0VK!v9WEfM|b_q#^zXTZmSqpy0e9BYo|{0@)@U%Za~v>R}0qv`AsZ+Bxj? zAxr3CP9x|~J4+2iww7VmMmp6>9^|O2X!!RIdxRz3SQbMC>2Vf06Na@22LJazRx{pD zq@s;x>^evJoVLHh&92Q&_}A_R=FGZht+CW%t2hXScN+1TDLMSV?uo;_ORHWBu0@FMTJXto#esIK3XjyS!aCsQsAWL61qVqiMYfJsPH%(@=S6Td3 zM_=RLQQSE{M*=}OY{M>fl_Pn4Q%c?+L$?-@s^PC=fs^YcsTZrvNa`{d9CMRI?_2cQ9kdYKs7&bQH{pD)9c9-n55Cp5|fsQj*J zzv*bpsa5C%M<$OeOO*n7A4Y;*;R6I0iX`@S=(mN%&TdGKGDCCgj=q!j-^*dg-!Oc@ zBrg=DJM+T9L3v)g*ayYFG!he1C>ll&cYk{B7vH4}lcHt_Hn#h&x>JOeAM@V|;^bxv9q)Pk+(YF7gP z6Z<=bev65VikN74bqq-*0+RSCDc0W=PxhP2oef;xStWC!UCNpcWYk6%n#$wx$_61- zQP=vA6dO>On(@c7Y$ZKpnh#0z!7SNWRR&V&S2J-@mcp$#$9AShT4aic#e!5c_|J~; z36kqQc(PZAu{11R(2dDhlg)DI&$QnGKi-eW`%P(eQCa5EAA-t3?YJLGeQ%`hg}II} zy0Zu&4|RsEUhP7ONf9$~X;M2aYxFGtkCn*VsxbAP`zr&|OMFEGem|#S9}*xmCWNj# zGx$O3)w?!~$NkH~dkVkK6ZzfJPngb$kLW}zR3_8aMKhlU_ zj-#0#uIXehWa+NDn?eq&zE+f1W`F{kM|1L8khQsFCoRK;i+}zfM@HIi1V=UvVvXEc zP;RJu>i3p>WH0rwjJU=ir>3=s417XCg&O2RA!S`}mdfa55S2P;Ukpts2#}K9P?Oq9 z{KNjF4dfy>X=@LdJopY{692{gJ;V4j9A$%yY2@qGzlM+L)Z{$f*W&#Mp9 z!y^7Citfz{H`Nao z)@t(W9JHUdJq}Yzo2TKwO){!r-tVbPLUL<+=MgCJlacMw!^%K0v*2^cNnvw9yWlbD z4{oi8{UTYVts@7|w^RtJ7tF_4;~@<`M)zmMCrbd3uw0Fxmn&pjmA%As>ofX#3U~WV z!{3y^bc{k-e5MgUYN(*(IKyF6jPxs|!0(1QwUOMFW19>ME);#zmCrG(+Z&aQakRjb zd+Fo~i+D;#*G z8k!B=)eL^bz!MA7Y7Ykc$kcY$FGK${!gr;lJux`#osuSPsNg9z^>~(TOj`vPip+sh zXE4X*dn(u{D2KAro(2?z8*H}Kao?P`k`Umr%$u>tKclsM=JLL#Eq=K7Dl$)6?Sy)~Kmz31;!jkZTLO&_drH#16<++Y@ zsH2>1#AcQP5MY*h{DGYAakK6!n_S~;BYS6~_Cg%p<{2%zWLwftZe0{v^MVlkCFGY1u*uF!GR+aIdHRY>^ecBahXL*^IrN)*dxTzM^|Y{7+xX z;I-F6`wcsl6@Q4K1szdEBQO*6Sc!D9ax$&I<7kuJz$qQUB9}bqIOnx7%xlZk#qloG z{TJfxSz&NRS)LH~dgKVi9y6miXOxX}=s6|dn*|z#-5wcC1OrcFh~P^&)zzjXR*l{NntIQ`(`4n$q4s*)))xT+BdPcr` z>3`F*GkeShZ+0(+vdrrqS?3wMEF5b=!)xJrj6de$Ck^TF9NL`|J0bv4k8~}hfnQG{ zSd})tBcW=fesC1c=iK z{>sRlpARexi}(1Y;b{FVGumELIO`WNp*M3c#uo19NvC?orU?9d$4HcbhT8rHIT#iW z^8hupH$tX2lSU>DwXEOL+SwU-S%(eJkN5EQy!9{EI4ld!OrF=h5KxUkLq{A{h@{Nw z!i>C`!i`w>`Vf7t@Rz*ct%W*X&b5gyhUEum8qPb3{2vB>!jp~y)qqJaaK)Egoae^2 zvh++Gz2NEXI%J)|`-Ko|+nV$tf-8WZ@f7)yH6qw{n4EE7mzy$1xC9}N)41p$+_WpGu|m8Qg9!Djt0 zG$Ae9;G50XM)aL0FNu;}&3GtE+dTG=i;b`_5QI-X&>K;5VY6Iek_R1AN4+Q`tnKi{ zW_>+lW!`+7<-Y)lq9m>MH=6~e2pZ<`2?gew<*ze!^tSKGHefhJ+ZFz{XMmD)Iag=8 z(pn!9`{TqLe;N3B&sdd1%S<|?ReQ@-VdhhBWcSAfP<=G%QcD;gSEDxTb9u@i*oSV} zD_(FSC$l1YR~7b5dCd-R{w;W;OulFk<`l_Zi~QP*deoe&>x^BNHr5$3qH0ee5Gigdg=+DwSp^mx#*G%h6%UbiLSp5{FY~& z?&;T<%0;bozpE8_^tZCHI*tZGxm+iIgd*Qol?FDrD+!($t<4C37p0T9?{?LqmVqOY zCL?b>2G#%n#c@x4cnf&4&+$KH>B9yzy@>Z&@_}ag`zmiT;zdV#(!ifKkbeQejELVf zOY5uQUcLxe_)iR_yCFKov#u;l>sa{fG=I>Mnq87?6sla(%6MQ=e1O?2oWM*MHe-H{ z8?)&03YwQdCxZU^2vL8_3h5b`%N_B3#`k2jK{&$;4W*J5OnmJq@6dt2Cc2KZe1dy# zj$B}|DQ)O1B7bQBEe)>p!+9tC)WzL|xQRuYOb9lgW7(3fY!Cw#a-|(0E#fc~IgHy^ zx>ODea-(lG@MC66U2bILEGt}dq#+qe?gY+?t|;rdytb8Pu5|ohv)_;ZQ63Rb^Mcia znKe^)JNg&C)qIWvMd3TeKl8U1#N`}-@7M~y%!qU)y1;7Sc_-9#ENMtPWf`TBr&3k( zuDH0Ph{0->g`^tHfAnNMos?hiemEmsTZ9FpQlzJ>72&Yu`e&7{UBCKf^HYPL!~AMV z9X0LqYPx8cqGN0{#KjHh^KPqw_`ker9B*0?N821j|0)M`4NotV2TL$QYyFr`Om`$u z#5`RN^yIQsmM4_)Yb-ns_OGq=&E{838_-o1`I-cLdh;kzJwB+8&!{kl`>DUz--qN} zFMKeS;=u@1hCikQ|4ej^^&zP|&`ogPZTBbjvI>9!|SGzbyO5aYr9#?jvV|$CqPoS!W$g%p$x8d`oU#YSxV(2 zDMK04;6rk&Z#4i3KF5OvE-HCeCg~jd>ok18l5VZZpH(T`vkIGSHX3+%Ht=l@U*gAm^ib8b%`|n; z%P};)EI_AF> zCxi<V5a7xFzau+g*L-kfDe{6W-ISFA zF72*hR+L7v)YlEDYgaQsB9F_4`*)!I7T!|94;0uY*grhem0vLM zGZ|rBiChs8pQ(^d)kw@t{M$kQh@odo0;FV%J?VjpyxGvEITR*eu5}bpt+#UNkg|AX zqxhm>%yy;c{jy9m*#S2yHIfSw0{qO8qA|}hesswn^blO|V@s+*SmA|6QYjgVLKX4X zI_;OVyH2!#^rFW+S?nez=M(80BiEyc18ta&?jH+=NwAqrgt>YPRxmUZYLRC$cxNNJ z$QCZEkcn8o#k4O1-w;9%`5YFBd0|pTf-E_0S^F~lu!6X(6J|QmB2T|37bcu7aHSKQlX`AXB;>%cW9ut2_rj@<2rp0&FK zF6Jv@pCTCtu(ZqX*UUXeqN5tRu6rv$FI~DJEWJ|zm2%DOzWw2hj31~baXh_3KFpKR zEPbtu>Rr2rlT9+YB&+l-Nxxh8$O`!;ufN3H*D?r9ylco$OnT-J5kVU)E#YNN$A6gSjLG)y%*=}UG)_g8koZg2o2^pVu0mN z&m1LcuR&H+Q~sv)!42K3;NlI?aFY(D^74??S_}T+UkBDT$rAtLp*4BD$tSp-(~0zZ zcUrbEjDGbOg+`wZOSxug8nXsjkSPxbSR^NhUvJdTwF7%Sd;-?qHd7a6*zY0XMn5Bm zyI2H}-W8cN#xh{9;_7T2o!R{lcYEf;Ipadk;xHU1NgMORWqAQ&{u@3#W6)1b9mwYy}FS9#I_8lps^P2R=+usI zt1k79kOR#UD3NR3cciss>e_i7VF)n4c~~o8xJToMJYI0yf4$lGFBgJ0n?PQcr90r_ z(~jg{mh_%SJ}!vsSz?BRH^Fp)&$I$FBfgySqJmX58y;`dGKG2yE#+Ss=B7MJ^jftp3Ye9vzRqU?Q zEb@MX@~NlnkBF!R%^(V_2!!}@V;Ge@c;)D^QM{=+H-{OMtVq3U^K=riBq1xEQHh>u z2L^cjM69)0*;Ng~4$p8 zxfx0TXDed)CK!V?T30&WNuX_-#LxD_$SLhj{wvg4%3W2WMbieI1%g0@LuD zo^_O`9pGez%U3vfC5S>3U46Oyh9{4PDxOKlx2o%!fxTQs_T&ObH!7zlgdrt-xJV-r zO{f`BHvU_mi$`IfQlNxKQ03x?`C6+MX8ph{PPfQ?jqJOecpxIa+KewCYMO(UDv{?3fwq$wT%HLpn9obF_C<1WfmOOTTt!~Z z3E$Th{B8p}vna0Q^6qB&kE%7=PZ&Wbj=LJf&vVMeAo-?QF?$Ak^Vqs-UXk$w*}%>Y zI=flaAmFrQ57bMt>G&MTIMTKxaul__8B4h0~+p_-B~?nlL90r*4SRYw~<=SG!(KUsuoG z8V5QyQYCPpl?k43Orh6wVvjWNkvbVC+j{zSaAk%U-K{a(J4kz)%(ep$vor00U6Kcx zXn7XWvY-;vAm8xh>Z#Lf5BDyTSd;~|K>m{wyUeZ2${qcGTVoF9sYBrO{ov9MJlPq( z7`wh8ini4zI73sYa|`<_oNU&hdHFD#(%5>7{ky=8PEwP+=rBh7O*1ZP5WbF}w`=_I zaSjaN!c8*QOAj|U2+Qp%#X?=^W0JbUi>v;m7BA(vi8lShNLh-Zhq8FJ4J)wlmD;zL zp_+M^?P*ho1s2<(Bjd;#g}E{n%W^-<@cUt?{4Dzx&wS}p?JMHn8Ykz) zgLdrfa1@%PuZ5XAeK}*iC`RAsPj}Tds(A}+3B>WOJ|yrXD14=(3e&HXa7Bagep(We zZ4g_a>ptI$Pt>{ZI*2bd1CRV!w$ToBsg~q3P4qw(okPp3qmlMGsYUMT*nZ?5O8nCk zr-X#xO44tx+AKpOzA{;3uCdU2HBSbgVh(7@`WiL*tSFw6M-Lc*bNxG*eP5Ni$NifB zS(a#Qe+yR%;;1B=>*)|%R%ywTGSdDCg8CNvpZHYAo9hKzWZ^13oNN%M*_2p=W)@NB5L?0Hoe=IiKngK|LmZeIT zJ2y7w)K&^=M@wjAF>KIQXT)|@ALHAnXeiG9n$Ave(#D2@SZ zlExmgsD>i{M+{zT1+3;?UtPkP62*}`dcg?74O(~-ugKh!S_0z#Zni;VLCEv9f&fxn zSNWbycuNyUX889asEc1S;yE^Zg{L&jKeY7L@uU2&JqpBVv;b>$w8|Jh=O zj-a_18sy4v*rC}G9`?n~mPy;z-7NHX0ixN2Z)&Z3SP@Pu^GmYyx^Ol175?i6}XLI zVYDCrzXYpchq~026^YULMfu>Hw(_qqKeOJC|BWtl-cV{uj5(0wUUHNNRUHH~7sRV{ z!1Z&ov91Jz(!XGC-GO+emci-(naRUFWd;vnm*u zJ_X`G%sgK(LT9JYgGKQznSIZ%`M+cxjT_=090~UanJ_Ohk`c^^2m<{dM)04tEcp>z zzTH#W$wE^^-c<^pVKY_@l6;Zb>e6b|_rc3Jc6}{%2djZb+{d<5i1J1=GeSYLP{6K}_bQWj~AKOAo5suf> zZ-v=k9rohtQ0kT#4UhPU6TVlCY^i4!#+gk}dPy+bgauKNQn}+D#5HB5Q(A<218U8G zV0!H0Cv@?{PW+F4mVA_*XHnBjN+*+gtW`ga4y}qMPAYRFf@tO+~VhrP`?!LJJ>g6W~&B_<)f^n zahLji$4b8>y3dP_X2cgY{-=_$H-dXw5T9^^E#2?ISucKnM0vf$jj`#L|BEe^=WJnL ztxIb$BJtd;UnKt(3$nZcn4jm0BMwu zyZCa2d$<8zwfw(nS@pK2<>1YN+#5VcyJ)h5X&oAouqr9vs0eR@P-vKi0{kL}xiQAf z$#FM2L0wbFm)Uu7ak_(|68nOO*Lec1G95ZH4>YmCwA3!y)=L38I{ma4c~a-QcBT(D zLXSDfHCchnOQ9x{n%3GdfDXMK6Hls^#R>8W`5I2AWb`XqZJ1#0^SDJhZk+7Yycu&@ zhVGqX|Ac_&(U-C8Hr4NFj*FrZ4tO)AdkVo&_f?r@bqF{?E~9Z55d2;q^-3b3%8p`! zQ+>jy@?Hd=@Axn!?BHWwxPvSlkHU4kvb4-X9cwtX*yu)=zrk+{wgOH~HJpw|@l+3g zX|u~>{NZM4jvQ;-8stO^9ToToeLVTE(Wz6|GdaTY|>9Nnd z;qIz=QrW+aJlmmq1i1~+3(AQ{6+Yb{Lj0rPrrU>RdaA-c&!Nmjo(wD?tXmX{;<)DFc;VP1)bS)Q>^U(@Spx9fu*Hz5%RLu^Z+^-H-umE z++}j7p9nlFBan%#Z?*e{_z@o0Ez4dk6M$qIFk~{VI|}@tF?@o@UCQ#mtI%4~$3zhn zxZ4aFAnD=7Uz6Fm4zj)t9K;t0tnCYOOOkrti-I#dF{Y-<;_e8pCTo{2-?l<8c|u27 z7!eDeQkFJb)CtKIfYp(Ls5F;igT5iYoMq4AXyPw4yV8JZ-xh>!=#%mi4ZnKhx@)e=$z8W)$oup#C{qmqGWK&kAX%{;8$TvUHoj`C`q{*aaE0AEZ<)9Gv#xmXl@ogYsj5aK>AI+A+zmu$duc2 zvD!E-oUeupN$M3ZI)dTH#f)twX)i2%*M`b7tk4eMOt^bu!J%2<72iZF07*w1{b8$1 z4CeV};U12Ax(3PND4J4W_S$OyIMY(#R``&#=WZeB4}rgch_AQC)+xdno`l>WOycJe z%24R(8EV>yYIuUq!pQkq*Em^COfE+n6ZCmm)HBFVbfuxtD)fis@M|f#E(lY=*$Vr< zr=8=e5sk@o2<7kjuP1BQcO^KozF;-1;YjdzC7s>jDL2_loyK$lJAA*Ug8j8#5~m-sQBvaGu~<6CQ7Ut+S@^vadnyHitrkH(oAcVhO}RYo#= z_gIQ93wt6M7El0+r9}KbOLvypt!24uR@>nxAU;H90Yx0)UW5IrnP1NFSJWW-If~T+ zde)YsY4lceaH||{+uE0_4kYML!Jpo+l_X#k$b&|P-W0Y^A;?geT$Z_RxB?K3^~BqO zIS7K-9PpgdP&s=vDQ%X#*n7;g0-FXOJ&0Caso6o2aCmyJ*< zg<8GnTQYZsZ#KiZxW=4g2lnNpbduVT6^Ao?b4+i^g}{@YTZ3dG5pT#con-E}lE`I4 zxB0zUACfoofuo*up8;R95v=Ca8YG9JxcXEczi3N#+PAK6>n1qdMu-IL&~gFR(7Stm`x3U5r9P>8<*PZ zL!w8^@wNj~xjLeJT9U&inw1AD316RMkLN+_)I8?*;*35G@z$rS9nJ~~Qa*HLmi<$f zk7NRKHTFRl9v9CT^h}Rmz;g37_*{DbC>m+eTa8dIg{FD>PFYx>L(hLI7uD#H9q3+) zb4he}mH{it#Zpi^z8%53-&(*^h;N?|TQX%4>e$tOZ^nmYYCaGuR@K#p|NU2ST+qiP z`Arm!%j11e^QTeMtEF_9Yuh@N`#d8YgEndwomr{hpz#0Xg#EVoWVr5&jFeI6J6ybb zXn2y&&iACbuKbSLu(lk{CW13v)GNqtazdAR(UVlJPiJvLSLw&J2y@Rl3j1u9z0#{j z_UU+02kD*v@nnHXtHG09#X&XG!4|lrZ#Iu-xtoEiuJc_w^Lv3NZL^<@pyvAh3I16- z9Eb?dHt}QNz@3HaB`#>Q6I_~CS*0w!R*LR}of8WV`f?u=WVSZE=tC4Q`4C;jRX>Bv z)uk|NA~TO*Ty}1bJGlTy!?Z6mKu0se4e_O0(Ago5&xa;w`7vSf*9J`QH7T#)vNeU=xu{UMmR~^_gS8)-Ie$S%MF2&j?Gh5Ot!?yqFV4xbk;u z>ZNkTNpRJYi%twezel*i3!bKOM?3ImbrmMTHN<4wJcVs_rNy4E!>iOe(spPmcrutC zh>7I!h|UgngZpfHR)lHSxw0qBy=&3l2x@u^o#*nKZE2lf6ze162>R$?HM0qKo{IpI z4~xu++0aL+;BpHbnNa zM>9Z$Fm}~zzdYtcax@p5k>}y~%Rd=vj>g3-^cd*y#pr81;SyH(!RKD+J)#&!(a#yO zokBNyi8o}iUj$OJrJStM%Pet139dUQsj)6Qis7fn>dhSUS_I!!t7bmU0CA|&P3AWj zSw71HXXihV479oTA?Y-jn~UrUj{Q9YzbEu*6mQOL>VL=tN$WsA3XY`b*>ODHqEb+}WbjP4N`+K*Xp#HU4XSDRTni0QgpC<= zVlMQw&YV+ZPc0|f4m`@yB%UdU|4HDBbC8k+VSlTo$Y&Mk00T|TSX3Wf`WPA*0-iwV zqAZtJq$okNHMSq2uW<0O7{1%%=CNF_h!073cvKER5^hML6<#&AL*}1|fG2yDlQep; zMa?NCFvR;J8qElnp}mq5UW=gfYLG0>1Q)jkyUM}|MecJa)W!E?7FfwO{-gk{HRy1W zTj@J8h+*X8C|c}5&w&r7(J@c#9cJ3LKFVpt07%Yo@id3ptO!}qpL@p+j#OkgOy(%` zQw}}Lp=Rjpu#nT-KHgeoAE=`F4uSCIYp65auowleOO3|YxwF2f2j4;=TtaU># zMR45m_-=JB1W26Db zG7jn=6e707=7cjOpNA0}6N=z=@UN`w9B4cAE?5pb6ZW4v zCx1`t>`t2{EtY@$Yi=gzsBc!e$6y=}(KNXQe?NEJ6wvfy6%0 zy;`q+VO9o&xXoVZXjZCM`Hns=%&8W-A;hQ<+-Dtf`Oj0l<5FFE?92>RHM>KJE&D_co-nLEXk8p_ge-kQn(lU8tC(a#l(-H-z~_|pQXrqRh>>J;B}-sL)z1SJX&In;Ni@|+@U z_rz;#?OavtPU;E@U3RGJ9BQu4*5$c-Txoz7Pc}x=2|DPYvw$IEg|@?fpUSE&05A8h zuWa6>sxa4A^K9=dYeewzW~%Mb*W5my-Bhczh|V0a8R9Va8uXrK@ttt+J^w|fM#k{I z0@J~PrXhPQFBIbZW5l+D6j)#_Sj$lCOPdb{`1h43jvrwA#kKXZ7?v%3E#_s%k&|6 zD~cv(Q6bMMX*AGF_wX&{YpyRz92dB_gMKuH8YI$!G=m|Xc^Z+39j zL*UJhaUb*S%f59~8X$AF>4GDa;`qg8aaUNX<(7DGj0Se{We#^w9HzZA9G9O-s0N80 zMudH>e!Mx$OPDU4Cr~GlDjKM8!!y)Pt@Ur{?0KFsKL=EdV_a`y%qXjS6S|j0XVD6{ zm<2ih7B$$H_&ETngF~4L&6uiEI}6l~$LdHh!GAOJwr#m2p|3|P&t&3xM-ng4+2Zt^RwR##`Au-J`RT#Vzto1wsz zM%4BY&Wj|J?1>@rSLatQ`c220Y>O8Rx3 z8RJFExk%dqnLn2#t}ll_N}wY~Bq-=ji8mm)vMOKjIf zP#~GA(X(x8M@~2r12!W)pXHXt@>ENdC#`gPq_o@-7rD0Lf8T_+^+MU?zFe zY7RaWI80-E6zy~I;)1}X(PYo*=V!_?Kc0k<$Sty|f17mmMSohWOts~IG-(2<_Z03z zoBAhD&#F~}pW9kS4_?q1H4;`o8x0O}Tm9ssGE8NswdWi1_?1+sY~!lJ9rKyUNcGb) z5GW`79-hC;xAO`>ve9BnIkr^W6ni@yBK}|zpA$n*<^$D&6H3*gQwrFQ%YSB&Bf;BL zDO8Z6vTk1d)DGIo(6LM$V*b+^+_{p5;4;HgPsu^ePx!GUzN#EPoS^PG9WisbM;EF~O5G`UJmR41F6z%d&L!VwQJ6nqf||If`LM zv&9Jil|;8@K}m{jD*+^g7c}~KCV8k7J8pUl@?a%=w|rz@iC!N;|76bFoyMm(1TV{?6UATlac#7cEcH^r$`)HQ^6oy*5IHys^30M|JgM#d2A`OJ; zpvp9tX$zcJDty>NS1YigAPj14myCdMhPMBYBTMdm7#vv#ejm??RX-A9zz8_8N>MMz z{r?0{_Jg0+<9;zbIv@DK4g*9mAuq+n0~yJY*e7adioj~(`Ox!r@L4nXL&g~b^aR3= zt)$=5nMd-%`#IqKK@)-)PnE;pCMaN^=3vpwl_ELrdX-&3lF+Yuy_$}slYfs6aW7_> z#h!UYr*9?S|s#3Q@XRpt5xh%y0)A$7>w6m;ylAstD zRqJuxIGeuRlde{|>xlA}g;%DdS>Ka^*pad%D=dhxD+oPN!yB!@`K8eQ7#i#{Rh9>S z6FftJQx^S?nztyCc>>G^{}t?poP{A*RRo;u`aX10Wo3W(Z=Y} zIDMmq&JD8rGofDa{fDT`9YrRer=#ic#XctN2*RD2W2^|iwFv7MBO$o3uhue_yw0r1 zKw60#<7j44+#QyF$>iVz_l%*Tq(>+IT`Tz$<2Pd1Xjo5VjWD+d#20`s&1o3GfiloPI1x%)`+HH(R+wT{WZ zhllvf3(O;){9pvHC(L*a&$a^7OY(cQ;;G8A|2E+5)txA6wdf5-_!EE2qVloK4lA;4 zJ4W(IqearIsK}l7CjNs{H1n`yyB%xewFy>Uwp24xI)(zdR4T|5ZLDzL}gx zxa#2G5(AXFq?LY3Rskzn8^upJ2+EY7Q}{m5>F-;~NPZ(Ru*kRCEJ;#374avJ+iize zMY)Zn!BM!07Ik=7WTD@3to#V-Y|$$JdZYeNoE`#YU66ku6S~|*Lsd3aWQut@oYnyJ zn-%VKBAk?C-3XS7{P=tSo084v9|cb~9ju1!UZY$!=`_%KyA@*q(JvkcgmIo^;R|$+ zp&6OLFoyw%zV{$ygv+JS9%i~#U8wW|F_m`n@&-HfrOBBDZVL;KIf1DT+M}~C=Gg5n zq-4|Ko5lYuhrdg72WD^`Hi0Sjh?l$$G2J zxV9A96+^HedNIqaG$2^(b`%vX<_SYV)f7FUwe+RTLV?@1V>*vDT1$P^qinovq6xqu zXQWV0-3;JR#=3S-|&GuLCf7i)t-(Nse?$!gJM!TMR^jl5@_!x z6IbbfdGV|4FrQ>RB92q|@lN0>hk8c`wHxsZAChbM=Se)+sO(8}ZE;WvTmQB~FL(_% zsr)vQde_2A+BiA+cO@h|oEMJR{M~RSg|H)muuKBWOQD@HG}7a$m$OV`9Lk;~iQ*sN zI)U|;mQVnf8uHpYu=?ockRyqEvi9XK)B*Jf5`D9OC5kZY4`)-14YcW$Blb1;KO6O*;_!XY@Su>& z1lP4@MyYIfF9wjnrO<7JTC6alp9A821b6j}wnNMK&p_VCM+p~nc2kCaA;&kxtGKtP z?+A+p;)_JJi{Vij$mZ{r`Z;{84uRm&aRav}(W1nzbI@nzcTtrAa_?of95mSziBnN{ z+kv93-9DZ9A}6l#VOi$;2hym#kx&lXD2}~9tdO2#0hafPu*<@raRYy0Y)I^%m$p=G z9*)h0UN-k`v6wnQ&9&vp9VZK|_PwuMN`L*7`9j`#@gJ<>^zB%9S8E zp)ijUaaJp3Md0Zgq3Wvtdb5A%e}Ok!$A7{LCI20Qw2bLRm{mnR8%Lnz`({||N#KqH zZi(SfGx(D{tJa}2J@qdG_a<>qVkHM1Hro=u_)+W@TPm8tGl?}0aueIHs{x`X^73LA zWc}Ci7npR{MrC`Vs{hMI3EXRr71VOfVwJnV)ZVt}eJS`omDZ5(V~+jQGge0EX(k@7 z;p<3XTSuc=dd!eFCao?7bWr98`Vg%HS^#qrIr)-u>@^d0 z&*G5`_fQr#g}9{=bQZDqr0JD)RS62*vt{9ZPr1O8=b1{s*}kCM8sJhE_-hS6fUV-# zDgPg$l{S7gC+$z6AG6{h-41Go(XvyGK#9s|Oj2LB! z4?6g`*=E$VD9*RT#1u!9#0W*Yy9UYodX>Qiyv%_Da~nU+q|RwncO}q;KpDX9Xp5Vd zmF|F(l_tH@0zv68)QkWLEGIl;tKiLKiyNTPXOY0(lDs*F59cxD0Jgt=JUj{M5`h*` zm+~HVg;zwutkW96ypYtq0vMbBp&4EHWU}L~0&Tt#H&_X*?3}_df;}@9Q_^=gc zMPU`8hAoVMGXo5#X8EV$IBX?}!gnCl`GdntbmsFs-M8w5()HAdP1@UW+9vvlAV0Su z6seH&p{~wL07-K)Vi2^Xwz&!3v=G5#yja_zz5IS2GPNV{!5Vb>Z&%n*442}d{;qEi zOXtA9wy zc+#XEa?yAO1>JBk$1RDV86@*wn)$qrz0E}fWqy$-0uK{@Nw-;kfGOM5p*%g;06i%d zGUa5AfOumRCvDWf6x)#kKUX=&cVv5gmn?_^OpuRWqeI9aU^|_&%#(2c6MkSTVuWym z2jj&$b8Vhc95GW*jcii3#+h$3!udgA7~HU}Sm&$UIj|XBvy#s<%B>2sK8v2I#Iq59 zAiME@92x)VdT?al@}KkEWO5unXq}F8gsU&ncAT2yg~5@{_Op820Q!TgEqpj9hU!4d zDfFd*=aEE{#Ei5N%sta8^F&r$V@tzKVF9s*DIwDi^toAlUuPbG9RmlZW#95sx+zyR zDz7BaH)%0R4vKOdms{TcDklDs8W1?Dw^ z0u%P~|AW!NjDA-<3g;d=`DViw^Ux~$mfx=m^GK)X%ZZI9b*jZRV7iwpU+$TUBj{Q} z-bvF>rI|i1I#(88{dQqCD0%4U3}1rbFffoC(JTY@2$|I!e`yEi?b$K7@bIC9#+Bk9 zq^i9~xoC)QHsAW6I3)5r{Ml!Ccdb=+qf2k~EAk4+8-1S9Zyb#7)S1qC+I6&4JvAGy zNyV8%z-|n3T^qm)wN_NFdtUgo?7*EZ=vmyMF#mGtjg?$u1nSsC+o8Ys1H5o?4U&XT zUr3n!)dHK2Qkbu=dT6Uj>E&zF- zEZjc|L;;giW;v&8_@_*rP!4T~;U9A75|Bp9gN2$Pa`9)z`zRjYoTLus@V7GCvmmzZ z_zSE?xS6!yQ#Ll4l<7kH$2x9kv6s3vg6<}nooQxGnm_LNj%>KAz|JT3sC#GnNzUUI zr8T0-27*d`d6i>N>A*ZaTU{7MD=d0WDf(2ZQh}{WACkWSl2%oOjvV;9;BG}2WYbGs z=8YO81x5HX11u5@w}U^=F(*1Ks3F|eq&^v^5lM`KVg}A^1&oRcnr5L7%g*qm%#+-5 z1~Pxj{LgGj&D$ssr_9Sh(*5abu&p zF@YvpNW-OfGD=TiHme-izX6l$NID8!*$E*DC`F?|F*ZVQ%EKV!{BUS&ZKvhdK{bt})D_}O_ssBIT?`_ZQm@UAX$5;z5EXD3f zk>^{ZBmA1*XX7hiB^?O=+(H%N{aqQF%CpbMaqBElm*W2Rr`C9h&R(5^g&Wy}^R`W4 zNK?Y3Zd6cM>qC+pr$P@#`n>G^YKE#Y;x1E|xQiA#fpP@R%PT`x|2HLjDgQWlGE4ZJ zmsZsvGIU7m!6M=MHwBxlFNB4MYo06?L(>Vf6cVsBOnbw-4g5Gsc959SHf~C`WmG>h zd~9PVY@Q|tj9W)ofqpkg2O<8$4^}!b!L)=aCx~w~s;?%3%@(B1#Z8&uLKoewvR8CN zdo3FFjcjNfhNL+}I3>s3>jxXFuZHzhYx}aiI)-4P3&G|{j$bh;1;Iuo;-p06tz>Yr zgT93|u{@kxw0wv*kZx3CY^_OM?_jfv#U8fwsF%7jf}ZtrGA5lCXE}JN%*P7MCNHt8 zK%Fwvf6bd=Xx@m&`qd0t4q`Ix8ESU$swk?r=(|g?TT*Clt25e9$t-|K3yQpxqTXB> zeAk~_;!}(I);QWWM{7`cGlfUE3G%mfiK;9obwqEVB2cO0HXNY zo;y@7oos^NMzArs*`X#oOmhUy&BF!kPQq6_RNlwn-;U{cu!S#i;Bq{*#?yfEv8iS? zS`3YH@UNgsSqGK6^tOSw5wo4dO}A-aDA%iSmjJ{4TW)qz+DW2glu+6V#BLD3(AhIQ zW}O3zWSxYAUBz$wG&y{j03?kUW#lET^{Z8G#dQ813*VB&KN5gMyg$P%m=LeU|MbZk zPNmT4HAp~d31-Uca>CV{YkH`8liWQhPTs9Q<}FNG)NY<=NXcvUo23EYgY3Ip-PQ-xB;3S58 z7VGrQu$$|EkSRLY6kZaCzGZS;kbAve{KOnRPGz@vp(EvT9o+RLg}W4Sg99%e?ht{F zBZw}gea2&|xBDTe!5C|n9f>P~*f3+*y+^#h`G zlz=>jdM7V-REDzg9+;{mxlf1yX7VM0%Ebmq`q*$$2q5VvEbS@;n$&v|1D_^PxR6sa z()!kh`~7T=f7`<6B{}GLP6!FlWVpM=$Dy+|Vq*PC8W4=qqspP>F*Fgz=PY!a!G?7P z=I>3!W=wT;QiEp15t-Wx`TmZ6!h33PnkhCnCLb^n>>C(Z`rHcBIsS?Wo@ojYTn?uA zZ*4SE7AEESZ9ph5P?ws%Ti8sfPK{`ofgUaRowDnENT~TyypEvdF10R&78d9lB>e!A zWKgWaSb)0bI%7{QP2QJdpZ2FDMp6+P{YjsAosJ&`IVG2|>k)2NABxkbkrc%H2kV4C z&9)0w<`vKQwcKKxq5i~Ms)&}q&EC6X1SRv~fBwgjEq(b3aAcz))^IaSaFMjE)4xK# zTg@k!IQ5dJJP{TrnSOBzLU;RZDp3mkkZy%zFdrItoT+q>xXXPqUB&V}8Cvy;#eM08 zpGz>4O=*l0e2@fsF3f+fGbe*Ex&vD>qlGSAMWac*J<)g>fwZjfdqZ%4Yx+TzbEatT zSoExv1oWQ?aG3n<40p{1;fEsl_X+84Fq1Fw@7(Opc&tv&jS$Ly#DvJ6LGT2lf zOj7-`_$Qg$2~DOQqlKNSSTSRL8sqnx)F!`Zl2%(`C?zkB;OS=MjWn~ij(f<)BV_(G zn|aulRu`zLrau(EoKVe;_*?^3Pbx6L{j0QRE;Iv|MA1}&_Lk^}QYc@*WBnXpw2zZ4 z3MUe3@O7#86|oaxG*5mej&c`qU^#vLnK`~j$ICPH2TsVTN15jE+Bgh*GZzH;yXu%9 z&9?C>^M*%%Q%)089ZI}A74f?oS+pgBs{g(ET$AkR%R{p>{7L7y~W7t%}|u{m~Y zI5-(D0>D%}hVQWhUMcoW+B=lxelqA8Cf!M5-}CFRN?xTOx6rSi_<4e5t@uzSG>rrr z7UsUv>G}db=)f-7OksByv873!l+aEh*ueEq!Gca}l{^H*#3|ZCK!Z=}Ed)&tNuaUU z=K}s=KUKDRX!tCWxVap@Er$3kTEO!E%8DH(ntw*{ImCX*RG`583*=p7_5{E0KU0A7 zD}R&Bm_}ozNzJmcj)VQI(5$R5ErJ-U;mtICYCSvAM#E)Zu_Hg)ReDhY0P(vWClRVk zBRL;NP=Ty1F5;>VJzjd7BU<(Ngy!(S;>Z=Re$J{qlI1rhpfY1eDiToWl!eyUI`c{%I_Hp~k|Y;~3?PfYw8L9N97%j~>5i5_?H5t;qSANkj3{`8Xl=xO(zYez=_Ap@|7`kkxO05a!a%P(h0Gn z5vXr7$IJmMl4z2P4}<_ zc^EN{lDXr)j#H&lpq9^qP5}NS6F##M_cc(LJid?P2epTvnlq#5yNoGk(S0eO*E`;~ zn&kqXuj(Rqz5jNGKT`w-mJSM4ac!LHH;-2oaXtY*BV4NE^IaM?z53Lje^Ik?Zyaiq zhKa!ShvT$0h(HONYHR_NuP4!^ig30c7I2RU8t%f~xb?!9JacCeZJJ5LF_&MgK>w2P zn?b?Z6oBNC4)EFV7g4;|3RFtz*VAYW=s$jCK&!3NMPiR<)I~`!8>Z35W>G7~LqE(+ zL4o;w2L1wUo-(OCv&ezX<@Lh7orNo!)X@oiBxBX#x{Dgr$rZ9euKZ#3vivmpS|p#}91Jo_|YdS`;15n7J$kki42h72j&s3sCV6JX zbh)o@mZt!Zyh_qN%KR#*UVKczOtuT{=REn~w9uk-IFfg^)2FE^HVC8bTIbh{#4Xybu5_*Me- z{b~3A*O5J1-Tw@DvVFq0JU_LFKAVXI9q7q{DJA(k!}nNVHlMZkE2vMRc!(9asg&H4 zM)$T-FB?#kWxGkxU=Ko8)TpwfGQ!`v@EZw8?tH6}h<5%${!^X4G)K>OU}F%4Ho2KfmF7o9ld6f2utgb zZ=POOmZyM|2}g~IocngOa!(xQo|(x({=zz3NVd&TA(VmAVzu+Wr1AzS+@=VNY}D)jFal!v_redb zOkM=Qa7d@~R^Xaa_<#YMtHo!-(%Sa?g(ms{I;~dVo|3UUjpntY9R`#**%KrtlfoO4 zR7aKhAtRh!6!#>A^xPE0e**Vou7kD=J;}i@Ixs2wUbwp2j@#9wol-k$SAa**Acm9F zdX-<;4jweRESZ2d{>%`+-a!i->ahsDpq&8gY|oH5XwlDzp;JMpie;a&#TQywkcN4Q zSo_S8%aUjGanSEF_eCDE=nz?Gy3Az{8)G$t8f~d@Nk#o z8-m8j{K}f(VY)!QInfU;glGUsCxiVaOReF!+3-G0(kDmZ&r_qyQSf9F96ZT~V^}`6UYfu!Zy+aIXkz@rTOCeNWcC21!82M@iuJQe>Y& zjq#W*Vd>@eFw>$wj^a=J)x6}cG`gqN+GR+u+>{4Lb{j#@C8=hWxg{eGD=LyH4Vh~U zQG&%P(IVHyKGJF6VgKL&W9hiiryciwlX?;yv>}DF=+M{(@pH3vlgjpN$35!OHzu`y zq%<=mZu8gh`)!Qi9_{#q#=k?%T%!!@AB=qWK?H@v=f1NFMAnnO{+KDcM;)zr0Jzp7z)`7Wd5FvuwXnT7N`*u z{ovA(kP8}_v_anu`3A@R*}^<^VZ7pxd+Mf@>+VXSE3#;c@5qh|*>)U2a+wKG<>-n-wr&Ta?-H*ld%9;4;|XAFs?*K}&+IYiz$b z$xk(z#ftEZh1y+<`$W*`cI4;(@nq_$&w(S;#BX_~QxRQaihpVJbN)a#_P#+qP>{BS z#TD(j^G)g_prew&E2Z?iaHY9WWp*0E?wbldB&Ih(JCjrwmDywoKj+vhwPHDQ7o?A|C(j-l<4;odd7ql<)_n>&+=;Izbhg+d_n87sUR|Q(sN+J7p&k zGO>|P82A(rkAV%@7UtH85!hGnPspw1x+N*pE{mr5R-=grt1Vo;D9kd$`B`DW$PXJO z{rWg{pan4EFEZt1GX}HSYNLD3Qva$$g%){aJUZPBP787;`Q6OQER~JgywzC#I|1Wr zbf+S;S?I!r5dU%i0;FWF2v(CSBABKB1p5vo@LVbRwn1eI^ro=1q}rYzVp4lS=a2+G zDnWgQq6NIefcOQ$h3!W0z9iLIWnfuiZjrko9=zmQbs)S-H3sKCo$f)f=t9rm6<=-P zoM!FR1Re|idNpxiEB5XN;gH$(gvvbM!ae4qF=p%nlAIM1Uh`AN#wR2A)fT>LXfXE_ zhc?RNV(2Q{AD6)s%(jT1NAN5Y?=VMQmP8l(uyDsMxaSL(AyjdH7qxqnG1kZ2B*5aTDDou&*A*I>Pj>J9WaTpZ-s$6M&7 z6P4}$StIFxyQn9aGzy&&(uJ}+3S0{4Um~_Le`j3^+jds8+Xw^7%XN$nYWX2M5 z&Gcj)17Guz0n)$g&}l77w|FXO#U}>YbNu_pl{qT2*20Cx4$ve3hR$tD@LqyGUx-hL z;2*#T9O^3mz;mcrg-22OUc3~FZ{a0w1>AG^_{c1B_382GuAekF~z=kXi< zreeC6#7rgBff_8oxgD=5hVP9_tLMc4ma#R$$8Mbt64r2GfZ0`C*utIAtoBU67Nm1F z9R%g_-+f5ft7?!qscPs_;>-^L8yG%F^yvt`tOeHfMA$r<)F_`HLnqr%^K++LV(%6K zBzq)Fd&L|DQn8(F^lzCvVxhJjUB$=2Qo5)^n-U{TV3~sTe5xJjP)g2+0Mi1Cnf?=R*UU`P>2`MDDOh!^rz$O4G!7oK zGA+p7SjWmXb+Jl|HYzrD>ge~HD^R>V3jF)07eZb}-H~VReBi%%S@WhBz?+>37_mQi z=*UbOARK+ov2@|VE5|uJy0$=!M5swGsQtI!iZ)S7T>NU4ycv=t3eMW z+n!e0b6P~m0e(-aHxV)~#KY!uk42GZBlPGNUax6{UDqg|9YcRwkOOc7K)|m>++Uk- zzHE+~ll1@mFPVGTf`D_TxIqgfz@+ zOmTdRV2SKKWoGBh`cD+)4=d28l)560#(+$nBJ}GhbZ=%R>hw`7@LYcuoZ0m)O7#~5 z^7G2{AlET1ylYXHsmuY3Zf_0Tz&GwULtzl<*hu;18tp7qj~-}Izcfg%Sy?cfWLmk& zqN=LD^L;{NN7K}9nx!pO_^y7rin~Ur?{nbEW`mUoPkLzFWOPu&KW6w~Il0xqujOE8 zRhmp6qlm@A5-rgA4R>k4`;s9d*7Lz-ISe8 z-!i*1NvMh_>IM)jprRB}B8e0Q1A>$ll`2J46bp(7h#)9}h=5p*3L=6WD+-F;BZ}B7 z=66q?_j%9rA0NVp%+9rUzwYbqt`b+e)Q)=o-!|MQ)%q*qGFSU@iL_rQnv=v6AtaNy zJA8IoUhN*mA9Wq@WM@?HFpl1#Qj2}znQC-2Ms0TM0g|!M;JU5qB?EsbgoOLE2fxD; z&x@d&l2BhVKwn?ubMG2x!^G<6LMtia)1iSXGfP}BlS$lTDz~t!^k~lR?!fkH;!2V} zS|KlMsXsFWk$lyydow1IZt1lW!-vAX$t88z@1w)^>_cvHrbkH@{#F%0Lj92=KJcl6 ziPpI8Z&_z>oB&?$xX?-_L2O|mwv=b_v)aw~ii$iZS<;p%ZH4N^muZE5y^%dL4{Bxj z8aY!>k66XEzpfMKhJ5vwj-&IrZ9cm_ zudz{bhwBU?iZ*kU)y4 zmw~ni>jR zL8^$9G3c;{8*$W_jX!3=523KJD;SzP9PFxRFZ#C*Tx`KNQ-eeg6$pdcnAVT=FT!cak zV#^v|eZCqkj}^tkZryB=zB5TCZ!3G=AU60Mr}1a@;3w7*XF$(C38^wOGa&(nZ@^S# zBDd8UJ|IRA5cwtghtO(PaO+imLLh#Ub3ToVkvIl>WOjo6+A(`U4i^9!wQg5Tu5+mg z5_6ymO|8P(>adm|{La1P787@Q1Yw~*Rm5X7bFWWc=Tm)6bil2s_oD4_0yH!yhpF<4 z5Ryuc?wv()J50+IDGB9Y^hz6T_Ek7Ten%sHl|x*j6aTo_?q=+lGIZSMKDX@ti|p$K z>Vr7_u8VF};W!A<*XzPM)(f+Yg$lb0{Lhd%c+S9}{OdTenfsohCZy2IZRm(bRJhSX zHueYj_0cI*Q;R+vzhzR=YGnoci7qoZnS@q;9e=0^0AKHP-*%6&T4c= zO#jN&W{K>oaOb;xi-D5?%V_*--MKqK)-wX{CahjYCImX*K;+_riQJRU@XDC{vWt*R zUj*XB`!{nNRW22Xf8}ByMzyS44jVD667Gac}`25K3<7W34_aKP6(s~$JAxfO%C&( zBE9UEtj;*2Y{Uij%TR3~e`O`^T4YaznQ~l#wUPy)nYd_> z*JL@|8RNBi3OhXbJU`ze8c`hPsxn=@YqPxcC!4Lu@-%G&VvG@`p}56e0aTG*@_ zi2uA5&@cIDmr0!FnlrOyPnDvtoIf6hPZH1p&rb_yq&4TL^pBNT?|QvQ1wsK|JVOz$ zcbI=oDtl1}xm##XfG2x}vjbN3)thYNT1N)8()&YY$d(sXS`UO5s?i~bpX{&;L}q6a zzi4jdHUpIgEU$5Acjum}D`|+JJKS(A(>Ed32i(hH=ujSYhE~V;TVdN!rs48l$NpC! z*09HY(7(^epNr~ey5+EsagQr}3YxYC`pIW@x!w&9^cqSb{+EP>EY=4KOh1IE%~6+o zILJFfz4{nU@APoXSI&UprK1h@?BQ{8eI=S2vSnW3>I1eabY$=|bVw2I1crMi4yqK@ zfk-Iqc@Y0Ebnt;Xev6BFg%UWA);Ey)GcI4@B3RY}DdHhs79 zC16v&3dQdvhXx6T+dHc)fTSVdU#doX98O8nw~5T&ByP>CdfGtec0y9wo%^t^Bo_g~ zF?KUW^-0Km0}ir-%y|0|XXrOhQR?U7l+0AQU^a(CPqxk%vw7#`sBu9UT$l|m4ijA9 zIBfE{-EMk{BVFOfCrH$;%8*mtr4EB|4u62A$%7t93F5a@5*umeM~~_1t3Bb=Owyj{ zId+_FtwcA5R&$u^8?e=Rc4S6`r#X%`LmntqH5$Hwxr6>ek5{ltO5M1%)Qz6*oP87cHq zEBd#FU+5ZhveCOO?6Yb(NG2@znfjn)7ch5SeQhxt-&;!m;~ZaM;kWus4<5#~*mbU2 zP?-spSY;-Xtia~@JU~Jw<;K+7TzD)$4AbMy{{l?Bbm<|gUv}#&6woi_(iNOAgYrv**At7E9aJ!%tGhTnt z8Tz5ay0CaD!}1p>V|)kRjBoYDzWLbxsNCk(3?sQmTpaih4F;Ovb35GZIdSn?w*p{U z)j5vx>ac4%Vd0Y2YLECnLUgah!BTQL?h;?^4nn9&X1*7>HJ&I|RpQgayzD#fKtTjk zc|U^=UtfMuQGgP2G!q?cqyEi2rf}mMnfn~-cVkhpi@bi4O7tgokh#9VPw#sEH zv8Ie|R$v2t^>jr9j@X2Dce_rwmGHd;%fa~h-MDeSV%bn}x13LK3(NU+b8Ggf^b1$& z&ljuF(@yw3-dYV!W{lsc3YYl$=)Ch;l%M9hpo|4me&AUH^>nx|?RM+FjR`lqW$h9@t`dKE zA*!jvuJT3bKZh=NwTFKm!GBLe4}f~vBd7X$w@!hOhdgImockh)ZVDm7_+JWKk|XzI zP^P{7fTEm85Wi)d^E>y7F@<@sk)4(&&(Mj_6Y7`elHZk~&4FBHTivD`(*^SKxY?0N z-41k2mmB9*&9R{^BivL}c*v&#qcQ_KJG@e2@;@?cEQLNFjqlU&8(sbBY}rzH>D9z$ zV95C55ue^_h85U>Z0VFzS&jX8uSK-^-08er$U#xeovX5+B=K`HF{T2$)>ltcg!xTu z_jYrOPJEUmSDyz1Oq1{3ja%$%rz|bxUqh>GYPtB~+{iwak*^{_$ZJAK(E&)9uM+s$ zIW@5FcSEyCYTS~p?2McYbkH9Y_DqWXH6;DEYziTF~cMQk+bI9#zMFli#c| zQ+?y6ynQmt-s-9#yV$Q%ggQ2D;8T40SvUJ`94p@8#wSY5MV0)i+v0Q`cC#N2oAN!S zM?LbR2)-kUL*M@*4>B{Yy9pjEyWMlBxVkopZVtVf$^Tkls$dk8LD6>Zpdx;e&{5WD zh6|JhxkTY!XkdzPu};VTPI%kTYnb zrRj4K%%=AdO$um0y`-$|A7U zs>4RicNP5Mg1jMwr0h;-=qN|U-LxdrlOY}7U&lY8@^|~@gL&&{6vQIxN0LQua3yQR zI>2+U_O)l-d`ldbPvq$mJqz@%7chU+V(U900bpQX3BLu-b~eT)S?X9I@SRz`6ppSv+=WRbVGqFQTPK5?A$!rRmU;6GJS5b z;qNl?w?OJ)16$pk0^Q5Ftj4jWDhZYM4A1x`yh|X?R5;jmB9`K%29`;p%%lJHWNWW@ z4LsRt{7HuSr5-JAMbCi@g=>72jon~j&s70L!s9*S90LZsAay z^e*yZG>5jj<$YA<+9WnE6aP;+_LQ%jsqjh@ea0m2NgZzs=Mw_*@M3Rv86>P zQhf>DEQP1U4yv@;%R=i6D0VK3(t_u)dSWr4t_L{EjGdVRH0ZMG-CW@Zx z@~D|z2P5MEEh;)g8yr<}s{y0$ssN+YcxaV9>T3Lq&yBx9NEHx@Q2DS4e0lBYCJ*|t+)!UvO8T_YL*^0@CAXm$Qf!m ziWR41nTA#Aj{WEJPpRx$KlXLrel*Ix=GKDrGMvBc*$K&GzOmiSK~8bNjou_tUsU4v z-`4eDEw;rE2bgE{;D$ToTM-SZyt2n60+LQi%+f2bc- z&ru@*lQtP3fhRsI>tt42IVfZw&Xc~5*N2i$%BHf!84a)m#*Yt}X##zAoIeft zmnv}&tdM(UeG=%(K)g}m)+Vuix8tUP^#zTo6D|DD4E=UJDg@FF4d3mWvR5n}W8o=~ zj+MCwd@<_N8%!M7$aP-DhjH!n*mrX+{A-^-ix-Y~=p#3Ay2_n&(VZFdU^(`quXItw zd=tC6-CV5$6ZwCvq=oOMVjsXZ5FW_DdH{~;bcdWKF`!lYpZW4go92UX%>Qh6?tF*& zAX2`^g_0kH1hSMBm}wBIoruM9<(ZfPbI(pQY2n}KN5R4Avoc6(bM`BGwW|-w#!{VB z3`ohmfZ5myNtbZPTYS1qxUxYw*QSDin<>z< zGO`Ses3P8ewD@07=Dqehc(SP>Mmy^f9|$`%qTL}9UfF01J6=gXD@z76l6-ZoiBEQ@ zX0QCiIPhdzrdc=}a0Oo3?V;-&)Kz7la+!xSv7xqN23k*ruV~_?I>JglTx1Q;I~<+L zzt@Fp4CEgyqxkwQ+JyuNn<|T43>Lw@?n~~6X0Kz69*->-=|&g6#a$l&(tAPvOBKa{ z5%RJP7hGNSCW_hO(oN0uN)V6onfcDpeNm;4Tf@ttkax%asgRPfvA{_9(FwMEtz%w6 zvJaGptvXmetqR0#uD75P6~{W-%@XYE<69O$4FdIIh*7pXKhR-zMCAEym^SCL%;|v& z0x3hr$Md;pKBi4`@j0Q@OyzGH$fP(rpFzL38T%CVbk`i4jU{a~t3U%pCwyjIp2@=8 z--Yg&(4$OP*r0Z?g&%zOCV`&hsKu+@%)Ki4?@H`0uQrpwj``vgg`MhHjgwKC0Rveu zn}z%j4EtC;^g)H48Wg|$8D3e7g*{dYlQLqZhiqR2NX9wbP|tcH9*%rwT6j9(&g11L zJt%yEiornT{d6XFsjYPhv@;Z;v5A@KU=Kt5zacamz+@r+XT};7sH$x~G@reQ;GT`M z7s8xPr3?KifP`_>N#n8mM7mRGK)WA$VFd~H9A5Y7+PtDg!Yb=#3bd%Cj)M4zf$#R2 zcIWZ~QT0+crOWh$5R!$El5sr(y_fG?W6P5r<_faNEH4Lt(gLfdX9e;W*Sir8yCnId z1jh?e-Mq5FHrBrrk}tY(gB{|j2zNectkG0WmL49cDHESRKGr`M|J+eP4RBsq^DpFI zDhTx)?PSnDt zR3!mNN$2K>u0C87!Re$q*{fI^mqx;1*CH+rsJ^_gz(aac>7sJI!@9Rv)@+wt5D<`) z4Q+rfZOaNBZw$=@>o~fSU(kh_9H^!pP0w%!6MQNzMBT_yl`8Fr@2y5J+4$J;*u5eQ zTENJ?yP$1S5RfL!^_l*8Sq_(`_**EtvWoe>z=4&_^qHHTp>IdI(QY+Bk_sUyuH?6> z%>HibC4TfQTN0C%ARxOsRO%U3+qurU&CTqJ5oVH`CDHKzwa&{m*jTnXobylY#*TA{ zjS({9;*ZnN(Pw4^N}Y+X9M6o-#mtyq;tKOZD_O}uIFQM3%%5rWNNd?1MS;@}%d>II zMo$zAH1uJ{`OL6ROh$*)CE>?X<;?~mZ4={tc9uY29!JyNF0icC57@>Yw7b#ezSQ2i zAPA7K26j5su#g`e`Bbd>d_!y+@j&YSZ?*Aqb!uDg!oUj7kXKsW$eiH(+y}a&yBO+C8CE_va%nszZ%3o{x#*e*%su(FH1$u0 zS{Z1GFmq;Z&J| z^L#?br-b@a(yOKFj}0Qo+KuuhC@?RH<8xj6Zj~Y`OBQFT-z%`uzCKCeNBd-HI}#17 zBTUQo^1m|l4fSYZCoE9^j=IH*jkc&yljKGj2x-I=U%Jyom-aMQdx=GH;YbpnVo@I# z#DTmrEQF=SSGi*e;n$3#*x2@hbebYP9#H4BTlYYLnUIrxpupVA%U!5v1G&+*-WvyL znQ&`d`Xj-90F%6H%mdZvJ)6628up;bol{Jr?f2=64gBvkXpivM_}qjNM^ROCztuNl-3@vx~d9J0()Za-UmhTO7fU~-(D}4JWE0lBqNcM-8BSOs&uV<^9 zf5L%0u;nI+KAF&}=T?>2CFeDVY1!Vc{IpzjLj?b+n20<|Qy*rCyP5?%#DshxXW!x& z$nCZygk&#&tw(tr{Yo1BdvyGHMVadwd$TdtMwe&o66hBD+#PuqAej?JN^wi6R@Nxj z*u+h~G+Q7`=qqQ3~_eztaE9Ck6mJrZX`H&XmqWiGr%KUj^3 zDC*t{0fwcLXwCilB2ZIJGbI{7*XNey6)u85=qfNB>tD&NhTAy?6u9Cz-Y^j?j=0HF0T{s&#M}>9M+Ggq*w_$}tfHdu`5?ntq#?M8? zFRYStpj0oxp^&{NXM>rDuKgHI&C3v96+}IRgx#5Q#yTeJ`b$D@c7&hhaSa@^DGd+I z?^KlKuJK+rirMI%EM&^eN}t`FCt)jZWf)+DM5%aoqXartYkXz4K-b4hHn{_rtHi=2 zmdQ}XqZQCWRVFHIcOQNgLIyT1i6`m}yCqr-6zaFMN;&zREzR}p`@dK>L zl`tNbg-bp5Szm(1_b+>BZ+oRP;>@rl-e!ScU@qpxl!tB{i)vwy*R3hbmVOvQBsD2Q zJb?9d*gw&6#;tm-H`Q_UB)_7G#v7CiZ0G?{LkN0hoGb$m7~UYz_f?}2oq_2=ky#P` zL7QjbZ>MR<0oME6_PhccI-A0@j2>3WL~{(-)Z@N*oip@5QCLZHA~N+`Xf-FH2f)41 z)qKZy{HPAgCS3=N85cFGUbVl1{A+%Te12i@vLmTlZF0-yu?IL_0Yfd z;;+W2WD+(N@wWc_FrJBon>%=o%7g#If^7U13tL%Wx+>B;K9d+1ov#z1=KE@Ivg0Tr zT;0S}HK^Cv&Wb>}nxK~@;SDigsMJa?c?fP0x!8(8S}B4qAwc5H2G5hB2o1XU{M((5 z>^WD1QOxy~bl)rmkgWCfan8`KQRx-ewPbo#X#e{O0T@ivx~hBq7-OsBC&b_yMpYc~ zvum3`8LL@(+RaskyKylv8}Mh-=h=^2B^MS#D#lF#voBY=IzqbfFb9~Hp-&Z9(Zp{I z*ps=a=@=Q8z9Y06LO>oFaO|CF)IVT%D9}jI8P6$#c#Gx{e}?5>_{55izZ_~xv){+H z=hGBO&203Qxo|Wlh8=WUmZ*f1gcB;{^A*^WzJ5KhV|=u@9i7qU#8& zFFd8;wT=29hpe+$&^6jATSv3hSH1*$?p=ClbS^$TMtu&V#Ftt4@qW?>o-66}WEG(@ zuhl18@u-DuE(lGExFl?($8OQ_w3}Mq8%SlgkZod`8`N>OH6Y+e68PGr(#ws0s?ubR zdAk~&>!QH{w?ZTz3RlzITMYDBn*2u0m zCn~+`8jcJntHG1m0<_9{byX^Y(lQ$|&kz!?irY849;RdO6~t%Ud{aoQt6Ct@-CSbY zJn~+vI zbA1|#0r#Au9dOO07yl;o9Na%Lg9YNxc^P(#-V5Ws`hHw?)0AnGWS}k(n88(OB1{2Q z@^u$6De`h#=K}G1h50LwZiKB-9lhd`d;X6jYj@uQN0t&!G1P^&sRk0HW$zao^kz^} zvaqLIC@_uHSt!}0g(m**?rK@C;nR`7iZ{vTfEj`;xaQegeWBd z7323VV(-9)yBLp-7eRt)Z=6`>BA}kWT@W|9^_PHr!+dAH#P;meEt+YStS*E*rcke< zd~|gL^j}Q_8olAOyA-X};TpWC zV6%Ux@jqlX5eSB_@H#v&1TlJdJd#Q?Us?=|nimUnp$biQ$k{5;d(eP-@&enc4YcbO z{$L)Bb;zG}Y)R1tVtFs&ABG-a>rH|5sD>|U(9d z;A0&YQnELac&SGh4U`Y07H8-cwmja^%4Nn2A?YPNsWQ)X5nF;-sjUwl9}<{`R`J7K z1gj^F(`uoZ`3tUv&DR!7-2afciq}{rLkeL|_AI#GymNO14RLMoWYghDctK!I^t8{M zlP~`yEM)!VAtb$ok283{(L>YdHXp18dJA+vFM87AFHDmFNuNN>0VhKT{w}jWU-DdB zv(unip`IPcO9ZNW6;hMr%_=>@#jXLxqM2r^WNx4JSwB4o(Vp}>XU;ei3g=H}nBp-Uspm-vZcoq->#!LDfzv*z=C zX>dNiC;}6~$VQs3&64jl^Br)o!560Fqh~>b%WYg1LNr=9KTSePmW9I(zOr4B)g&aDrbjgI(jA`bqSINPH}@Whf%OjMPhBU)eDx7b?SZ&E?IcbCO1OToBI?w+F-`6>a2lX~jo zbNQ>|@`)6`JABrb#c=!--}$BD&4 z2}|v&LvIwEhc#|$AkE5^$6*g4k=as|Bll%P$fv+sY*%GK0VBo7Ym2;bh1(1VaqUDo{e)_4YAgZ zyr+_zJnGGA^4kQu%UACgn3zkw1bW#9 zD!X1A?hO6fQckt^vSt262+Lwf%h;Vw%!$Ch)RxvvD}|bWeiByO^noBVIhFxu_JfVS zofe-b@ppAfe!xMVkD*8^!Eg7~+w&2)kN2<}*+4V!j8wM`8|av;gz8mS5p}qn1j4Ij4izL%ryragg%yi)~$Up zWEKi@Bz_I-KU{VP{#XrmcLpjO{7GNlnz!ag@U5=3iDm|7sP$RycLQ<&>D_$%+bC?a z)~yK5W|hzwZ&BopjoNFTvDZQmK!PjF_hji;eEA;@&Fra8$$3lS{HYYb z$C5uAC@c|}Hs{>6W1I;p$GJrsyxGMSSbITgRk(q9^wt>sn2w-S?>Mndz*!3JW)CPt z?$@~EzW7Wo&RNKCqfg7RsTt<)0zL`UK?Cl?T=aBDh`SOW-dAe@tLd8s?uQ|&{6^RN zHES#7n3v%_MVOuAt_!5AbbPy;f^@OtXmOixUY@$4QN7-l*ZJ0Boc+2Q25=SsR>>=K z#5-``I02(XXN9QLHW1ghS6pl0YMMBua(x=GgTD5SiDpbBZ=v86D0(_gE;4YUIRcPC zkFxcK8b=nQajawiwh)pp1H7RjHpVtq1=>gwIJ{!Y6)!Cs()IGN-u8{E>E#t zIQnP`sA~EaMH$(s3~;DdEVMVpB1IdPrFQyyiH=6}kZ;W8N5=R?DehR&5_1J^sX!JS zB{$g^qq16Do=}IMS%KYDV6Rcw9(nw(G3a9*IdM2lzE5CT&M?o_)m^{uu&gus~`E|GMss@8rCS?w^VXyjyzf|jCazTIH%-7a-|U zft^#}TEN-n@oU=b4|J^7t$F7E_hfU1_Zjj5II@qxYG^pP_fvtmU*jRA_&yiqEz}*l zv9dim!&Wtyz*2P{>ZUw@GFp_IT${F-p*gyZr<^SE0*Ql!)uAfA$X{jHG7pwQB|XRg z>dV7)PeDYk@5IAw)10 z+(gsQWbm$8@&^OO13Bl%X4~R8$GBJKA^v|PT$Q51Y%aB#WS~B&$S*f2eH?xp=$xk1 z4p}~#AsYe-_Ki1pm*(d(*_b#gB|c*5WPkQfI8y2`?QPtsu>7k9N9I*v=NH&EMbPua zvDVbvI(E7Xko+i+EOTWY`mVq|pz(FS%I6)%LIpP&#{Y2{c0hB<)h79aFW%hCJrPy< zx%RCQEfzXrieNTRWTe4?@`pye-ksf% zPjrbHN6hGa%WNMg-6xQLMj=Wn0LcKi9*gKz71$*O24c&%IZ|jN59-h|gxErfG)wod zL&YA=*nOJtRo}qh`;+RrR?uG^5^xWS!uo(Y++Kc#fexAx@MKN{HZ{<`Fwv~>GE^`9-HyX%D8dY- z$wkf(C4>ZrlGx3xQcemIU6I`|kD93yvA7CrCg&q^YgBFqMg zQ<8aoQt2L3?3;mX58rm4T)V=mfUFdir`rOf^VQk*~ARYi0!v+DRGfhCuyWBjVk$7xP+eOgm^+jfVRM-FPnT1=RciZ|xP?v6asb>1`GfoXOOPXdc~j4zWa z&nK(eJoA8QuT6ncyg1t9&hw)e>&Qy-t1|?|e@EP7R(zA9A~w_wEyD=3s2V3WWvVEp{(hJk($IesRd}n&+NhdIyJ*GQ1t$hG8bOYphzQc7EvUkaFH`WpNnugDT zMljl0PynLO0;s(8RS^HpiV{WrG|M~?$fq=P-x%__ro?hbe8-GVg#GIyS^RE6pra)- z$8(pd^mw=aPc!ONkaG*-7+`Sbs0&-!{W>-Zo7_ zk(PR7aaSPzp`lgXq*t3No^`Y@P5dEC>E==Q2*Smc_#30GOI7YBw-WwKx`KT*i(jP( z59X-Bt>_gUo9#kz*;`~-Hdcos&D6abSC=;?<((fR#C$jMtjwZ3eq~><5?Je&U+R^p zcc4abJ~CtHr>Su~^=bw$&h=GB70f36K`(O5l;8|bN|Aoe@{9afGfc)#6CMpA=^akm zp^X2|g6>Dl5Q3RfjSriwyrPmnWQd=t-SZRFBL!`hD8Pcsuagr)!k5uLNcvB6Tk2BuI)k{v!v{D+F0swx$+4Ivi*tb)y1%#hs>=SD=Xy4lerJJv7oF|ApPT)=FGb~~&HJZ|GRjxN1Sg_|wa@TSz898HlUjI8n7FW5+T~N&Dn9+Sph5`7#RN2c+ zJFuD_I~0+uGzq5jM21)e9aUBMSEK%v2VJ|CT`93v(RO5ojefKMET*2);~`9g#kpzf zr8Gl_6bT2;Ew)ypSH{%5s8Zi%$N|-KHW70B*NE~epM7hLbs^{v{*i)qnfOP5Is)}= z6MZsG2N|YCZc9~)-eM3n&C+?!kl{9;nT~8(xIZ+V!Qx&OrnT&-#>ixlc=pYaI5DUe z?Qo5$26J_e+~cOpk_eKMnUefw13#tRt*${^($EgVM+}f&_M@GagM%~c0{1swP2a&lC$o#(4QHcQndH8WVdGV2RIZ} zVtw3HeybyYouU_7^hi&+SCB`*A+G=*tg>su!43IlIdyTSX@tVn=jir8+Non}+;qo@ zHc?`Wa2*2ukv74bZOB>AbH{hqa@40|^vCKYpTmVer>07w9&^?z0=l#0D5}421+L#=3Kv$_DKn=s5&DY%Z;I^Q%)N ztY6&j+5Md%ci7?+fdU2QCKravZQ?$aE#}3vCrq)?IzM(5PIjq9dte-GFs(WIWjAXi z(PO?|l$0e6LeKUxt_B%tXmu9xWPfs(UokDbA%s6gGsP4&G0g%bRv(#t(LP*y6^4F&+`=ateD2gLObBb!`$whFI%~x?%sB5%7^CIiY zuqi3FR*77g<#+h;bD@jfgWMECGDED%lJ}=^-WD9Nf1t;VbFdr7*`O?PZkDR7Wa<*w z!h#MR%nF}9eT*}}z#G#fsR{1~sL-IjY2vK`4V|(_lgxq?2}?`cJ-XQ$vd~tp3IvGx zyF)9PAs$ruX?eEFBd)TUgTB;)leM+zh#Q}6F#U7Xt8VSpHuG)Kmx_|Gw1NGu9ph`z zhtP8@!8`gHe4tJVZ?WQAXsSAeA5AfzL2seI{J3AyGu&LMTNDPE8RCpA1(5Vkp<9}n z)rvCB=fBEDW?SgN6iX`7v@8YJoIcaYL4o*FQ$@m2-%SZH@tx{XD+HoYiOwko@`Wm> z^Fn~Z-zvurrD>3Jea54I@`bHBw%<*y|398g2|fjgmWm2Xzh8^KO|#22-p@sT&zE8r z`oOh7o%`V|wb~>5oA@bTx}%4)E-KG(h&y2aD#ZXqQ!@n2PAOIVpus-n*#J>7pAyoF zU6vKhAbyUH#*8x`4>4LQj?9q1r0{PoYED1#0)p>XjmEddx2jx27R4$_po(5qP}Ydh z^ki4Im4Rf!xfuf2*y$cIu>q1#ydnT@F})?pEJ@)n7}Q3OI@=j?mn{SH73#}L4y<4< z6%WDw$=p0U!NUjHvJ^zd;AFfOMuXHMgPEM;Uxy27wh6W5Et1%)fnDI>e^+DQbV77w zgjpX%{|BNcX!3A9{#T0sCahzP{(;jAbPVP=i^E{ERNR>*dU9}^2l^1i!-~}4^CkJn zbPGR_rZ}ajy^*21HtXMLtQrVZm*lTe<>eGRKccP;gALKM5>bIPNaf(60HPZr`jcq^ zPP)wW=&iuL)Ug(rtejXKLed_Q-vh}lP59l5=zip61hqQaZkb`S#5hms8@>|h?jFtq zQ5fQ~e}KSvXf;J@M24&m)Do3n++gTA^X@Y2mK0a3*vB%kLG1L_QP*+N4Iw0}#VHx` z9SGkR$MqM65_~V%@oO`-s4@sU#NZHW0*YU4ttdQ@XA7N>TxOQQ(h_U~-qE1%17$9s z26>-$*djHteFpKgN1W{xhpe~d&wK%@nKlQG#;k_v8{3wnCwj&pTgeCdH8`o&qDc$INhD=#mlQz`z1gw2%iz)ALjKF_SrI;9nP* z>w@S-0R5c!qR^487GF4%>%~#|6b}3oVWpz{oEOUT=41;!lVSx$n3$&{efi@Wn5|%T zaes@d=b4}sUp~+ymJ3v_56qpz?lEW}$=tI?CB5epWG1_Vm!&Y-Waoe`(`;O?5I)HD$== zKD>byC8_4p`)c^qw7LQwu__Fr&3j$*tPDr&N1w=exP*CQ*85(r%-xnI z?iMJx&H{oa=cyc?gp>>_G`BI$jZ|3HqkH<|1|7qb`oK;9P04<^`*Uz)`$Y}n{~oin z!(;B$xH(?rLf`r!f+_EWg@YwA;Zk^`1ebJ<@C z-w|kibCJ1a*vn=ztJn`_q>|>y={gd|+UvuVY`-`$O}$|Z&TKP4X{6DNfGWm8pFGl_|I5UO`82d;;3>M8?)wJ1I*S8D z|FJ=B2ZD{rC*d&pe(_zEeZ}muCr#a8gP#~R0VlAqz#O&4p!S=!huq3zAwLSJm||PN zjG1J;QH>oifoojE`}L!i1$JvEMw@BopE~*-vm6@C`wG^RfqkJ zmFO~G?;BF-poM_HX4c)C3gbU_C`*s@l{Gp>1B3CzF;Qlj*UZFmk6os*7kcId-~P4p zzTr-pd)bVyP4j1%c-JejZQa%1!eV69hc^DasZQmo!)fa6g8HYzZw=I|bCDTk@FgtE zDy1J~sc#A8V$I9ze$WfVS#Q3QKyCIDK z;s-g_Yjw^7vW01B8o$dYsYc@^6TiY|fLJcq{c_86dag_zyLJLAPxN{ibOjb(62U=-pyLo+n9_0n=-8YHu~@7lzZz z=HdD?fdi0qoi1*r>0b537pC@yfgdQy?+2wf+FJMNr3+-KW9KpPud}&xIJ%>rD9w=f zD{?L`wdYN^qj6V?r4+gkj0(=9Pip*FU##t7w}of4THZ4&r>Dt>1X_WW^rCO{g&pFa z@B{piSurieU#V~~y_x1q015o-juStNCQH3%T0eLYT)2p5F7u<`cS7>A%pWwRUsG%^ z@FXL#NOw&NyC|df+xSrvO$U9SH1$-0`a=;W1@g_g$PH!KCnlCw;u}12RY3ztgyLB3 zwtTmaqd$xAC3?xUmpi!Y5f>36RgGUi+I=X5gpa~1WCiwCmR>9JD{}0Wtuc_X0L#=g zVR|33rcvK*5=EbZjaafCZ#FS#k38$Ky__NM*+BX?BeIZfgzFbSgCpbaO7n+PjThLc zPqQ%*$BQ4;!^9B$Ls3Wes%SA^9hVlMLNPCNHtH$6+AiSH;hM6A((NSSa#ym|k z=hhQlQyf4tz~lZ7qQh*Bn_f0AY+n8>PDqhwbM%pV;xEWy6==Upi}Dt1d5y?Xpn`RA zmcF7d^BwH+`cm&M)y4G=r>5!EQR2)Dey;$xX3)L92|L6qdxQlO0PrZ>vsajrS$c&p zuMHuo`}zNPvhS#`z>_hO%7z{SCargA{Cinrqi=l^Le%9YnH!j*e@XE@O*}mko6t>Z zw8cl;(LNi$GR54&7s;t<>Ic}#Q}|S%-kY=9%CP@t}2hi^G3&4s>;eV5w9das=&U_GLMMT6*>0iKxu+QuPHL3@j$lT z>T%DRI24^=HDA@?E7Igg2F2u<(;)tDjKh@I&}H$h1~3~&dJkl=(o{{_yuhXs;hsgy zo*MMVnDW;R{>FpP>~%dt%HeJ0*uyDdIP|izpgE0aKsj zpsPIjLPGkq3VtT9P=zzokSP;yS76s{7xbw(db$R^Gs!$? z2wIl;*sXckMU4e{z9e1ZGqcC|_f=yvQ(=BIa2S-CEtf~|)qw(OnOjdbq!GX}zFF+k z5G_7vD-Q(LZDC#puPcoMCQIvylWF=PMQ+bYhw^4?NXMjUg&ChEPxV8`HEx}+T->F) z#Nm&pnERtRJk&~o|27HgO!k>7_g44Na%Pod{ZsrfMf@!T`cuYzI@agfx{ec`WU%zm zT2z+iAmm?{EgIYXvX3ID*KI6ZCA&RE%}KM}O(NF6WV;`oW^>(dK+nP97mt_$2fNeM zZ3W|JMF5SYgE?nN88$E_HYstaroJtxU@7wh;f;KG$5Bt(m?9UNDzGl|9&<6F?gy>t zz`9$NMx=?-O7b-zRA*>N+CTG(EFGv>1OGGy_kH*`^Gu1yZ8qVP0N0NK&BvNF^`$|c z^2jrsAE+D1SE*kq=`fY1yMn<;0e;KD2lx+2#SK;7p!0f z6cGz5Sg@cXyeb0zM9gnC|M-4B{J|#);qGQ<=9!sio`KZ5JVH%yg-0aztg!NDIS4ze zuXLHD3d9KCON7_+OlMiU$0SCdU*+#w`!6nAG2>^5X8j?W(E}awQ&(7Sh`kG@QPDp4 zqZzebC0&D zh0Hx(Dwm~ z*LN2I*26CV>G+JJfArF`FExNMUrE1gkr9pj-=hHDSD)Kj!wJh8na`*;ASX<=I zFG_GByuJb^;o#`vO?}xK%uFgVCq&1L35S!FKuDEv6A+k2DfLLcw!nVv(lcTN*IHG^ zBl;qneDR#x3{t-+a=nAZ8TDjr2zQO5-O|WWQwy^#asu{cTxJ!y_)zxLAhidmC@lMi zgC=54@q61Hk2M9ihGBcbyvFyMQOYMCHArCgVB!cHoLL<)R`eGaMF2Gst0ZA$*z8lmAX-6pxy^YgVi)Gd!p*Qe+q0tH3T`t4 z3e0IrcN87tK#|LXNnXgCqbspbf@H^x+8i?5bMh{%}}cTZE|F31>)O0ebO zA{3a?tr-%c>5V#&N2q9;{tV-@0KLde_aZm6tiu-TUYpJu!WL{yC`zj^*}nq0g3>FG78Yqbnu$u?F(H7WsHxSkx1|Byna6D)PE9nx4(GQ!2_WCh^P+=EQaX2C{2z z`~?Epl}a}h9pM154#JH2jy#@I32zUQqi6W0n3!YV$H8g=Q+OhAZ+CiinAc~J4G3V0 zJV)fFxXe+H`dt%mEpxpZBmI)Z0+)r3Z@Q6RbFu_pv!E6_?E<&PXa7)!fw{goaA z!X@*8^bQZAF2W=bO!OX3eC0BC$^un{$}H6Y1SW?r82no}ysRWu;Y2t*ztCWwm4%q2 zX_$E%ry&2&j*}x>0hUSMRlr17Dk)^VmKQ$6$unZaD=k3B)JUK*D-cy=m+AOLst4pN1B^7R6HtpbB~_JVWl z7T+X(TW0J)*%-_Y4pJTEstTBFrh|Inm;|+xg@iz=2IgqJK(M=q zw8vHlr=Y$KP0-9YJ@$!~*bURt=)h+tOh z0AZ=DKVNn`cdt~Q%^}A_-{2rrE8rz(X263I3#+=g%pC`A@+H<^d#FBu;v=d_sMC9nzAxpk!yL9i6&*Ndmb z$bm(E9AdlMO<`q2;;pJA?S_CPgezD1oE0q2%hNoYy~8EX~$>ipau@^iL+B4DzrtAd-{Pmg{7Kap(5g$E##tygT6sBzdCF8iP%f{?~HmGFDeV7@#aK?WcXc;0$o>ihA; zjwYuXHZQ+|#7I8Pqrhu+=a`H0!mpZeYdHkm>s*o`i}VSaac%)6Vg8&m(OqR@TN$|i z>y^K=sJ1U|j?zQ&)G%5aks()bJ8$|jeUJXiu3@-U=3%*H_Z!7U5Dni*JwXPxa+>+d&D1!5?=< zHT-yU+6%MuEq1bRqmES)GqwTt&9&ooeoPPfW?Sl>B375=vo!N8kNLJGdYw;{;5rYy zuQ(|BmCa5qarYa7Ug7Dc&{jA%bvX@p4bwTg;tEh(UNfH9-PCJsSULAR(nNr5A^&sh za?Ey*`!9$(m8+5Ujq$o9aesmCt!XO?{Or8yn!<*1;1Azz-dC39n0^KN_$Yb66+o!0 zEd$Gi@ddi%LG!$(V_GfwfXh4rw|ooS=5kUEkY8DJH$yz#gB$exwU{JY<#`Mr^>a%{ zFU+C>3xTXXPM+NY>NnECausayzM>=irOW;4(gR||rL8(dGHipWk**+Zs>hQ_8ZKvV zDhf9#Qb$P$R>Ve&T-jAzURPo+8zS_A&08Rfv#@``_4O!dbzD%=J}AoV3G%VB(*?=i zSN?EOo4}>AY@??_e|dI6eybdxS`E?NZ5ocoWn6UFRemwV9h3Y8gGc|<3?N;d?eOCx z6o8|Z5)aF;>A_NOP>8JX+ik&05pb>K3{C6iv0t`?t~cTOjNW-*kJ5k=FWcPBCGJr} z99m|wO_4W(#PW&`tB-9ty20goVRV9TmJ`;6&FY;MLqSrlM_vrl7&&HHUi?MlSC{K{ zz?wpmNEJaDLwdNt*5vh~DLh$@;0l;!k8(|pnNwhUM9FJh4FpPiWMDHoJx`Z!^3S7$ zCe;%C!Bb`K$2|8!xlRj^Ih#7cVD9(mk6dm6CTm;e#SA0C{*`Q{`eTMHuz<^k#K}P| zp@1qrTZXIGdlVT3w|V?VH`y~rY$~weDLh28iXkF>peJ-D(D!xZ<|4X55t>Tk&azar z$d??jG<8!6t_>4Sz#}iK&#~4d;2 zBr(@vPSV7A1@5*ymo@pnL6xln4B5lV6FKyoM;4=G!j-{96T&K6shg`yKYQ>Ig-)v_ zM!Uj_s*Ik`b4sP255RpxKcJkQXTEURt9%>z6xkyVb%K9&x#QFV3mwgYadK=M4y*DA z-$aKM0pYVf{w`PQ9wYV_n2Ct{9kP7I1QS^vs!7tr%M_6*iFcR%0a3#7VOd)V z_3(^xHAqPy*TgbwZSMTO+$ossU4r^5FfObIDv7SP%wc7{&lc?X++p^*{%D3P$S@h4 z5F($n{J{TcPCDQ!`wd>36ihXXSA~Vm88k6M{@G7_SQ5((ut6pD)WviKqMxd#h_Nm( zWc80+=D}9=`l?C9D{|)nLA6l)Qk#9!4XiQ5TN|ZAgZ02G1XtojQ&< z($x5Dm=P+9iMU4x2p5ZDw;c16Cmzs*NF}V7qcusQ$rex2q$>)no<})Tj8}|Pe6JDI zJ922RM}bLZxXh`v&>jv|?Mia4E+5MQu`4vNmKf;DD`a{>o-0>UG^}6PWFr!8$}t;G{khHI=j{U56DlK6^yk1IAROdS}-LPC8}G~<}kgrEGvkA&tonUdEn#n zdHw*1I#i;-w?3F4Xa^0@_%AW@K%TKo;kZg@wr`STRb_I_>HXz+6v(|1Kj(+lp_N2c zS9a!nHv!W7cR2QhEVbv^Q!7a>Kwh0gDWpFRUV;OcVyd;3f~N8ghe}(Ng_6MB1C!)^ zlLR2aaAjb}B-IeY%RP1|=67Sj5-JogyDVTRfvKvx=~4jkKfwAKCH5wTo?lcO%W=b^ zf{qW%-pBazqTmFnp%uva+&wm1@x2j7jG=~-baq%AR*5e5bAD3Y?9ydqEOyv!*ak0w zN#OKKa7c){E{8m%7IIMhTE7{>f{Dy$-K5*Y!nGMbg{qWVV!$S11No^(flVGLi?`VN zUrAzgNt~vcm%5D5$}KX9yUTLp)Bi>?rsfZbWR0qal0_Rbit&^op4F&)(Q3XJBo~2_ z911LUppzMHhjr0nS6oSwOJJOh_z`(}wkW)b&5vCE*Q&;s%3OOnwl_h{x0zPhjmF8v zdCfJsJI}1WsRC`8Mzxfq?;jpWM9KHD4JHyZ)SedQa$UM6=O>$7E%7l;lEQeZ#C#vDv;YS9)l{APz*nqgxoxURtViH@$1lQl&Ytg6!dG8CANY7F6h zt_U{Tj`1PSoP@;f7I|J-3nTqlj`}A7C0lfg$AT(Gdr>{P9RD*zAGN`2sW)*97L04V z7_yLT-mv-O9qK|%y@f+|NvlghAQi9m`^$~$^1GRo zgY>_$@(!H--H_rFDYqNk{F5)rC@m3US&@QBcC4QK&Z9uy?aZ>c-DZDD5{q2^TrCXO z!k4zzTx}9#eXkj)mQhr-*%D4XV+fy@q&Y(ZPs3@0vKB+;Jcoga;YdtRKi!|LjZTu) zlgmmJ3F~cYw#dJW!>_u+K8=&h%z5R=t_0yY9GGM)j-6fLU6a3Ka{MXZBm>p<9Qw39 z7Kj32ycS^D{xlV8)h^eSOS_UwpcYO##UGcY{T}-X%tTG{XcncB`C^{gg#&O?_n8)X z0mHxOP}PMQ8Y8Tgn7+|dV{!68fdRKUtqfbS1Jxu7s-8H)W1xYt!=pi<9JFaCmVp~= zto3Lj3Dkqo8kf0N;p>aq%yQzZ4C>$I9q+=Fs6=Oi^!$^l=UBADW{oU)87LcKi~+zU zfB>Lf>wC?>s`^uoc2Q)210%-3{hD97K35433{k)4=sKi-lx4ri@goNR>jdhmCh?lE zz9++<93d`n#YZF&4xNAInN2!BrL4bh(YuqxWiFbk1?yern^tkINsKESod?FK-B9X~ z#dXJ#^@gy&DD@s}J|2W;OKm_^X|lsNVq-i;#glwR?~{|{jIt6(!ean+MBx+gELYgC z@k4sDH-?@8?Iw*(ma4biOuQ388Oi-e9TBR#> zb(%}}$`&*~kP%PF;yWI*wj~B8iRB`-sA_!g16h6+Cda}whGFh=sCzR2;e)V9113@8 zm~Sz9$<-Gt{GNhx zV>$Ll1`X=+l6yV+Lpb9Tr0_86MW`=rVXwn1#$ETP-YYP2f;_9m=)z=U)F*S4hr;y^ zcvlBdFC$Ipvo4cBTP2D3ceDNy_925mZ$jXsiUBQjchq~w{A~rsGSgK(hwOG!h?0-_Z5iof&_7($B3-Vle|U87tR~bFx4LMZ ztlZ@>@3inoP4ZWpN+A757d{CN?j8$8b}@tQbf_ z=NaS$K_b?Db-?!AwNg`7e z0h7I*Lz4>#AlZFov-7|_wJ(Z2WwAfF>?T7zp{QoL zqm+|S{6giU|7t@a!yTVR`&=1N^4mS2EQE_P#LJdAR1@dB><^yMWQx1a2;rvM&fW8> zYLmmhvMscwAbqGUF3EJXxM5}4#Fk6YKG{b7>7*%U_RR+nzh z^RqD-D)~IWB@P9LVtIt`@d(KOM`L6Y97$Bg7fO&@=BX|+*XN|a3iOdEsOPYtgn5HS zt}iEme{YO}bZ z2cqawi@U*PHyixWqMQMeV9?(MEyL|`2PTv(?2%tx5_T4ZY|=NChwzU%dX@+!I5X7` zWWsfg?51+^sRZ$q#SPP{Vh@+;2{TVqSa3$jYD#qOUar<<(Q1qQGeQh5(!*)_ximSi zg`2JGeLebjhd-1e`jnW*Wce&l{IEs;1-Q-*4TAAgJ$gw|gh!&LrXO_5E_A5dG9-h{ z)ABS7FAv4YokcpS%7;pTl9#Imgg55I0o8(XAWA&!@_@;fSTI{iH6i2Y90kc`S{+&I zDvK4aX8{DwQWs^Ir8fL-3KvkP%Ygbuv=sqLhN9s>hJP4SX%EgE%fI?HtZ=pOCCk-U zJSvKkPlHKZ`XLQ}Qx^L)MS8)7`5dXCz|1TYsk$s_@~4eAyfXVrSh_AFHX%PX-z&)v z*OQOsrJ~NQD;w)AenXNd6`Aujb5;)e1FO&{MeY)l0HVc}&-@F^X1MU@>%ekodf;_CU~^7Vj(2^Ds4{B#tRmPn#B|e<>?P6o}dAa*;UbpdPOH z6CBxUqD812AMHRWVR9I=8Nd)ETUC#jE>E-$jX2OB^Je@!=p-i8doO1hNhZW^5g)x%@JP zrVDzok{F&r)BGFH6qLi0-2j;Bk2W3>&L*2LTYf@0l1C?c(vNZSxna@*wFp+uXDwUagD`4oFpbY=n_r+ z9uwV){A?5ChXb7lwyP-~RU0k#fX%*daO(o%n6d{NbGn^I{rOBl&>czUTa*TPABUax}5ldWptt?WW_GgRoqe&)RI);p09`%~b z&+D3wK~uTEL+!I5=Nq?pa2{1i2hSW@;v*{cauIIDZ&zy!u8+?P@AxDNyh`m1Buoe^ zEtUA!0cLLw{hdIA>PP^;%M^Y`ULR43#xl&AU0zZ>tAIYo_CXk4522rD*{5vbS)0rw zrKZGwhxHHR{9vZHVn{c(D~hh@$N$KXo5JcB991@ zn_Q|p3M_P>Y={5`xT{&atP;H`L408`MWjs4F(2VXUsG@m6o#M%*1C z9xO7jwFDPJerk~~*7bKsnPppj8|FqXf@)^7t88cye=tcmODB-F+oL*Mei5cZd3qtk zG&$5O7Npw1Twr&G#7}UjFBE$!dwLN9*>~zOogbSM9v&{f8wIXz5CYi%3;eIu{5Zhg z>IRM_=*Bt{hN3qr;;Oths}k!>GgZGWL>*s%iGAHZ3@-|*8HRHBZ!>inB>h_CzQn;T zagr^nUC8-6^(zZ(m&)3xglku5sisE37#z=s$bWJ~8ZkFIY&YzvrtnNrZZ1!uKXgyL1L>5RV?_3ZP%dcbUZTyTKjMi@4LH-wVl~uR>0<%>Q{NAuo-TDPfjr-B%w>vjZ5~Kn9Y3U* z7rS8DFE08Xr+&fohb=(IWWp9ZJ0sK~X?>C14TC(tj!ksUl>b!Uw%A4#mu=J?Cst~) z3rbvmaI!H3on@*XX;tWw^v0HH@*fP4!EMqhaz}>mhKMOP1*Ed~ar||cgN6OMJ*BHG z>G~vbu7j@7U=AL-IL};V(l1S}?>r!Bbv*N7h6TRD7l!Z-mI3_E57IkZBHySmTtZj1 z6VGE9Q|r5n+TH~DWlN;5uVGI^kyY*Gfd896X+o$u@Jb~-H$kkiQ3DcpW!W#VI>_W7 znkbKN0s&b`3pwX(Hg9W{^rRS>guL3YJXc@n<6$9*{5acJU4LB$=tUl zS??mCf;{L^dY)YdYTS7mU>SC(B`y{BN5>u8L$dGx&$+6o@@d~qBn?Cw&d-VZDdvVK z0qr{IUP9P;a1wqkKzDT2{PkTY;=xPOdFlHW{7#yIVhFtCBbVOi3SVJhA%d5%5sP1y zfeK#QSfpoq;`%t*n&+0J5+a_pokt|$8_d*tAg3Yq=_&TNq`2CtX6B_nHQi4ve7Ps=RNsr*O(O~f2p?U;5HB0+;EG1qpQ+d=doWT$U9p? zeZthD9GOK?y{i!3uW_Gu4}Vh$UYsEI=hzgIAI=Z+gAJ?Cz3@z3eRYifSeSh%MGPvTXJw(q4Z!>f0@?hkLl%&6ah`nC)OdV(HgEl5hXAz(IGAjl8&w73jz9g zACe)Xj{LR6ELFtedF88?$htIhxGVo(;L+V&dKV^-D=IIt44ffbQq7WOI5Pcrj`VrizDdAs_+M;5$%Ks}59gR|Aq6P?w?mRv z`DY3c$(podx-m7!A8pqkixLwH>=Y#E7P+P+{#=0m+ixCpuyy3UF1<{VH+yQRHF#T^ z8Q&Gi;QmX8?V*n_r59On8^YoyX2>w|iTW!&{-HS8t0;DD$TVpkE_DKmKWd>RE zDMfMYkT~4VJ`P%2h`G!WA1E*hsN+gX-=ct0WM_sdBA_df4@d&2OaAHtN>I(A@o zmIo)H#5WRTz9k4I`6~w|32wL13|Bm)iCGx*G~w|H;uGMTBJ-6jGtf0#On%t}{#4&2 zzS<;qkqY=TFh?~1VI87t9Xl7Jt{com6# zJ>fL)(l~ibD}TLTVEXTb?2n?0E#@zmeq4*qE((3S&YAz8P4+-qKZm`ypIB=Omz0E) zih;v${mMZ_gidnl2PGz2Pxkey$O9dbMy6+$osuM0S;Sn8JS!_*;R#om$QTlv`P{#d z?Ds$oFqp?_X`Y#sfeAVFtpT$|X^Lx12@+qnaS+IEvxOfrK%^tj&vU2d)tCIPo?Ho& zcjN%g$5z>Bx+@;hxLswTttmV@K{P}BF%UjI%LY6&*yQI;K=#S z+CUK+%yntVANr-bw0*qxQ#iCBMVxNaPs!2?IelE70ePtZIAkxRUF&u`vmgPdd>*ug z8TPy||8a(CLZMe&fMm*DF~~_WR#Bw@h0HkZPd!l0I6mR+_9*dsfre8{*y5(Q7;r!9 zr(vM;OdYHxKPu3mR{ET$=UVkiY3A0h0rQ!jvke5rFsT(u*pU4q!?$FiRFvv{%c7-m z^66ITI-e~wPJ7y+PeReNEcBqmtk&x9Du~eTkVE8ni|UK?>VIwSl74}-$sZ}Qx8#|# z!x75QPR#x;w>98kr^f;$+tM7p-J-`OiSr%5e>W#9G<$s2M6n@!=Yg48hG+W#TFQ2Z z@BQHS2UZJht}!}De%hvdqw7 zUmE{WS-h|*(3T+bE)_uf;4E{QM-Mf*2}SZ)3CuE6+hPMOLoY@MATvTVTNDIVzI353 zKH_jx1YeON&anBXW$~k&d|eSig89^;`yus47Y!=-D;OI~AnVJ*jBTSu^+bWexhlOi zq}>=JE3O_^>A&;fIy1E+df-GyTVzSMM2V*h44CE53^S%hSp!R(qkXe{SxZKWBX3f~ z7Eg?|riP`N-Cajyul1NSaLv1zc8VkvGoNJG(YDV7y4NG8xaxwSwz^gAlJ%ddJ?Ws~ zC^)ccp&xB}jh2{E5YF&06CxM*_R{aO#f|}-V}d#gTT>LrgoA%)*k*)2@#vn&_`8mL z-W5x__zBZ}2!mCHRIFuaZTc!#_*)Z(m&IjGq1FWPp#|+d zu99Wiv3iQhpITIVLpi>Cfd(_d6CH9xq~?k|J&Klp!xL6}`USeY%HeSYUz8%wx6xWz zxG~4I7X-*JLmaBrko);e{Ep343|b%@|N_YG^0B=EYM&mIzo_bi)nWtn$>-RRqP3H zoO!52x*9*;MvwLnUu#gXvH(FF4B?j8G>ah^bo^F(1XbK&dAof~J9a5igxZXH%swoUA zqKAu+aPH8`Hvd7!H&L5S52cl@xb7hzIm0la+L5=pX({45+wTFqhpmHvYEANXhaO_+ zulu7JVkaiI;PCYf+dW(pv`81zlFPjp(&xqC>#3kBJd}ry<{jE$9U_?k6r`)8#Jfcw zIj_qIbgTGKfG&*o@zguDwp+qEDdGy70u1mD&hK&q(3XMyq&7o)$AxzYTZABLgrO}{8?LGMy@orQ zW8Vv@7x^Zs1(R&Zg9O7G@ERrM=$}|zgDY%6YGau<)0wgCrcDHHfOUp4Hrr#e8TZ`UVbS_d}&i3gsE9MpeuxT zRqMzva9s{q%gq7R(t0O}DLEESh_7~}_px!CiN2WD(0SlB@DlbDIOu8t_d%0$(kIyL zA0!U8XuDP5CyM80m@o=F=JNZozA!;A`wKf*4=} zQkR}`m_{6(P&I{q1H?aIA!qk%+Fnaook0&ri0(FAz>>G&hPc(I@zbDQra zuYpPQiH`P4#<(;J_odh>xXINS=65f?A|UP`1=KrgZ7unj3)Kt1$ORNE9cW+=`&1AL zwrB=pDF38yJmv)!c@}+%3+0(|g+~D!<}+-(?uKXjcVb`DoUziWg0eNkP&W6R7XJ+M z-?+y9Ao*h!x_qo{(-#eA%O(qh+G;q@uSt?eGt|3bYEKSW0I@A~t)d<%bkL%IC<=dQ>imLq>0l$9ARf-CjY$2* zLD#!{hbbQJkYJ6ibN3GIb4%Qqq3@0mEjCm$5LG%TPo1Uv<-#lB#Gn*$#6nQae3TU~ zEl6OZ3oN?DFjl$D&UWKhe~YE#ItKLdi6zk9#Zr@7rMHB%@qW+01Lpn>c_5YT(0WooebaRc*hSAqGZOC8KB zdog`;kp((tpA0v~Axp@ZkfYXk5a~KLy3!T?>4hEIxUuXAL3+NLq4PHVlIFJ~J_Qz8 zki5hpvKsfAt25L3Vks zw%OtjWvFElV!I2(a`VFmS}3rW=zeVgjOl?X;*Ts1knGhgv%+J4GD&F5_A>&P<>+ng z#QrMQ8$1O0|2;Tjp9Kh~p6Jn=L&oSB={0gORcpw@+^__s33w5UIxIs@^u zGUQ%Qz9pbGj`1Ve{k0^Ng*PbDi7r33AiUnd)^s6d(Io=~v=>utu0JgspP?66s0qmh zU;=wmYc)FBeEn};w162I3l+}aRvN>((n z5y>-~L&_+qUK;tZ8hFuzNOn|X432f!2QuQ6C^5i8laVkvLlSxM`hY)#X z$w)z(lR*nD?lp~j1x6Aszbi-rVbRmLRkr+^#hd`od!C=}3D+da(;W0tn0(&`teRQ{ z`Q8CB;mL)sEs!|@?fZAP5SF%ZFTYs|6;Of?JPtxRRwrmb=qV*imbJSs~!3uP0PSk-mBFT zM8<+~4ZqD{AzsWd`A>>;SFTa@w=6bj(^pp`kW?t3$1ZI^r+UogzT21!YzcJE=QyB> zLEMsK*OXw$Ob&9`Rs(wu|G;o4K{~E3P>UG$_7HJqmez1Y@Egp^;22pf@&PsWu?GdF zs?!GhnyoLesBuxE*(0G-1}g<@UR)S3Uvm6~plcxi2Rv%A5}o03g9?G$8hmyqd;_%Z z{_4y9gXue5=2@1BXPA8s+Z)NBxOBLn9~Xzww7O6=Iyb2LqA7t9f;cjRzU<=fmR;^* zSA|VH*a2$P_~&fJ?4rpY&T~CIeZF5oqL;(4s*4gRz8v!ZI#+Dch2<6DJX@5Kgpj4e zDDt3mj%3Qr-tDnj>9SHQApa&iQWBpl|77 zq0EX9wnsr*W@-aEQsU+SOrFA=nC0vg@x2W(kX@XEoGbop(g}wiWCYK0Slgk~DEL_c zfjD_JL;%Vbaj4Uy-VJH}Vq~nu2GsCI-y{t>YjC$Y;-(BaEJ`$bbQMTt3xo0#9({EH zKjAye1@V@z)Gspa3fHRng;S zCW&PZ{d|~gwg4u_Z-C>yxaI_1It+YsxYC>?KJy1`>hHEV9@ji#`t7{V1I>Dt=X$02 zu`VPR^ZKmtgDb#^>5EIs=c@QcMm&(AWfTSNmmZ$JFlc<^Nu8nEdmNx%a+kxKe9RKg zb@+d@s`;eHk)9+bh|LZ&L8DjNsJ8>d9u^AU7xSP{-mHHID&!eh;UO;bz*FSm4a{y# z&(XC5Bc=Ck5#;6>hc2SnxEzqe=$}p0)1li9lXZmCvw%g?vHq}2#!e0Sd4tDME$^57 zynaYy9?|kFSGKLC_u{|7?7|;;2xe`%!*lg%{zNb=3jE=S ztvCR4m1#xpGgbU6qxk(-0|jLd_4V|hFuvF0kB0C+mQO4jV{ua<6zZYPICIn$$b?_X zpQ&*d+pOm>3rv`qMK|T6ox9ugw=F@;QfEg9DNhfft(am3=E1!;xUTOSy z!kcs4PMmlrNS>7CavJxg#qPI&+#5QOKLef*xK#6kL#_!^y)0l1#xJZRVYjoN4%>MA zGMfh4_Z~~iAg*dF-7tR4gnJ2~AwN-fd0t8LV{D+LR`Fp+?2V-@IC3^{RaK$Jl3?Wl zIP}>`wZFLh=Q!Hr@xO(F4K@iZrrwqSFoe`WyUIHykB<4bxEYW`yT*n`R9kEcAK=8L zd04-gs6#HQcd3aH;;tNmPMOs}e}W6Mb!q7+e7(&nDPp+|6uN43e^&Vb*Bvq0-dTF6 zp^b9*yv>GC{m3E>u&if@_{c^S4jmg6foSH%$Xi?ut8oBrom(gBc|+K1nJY8QaZ#el z1Fk>61KV$V?8SjFtY*VUKdF|qY;>Jcw+*M@@@W4Cwy#feq(Ck5?slyhteRVK1Tes$ z3~0qu^Kqyyj}}Y}M0}If&sW2p8z$;6j8dWI|2>U%*Z^{)&*ot49Dg}Tws(2WIE()y zhhT&HBELxzZVC~{TFfq}^Mfz=)u+BzfBE%cOYNN$i z1NCtg$1l;P#iN1=M_^O%SVQtle4mBhLg-HuXnl06VZ7n6?_}rzvdcvhn##!#@w`ow zIQYXT3^l(UBiFcWNR5b4A#J@#uQ!B{ZN8adnxh2kla^sv8w+~M>_BXaGYCHV(X}LW zd#+JHf*5b9y758-yWECB0R?^G3Bw_X<6T&U{l5Mg?l&vA2nTz(^!3gFIZp1x+*Q6w zF48X;rJg1zAEr^g!$(lm$-%5dTn~HdSr7teM_Tfvj9ibDi(zrArXwDLjcMcYFbN%v zCKMiDM=mNL2xRv*a>uGp;O7L<%VuEYG}M-FcKN4GFbVtQ|3tF4M@SIK7Won#yBqk8 zHjEH3nH7)a5eW8{^UQ9Q9hQ-^4qK0cJ96ld$Lz=a!>;soNL)WU3H$znCH$X-csPAfFlLgi@He_GB&K6S=`_D>-G?P$Ni99&Coa==E>@vgMV4J8_w zX_gPE;bPDZi>wd&KmR<-JeOwA%8~PNuo-f5mg3{&u{?9Nj{z3xW}7%tP}ZmE^KCka z5(lzy&_`JtB*$fiyvDa${F@mdl2(m{wW_PazAQ#J6h5VneAgBF!&%o7 zf6&psOAr8xi^%M0^H;g_dXpYk0ec8GSKaUOKg9{)j!o-wo42#nEhc|3&mZ>l z|6TeL3nr@ihzRiseAcv>XrSi1@ft|M$gul^#N#%7C=lK>MtL_Rhhrq;0lmMP9O~Encj-|>f~S4IL+7HzOEReA5PPc=O{1v!?YXfP+68~R^-kBi!TWkfM99#O-V%+@~{lwnV|vrZFI>>M^gm27FAc+5hAZ19hoHx z?`DL376)$9)05|T{P%I2Zc|>X5((8A(LR6Fde8OP>ab8Q?ev z0>Keu{00siBmPrlKuEXQ?_NHs|Doz%TlgLarK7~ft_VH<-D&dq68EbLcXj;(k}OzWlaW@c~udbm+Z7O=jF%?a3biT?m7O?7UGerHH6u$`G>)-kn3I{vob7Snc-+UnNul&I&sc#1xA<4u!t3Bv=%G!=z6ssU!aLFC>$mpeOUt%}i%l({E4&n>@DC(MwB^`(1Xg8hdNB24XT#WRy=WhS#Cc zk#BLiZ{oy}97HndNn4njrSCP#Tl3uG@Ide0s9yz?U5jjs5D(;F#;pBaPf;Fyi7xCL z#eWRS6-lC(3jwQIAI^eH2h{*KI*TS4;_Ehjt|c(YihJxLhI`e2#~u3uT4;>l`(` z+$j$HB9Q-Qe#^jLsvSKG@{24#H_i2M*mH3l;Q5rCxIaerF0x&bY$Lc$Y?L5enWmZ@ z%0Tf{j{gzl$bI#l4o?$R3u+A*vT2)K<0?;F85D9N+bwqmVc|(UNI#yTNH1~sFAKs_#Lhc1c04!VnmLD{QslPT-c@CPrz=m zFT41uei{%JT(%`b-eyA}lfMH_Le=Fj)46$rnU8E5c13b716R9&WPZI%8v%bpHp}3) z+l60UhDE8jI_hDOY*CPIA1r-?_`W`j?n}z#jnNXAn z149t;o6_XlF7>@yPK*LKqtdnHss5b5qo*s3sd~bD^=yx>0<+2Cr&zp;@a6&oVlwBY z`5q2=7RHzQs{b8(W8~{4bd?(H-0-P>?nHU4z@M9@s2pI`*r6;3?|xAbeokdkzjf7v_#ybUO;w){$R1Y9C!5Sz%L--AR1U?-%z#vX?~W&^hU{{t z2dA7gSpGb~Jmx_B3mt-MvygPv84UrA^$T!AgQO)}gnX=sm3e^*@oU;c62i z**}nMmIHuTas5KHd`gI%MAn znX|-`Y59$MvL6mzrHey)z%v(mGfA8R3T@Chb+myvnG7(mwMZ8llI5UAmo-u9BAbS} z|9iN$p^f>b>k20Pt6!sJ&#JA3)F=q9c5eMgKdN%FZOnIRB}ynTctGNvX&9&_{#04Z zPi&M1(abipi1{f88*p`x*RyYD;s1vXb(XTpGzu*&vS6m$(+ceSor_WTJpJhy?XwsO z>WK6G`tqOuXX-n^qp0)uGv6uSX}dGCGqbzd>?YZrowB>3h#(QWSV#g0gd`A}l+ddv z(pOLr1PdrCqKHxy^{^op?Bx`X)3cnO1$#M91vv|6&HtVJe*fow&*Q^ml1+AJKJ)$5 z_kBO1GedoOW}X6*fTl`$V?i8k%kSCoF^yV5SI2nbH6;|DmRiT;>ry}ppEgd}m5i?Q zq#M+TktJsp#0EoyI4|B7B$iWsW|JIPn&q6ntT$D zqtn0oS|8hSEaA!l`ka{3E#Mw-X(gY(#OGF^TXw*Pwbide>E*8Wbc*>r;7u+5tPL_* zEQSTZim(4CP&r`zi`+zByE>04ZuJC=rjRKqyiwHtZs%^uiHQ)QfMC>1*L_^`qpo9$a-9iMrliu5mus4vT%`(v@6`-&rEwLUK*C9dTwFE5}| ziGf7Ud^vwoho+LlB7=ug%x>dl06yb50AM) zmrwT81;J^DOdg`Work^HnG)&i$T#?uF>Uyv{Lsp?;{1ztISnD(@viV>f&I~D_m$NC zLGXE+ylk6)POxL!5_1(L=jtCp2$5I*TGT$U?N`#w(Sm>gv%{00aU&Mbzu%hp!3Gq= zi;Zx^?E!mICDYfFS~(fJvro25ml?`<2e%}#x0(S3rpQ;G?Tg3T*{sD+cgn)FnDSST z1Hv@TJ8eEjF+8UF(;XFSkm5lre(kdq`KS&t9}iuo^Pm^|!Jzke)-s>+DW+G6OyIRk z^B}LsCtB>CZQ)M%-)hLXB5Dqd_oMII8di|53>9+NwgUgMi@AsWbPtUAg`tkI#V<#u z+blrX{XPCKRT#w}z}TJpz1UDE+Aho0dFh|Uh{H$DD~QqV^ex*S?8IF?67!;G2W*Lt z)z?*gR~LKFPEK*G>yyTp0i2oq?^@CT|7__00HfB4-I-zDEtogzY9B95PCqn3+l_8} z?0?d-vj5@gvHg$Q@MisDb9u&b9Ih%+DB%qN=iMLt4&>4?qttCJx0 z2X}=(^<09SH6pb@p?~Dfenlb0D|?F3yHT;FnM6^*&aLGhgbTSC&;F}bdcIqA=b?VF z!H)gI0Q2}trrN`)QOY}Wz@aFs47t%kG*8@HP2TcwW$Dv=5yZQ|5?Y+0(L0yZ}`Cu$J(A@<_6qmT_#>+lP7%szfI=Bu?u)saipq% zqh{nbU%A7RUdK|>?(}m_xj8Q_E<*l`{R2A#ed7&mn(QVVNU&0qxkM4a%4-!R8t3Ji z#pt~y;h8kkULaT=IMx%}d^W<1tH<=%(JfN$JTy3Vp+jdiXgx5&^jT13uFsJ-OU7Cw zI?V|^*`3wo0}oWi%$dHH?#6Yu__+>qeoS$E3W+R-&rK{rdn^R~;=hmnze(Osk*7WI z{p1r%s4oY{{%P=Ed$C>~`L&Wkgc;4N9eD@@mnGPwTNkM8+Zu8~5ecqvMlpIkvV!b_2lmRlj-0Ui6dU8)b-lLA}>XrZ!Kg_?^C1ZDuh~KQrU)GWzJ-)@zH`Rry z{^ksGVj$k6huxFLfPz2wXEc}&Plzq&*S7s|>EJvzjrN5TmXeQAtc z=nkCU1YC)*u0iirN#6HEUH`Q?Z1jk&HPj7V@&1--vdR>+quH{N;EC(XPBP|nY-neR32q;`~xiC0qOm@j8Fxp!!i39-)%{*JP*0=fN5C9}jQ z9XvfRPd+c{qoDrY7FI7G){yN*UguHjLmQX2Zij(WHNSf!~IM83PQBGl3D_*ILXU3QhT0zeV% zjm^p9x<@|9gns2?O<6r6j>U2B)e_U^h8fYTpk-6hu_42}QV?zit=N^H8(j0V$=udW zI%ofX3(Qz+5{_&^Yz*(gNEwdnYiYM-E zjP|G`x8fvo%Ca1Jz9e30MEBH(!DdS}nI2*+6DRrh#*)~_5>9DNe5s}G_XWT`dh*#F z&Fz#UWwdE0wgB+%ENw@CO&mxOG2k4HRF$BNwIH<7oQN9suT?#f%> z+O;O$)1r5cFmF=DH)@IKhepHn77L`;g$8tP(OAqZCaqLS1_XJCl}^UW%7CsnB729T zm`Pk;O(q9IzYuRruYumFMbBz2n_p?pxjs#MnC@m9OPt2BipO5uV!x;PC$^*Um3S7M zabV1N@=6gVxgz!f%Ar70OZ3x9=Cp2H2Pb0v#3vH~CE^RE!<81csKn9WRwkm|}$l4H8c17&&R>Xhx0Y?S- z^i1BWDZszlGvkpz4~=}S#RXSIme`*+j+IWUs5l!{z1v##zGmJ$B6fo+y@=pa1nN3g zT?hZoUXo#A1$L)Szj4)9Jmf#Y@7<)%!&_rLCE=NJPC+X|GR2R5sov9SdFyC*`fp8{ znpd?z_{J872jXH+yg$u6*;9EqVbs>M=#*WNj|L^t#ukiX^pO&MIL!=hlE>+>(>+-# za8X|Ttd2eqwqdr$3{N_zQLU?F*shv?9O}zJfXebKtzo#oqFhZXJy2rh&pp89mD4Ty zVypgzmif^WmKB8a;uXL|=o}#)d$3LZNUJG#d9p`S1hcblVZMRk<<{88SaR+~cNc|^ zG46p}FUMEqNvjY@B_nhMef(0}I=Osu8x8&xwZzgayqvWnZ|*#}Dji9nxgl z(@}agniFi{&Oom7$t_jnS)X(%m28cos_nIoZ za&y2>F%yj?;i;hG$qbp-3i_A1zsiUJlXxReiEbsBurqbDV^!duelN^6-#=kKWaib9}ytQWy>c68Q~ds zrkSS!@k!u8@i8e|l8-bMkub@Fi`qH1f>X1yK^m)T13d9fS2FnUnLMR?9P$7D7%=+F z8s(spc`=OtkKi7ren(v2|48H$bqcXw9N$ZG|q)k=i zIA873_`5&0fmXE3%9W0OLy`PLSNj*lGtM$+$8oKFOeXqWZFRWI#qhOmYn1>E*}Sk6>qx)J%A!}3pCDMX-9~=?Dn_rTIb;xVh>RM)*J{y zykbgkdZ1#08)DoRF6-==l$WFeWS^r=0d4jKuy=02#`^H^bBO<=@{ywf5A@8sA{}ol zYiPyLhO#nJw+DK3ql;`5e5Dc47Xa11jD3wC^dv!Se|@UIBw zo9z^YgN!d&V zu%0Q+#g~k@5HuI?dqKLAD@Fx(#xK_5`APo25R@^lwXsVcLWqG zOkfJni{F^WI7(SY`7sVtM$La}9^RBf&-UYjw6X`ch;rvUWT+lL4av64CwW?$T)8EL zU%nGtO!*m3MW&LQ9d^qi{c}X~%`Jwyobqot?A&Vdi>K_27=wN3d*2*v;jZu}#dyh= z(>@&;m;EA};>epWDO3J$mT_fU3i*F%lQ94|@R3XyVBU$XphB~gIWeGbV!qIpoXP&&6|sNBT2hiPq3GAd@AIL{m3+dlD0s%EH1i-<#!+#Y zlYug3I&T~TV40VGDMa6ZNIc~lo!l_puJM$)MGm}-w#n9AXf_`DHg*9Ora0Bo8+;<*1K}yf;dv&chXEc>^_P=j1&;n1jkw z7-Exm@}v}$D!FuQYestoLtP2Pd)v1BXTj;P2wd}tI0~VTvWpr?huW_#JqA4>HvTKsDIBw9jQPqWp7~bzI1%NNh=w2}L|?k;O$IWGl=? zREl~W*7t$x`G7|za<#8GXsARlr2K-=HtgmavdhCW1caY_Qk^)DipQGbcz?DNXW4^d zbn?;?cN!m`LqnI{&(5@r(=d|(fF0t;SBK2y3KLfklbr2nt9|)XJ@O_7qF!Ne5=Tur zS*P3b%4J1Dg+KmwK(P*6<~1}mDkt>}!F(;m3RwNxeKX0DKEd`3s2eJF~5R%bSa{G z4|x_1`#Osh=?5p;&Exv=!nA_=W=ZX!h}0c}b$gX7wgzH>rz7g`T8z8Aqt5W>N8urqILvqrm^$#g)Wg_bbleE2mR^cWdl>E%Da4#OE$E zr;0oh2v>&)S<9S7mGN@4j}v{!=RVNY=X^TKi=LBYW>UFcryKLiV4t00(r42xwel%Cy)v(!ACP4xof^a*@Di}mJeoWyDI9H7wx}v_ zhj^*Zr~X}}OKECChWWTrzDbWQb?Kx)r2KL1b?{^-n^)7!sX6g15JF6Kz6W(pmGBAR z*XPsNw+@Gv(PMV%`oT;TPji|%#TRDM%4_R|@=`_mixa&7!qL3YQiz&o$Q@Lj-D(`x zGP9BR`C@OL0vEoafZ%enIhAJWTC0B4kf~J;<`f}EUJXHzxDp>XcX%~u|c?LE9G%~FDy#m)O;7;c) zZ0S6iPfnrPdq>!xX~&^nNA@?eiu~OpprLf`KiQl~YdU0Abjq=D0sEOAy~&rJccTTq zZ~?6uqw{Tfby|U4Ys%FH+UCVjLS8^K#UzipC)O)ZttA6WC`1xiQn7@l#%72xSly&Y zZ_m@AfP(S8n(8o99%62w$zm5KLBiE|GFWR+Xq)Ma3uugYB0mh!_uA#m+8}YJ$91HE z1LvmE9PkKeC_n4yovv^?Fa4>Yynlv*Cz}pa4{PbZE=09(Z36mdO$BtyhL|1Hy0tZa zR1?;>*=Q&;IV89s9;T+yFy9>j5NR=__MPNu*Laf84}g0w#^{zn7+Hcz%879viw%H_ zTrz`39=7beCxyXfZHf#iV(zKD8z9~ffl1&7qbD{g&r~wI0%<(w-{g>*z?x0ff3$|x z!u%R?a=`DzDnCC`8}Kuzy0bM*$;KDh=?XeEB4N1yh^KU~@6dv;J|w9Z|akNgHH5mWj$psE)pT{CE9 zU6PZ|mo}@$q*?-bxdfj=MZAnAN1+YVC|<8em%Hi@o)F{f50?1%{*NP@t>@s#CYj}H zXgZVQK~oe=b)u*I)g|Z|eeTl>sW!?HuW4ZJvlFKVBFr}`&Ab`JahHBTnGj|1H z58w@7{MwZ=p@~97+Vs3Kyud9q6@VFS_?ZluNr9f~=GLDx6s1+4$D`MTGk-f?)LsnM_~esF-mn#v+i1|bO|Xe~ayDE!17-#1k3wyRDF z=ua-&k|yhYI+dzdP-dYbU+cj0vEblLEkxH1wQ%JtXhn@)C%N>2B6-e~J4@WJ0T{6h zLzldYl1OEloe|nZI-DhE_yQ+mT<2;Km%%sYC$}P;xd>~(BhUTgEtVv+r zQws%?cOrYeY7asDhbPPNm9G@}%V=^X<@+>=SL*t8dFi}@P{W@v1$eK+>rIK)ET`Nn z10qnOUE#@3hU5WD=_W3wGJXdic&DBD!55%OJUGq3{~%99WM8I8YaQhkkL_znHx`7? zhs5Vo=`zao(KFPgOo4sIEQ@ZPc0z!7zaE)PWI0vUN`BQKbqFWDpADavIG=zWZ=edO zq2CUQ-4l_(gWBTiHt#N?;uVxXDdcKpL<`A zR0Ps2Ptkc7cjoeN_Nfo`l{uzTZW`$v=jkKE0@FrbILfhaQth*A$;06kKK^J?T2139 z=>|JhYxT%%mtGyRk4xjB_4wp})3UjDx$tJ&%s&KuPFRN|zKsbdd&;UJnC{kg4BDx< z5V&{8yvJ-~=?d?vTMOJP zCf!()1_tQ+Z$nlqUrZB1rO-A=$H{pk3w4da!a2nzR4B+BtxM8I|kCw$oCyS#4THg)fY+AVm=kwq;a|KoAQGT+MdZ>~a zKFOHH#l}12S5I0+ML4b>oW%GV2D=uvM8z+C;RH`uN+IQl0RoF!WjE%`acNOEA>h*} zJQq41s0nU_*weVIn@&YAs-+&en7CBzO_)OZ&;JwEh6$JiF| z(@Z7O?hNv*mJD+Vjn1I7+0kL5et?4(36z_^E8sAz`2Km$o;AAubY9rw;+;#7-0VEO z*E}ZRRMYdF=;txM!&4r1p*>|C03@EW@bZ(&PGqy4YzXM(Ad02K+8pNz_Fk#TTO4Id zkwUU=LZIK|MVC?*W#NUo{B~Y^6g>-599&2BAl7+kueq9X^J&d*N#U19Z3rj7oF#{# zCcwuprQA9iJFc2E7x;%Fa>}!WP{c2XH@}ohBORr&3~FOMy3-?Pap@jd2}HvfGtogP zNlZzRJ405xGCzPf+ly?5Oz+Cp@2_Ou9a%Y_9rIml%~SvSjMz+i4>~{q!OZ`P4=R&U^Y^^HD_b9 z%UinL<_ja;sLJQBr8pqsJ9%NcPp6p5z(73C6NYw8%cfK5(RzA|8tYR_0F{FDo?HwA z1#Ub3U86^i&-3d-9#maR9Y!%P;go0{T|fIYM$0F9@)vF_&s&`(`nASR>xwZq08SB5 z1jXKI<|LoLFTu`4hfk4jbX07OJ;9K^^wm4P==wAYTxAKCr{(2gKKqs_O|7E`JoNov zGJkPU#b^GL6c08xb7cFNCKAky-#pWkgoQ--1bA4UB7j@^qXpe^UetC39^KjSV?zXI`6P z%q!8JRYVFX9-z+sFNFjAUIKf4PM?AvqHg}|iQ`>S#46J`j*Gru5e_S>KcD!?}M3#r4LP_>E;X;nb4p zfp7+|zuqNmKB?<0AJwW}&kOz9yY=Raz<75aK7s}1*$GsuX%)WGYSz2pVnfZ+Tr#oW zH=#-F{w?H?mOrsQbG4^>X=X>jZ%>ffG_^_*i;jZMaxX*L@0-It?S?e!+Ze!w@8p%g zmjn4FQ@JwWzwuCD9x-3Z(FYon;dd9+0uxQrN@q;@)u@9P>xk4lkQp4N|7*w7?L%smD-o)&f; zh-|AA%TKqa!1e3nkiQn#6D_HO4#2HHvxYPj;K|gtd~n;vld@u0HO2nY5S4-)*5$Q( z(s4W;lB2U}OtaMwW;56Ld`%U0%K$9^lN>Sk<=K-3c3LiaT!H*mkKN_bTSDG&b!~HW zF^#NMO0nulX*?55yx;B zCP^R5lgFAR+{MSkT0GI7VwOOCNF(L@e6-3~>)y~N(Ow6lw^WKdTPxwoiVgv!{X`4V zFs$uQsv+}>{N`xHz!Du#=#>@GTfq0nG#VfK;=wp8di*GkKQ$-Mrix+npV#w^MN(Tu zMmA&R8BD@jM;x|HBV%&<9|NMV=+^a~bemfS$GdimgJeYA=P1`V#`~N6_CQ?fCZIym zFbX}W$cAD1HnlQdOJ)Z2LIWFb;mPpCYu^ry{97~E=Ox_UlEr>div9KfI5M-X07sUv zWSTucbjA8nt)`EQ8MBNP+i#XSKGoRCh&4F>pK1Ad1?JO$x6=$n^0y?&RH|IAi2u&% zD~q5;OV|76SFW%w&7k+RUg!7ZBR>|UM@r7^N={wSl}B{e^Zx<#4^*6~p{O$Af5MuSXQi$n zF|$E?Lr<;*>=m-Ayt~O^7I(#L+N7UqazFUthQQhk^I3c5f7-k^tCm(vfDZ##>(%ho z{BJ0?bnW@P`gfnNxA;p-eCOe!Wl;3E6wFHBj#=ebT`}dcZC&i(&opi_m9Ight>}1S z6ytlGl4eF0d4GXI!H zl3nD6!Cd^4Jh6wP`+~VA%JjsL6nP1#X$?FDbT5n6Zi7Rc_eRR!SSgHd%Y%Lyb4bSL zPPfQKRDFz+-Zf-*n+=nk;L%cnrm|@JhbCzXST3N?#@X_Gj~mHJEjhU>eaEp89`)@?#McIOkl4T~5)GmfTFsF8x0$}pKx z@)Sz1q{3D;F4tm77P-KX_ZR5tBAr1+e7~2j{hsG06vY#;e`sIn^v=VlTIWh=a*J!J z{I^(srYrs1xE6oeCu*eQ6* zTzVY@qba?Lay#fJfI znkG>~%yF2{|T#Tj|)e1GFG|)mycDxsv>y||| zixzE|Cbu~Pat7GsnW8X)lh4ngk%c=VjdPS*zfY`++*@R!GSIpIRI4+`9uw@P;ZQC5 zrXF7lw2dcJ@$SIp2#T7yRGR9<`Czt|+OZ>qHIRc59Q!TQbO1DrWTSKG~+D%dM7gyNpawID*3eP%wmSay2w5Q`N z*2%YU(qFUaXrT5~204*Yz93hT8$%IaG&F}cjx^NMzePb^cIZ1ZTjr z_)AJ?%}ll$q&Vu;i>YxS=6s!(Qob}M!EWuwzOQkMDYuMKv8aYWQ3%tA+z-(wdO967XB> ztvMNO%(XTv`ebiGK31+`VgYw`LTGZ>E2y+Pr<{dFDTeX2uWa;K6qvYC=%kr04FY|$ zN%xI0H+kq_F1AL8y{!%uH}BLVz$nljSRIIX@NUb7*iuw;`1gs3y4cmu3!nh*IpboH z7{WzZfeCSTU^`tbNDr3thT`z$gi%%(aTQ{+hi>os}24|vSt(3{mcI7Zd0D#>?k zCepG`b4dS$lP#h++;!AU)-ac!m$)%1{_aM1x#E%9@I%2QW9r2R1O2JEips48`?<2w z&zp_KRG%OAt~;12^z5wTVUqIx#a0i8`B|u*McmQ$%(^2BQbK(br%}`l3^bH;bl<0~yv!yu(M`O4`w?Mec6b_HEZt|eJOG=*HmrwWZLPVlL8{)5@iKxR|3>3+Ue79f5V&x(`rE3KJm1fkn8eWWxDFc~si!YDMt@0> z6Fli89%S;XtjiqcH^G@3<_^hkwVKtg@QKUy;!DUkd+SJsW8+7}ztM8|c&B*U_uz7k z*Q%1*T$n|Y(I6K@Z*l|h*W3H;lb>T}#A5|<1QHwu6Y%__i&)zxWcRWqPUW-Z9?1B@$7%!HYnTu?A?x4z2BPqgRe(A3i{iILcX4gH~y0}+_m z)*Sax9vOBx{eL>5j&zOwKH$rRt2_ZFnL%->$kY?(wh7Axx;0NWc*3I==Gv2xmNlhF z&jJm!$g^QucDuFHU_W-`X|!fZB{ON9jr#KK965Ym@&t>lap0RQp$0=->87ZZFMAR6 zrrxWS&I|FN?2#eK#~P!1 z`-jG2{y&w*uC%30V?0$*zOG_Ai_*%3aaA6{O=GLL z!jTs@s+XJmJwfDdSL`ewddTt|rDjy^9GaXlEH;``TeIX{G^lxVH8xGNI70n3g>R zlW=!Bn4|W*xRQBeb^<1OEf8xVWC!tEq7v8$oX5RVE6!^PO;SJ9UfCq> zhIVftf>U)Yt3KCkETEa+M{4ZMBu>fQKD$dpf%%YiohPs~K93sTwb=jC(tmZu8jt@t z!CdR{J$2M0T1RXAORZ*If%~B({R=2O5B$d@hHBBYn&No-DbpCp_5!#Q$_tR=9v#55{WW%PYr_Y9@el65i0bK{**? z$+fn0Ph)zUZ+%$BWPP@rFxTbLOcAH%q-UDS6}^qP=^LwDWo??<;UEQ2{^8IC4d$gL zKPs4XxvO^`I$${t;F}mjsjm$)CUeS=EZOTxPaDRqPFR-Ar0Qowb;SRd@`mk^o2>Ah z|0gt2ILrD(vlq4{mkHvUJYL-Kpe0SFxUq?|!RTu%=V7BAVGrOyXrm1dMl+Kxs$?FT zgdTu=Fh^c53a47^KXZuAF|meua*%afRQ|=)k9gdRwc-!M!iS)cXL>b=+v56D0Ugar zB&WXGtS_N@u00H&Kcz^Il5lq@R(1fd?vQC>e%Rxhh}PoKvMcrUxOc)0m>s^3TaNJ5 z_o!w+IHLAPSN)_b{zj4-e&JS?Jy=8P3MeqmBfh#w)cR#msfST>q(iHG?hho~ZC>Z$ zLpU|@)3eh2E_eMvUcv;ZZz59ggf}&IIPia6q50~1>5G7S5AokC(TfuLV>vd`l@{GO zi0NfS{^^PB*ERLvq9Sw|~6IC@T&yx`Gi zLQUU}MzI33bhON0h$!#p%`-iAqb05%lR9SLn5&xrt+my@ZJ8B&vKiRR~~~L68mt>0V7o{6Azp;gC5p zhF|JNs{TuleBsL9xGYpDD$X|xI$SSGbvAA0K5xr{&GbH4Lz65nsiMHWnQ|}HkbMPl zo?%u7(gKk=J%dChx&h^)BkwF=%Ov-BTfXz~QR_TO>z75M3Jj*OKQABku`OP^8|UwJ zjqRU{U=(v{IL8$E5`DXh`MJO?OITkb`xHdXD}QaMzyjw-z4&deurkdGd3068rIi1s zNnd1godHL}PT5hbpCctlRbwWKieNTJ&&ZN1JoR})*_N|T6K$kqz~a6Xi8i|WPet_# zi$YJW{DZ-vdvYm_d}*t{v?dn|;;K9wpJeT}qBE)X9F3ln;@E)}3QXhC zJu)i)l<913vjzkj7^z4LxFiZB%)w=G0)K&jMPmo$q9}|oF>G_>2Lt8x zDrRVrUzjky&a(RjH1GJaj&X(||H(^lbR|H}o@~~yptwoGc)(}F0t>dqjG4EO<&=lo zYfxWerh5UW^hW&uv`8K{q~SU4EU|!b;c6ZMsK?%_2RNWF)Pb_=U1upkOE&oPKh-|u;N)sGsZ9MYKh|F`8Ov#DUTXaB-@e3C^ z3B>;m0o@s*V}TEBi>D>IVYrA7T|Gppefg&`(UZDHM>ev`U1YLOz$$L5_Yb5dK_+CcAh+Lak}8dP4vp6yxTO(+zotXB_lc z$gK8r*sCc&jf&$O>jIO%HQ@WAEmJ;JX=fZIH7c`$a=6P2IT1ULHhO~|HSobY`ij|A z;rLj3D9mC7JawLLi2v5f5$z8y;hqpemH7Y?iaSGD$dkfspwUix) zClKRsb)h3%5mz^k)E}qx#GLr+@F@H!=AIiJ=5UJC6uDg?ajDWiGFH4m)~}}Q0%~xE z^eCXG7)K|_1=qofR|Y0P&`_>MC7h9y>U{+Fc-x(ZMR4t&% zzuOUEgt=It3-hQ(&0DS5np|W%jrB^=SxuocdpbNR-RxaugB{-0TbSDw6>(JV$dRK3 zuCGPT&4sx*@HP1N_NdbC>e~v!@mad44R%D!N!!$_ua0Z8M@o-UdP+|2He8I_nEHhG z|hTeD$n5Ec6DdaPR%Z_9yyLAzP(tgeULRJynrWvn-kkYz;>#3iDoW*Tp^eV4+Xk8! z%i83uF@u^FhH$4V-rJCTD8ZgMN=fSMRXJ%MrhujzZGv^_cJS>cWPVPt5aC)yBliGz zP#}v8{lzX3?#2wcG8|3EkLHwF15*DmS#B&&O$$zqrf1Dmv$v4i5m#(((9J|Se3o9& zSS5!<4o|vvNj-FE*~hBLgSe7}vD#yQ7h-@d;`)zjnX+d-<8mv~%m&Yxs0-6VjHUIt z=6yFQ+dUjAx7f%5HhbKzBvQlljhtv@$w`6mh!Ixq_>Zdwdm-_9guN+m4)eunR=EGb z`PSf^96yyN|6;?r2`dCTDlaS=Uv;x(eD09jsF_c(g9bClY2vZao3(@i=15NSMpe$B z&fa>81tmA;$kzei-6HEk-0iuuXnH`CwKFOn@9N(M{9RdkjTf3^9z7kV{!ELm9jQD< z=|j0Py}{EpyYd1${@8)|S1EE+QP>p*m=>EKs9q#1bF#6i0P7h70NVF7nD-{|aHy3! zdtpw!fL2mdoZJW?M+XLo6&1PP5@CjaIkk4yke?frrACAV^5Vz&vogdS9$iF}+jEiI z8f)VPcntE0n|0Lz8BVO-OYFmKAU2?$s z0+_;rvMnT%O|$iZbh)ff$;L29{aF{*xpJo;xhFJ9GNH30a|-Sjh_}n?#S;tsm7z(F z|2;vzZ3dlA+f_qu8DuOlqO&}%HZ%!q=9wkvlKv?deY`>WtI2K+B76RiC%ek6hbLPa z9-D7!W7v$cm>RF;#WNb>Ttc`fka22G&MALx#yMBF4Mp9=?WrPj194*5DeDlZ+C?N` zj%d~uo`wYjmjD$o#s-oXJ;-89>=Ui_gwa|#@3WnUmfFua(k_pAAt|Cd+RjlaOQr>M zpOGBa6k9I3zhrde1}{d`1^KuU@T0m+^qs+i+%%VVyk_$s)K`=R>9{=J+1zXy2?seq zGLvHZG$!lNmT}R{Txz2&^QL2*I|}8Wo@+J6@^oFUOm6jfc(QkM>`7w9)Ud$?h^+dz zJcy!PDF@r**kYJ2&l{n9rAfov%x5Y0r>=;_+ZH@x^gt9Qx}r#Sgr{by{aus1T$YE0 zrzZA`&OG7@6AIk+@LbT8&bH)KuvHk7*;_B2?aN{Og-`q=!RCkS8kKIY!I$=8L+$UY zpYG@TX1IC>;|TTf9GNyqI%u+u!GO-g*VscP{p;G;Rc#a<_G1p;t0CDLYHyVu*H|g1 zJl>39zHt>E*NV1XRg7DrQxn2wha@QwBq93e4^8aj8GxfN$NQf-#%R}3gWv~k-)ZXi zZK;7iQsrxG2`f;>*1nLW_@#R}k;{@;QQBuDMl?khiTPt0;I+eq>gv35Z$WDP|EK2r zESwDPS;xY9cBvp{v9zPYyx!9H<%BzED+x1l(qm(4aShX`j0x`exV*V7_7q1x z40KBr*7 zdQ}M2%|tz8d3bC9L1sS#dtNX%QE^&>y39ZqU%zladvb<*v<=xX2C{^2ioN{5OG$Uw zQzY@V+SF^qK%-F>QtsA<#Lsc=?Lc})W27=& zYcX^&Ezz`*8clLv(wPfzEe9d?hreA2k|3rX}AlzphGYq8No ze#k(>t8$iT9?PIF1=K0uo;T-WqjQ%@{$;QO9dz(IkYBge^DqerIxxu%Ry3KD_LQj! z?&hZhjUHOG0?4(4JHlf!#;Ke%Dgg*92Co>ytjV$GV~eOoM&!8RBC=iy^vS!T(Vy~4 zhsSOY<9c711b1-_6-LMDpf>YG5TYH4pH$fy7D@QN`eBN!DahNyaK8g4Vb;iz{#m1p zBXk)RH5Z71$llNGnVI_hunGTyO> zWAjs%Zf@p)rA8fexub5bVtQgfa93OCc11)TcS)Ctj=HfQToJUh^jM=!2UQl6-q<9Q zf3U6cGY_Zc5&ITbu9*~nBpDJ2U*yzdwPa~PA2up)b3@niT_)NEho!?D^A2A<&nmOn zGK*jX;{8Gj03Z+Hqe}$th=Zp=++vCCIpG0{X|piIsqU#swVv5|@R2Yj`!#2^h!r4p z;&-6yKRw6ZhOJN*xg;ly7DIp~inBdY0=JYwJEYO7?mm<5y&u3sALsI>O4RhZ;aOn3_kHrJ4C-W34*3GK3^V#+&>}P5Lo7nL`Kd>)dG5q~zXY1P|0pT;zvZ z@=ih6XIS_?;%~LFx)F2kqNjb%h+s zW#hOKoK7e(0S)qNS`csEyeWt3W?=RBO%8SV}s=dPHN> zIYbF&ijDdqtg^1EVh#uN(gYbjI=)L$FUum4k_Q^7xy``^Zc&<<-DQ&Ja$r1ZaAf=1 z%u-leeq;~rEj)aF^8Ta-{z=DkoC-ZCR9O!j@$~UD56dR^dj^7crHs!URCBQ%EUnasuv)giLpvY~Za1#3_M~>u$H^-|# zS<3l2;A&#f5ki09zRQ~Atzm%q$XRydKF?>fBVt2E`B)MsI6|EZm(<5^}Y_N+%y52-Y=t4bzI?vt{ znyJUN78&1_H(^@vVv~7-rnVq`Eg$>=c4Dt^tidAFR2hc#QM@`T$DRi9FpFFVLx{>p z)o^Iao~U(UK6+k3xzthDP7FJmyTd-H+8%6$B$b4PEQmb<4YOdY>r;3^Kd{jTk~IO_Mwr-bsiSu6D9S&EFCwF-4p{=(Cr<%%bi8c~RJ!pyhK0X75$RrCA+hl5-8Ej~Ct4U@l0L zvq$Meb#6-zV??vnrqidAx%n;VSJlH1aZC{CX2_p!4!XDdB%M1EbNc?u{Djj;psN`Exw@#t1m%vY>5!8F!m$|Fy}zNs*Sv>=y|3 zQw-tdgt4HMTo@v)-NDm!2sjj^`lq?L-bU?Y%9K@jpRe?P)t$P_Cy%w5J*@H?b`dlx zj~hx}YJg!mJ`9uUI65Tu*DUYD4a!iuA~ud3ATi2JXKm2q8X0jO&z)Z|n^kV|DGfL# z3g3R?y@2QhT3}XqAz&I+?7KwlGv1G$hlD2cSd06(luNnE$R^4FeH4L+L)z-l*A=^t zmGBo7%kV$cY@n(E(V3&Ws}&+^zlXW~Nw}(Q0`$K<;c*3e`-7cT%-&t*rhP z^*Wj{n5LeZ;6^u?x0&L43K2R?rgkWUyzi;K)|G$xNDun3%&t-}6LG zVJUgp>P7K_$51xeJJxTTmlycSoK$V`b4%1gG*|&;atK%J(Q28STkKg@0$mRLA+?fU zEwt^RG!;sR(CZZ+D3|4Kt&aytA{%Z&620$)|B#oh)REmPD=00x$9hn$qg{DMi*m{{+UoP(6C-Fh%Ir)_y%=Gh`m1{H|Xp-%CdqR6)}=G zlM2gcdCRN$o`h|^kDVWf)z|^~S@F>8hWx~6$0I$SzryUHIBF2cD8zH(%pf-q0KZJy zi*YlF0ih@!_$6S<3XW{0o5_Dp&D<;$zT#j_`?eUtW)_YAHzxw8PWCnUZD_P*IBAe2 z-~#b#H*IFI%dY>3rzLj9cmw)@U;B%fK93J^tn%E-yat17y&AYo)wGv_9i!Cky9Or}iI@;ZyoJ9=E3T>K5Ki2r%-6v@HH zrKvOQOPwgc(3;}k^>U4^i3c=-b!2jTo?-%#H)_T?LEGBW&^@NHETO%u2u(2!T59xH z8{_d;N*F+LYr+jkW?E=bgA)_S$Ia6y=b!g>jP`Cy_}2NDqhpOHSy+{GTzus>hCHQ; z%k=oz2)_a8qJTM2ITL3~+;EjNOFpMq?kDC0uq8}3K#LhEV6xoJv|2dPCWevGM6J@? zFBijX@-+UhN_e+UG3&8FRv@5dhFStHiK%pxbqOlDcq@YGSV~EZk9#iZE2I)+LxOVt zU~iVvzokrwtB5U|%DIk&<1aVkqEk}&b}S*u#l82@G&%1L)UvB(dobp)TGcgl7F0Pe zZp=5;Q)+ECosliId#VSTTQERN@l6Vl_alt%4(SjG#`N0FtG7`a}M8FYjy$z?1DQRgs z_Ch7~oFZ1nXdC8AL7Ne`&uwr_3DI90sk04*3JWdFbK>j|l=ELjgDw7hz-P?WDg=GQ?8H8k4_h_b&^*s3?vHsy!a|jcWdN| zl$4rgo9SV<#@X3|9iD7_Q{WDhxx9+qtB9pBN^@Nd59)^AAps zoB}DP#bh`IN$l`arrgbhDsg=BWM72V*&r@%iQ5mBkYNc*F5qFE9Va7OuqVQ84dHhR zg1ww(HNUwTFl`7f?SgYllm0M`{||a^NlPnab#=^}YV|*c0kd^LOTR;!eN|fc zOCyVDeJOqJjGrqQM_(k-0!&UHJ3T+f{i7<}ScJULz7Q9IBSqke)DwyLMM5H>Mzx2y|5(Dy&9>I+U=sKVzSF2sz?fW(Cz?knRcFg$1mb7S}YJpj44GNjt<5ImCeba;B z8Jx?DUs98#1!m!4nm_sRR9q)(+KgiG{yj7Y_`I6EW_mb3)Nfm9aWI{eEqMlR>~@od zl{Ec&A;OKbY!Fd!aczF1adHAEQIh$GI9J|+(b>S9Asljm3FYdtt|A1OQ{#AY?NG7q zZc;W=%jxkxnig)B9S+NLT~c~h=i7y{@5c{#Uvn)^i@#~)eoMg|O#ZObcdk%5>qQbS zV50g+YK(qZm9C_a1m_xjD5(tZBx;x`$*Py@?7J~#mf*e1<$R*m-+Sy;??g!!DWOgP z$#WJa99?_8${jD0yEIas(%Yvo=Xr#O=q$K#e$e*9m_GkNA`OZ;Ud-6?mkWXU3HR#_ zj%0w_O+KG8|uKDN9O8iJQ!+qQ~;t2sy(76XQ5+Ia?ak zQ>dlTwCop4y0KY1U+{!moSOt;<3OdVOZ&skyh&3F``JQd{#eHvdfn2i-kK5Oa@l^O zAV{!or8&c*X04{&NzLY<_ilsy zQfVITb`141ev8X-T+kBMoa(~(>8L`$c|XF4#o(VEd|a8`DDxrLhn32 zR@f%+4-8a}cj|!XmOMQRAh`4&&Qw=W?cYJ~)DhBhS!=Qk-=y#pI%a>7L^wazv>~;^ zFB&5h8g1V=;rr>63lyxz=fhu#A5x{Oi;y#@vkj&qY47adj4-o1E6&&1Juw4)@mpPN zc8Jt_>=$oF;+7XvGtcLpT^5g4G$s+S3j-U(S@NmAS&5=#~D~*ypAKB)b&QMcUQPHe}FfF-BU=wh(h>XJD|-LiEcvV;?CRvUs91 zdJo9vyDh+thJ4o)-!7Ud=Z%#D`-WlvHpMsX^1KrkIp?e;=LmNVR5m`RDk4Z z4^#j=V*VWkD*>V0T}^BLxBOUUg{q31U+nGOC!2Q|WansiuG<*qXK%6C2^>}%v3HDC zLvGTylAf(EBFr;!k;-0$Jg<%MM*lIBNuwN#n$e1efLDPh`>0&JsFQlKo;Xth=CvSW zT|$NAvROAm0VKyQ#|x94yLHUps5fD)k136<<-gOIKjV%$?b=sPr~vW7e6En~)tu&_ zkc{|Hm5`Q!9=bsgUP|PZ@($4(hQIM%rnCEFsOM1F;6utMJpVsWcE-=tlSRxniF>mE z5jwLCbCcAgDD9a2yspkxNUW@A7 z6?`GgpES|;g&mA7oq*Nd{-1}d@ML!-=)r&7g8?G`QeM2tl26Z-t#Fe^6KGzWZ~N)? zPSjb=aX7Mw39Henqz>eWC;PecEpLv4n3K=M!yY#|sfwD-!3cu{^Li@cmCufQob=CA zPlg9|;W!V*8X=3=jP7)W;w*Tw-z?i8(R-PoU>x)o8vi4vzgAi*i?+CL$FxAVjuA;z zqp>-HEwo z_Vz@0o=&cfInhDARN%(OLCaK{If*Mucs3*g3!G%O1r<4udZrqi=#yjGN-% z{434A1xWtoV_uqs_>aA@80W?Kh4gnN^KzH@a#(1eWPWZ(rHpM(ir^0NHTEB9x#)U% zin7b2V@7)}FU+-+Jz38(H(5g~c=KI99wC=U2l>=^qIX{<#iXQ?>rOaN@bjf{W(o(s z0|jfq?Iyu0%4&Q?Jy{6Ltl!~_2i5*W3C)<2}%aAaSVEBiY%WXdg;tz7g%j|)_` z(%6D8GQxhPESwd0J~%zpqeG3HXVF3)VoF!0MJ%m2yI2lS3w-WmuMx;XAq=w_kn^fO z=8lB@Jyk|ZhSxC^jTOUNb`m4Z-j~oW(b;?qyN1x(7DmUh3A^4zaQSxvS0xJ9ILSOq zLj8%(^7OcGy++oTYh4MU+2gFX*cDKK!~Unn+pjlCQ(E4x$Yn8Y;y4?8CGw2F63iJellM|M-_(=gAD~{G5yyU? zdh@XEA;gp+Hp7Y^`uaxs9qT0KpSnfGbaF?b45Vt~ z6SWWjpCdbYSrZ&t#vCtk9~2x$evy-OS<>P0Md+eP(B1{pi~qaG zB;(W4MnyU|rVnrC!v->K`fKAuwsC10(^X?Ep?|x(+EsdCp`Y4&AY-N~@%Za+_AzU- z#^bDWQxs=J+GgCjLr9G4okJ8v95I)xk6+%g|u+YPzWZu5f=pxM&&iAEbP?C1AM8XK5Gy z+F;I@dumufbVpomEO;_^96m!$ncT)&3BksbQs+&LzURc06zIi}5wac6YAl7Q{Y_QI zW=>@aNIx=jhP%>QA;t^4OlWa0sqjynqH5`~KJb~t2`RbLp7v5X7I~W?C+iar^EcM**>4x z?L#aFG?{<8wCA!un9XMe|Fg-XZ$$mUi=!>&xvU0H)<*rJ`I29h#z!v}%wus#F)lFI z8HA~g9_Vrg{jyXn0Fny??syQ?=I+GKpE!rUSU;1! zy$07hGQU^Ity2^4I?0mwpm{>f5wg9X)wzPzyrD|7iog$S;}5s0m*fTS&V>5g4i0n8 zXLJRC%Y8BZ((zas9+^Ev?mf1Mdb6>mz>FZ~XD#~)&FB~!(^`twYNWlKc5%+|xQ`Z! z-wTDJ&(DlsVUnNH+}#Qnv(PKGYjm+r8NS%KknP8`+D~V@EMY~`D088aSGy$tB5+w` zenZdp@PE-ttM8MnePa|vSKtwYI*}cn=D)*iJlp4EyQ9*gGrh-M_M5X&q-DG5zarZ` z`usS#h!;<=l=<1@4Q^%xEf>va{KDksz$Joy$bx8T5p`x2wZX+*Mv-5>CW#SD5Teff zH7x;$n~bid-{hSLe|1uQl6o`a`SJ0wNxrTC%h!$K%A|SHH4EQ`!pHC$fiuA&;65!-e4O-n)(r_3ZXYK4Ou^K%6%w&pjT*ThW=bG_oDa!8-5f{DizqD-o zFQ>wrt)bqmwiHH7P|QrVWM6Xx>%jW725$w+P>y#*eJOozk-d{jVYa7_^&tmfNAQ3s zXXTx@Bn8<(Z(9Fyd~ia@R#wYn4)HUP-$^my0u7*hU&O_6Ys`hC@Q8-r;=_sOyIK9- zDAIlVLk7Pi#b4Oz+Z85vbu%B><(U~A`Av(R$Z_b6J>KG%3VnZklQ$?^He-(i zYl84`B14k=qBPhpvaU&Zbw(W0VA%RbfiJ7jn&vnG(by*UJdwLBfNr7IO&6B0F{{(q zI?1go7H;p>x8-$?jSFa&oNU^jN&_RZsX~3CTYlR~u8xCGZpQ{5s6!QcGUG3+Tzio` zx!HtJ5JZYeY3bq zBYjd7+|xV+6m~v8IgI|o`c@fcvvh>xPKCY30%Gkv-K?iA8E>D874zv3An6;2sYhZi zB)$l>uHFNWn0JiAuL2UBcCv>x)<;o!(_m#)awVN1T!C{&xB04_8)fN*ZG7!BvmS8F z30lmM9Ul8O)VFya&$IoJto>>?Ifa(+=2Lz$q!|4#T4VO^d&FF0(3tvHryli-k6G+Y z8enLTQ*x6}Xf;KiittA!_I=!eYRZAv%ag*sG(B`*R7-cxa8JPP;(`N^I4b1QImQtR zq~n^Y{y70kIa2<)x91VF0d%9xZz$GlyY=ll_fVlCryn3Kf21)7E9m94Cw-xD*I0_y7PWz}Gyc(8fcbeyb@{MV}W*?-B3xqzs#~wFZC9e7( zNA`D2x_(>;%NFy<+?GR&Q9-kr77z1;#f}ouh^H%jE;mVTguYtgcUVSm&Xnl>DaS1W zhnW9BjgZvI;<)_441c8y?Q7ci>^<xxxA;fG!9zgc~C6eD%YjRJjyUw8Ok zq`{B8Xy*c!K2LDqz4IdqX7c=K8W$e+$O{Vr23?68v-(wT;;zK!f|)Q+)9H06OiAy) z$IV*}va6D8?t~{39*Z-xIRS67Oprx4!?e)Dus0&LPxkJ1D9HU*2~r}-okhuRa&fiv z@>DmZ7;^!M$e=%Q-io2{gz}Uv$-2Zci@s0+U*S``45NFAN(s}AJwiw!Gurzm_Wu= z$fI-CAva!E$<)w-0G-iXC?G9+-Mqg+zgp&_3FUzV*{X9dSoi_mo9oCLA8SlUxwbtK z1Vk^!gzE&90o;hJ)@zalX|hM{ds>lkX0vuZdei3%{HxnJIm{jG@Xpl92{F%}v4I7& zEX0V+A)1yAC_sWt8QbLDImpz|{qm}vz_T0QJ-7F#KX@a8z9u$p5v;xZ+u#9d93 zY>dI;17l!qaLD#b)*08y++uOm3||UeY&7h#G`IJ_A@ideUdj0u`_$VK@h4gRswgHE zQ62FQH%c=)0@UE6M*goF2Mc68crU17p3+Vu3B@5ycfFXaCGiR@1&``?3HF?gtxKdV3C;pVlZ> z%N(@RcPGdeo&C}h3X68RqZza+n0v~NO$pb2C%dIkk)MrrcyZRj)0i6Hqb8b)9B+@) zZxPrTf^^Vb;ivS76I^hCNK>iV_6$+ThPfU-My9jE}>jZ!Af#c>= z^?YT{f1S_11!lt9uZF|Tx!E32rLJngrQiU*rD26sI4?mG@h^2DfQKj?6J{M@w}#{(Rh z5d*oQz>{@SyCSbfM1Pjs?BK7qRGgzd!R zQ_0@E+p{u25e9S9+jHDp(kLR{AA;Dr&-6_?`*C4F70aDp$v8gN@-P$HF+_p+b3t!? zwjc^w-R@&MYK`aA;-(_!mS)d51CYp5wsTCFe>ROVFETdfJ#U=3#KlY(gjWil>_3id z!0*j)WOg4QivMFZNeYn=F|n;lUxK-^0z_jxWQ9eb|8oxwB7PWiOwvEC-K4}e7p{`} zODE-YE>us2YqR@iJLbN3tO||pzKjPDb*3pZeXob3it|kKH+Y$078%Sl{Zjf*S^Z--NmNNgcl(wGgnuXJdxDNM9H_bHRWK&NSk&B-VQU%yUcxdZcog)e!LF-UcNiy!T80| zG=2X^J>-ixGl!?E*oc|5|_jR`&EKnoKWLpU%u{Zy8|K~pkAHDMxV_oLH|*_+`2r2f964~LA3??RsLnlLiABw&zrrpbhmb5zQ@R$%})UD9S;0jt1kMNK$8~dR69UerLH30Gct6FJ=l4vN#_p$XN znpo)g`bJ~6uZG8Jh)7CWKFzXR>}m`0XjsW0--LSUoveAaPaoLD?`Gv`QPSQ_J5KjD zsB?DagKvh(&@KjM@?b2YOu__HyeZ@Q${?XyJbFOFd~eAY@&Y7pEg9oN3JC}<^D{p| zFLac~O%ZS@`5@mCgWNPqG&-D$pY56GILPreG1MqJ9NBY)HcV#(z*ODi;Ko=E%!u|R z`Ni3RwEw@cny>0fj`lM56mxeAa!rcAG#dsaUsv&KdVGrlLgjd@a=_ZfLB634+AKNv zbwARVLc%V$lts-+IF+>-1q+b?$?0A4ekVSd1GD&$Eo{lyZ9Xz&g!FGUIjBfnn$+uQ zS>fEWO=AkqVWOTV^D#)1v|s0fcvrjlrGJV`5Cq$=pLF6qt?*_I)O7lml1I}%P&4tk zxFYFbOstPJmTCmt7ar3v53x1%IZy0UAB2}vFEq)VtN~|seKC!nf1rf5AZ0MX`(Ie2 zU_Hcv3R2 z=k4tFm~q`i)TQdvnSP&R7fG$Yw?ux-LpS4{&r7hJmow#n>C>4OU^?RGu1|`?C`{-v zH&DyDew6;)PQXO2YYH4ev0fFkL+=99`Jmvilh* z5w`u5mfLi)zOaqpS{HHvsrOjUhqR2xHj1=?w5%d7)lDmX*GuQe0m=K+U6P?5a#}Sv zTlAa;g{+{=HA!9CxlDF^lsY6RcWN7yKX>@w40DflGEdw2^JDrg>6;qlejpIS3vTwfx3R>A7y^@tJWz@{OPSbz;Av6cXeB`5eV$%_!lzolb`zxxM=< zPU;)eP?3vn5-X%-4;LW0%fYoP1YiN)Kg90m)xALbsYIFXCD!`f6!yp^e-oIm5Qj8oos*?@&>V?HU&x6Cj!G z0}Z2m4)}~7FRe#bYUJH=TEPMm49U(DlYj&oPmExmm`6uMiQQE&lizf* z25oZzeSTX}tq3#OUm>5`jXautCI<2wkj(b^>V-?QCV2n)PQHhgM@5O;qM?80Y;f$^ zftb%t>tvp_^9y3myT;MG7*}Tc0+M@MBCb+ln}>NQ&YZ`Clj3(|f-~IY=KRcJVDhnF zNKP&pq;c3w+`Df!^=4BWou}_~>wa5HmH0I$`lzm265M1(BP~+?1Ie8Z?i35R$w^No z3FbBN`W|{UX;r;fIKd)8%wbfh;cW1AH#wLBw86On4kJ#5OnJ8Ns*HKQ9L@LiV_G`3 zM|5tZC6%b@)$S1-!h3K(H>xxFcfY*&FNyQjfQ=>i++9D>TVtT`mEYgW!;!786(;B;5qB<}R=muG z#wzN|{90d=WcW)NxyA|A^6+BugWcsjy)LR4FPKeZPC3Pcz7;-a`7(XfOCiA!1Cw(k{LH@+=3y-SkKu#yuo`e)_(SU=sN$Ws zIrzaAWbfRbB=dPbQ;8qok3E_w8tGNj7V8o`Usb7xGrpJH%&bc8`Gj#%fO$R6ECs>T zv)1=>m3>wLl6@V{2XwZPCbA`02;}Q3$D0~6s!&_J?j%=P>_G7(OeEW@dE@{;WbK<& z7LeRBNgHNBBF)~vRaC>aG5LZgdob?!W*T;fLfek37B>3MkU}SyGJg*DP)}AY&)@Ce z?$y!zT&XeVRESp2cCrWG#PR2DZd4HZY-Tn#{x&#PDWUHY!rcis9NC3&c@+kOL(HL! z;nB(Na`B;rC+;E_#>iSctpgiV{VR!$1r zCZ~lnb@E(XpETV8Pu3AaAX_+hRdx zmZn@%&UR9vm|4D?)C6fi?-G-IF*>+Hk>5+u?}?ObQ4H3cZ^zAlFJzpE|Ag|=$jQjM zI8HqjOnc}xXe^EY%qz9_ofIPBzDb^I44$cXytdu{a+p5KC++;-v4B3#bKDh+WCnc% z@k>Fiv)x1Z$^5xI+Zt2KG6T+WlS>Od=8ydRtVvpbjlaz*Lj2!DgAKfjob#USXD_Yd zKI0rmqN>#F<=x~$x^9O&Li_%wuW|5S7IscWOKh)XXwvyC{Qs`xDPDDaTrdUi(BaC# zjB6hyGr9A3MHdE`W0q|Pg=mlO^LkiKCmvldbuUKvVG5kIyIm1!)#8kaN0Z6 zH=G1=v=Y(rbTYsU(6+ESbb(2} z$&dEjsIZ?V@Ce#rHaA;FzQx@hVmdPhAaT(ut3Bod@l79f?}7ck)%DyL8S^F|;~Syu zVEK!q;)qFZKr*>rUcKG_YFLP;H9!)lT?BN>!eXZMJ&0Wji4;;YJn30HTTeGYm7nD% zNAoo}<}e%5oAdV5_;W1O{QG@3VEm%d{(aUx!q3{O0g3ZaRC}p8$hb*O11%&sQb>e< zIk;D2c4wQ*C}DOME|mQ#tv}TjIK^v+klZJ@Yln+ZWsK*k)e!%#ARt+mBwHyY`+Zvq zkmL{aCtvP#-mP~ogL90=O@Oh0VFg2?s(l^t6oKALk4Hi$DWAKe12zs;8B zn{+a#m{J&5xolG`(*E-QQnKRDC&7{B|Ag5DFDheqWcw|4lG>Cj)f0Hst3F!Hqml`x z_yt)~f9{3Xw@kcXNu$sGTWjL~Pq8t>|hP-%aZDMF7G=9 zjD{63y30duX>tLgR7^e4R(iIZTu#{(Z~)B76K$5p^|P?o|4-j_nDra4Zppfb`h}aS zghQPCM%39g!Pm!4d<93=9l^5_ZgFr=#T-M%JIoUDL_RYN-yv7)@OAksy^g_gHdbh4 zJ)5!ix|ug-245^O0MYs+vqeMv|I;UqvY#&(u>;7ww0xJ&RmTNv@f~F{W9y~;8bb<< zJRth6nw=|Z9|UdRwv{1ko|2XxQrS^OQntI~1cTJX#cf+ewEVBi*N9_uvZB~^Yd5*l z#as)$*D>9HrWC!PjPK5BFdJ9Ov!T1>L9cv5!IN1hNt3d~0za_BLr8-s(!&o7+IGg- zvrV$3!L>voZ3S3<(#bAM|8A@Y#mwqV7&GqCl>APo=BFEL*gqzEdJpJ+vp%mppXrCZ zY;TRQmE|Wz`HLrpE;Tquo&CpcFdd1c?Ok>jIX5c9qb@Kn!#{+uY&_k-v(Cdzt0J>` zHXc)kwt3H@6BV#Ih?Z@))5^rSaOTtmj0(_*ND7Ij1}wH7*#J>~)b3 z8uQddx(Ws6DhJyea}FLi&{x9WmMO>UbuF%UJAEmygjslnr2CO)G$Kh4X}HOpQh?=9K^%$r@@h4?NIdzyLPY+- zBxAFAeWS|O7AfLH5x6YJF2ybUpCLv~%Ydb~7-=TC$Ynb(KEC%@v45--nO?@|yna8jMUbDM8x zSlwNtY_!8&YvOeOS1!-gHYdElv2!!_BsT!^z!I?TfL+HaEFA6DdG~2k2Vq;8w<*UpDvkmT-?2 z(z3f+q!pd86#FxAcCR43JIuTz<3oVSQOQU96#?eT$)1hWnHBp_sO7Jc*)s+pf}DK2 z&aI^t`Jh22^M0L-rMo-mJdN}w6ca0|nYkj_AGFPH(|gA5c1VkD z+QJ_XF~hRjXsn)1xTD=;)>M;&>hr*v8bW^;DNa_HpO z3VCR!470&f#S=t$vmyS4b*|eoW$fz0P!h!L$t@g) zmV8;gK_~AejP8VbzRRY=Egu^LNCH#J#PL}M#SBTgb|->&dAUIrhgQt@ReAaM3?D4; zGVdmwA#B5Lj?FOf0|}li@ed@QTApXK1{AWrRkEbBk5wq7(_wuB=sWa`43%t7;A%E|U9H(+s+~vfb7h9O$*56z}t*!2Nn64yN{u zn>j6=muGeQFAXrRN&ZJECS&|%^<<9BUNC??J1wu*xyOnnb!sqdl2_^kKq6MCN3u=? zn6(M;JxwnMnWi@9PpBM| zQa8(<5#`Hw7hP;{6Y7=FHs9tj-<;MS%G)DKv3}3A&>@%e>N?{CgM3mWyp^*p_F&Lh zS;X_dN7WxE#F3Vr+eAIt_kP=530FX4zm8$PZ;F43!4zd2MOkl?-fmgaCp#{9q)4mE^rujzgdH9Jy1bVU=fr&i$DE|qWg>|ACsR*m z10?59G76AP@%!q83uN}H0o>9WWi{>=NpS2`Z^&d)b+|5siB~v0IX8j}uDWL1N6gBmI;!og@CWRUymq7?#1b|9kxl7mzi-#$C$P2laF#>gzuve(A$-AVzSA*( z<^DDk856R3GJR#8jI0o5b!bi(-O+M_*thq<#s07B@->p8TBCU6^%;=~vJtxmG zxW#q$pSK1d4s&bM%7gZzTjR!#X}-@~+OawVX0yK0@ky=(5aG@L#goHPc|e;xiy|e`GwE_n%S4e!Nq|Rp-FzTh{pI)z%y_9o|UFc$Rr~!^G_MaxjhnESjWh98oR-{}%b(P=g zWsqthQ(iG#cq?Or)qIwAE!j2L5wsn&2&`sFy>qETejR|=N50j`TbA)zCfF3R{ni#z zb@EyT_Mc)CnG1y{(_h3@ON;$ob;iI<>1rQyyhiO{nfj=>w5RAIkl%Ior?!Uf3G-a7 zc%R)jtk~5u&G^ja_^Zyo-yn}>?A^JFl^#-D1=f@KG^!45QzyC^t${-FRRI!HV}FVv zwk-C8Df6_*hcfOnacK<7DVWWvG0``v|8Fj`WfV=xZjY!{Y2_LRhZ~8S$Ax|PjAw=^@r?Pbn|xl$-r5nkFu*Vq)q5!;3m3~|@&Nvcta*#h zy`0j{nKrQ4WVCweJ&kEjX|H8nH2%L@EuFTT><+SGn{gDBJT;q0-y-j|U1p_0ezMf7 zHmiJ?S)b9DX&LxDH~iSY{>BVLlaW&ORl7HE$I$gBz z&596}t@qzpr$;jV*Z9c8H5evmYNNuNx!^p5^VF+1Zw=iZ=0?>>_t`@y7MrK_ASGki zddE8;RT{N>a^*LAm<3hr5uSNJswizn#!Ut_z?jWX=z|~O%4_UbF*KFeBTZ%>uamFN zxXu83x!n({?2MRrW77Exd}=+yFIgXPY)kWt9qe;)?dGKYmm=?HZPj>vXr=JYPTwhB z=3tY0hY+hAj;f4DmV9%HjOz#jlDeF7Cxv9aU#U~hliAh*{Jd;*jm~XPIiUX<5jUBN zIt9U{GUe#VdJ$aGl>%3QoY6^i@40g^o}9@EL2mS<&BLHwUrfau~1X-3*`x!46w+BqU_ z!`kfk)M;#{F9gg}8r1+phDC*oaw<|Xu3nkGHFRs3{ieo#pWQ#N*!^d>|EP<3VuA~_ z%%=@`=M}lK>pbMHDzvcp*P^P{reeJ;S_Q!9BfpL9B2JBaCFbtkx7m*Z6H8;(Zyh|s z&%C|O{EAa*WAd`3{JV?Db+kQkYsB$D+P=tvwXKd-N#%Hv_Dov^UjL(#ziSQz%;bY6 z={})k#c=-Pwh$cI>&QRkj?iTRGASqBNz>-depfv>f6_33+mm%K!#=~5!|W-BC%by2 z{H6vHMO>5B(PUm(Dedkdj|Z7|C+J5^c1NRrml`ZBavVXyWRPgwZf)lEFmq4FUyBu| z1LZ$D3F7}QYBf*OiIS7c*v?G(0+`LMDYIW!@E)&CjI%drVviC>IrCUR*alcKCdLQEdWyS8*-GOf?CT>(Rk2abUbL9&> z%=3^K3F7ln_4ovPtD9U^faDFoZF48_Y3!FVY{ht*2A5DhH)*STByC=X;mFR6$)Dt6 zKf1{H0wlLZkOerdbFiOT!v3lKn5d_38|9ZV>NIdpXlUL`N~`!SLa1yc3ZC}o+zj93 zesQONZh&p=_TE9w=4t=2I&?4DQwH!4X4U07yDQ~*vO5+vnYZgCSdIH6&z!6qkbFPd z+tNcNz zMdcygMRN^q!!YIVE#XJQ%($$3gFSd|!ab(jf7r$Rdzgxtk8Y|b*Z0ao^%4=J?x@;5 z%xH6yhYQ8aD+ukK#HEov6qa{r%|EZsli2Enr9d9{B~~xS#O8_CuP(Nvj;3X>6gjQj z;K*}l$2ERNl8-v4x6!8Z%0|6qj-!8J^&&nx{=2kIhpCKc(r?-s#0UoI_O7L{yyL%j znB#nzEg!&NkyV%IY_8HivbzXr**(J)aLT@ujOMHk`Q_W#X+$l>_QEjZut~B_%Dt*z zD^g~lNP__uVwn8Wj5Q2d(m-WOCpp)}yke2R{+~DddhJYjv%~&z5_>DX%X}2Z zG0sW3S9OLT^4gw?bJyd$*V(VlSWyoKe{G-i)sF|5jgv{nB$MmZg^Fk60C9PZ_yrnp zR5}xY<$O3&mJxq;ro?x0b}tP$crqZF5BqyZIxcH7m-ra5RtzHNkIF}PMK3nk{Ug;k zwgk6^nZa4#gLV(53&n2#5f`&}nD8!z2(f<1RTLru%h?`PZkga54*^U8qJ4f_aVPO; zYz-}D4*M4vq@~W6|89$?&d-d<6@Si&xU^8282;5oh88ed6;Uv?hJdp?uDGTJol&{2 z4QT-0r+s=ZQRXENC;GfokXE;}8L*rQjaqtVV0M5*KXf&9W{3S3i~>ZY?*Q(sth!WZ zZ%b)=6SlC)Oqrm=a@3Q2c~ny{ogJfN-z54xgY|9`TwegAjQc({pcILLP6QmHQ0kz` z4BN(K!b5dZF;K=gfj66M;kw0M1Q^m)CY%fDsgoU(a-Gr{+~8$ynv?=0Z=dMBAQOY- z1S@epqIE35My5DgP1acl(Q@GS0b+hdjS5WW6uZLHLol7ABPFEDf0PR+7N-8Z%_377qyyR|Jr)TIWij`z`dCnaJ`;qZI#;Agf-A)Pn}?g*&M9W%&ZI5 z3{ZYO!95kUT{povM9V+>9cq{>5?|~HBEa;CE9Y$zonhu^l?PT69jLtBLC$e8&s(@+ z8Fws5>~}@d@hW4!leDB9Upgk*uGPrvC&JA2A`fX#arc(w*>3~F-4ku&O!D4H z$08-Tcz~Fykw3=>VL}@;-M}W!&qvz9URGC#M$UOG`?iJ) zGWO!A_+TPD$6!Ajsa?J$v@^{7m&XS)ZY9Ub_>#k5T@5c7YdkdVtgOlzergh`YG zQTgl%#+h#Na}`b*RV`mw>#}QDnE>|E6Z*isljF5AG#wnM@_~dRstmI4T zX2}f^X;ZEHS_fN;{c+PuV^O0|TN1C&YqZC6de}=IOb7=Ho8La35Ps6ltZlUaohv#! zpgfYmG)f+rxB~ap+s~5SkpYk?yRX&RKT_Hg39-cFzHhaIR9-S%vlXhBO|`bK6Xc1Y zZR7+Ekd$U3_o_v%$D#{NKyVHF>(TT50?49a8HDp5|5_OWTkhq-bcCnq52L?pR09&V}sMU~18k_;f z5sl*5w_gO_zs}LPCDaur`2!jMgLd|jfq3@qpSYObR%$lR7Ro_h;bEp$+5&>C#Z+U0 zKF-aA>)|@hJzz7_x~35)<^7X^D^QWvYb9H-8H;%&#eT|33uD{|J+9*}vgE&xOg^tx zx)yTGVtK{1ekVjde->VUy-ChT;qyRGM_SMvE zl7ah&iRa5fYXJ8~#<^H$dsEa`$4#MZLhv<>xq5i}#~GSAKaq~rCfVIVTkC}K&rG6c z0-II4P{a-E@C`s4Fs>vwiG0{5XQD%NVjHOD|BtEb4v(r#zs&va^qE`cPVbXKfRK;| z2uMi6+&eP~QY<)gCrE?@6|o@}ER0=O#e!>D3#+J*nS@RXV8a3`h=M3c5gQg%1YNP4 z-}$b)kH7!+$@&13Gw(U?d*1S8d&z8xSxIw%vHt01G7xcxy2g0q{4WAqu~<)Lv-wrSz!gc?6L{^ ze_^%lv#bj>e`Bqw=Q-?=jr9j)A&_ySr<_j-(0|SwHE!u2ajD3rWqWW_r^f>~b?M>nW2j7__Qh42xcG2OEM~4x51WibB?>h!F|=IKXy@LH#-2yLG4$+IBdG8$#?_wzof*06S2uCcRKx(NOgvU2E_hzwyTY(t9Z+WBqR{;>DIgv_ij8b=`)JJw4?zF590H{#3G@q9qnkS;&yA-~CV6yx_W`&t7x0{Xwd$gE#wLI?ABCJanY zR9Kfb4m#(**RUu1PdAhABhb~vRkY@J5AThvbQ?~aR0$@_%G`p{NGQq0wdTT5&sTo^ zmaJ}?huj&r-DWLbP+^?iU;-pct$D(%a02}}#R4Kbt=jTJ)(t<|TWe^2E*BX%G}(U- z77Q|;TfHQfvIQ7Uikjy4m*UXP7={03bzoJ9nXY;|?c_u$dwu_KKypSpwp%1m%f3ab z?g|YOkCA&QX1zNdIm3y}ixw~2e7a{Et!ADqD~1g-nL;u_w*6hBC2?2XPFIsMHgcKs~Jc~Qrw=?eV(Xo`O+D|oe(>@y>YMu{%te!)qG zq+E}+7G?d$G5wyqDI}BqlN8%U@X9OL$*SW<+{drsdis%)S%jn+QSy__ovXUuagd6p z@b80-fMk6x?K_OuFBE>cjp!q+tI=91k~fNMhgNcUeED$3H&!5@RamcY^tDRNfo4-` z*WXOma`{DIvRM!t=KF~MaAqVRdZOC-@MWG(H~V%=;8yCC8UGxuM_VRRW4V85;B&wJ zXjV7XL&Ui4W^4FBg*i8~fqaS^-L)oTZ#dcK)}m&XKbFKOhVPf*q+cC=GxUFQjWD`D==Io^BrOn|n;ZC@>PSp5&1eeL zmKiruZ?X16h>c=@#zu-Fq@>YWE)sLGxN4;t5G|FhV+69J0_Cr#O~NfW^T4qyskrf(8fRCJA5IzOLT=_sjm!@oJ*braN|4>>I==Li-?F+X6cglRMdwwTZ)&iA zERe5jxcnyjxS;OevK34=z1jjF36MBaj@vgQYOeI-irt>HYY{GXsNOIm*rKKn`(jAR zqO#@T)pY&xNwpH%a#JODqK`tdI2%DBla~?AWFh_gEdgWBDim2)WQTys&X%dc{F;wB z*1(x~vbGrFa;1L}&8tn*G9KuEb&GUZuU{53eBEmKT_OhMubQ8npXF}kSWGB(Zz4}b zg%{JM_!~aO6RKH<%T2DY)qiPZZ;7$pY3F7PaHgbrts~F&8&>pr@6z=DO20}maeq9V zJffE1JYRn`uj?<8JoZG&{5H?*k<#Mx38(Pr&F|~}(XgQ`wo6=s?$tcV#fJ z#3NrW(3l$4g(E?;Sdwv3aFfMjij#n?k; zNDMc3=y!h+Sx#HOWWKlr7%fHEu$HLr^o$-%wy=g@c$s4vJqcZQD|T?|t#dOxAnI%u zm-W;c0*q@DY4DJqdMi3*7mYBD%j!PFPtR-jNdax4Hd%c&rEZ4$E7@kB8@xIuFB73i5S5^o1gvbJQIC6mVDy6gg0tlVATfOg# z?0A`$e>b|ATN_PIBe%H7a=5h=FaK!eA~I(NrvL%d#$psRODRm>#~oK^9AkV;Q8sW` zU$Q)AIJ(h|zW>*8gc^A;%nZ(DeTz79sFY_nk$0oko6<%2KPEKuld`;^3C?7bu}QWp zPCGU_nQq#ZD^L23QlIx9RB)F1?@?^+7A{|FdQj!A64-xK+ivU&iXMB%OaX%Pt}Nc6 z4u{~(s9{b0Mg0MC&rCORfM(h9w2ed}WOA;-HUwwbN~DIBCWOwuxCsU3(-r1K>y()i zv#b=G%j^8p%)}M-FO|(;vpZ{CXSR;}x0`vU)QB8_k-4cE9Ry~0^Pu(~1L~0Fcv`?i z_9?>MR=E&UZav!JLF?k{2>VpDA3&^rH*GWU2oaGjSK zsD<0jF;VlMy$~3Er)>7D4q=(BLoNEZ-IA?zx%&bL9cx?oJ+z2rx}^g)t7@%q8f|YC zSthjk0Lc>?nZ52~zHQ=x@A>pt$vT;3-XIxc2#*+2y*O%m;is=ib(Lql3Se$k+ z?+-IO8`x_(_V-F|RcWLo#$S+zT}ZyJwGP1=z6Qx@CSzMvcLRk4g)BI*W4zyZTa%#W z0PFmxB~2Gvygx-)JS}~-K%TGW%lg8+$3CNt1DQQB*3Q)FF<18GS>nb%l3N!rJk%y3 z2bd8zKWQUkgp6#ml!QEF#FeG~ z9M)o|rUe7$%xY~PsWGoaifRpaZ7Ll&wAIfixLeb%YrR-9L0TsK5;1S?ja($M4=Cc# zt3ta&3zF53`j0(^S*-vrDN&8d=aK|T0;&zpIdBN)aFb($+a>qUbaI< znru3r%qqpu^46UH8j&21`yntRe9Wf}j*s+19*^mtD)kd5`A?i`{=;ErYlGn$jy+N7 zS&4g6G0XHc1^tg&6PFdt|AoZ#Skyc>EdUZjouPAGNuA$xZj=2s8YNr(Cz7UlmJo^B zPf=rl4AywvvK?!VKr^QX-RneF$tm~BbS01kzPQ>qT5l|Nd+N zX&L_acdE-Tv0pZtaio3V(0+eDVJoK)5w}`W!f<~?ELZf#08t=m-MflLO_^Hxj6E{4 z(tBGkjT(#$?h=Vkp>lAYi`tCPG>J!8)fAM;d`@Eb>JOHj@1_b(J# zMh?_vJVSg;f68-6KPFEbg&k-z7t=VyU^%lTC0@?4?^e>?&c-5UOu869AEXE;RMDbA zG|6P#E?cLhgZ&tmmW4~!1?&9AIk_gwEmUy!``=9H=URM1)E!bwuMpV2YT<$2pwVOB zHOmZ$UY8xWjI_MrAeI`-=swaFz(3gdDV8G?{s}5LY(s;kNF-~u+Y%tMSK}5yw6MbT zUDiEA(v{WX#LqGRR5RBc_3x04faEijORb^YKheRgwZbYp80Yq;i&4!SXkm}E$_!2X zCdeN07Hujs3#-j&)a((+!5ZGVF<2YaMbkb#24*LicdIllJJ9I)a%1tpp=16Yh0CTZ zuc60o_!uLcj2OS}DTTJ|O<0~;lJ|>lNe5^lpb&Q%0faFsx zQ+_hc+>>%$!LhGb!lgl`*-?}pNg)~J+^Y)4|3wY@U%IjBV6T&TPZlcHd8_@br_p*H z4Vz>BzJ%!#i?293X1MCZ5zD>RT&6e7cx(^02j8HOIG-D7ejNvrt1UnFl4SwIhIZRW z9&#XVdD6xfN7$`dHz0Yp&akDMaJV0ztS?J?JebkSg%s_M44CaeMGntn3TLzX1O+pJ7awfPARlCNrP8~Y7o zuo07X=mgR|fnBez%g5|*wEoGF zD@$;8i3waUvNy-dxQx35$4OJdNBUDX#0)d~Pl4V?6dEOfq*;{~aO8zbKG)xL^-$)n zbdDx|&&rMqRNjWXtdU8W@XfX?OG{v~M`TX7E-=o|{M=xLTY^HA|1mQZ zkla)af(R0i_2G6aqNH7RmW{G*cd&4#*7uTs2H5x7?Z}j^aqA;C36N}Vu$GGC{9668 zZathbM#<4ISzY0|I6DQH45>Abd-rc9yZyxlU@~`Ln%O-+8X8D5muWfp%h}jnZluH(a%*DxSU;U$8mo=VJRN4%tFcQt@?@p2te@nDGM{GXu&1uU@_|}u z)86$-nM^Yk>+wtgOokYJV{K?69w}|IXi?)1BvOW}EqW;`y_zYxLLkR#jC*>5gFL3e zT~?%IBW352QO0c!>=sgS%K;;Vi;Iq%-0}!A{)KKt&{2u(El4_o;%XTFqn6zjQ6#+xB}n> z8Z{UnyvNFnt~ISyL+{Y~(mAT%ltbVDm!y>-Id32v)nS6f&THaKl*xt#Rx09V)xFTm z+^pDrjN@p;_(g;Le35-3VIRFJ_+E&q&P4uY5C2*by0&NdVLDh_{5FPNG)F$?V%9a7 zT)5CpPo_!dIEhDd%69vhI~r`iaB%8z-e*`YfFZT}WY6KW)9YhiZ4nOX!(B1MyM11S z%~_hk+!bc-RjV)L$b*%>ulvY-^sGSwAL((~`J!6FyUDeU_7;=r5yg6+>g;n8K^7ig z8%p|_6AkujXw(b~tV@^{SV%a^kI4A1#OxNmY9pCElNtTOda!kVn-LQDWbl?&<4Cl#CC|Qp89rceR%cm+dh|{5)ck8bv^I zeL^_8a?HCSCayS^+FeI0!qq+g{WMC7cVhOco_jWP)-5i^Si`uDJRZZs=bz~$E9-Mm z2G1TJGdUanl_T5e3nk+bChQ+_@cnw1)5lb$+=ul=faK0T4+>07+u)y$^@|(SVe>e0 zW2JLxAGu^G^F}Lfx{)2S@QhjtBCD9lBu$n#75mXv3du7vH)Cz^EI-^8qXxYdGhW`re`YBeVWPr%uXlcg z{fc{i+UcPB4<;*mHD(ys=K@6cYhr_Sj1IN@d=6U*{MmivhM~;PR;(eAM%i(PdJ2dv z(P~VXOu6HV?aNkMuams3*elnDXZXp~MvsQkw7~ZXES8blsB~J!f$O}d)tIko9c}e6 zy#-{=82J!eGvU`9?61w@(>>$?N@V=I9->d!F^Un2kkYId`oAIR8PaXVtpC+%JFdGv zKf-!d);Uwstxc8<9P7w|$-j+TQ5OzSx4hP0!Z)+7>g4@0aoav zOcqzn*H~$`)1eN2OCatVZbqM}2{#63x{Lx_JjHRl8bQzh;90IB3Q0#`KFxQluJV$p z3ZjNP5;5M_V3{qlGZQ&s*~&3UlV6p&C+z-h72!l{8JO&?0t|w_5!*%bXWV^tMt75o zEKgy{OW#j-(w_*is5;LcVJQX0n z6x@3~(EQV7$1`^O^A+9`S#h5hDX)v{XK|;hL2|gk>NDy$Xpz$Hgcm^z%xyjhj{r!{ z8G)gtg@8o=FU9;1_zphi>sskUeQ_aXSl8=DPx&{+j{KKAA7*~2wV%gfCdII$mmD0* zw6+ED^N}*=uOonDL!&8aGG!CC>)IS}%T~+$n`=TDKT|x>d>Ky$HZMdH*N#5_n5ghg zIs!cUh&{uO{wpS?bAu9sRCj}SCOiBp3M{R*XgdA5rL6MG0 zf7xaGCa4>p=4%D=dX?! z3@+kHIHoI2>zp)l+%K=wpY-E@P`7M!QoP>kbVT*F>d?0Z=JV>D^meZm1!hYdKfsgK zW5pUss>CL%4NvyL16Uk*MRDBI=2_syf{!i22nQpEj~Z;}ifk^yt1C~z8Kz;ffF^TS zMbO;p{6J!^C{!XX`#J82XLQ%Q$mW#YWz@f*K{N|Sqn0_p=wr4tn7`*pbVLsGn2RAe z`hwyZkrpvp5L6r==*yPJESL6r(JtGcplQ;!Fym4yIyiDlrSqm<@+HjyM&ak^r0=UU z!}J#Gs`BV>>22~jV+>{Ic<#>kF^Bkf4bwr5Rolcg_VZ)!K9r`#_K zGuNP}O!hSx=Tb&n;~Lkwx~D z8-}MxAT7%(gLbRY8)z2aave{uiRyB7>4?ikHqbs5|CV1THVX9~^3Mc!qt$a}6rXSi z1ZGSP*VJn~HK==}J&d$$FYTaoa1#4wwOOQ)YzVj$j=k;Ct6^Tsb`aU&i0S356Odfm zVhyZ}@5aEA?0}zqu)_aN)`cj6{=tBo50!Ut} zM3iix;xaQ4cr7h4KIVvQKcFw$60^q|-I(>;s71-nFp8wXb2t*hNNO)J4P#cc7Xy+y znJ*pXWZh(M^`MC+^D7Dai|xWIPS`*~u5L{TVX`7CTtqS15a>)Uvw^&!LGr$bbR{tB7l7}7n(Fr9y@Fc9on5A1 zaXK{3j~2+KHI|ub0NN61DjELX-$XWry)FkPdp&@~vggW8|4c{cI!K)|=seXAj21Qq zfYCPDwpwGdB{IDlz00qAvcYx=whIz;sLUN@KF$nz6Ju)${$!73Vo+Ds6~z#9hvNDq zQ)Z_#W&GY=K=gW`KOyD1supRlg;&7b`ASW3uTjKGBGW$w2{hvCOTFV)Xi$IjZ|Rjyzilv3Z?FO?4u?A?*M} zPsp}I`m${?+k{5@PZBvjfv*_Z6=vYic5sX`!u&!Hsml#x#&nh8|0t6M&uA0E=H3P? znCw3Z`i8)w0-`aBxDm}-55sBte^qSo zuC(iQ2U|ButkNJ_Q1Bov8=Hig$(Kdg=hUGdRB5%IE4$3ULjPY*T3|3Qs4=~$PJ-A> zZ7LZ!b`X%n`pfYzuDsB}+8YMFtB$?V%}kkSx*iA0=|?Bf|7T?qa&@PW6z* z3G2;PS1@YZni=}0z&x1{cl21``8zOE3FAlRw`F2hiM7^P@9G^qaOhwll$3JwyJ|1P zU4L1KG4_KI{#AEBRAw!95 zmxsiXd~St}R7c1|YH>g$)wPDRyUf^Jz9VU<6BxG6vQ8a`a0lBA96Jt3{N3fqh-)vz ze(eNqomz`1shcP);+f4_a>={MHL_>rTK$K9+`6^{l2a3oo2*hv)I3rVwhQD(dJ4>n zV`X0zBC!0SZMkH|1txo;hLwBKR6ZV7CS=1SC; z#{*cfxmS@EqlxUzF+N#3pdWfDX1Sr!iZuD6|1nuUF3jf09~HLIJ!Hu+=Jx`1FT3kG z+bJBH$}L%gY%)zr+C5z&m~2J8YuW11WIws0(LRepay-zLvRrH-JEM+G^?E>pwDgK> zspw($FL)CSbA$6Vy;17GZ8uOWY#D!VvE={T|fqYpsRe z`|7OA)l*drEKMK$?*C)5NedQ%$k<@YtbexL{Aufu^YE;X%q~}JZgDd$O)e1Gql)9} zRvI;>vU~no!!f_^o(6Fg^#9(3{bs8;EXog7T(6;TonS}x81ZoJdj%Rc&(?e9WL#h} zd$ZrvJ7nMx8{Cl)%e$&B@{%?6)+ob$5HU@J$t|*TQubZlC5W2m>UlJo_l)o_&hoEl z5N*TkmEt~9AGr!=A5(5<&ECJX2KqmW`Zb=FKIQ^-6qqbB0^LhC2qt>~)HfseGv*5$ ztq1f&K93pvjrQXbNz+T*IJ?Xoi1QGe&nsL9S_i#0jO;B`;^!a6`3o`*(M@WyhDH;6 zdD8x4L4^L#l(~hgLoI$XBSkJF zvxurHz3tL7lbKnA7t#MeF_2;1OoS8fz`mNS*k2>-! zN!LCd1*SKMlS@m>EeB?nchEvccb7Uc=Vm&Z_^WwzTcq4wGj*a1UV5-@t%(Gf>PF`% z?V`YqR;fN}eOtCeT+W&9ncG?paampnA|=BP#1h$Tme{LXgqM3z$#{bkk`7x}?ZsY# zwliw}eGyYx*4-wuYnyF_?&!V{GdCSrYA4gH-1D>IYyX9WO(>4s`m`NPR^Mz#*nFyC zg7u4b8qS_)eauv~?rV-Tj6m3UgV6tpieKrD4S1Pbn(X`aGDWf@7hfGb!;hNKaW2Kg z8~j(&FyG=GiC5mz^hF+QL&md3dJnTCZ{5Z-|3b!+rdjf_T0Xg+yd2P(3$ER$D-u>j z4Gxu9>ntuXbhXjeW%?zkYi|>w|Idw;xH{`JiTSez=4E*h=lmWjw_e^BIv?>@7)zTI zi`=?>jRM@u4GMopn+|ERUk;ep>f!kh8q{1zA(?oS)jKw7jm!M&0$dsPKUwDl6qkik zK*Gqb(HXZ*V!vvzJkWzB)IY5%EEeV&)})|*Ng`<{r&mUST|!?VTrbcX=RBE|Y| zdyd^xeycf6Z*B9-Kk?$thzm>?P8Z4W`%%ie2i(?K{2tQ|idxw#S3e@(0JMO5@ zWq3PqX|Tmj`i}92LV*fQtt>iM2dDa(5f8a9 zZ`+QcrKs+bw1h}GRxA9vj%*C*_T@cqdC1{}6+Pvt5u&dXo%Cq8k#v~>%NcDVBBi|E zZqC(lz~$2#)79_)otGs)y8&!AA&8ZXyUOjYZHDt5q;qUXq)rbH;FqlXTAnx){8buE z7TNd78a>*>OPX}G6sDRRt>H0IOF%ZgE-+6iwz5_iteI;xGW$O6{Ulv%k=W8^VR8@B zvI)81KKk1Ag!3_2R&O56*xrwrzEj;OFl%uCvpWJ0;E%JN|F*NIS9`HS`B&&5b!HOI zshZ$CsW`!AUu!VUaFUbsB)#WfJ|?7&KFX0T6ru@;9DOw5G;}-v@G=a|oJ;n{*e4sT zM zddyUBwtI3Uk>n6MXGTbwS^2Vr=|?BnC3{MdR;)1~a^7e#ReQ+bl>aU(e@RsTk}M)}HYirE z)d_vc7D5E~H-C@2CuUqGiQT1&QV)FpGlCr{v9C~lK1O8g&83X(-H7ph)pd@@4ocZZ zb(h2UuSpL_T6VJ9yH9n!s720JktiI^~LYT^!u{m?<8WLL~DLPa!#B_&Hq$|@5^lDlVM~| zp&UQwWC5r45H(85IMJjpOIhyJ1m>Z7>x-*=Q~a1%a%wri8Nu~Q%VieshjJ#C9t=o0 zWzbh@De*8<^0b(-Den4Qy6QOxyF~Uqw2pND7ZWlgiE4(-h!CQlB4Smv#=F0uhsiv> z-3A9!SI-SrN1Y+*Y8%CYW9LC&$c^QeOJ}mG{^CT>j$%%d@;CL@5&qAkK(8=(2; z1u?qStwC}$VJl;-dm@HD)s+!hXUgp99=;O?ZqsG|wv$|q>t)rwQG?_Sk=>#=cc*pG z{ME837}*2=gJe0~arHdpV~*xBbqJI3Rd6rQqf9m`;p^*ifXN=Gkd*C?>7UDD!-kE} z9U8JR%&dyrAuwlF@^5CtpAREb3xo0VxeE7dnuiUuR5jF@+-IjO7ZpTo#qN{EhgJno z^E0X{&7}HrUhsux^92_B)^g)N(_TE3MDy>pYVjZs(~`Gt#eP3^PlGQx*av0L>~(N2 zbzONknC$%o|8EPgDuDB$o&biubqL(e5Nc^uQBTa4BIFoY;-BhtyYXP z+S+944S`fD;a9UxoL(ML2(bdWBWC|S?FEyqP4V|`Ks9r1(4G?iQK*{jCElbMWvmAx z#g2+r^SW3o@ECEkAJ7l}IA(aBG8wt1g+|Q_VWv*DpUaW8 zm5#f!!@nIy8Vj^=K3@?&P75$IA8Ij=G({d8ub)+LzUItffL%CmRd})=7qqik( zo|&@Fw+MaZhC9+6Fk0JSd{-@IJk0RCZ7WZfC>T^Y2M{fh#ppWn5S|UsyS8}pl=LI63y z?J@C>w1BiMld_K8fMVv};0-C~d4*a)l1U0f8SX$t-={XIB0DK%8|W%|J;WTyB?X8} zUoF2`9p9&6^0LT&sn8MG%g~CEd5DX<1Y|CO$+puHo`%h>vI9&OszS|wZ*ZQdpO$o7 z)#dt+m-$)d_v?!dMPyMn@U?`V0galE!^~`1LZ)0i!nrN$`(qgWB{kjctOOj-yFs9L`F>c$rEbj3<}A;u%p{Ar;u14%T}X<`P&5NyXrKgWzoD1 zY1tt~tjrpocj&K>JwL1^_XTwK=iOU9B$42j*~o1Xwl3oaBwY#Np@NAE=>`fElH#bY zA(t6}ut7;aaO`OsCKs2}nO;p?bQg@a-00T5+90BO`ACB#=%Ojb7pn~?{mkwL0q+Xo z;SgNHdM7I6We%A#)bEb06MFw$KJXh)o{W-(X^%l-g%;kk0ow9(aAQh3y-+j5OJ*jy z;fyu+X~gh|T6ea{zS3-ct!va9AqG}I#3f$Gb*Z(RG)P_$*;f@h@^!h3cx4GpR-!?I zMY8J>fXcJP$Lx%|zTk+x3QpP6!HY!wl}Yc+F3$-sqbl6{`qH0chHTdVDOUSZ^aFAc zW^=t2C4cUz5zf_Fx4oSFCr@*-9$DN~Z`8Z7rEWddG~~JQhQS4Dl|8N4j@Mh7{U~HB zRSL<|fFv;2BJ`J=mSlaG3&h-j(y+ z581>=BkaAh%`B2!SHgBx!HQXog9YCR0hd8dmt~4iM;oSDdgcEy**!;Z1C#XyF(KQI zuo*;VQznyg8EP<3$cB)TjY!h6EaW1O)%#bjww~}amo*Ay9&&3lcej-}5H+r-FM`&5 zFMBV@x@4?h=0k&^|0|-X7Y$%Cbb1f0$GA*ia9hgRP^dY_3n3Is7~8>!`3805=_31& zX4_j`quvZL`&xxZ?d+NL;vQAlph5JC$j(>jbS$E#wy8rhk{S&n%$1)>zdD|~;Q7Zz zKy-WrMlt&kHSBGvz}Q@u`y|aX?ECcPKgIM-S>I<8Y1hI=A7M7uTcQ8KD(C%Km%p6s z*C28z(qm~3Om<<5fxU~tL7>(-LR8b&X9NO6jL(B@qc(Z3J`{ahK~GFSW`()DQhB#>TX;K_3a9 zWFX9(A@j(RAFbjq%DN-v?BjV_V4_KRcbYS}8CSEV-ZcE%@rLj7w7|Sx5iZGy%5#s$>HF+%}!^bHsd89Bix|3wLUUBJ3bH5zHjR~8TcE+T}g4Gz(U0d)1lJ=;{oGG3{ zzlou_`~FVJR;K>}BKv{r|1>}Z{Xf^iUM_QEG9gSbp)Z35Gki&W0x+3@wx$Tg<_pye zh%!klhRX2wPD|@{2;|RNqbuuf4(jgC2mj#pQxwmcX$PXlQfI7PkENv_f_FDNPv&dR z@RIA2_6TF&7_pC2N1TCGzbTd_U1Oj%*<2eHn^(t%8`a9c^dC&NUBd_-z#nmoWMqfZ z$I~f9-L#yiOg16zgZ}3$F!%QZn9LAK8NVrbzD3qtFCEku{T5@tgg>xR#p(cAre)6N z2op*8kvT7~wx3i(p>lRbo}OXIRV5@b%_DSPR-BEd@+X_^FXY`X;)rZgY|MzjDW;Cr zLgxnx)8&@H!{wNK7%^X9A0OL(bDa@s*>jyd(z3Dy6jFTN!78%n!!?K;T`~S351Czv zJYnz=W(Zgw=tblx1hZ zbJWW$sWZ8YWW{_LlTeOf9cd z`0=LlH=4Osd9er6QVEX9h@pP8C8Wiw-FU8mzli+M@8p=0(iL=HasKS%lv9%gl? zeH%~O60R?2>k&CCW#^_fomZyJs|wD~z07}PX}>=5VJ=42sDXnLyG+x3j2MKI z4&-Gg#uWFd!C*Oim8SU*B>1^$2iWY0EH#;ipFm2J7cp2SCBcD?8b7m7wr40L0dQa7 zW(&Ei-0)<3(PaX=Ocsxgv?DF+)HHuy!uedg7bX7$*?aFAvNT5p#{Zm$>`K|t=l?yT zAE(%O5w(SXXu%2_X0Qgy+tDe$jB%>Oe4KI#ANq@3q6TC(d=jAZE^(A4H9I^x5V5B(-AZLta+v-4qg9V4k4ew+;hZF%71AQ~9tKzCG_)=OkYx93OTED{zoN&hZ*16GNF! z$JG}0nsS4!OS(j0Z)j9fz=)|d>La%(eue}8F| z-K^L^WZZP`7kNClsQWGNuD}3O)O9?qN7OW?oCC+s4ox+ej4Zdkou|c1Ag14v4(3qv z-;nacDtk}kWQ56HMa*ZMKlz#a)zM%w`2M$8rFS$)&>e%X{)$?H0yB`0{La%B)xWdD zATE`%%eM|`+1a7)N#@7%RS7Rq5<(fny%iDdN&wojqQ!c&a4OQW9|{bdvV-Hf+Kkkf z)52tvsBfpgdb&tR~);A4waovqvUwXKC9sQ#LJ9N zaDe377sSsG9ej)-UEP#)LOn=KUgEOGZkTUs|itp{{|($C0EUykr&rE z$?XYoQ+IHPpBW_cT7h|X=;|rl^%gR}++gl~L^@A2=Dj+TkI_-c&O1cMk+4~%Z zjrH8XYD5W$%!?>lma<|LBN#=0)5?ih_va7gMSF-jl6Mcq3TxE(TK%BYBpsJ3?gf$M zMnCn}!*Qp+x)@A07y4gXRZhbLX&D}LeY4&HH#4V}!UH(2F`3sz?v^o08u`J`+^CKK zL?=7t`>foqa^t~P9f<5f*}FTBB32CJs(R;^-e_12x>6TMbsExO1TpS_Xl1^NZQ}kyZ(%LZ&0iDOXM}}ff8ec zxj2~<;mdT^OFPw=q1-S;!ziZ+Kef7n(eI5W6qu`8#IbqDdMD{fNRM`h0MR>fPK%nk zpyY92vU%mkj|x1*W_`Wq%FJ+x&AFZM0GNFVm(XQ}Q?{;N*tZ&HCLrQBd)W7yEz4|9 zEU9m=&l%CdJR-Yy=dB2v_wqi34K|zJsUHL;v!wF;;NJkga z2__e!W>T}3$++0d~_i~eH&}rBBvFrDtYyl*vYLFmmex^+w&m12Ulclc_HC1TCEJD< zeN^6osJSd5-O?Q#>}TGlkYE&ZQRud*W}IEVpd2IqJhJ4Iac_Hudj2yyty_5J(xmHy zf^CaKe=zRPuOC(+RW>)uT#$Cbm-(gE@Jim~3^8l+UZly!7`Y~GpDZyk z1@7e%h)b|kvted9*pZ6=wshcHx9-PU4&oATrqt_p!4!91l5reCL=S4$AenfN)w#3W za(XLGpGz*O2+Ez%1?)^`~k?hA2^G2Z(I6Mr3g(G10Gz=R6-% zD|5(_$5vYgb}R|ykdr;u>~j`e`@PIr3Tznu`H1~Qt@C}1$F$&gNPY`5z9elbcaDu2 z>zquvVP7XLFgGiX+uB6Eo6*b038rFs5@**S`A0&W-t8+w8%D8cQL-fT=@be{N4aTL zL0BN@0m>aL^8Rw_{h>|015kq$%uf39@^ zqE0PpBp2JLi?e4CE^ zRbOrt^*g^~X-f8k!r$IzhyL>k(qJmSe-dxb ziz}UEM?$FT4n+LSta#3>iOuqmdn$XKg=EW3_ZJ+{e~T>D;Ea=pY3j7XD*I>By}Dq9 zoB3TlaN26pr!iT-hn$}ju}FSpl==B=3HrZHwm+HgC<-w*vG{5Ip~6Gjx_<6!X`F(4296=GW<|xPWlV?zVciXh^=Q zp^kxHbT6OlL`p^kn%ow{^DoGvZ!P-%n?htVU!1S2_mb5q2MQT|l)qGVA|<YH*VKl63v@Tr9$*M}G-% znSkk-O@PGkYP0`~yk{TG%LKPqZ+kf+xzx&cu^}^wM$MmL=A)zyM0Q8Lt5hBJ`!M{F z@&de~j@f2F0)JrBg$Xt{(PV#q636D9-A?jWiW9rT0Y6g{w`rlXDbzI83|OY4z$^^E zOwd0hlUSw%p;Jj=A(NBhT?NZ#2OE)nfz@PlfVs2NwZTKiH&frAkLrrkMIbXym7dCX zghR}{ybqC+j^e{KOqFytC72sHwiCE`UH=Ugwk%<4OjjdRa!LqI<$jIL0Lw|m41*1W zWj|)BODSEJ-DwSN)=V~}WxHkn)g!GqR55|*B%gq^Y$t`~n`Zysyc4j564rxy^J@|Dw@lS8iEN)t zGvzEW5Z-C`W10LsS*SOWgOm6ponn`hls8K!y236$ zGcs<|B4sBnFagQba>H2#CnDvsm}JP5z`zV^kkqC;muLcWuI%}C70&uHH+6b?Jvacy z;eO1|)UETtE&C>e57Ocf<#cD|y_)9Rn$o36l@-~iJMcG~ojCOYu-PZ@06hPLNPjTF z-k&al@4sB}UdyweXly3p1VRFr3LGEdwGP=8p%7KwW%aD5!0He=AIY3o9gHWJpYEiY z^ACz^V|&<;lW3LIvj%MTN$Abf?B;y+STAX4W-*RAILa3*76{JcQyupf!kA(nPE%)g zajfyjbnRar0IHcI+E?US7r_QG$ZSC=^#CR~*&mazBq&5BNiPIv(4g}Mc6>rJ=Mzk3t}vR+ zhvI@_B6X+n!>b1&Y64T7Z*@iNC@|wz&6fEjG<=!~f|DvYCoJTh{ClYpc|(sBURp}#*lsE`h#TQ)o)!j?H+MJq@^a(^KQbppYHUXqa4;upH2{+auCznaVdMg1Quc64>m41SXhBY6Aa8 zrtYU0Kd=Vw5Rn*#z)9N~;Iuoj5rvY{1X`%rkNO+0>RfNu%Z}iz!J< zQ~qK>|3FNCC>4lLb(2HCO%C3(3ga=%yiVUH4;hlLMh-9#(S4yh z;QJ415a;JjWg%Tn-d9E;!Pa5%X*in~_Y54fgwHY$wUyJ1_$-G$r#S3c0e$}8We@aa zWD9l5Y%aE4aSe3q5Br&*?2Kam2HDwStN)pDp`?p|$pW(d?2HSL;KLwQ?oW7j6le$Y zDuruVgHa4i__N9QCAN?85_`&6#BkH2_LXS~1*UDPu%HmdgzT?*2A=ZvsQ6CW(W4RB zdXe3&MG5Ll%=_4lWCpz@A&p1>{hel-D!2QX>ypAzjy+P3KEEZ5rgHrx%k6pZZcN7{ z_{pn`DU156-gJq;5SCRDr=8R6~IuGm0R|1lvD06D7*?>z}4Mspx8q)dlz8DJha`C>boRF9rIkMva z5!tg3J_sTUhuh40s|L|@2YaL9%C)xIfsrb^&@MY&b2IENHmCUZb{h`*b@OEoVspzB z+kIB{*>c-21)}8u!fhEB7RxT{4F1fsI}>h0mx#0sM~;T9K`|2!|2oBXptGvROZXJd z`*4>>t*h#NQ}8RDD$OYbaf0DX4Wd`0rref#;|2|*bt1b)`^Yy-g9brIZcyf~Y#=K{zm$@q8JftTdMr;dYZX5dk)6g-X9squ&vp8xC z&&h;O3^UKywC0VZ;OGi~$ncNKX&8-O-sxP9>l@AXE4#u*jAGQgHL(e!xrVUuk1IES znRg;=-iVUD_5R;Ah+e{_p_D67u=Y9hugjqRFc!-YU4SSs)d(W1iQ;Y%p0yzF$o$N_ zc}PfS&wCLyC(EseTZ>wdmdSqTe@(d6Ojs>1L#n)3@f>R{Le2kWqjMq8ey+Vzh_Lxe z@fNzR`~1xBao12y{~xrHrJBL^ia?IW9T#R?bwOQQXW%5yo|$xiTo6HI2jb2@SA)oE z!bMYT?{wDIdP%g|iVc|uqPFYPjw#UpMN_%Sg%B`#n_@zVXmMKl3zD^>{$Mk;Wv)Rh zCV^HAc`-u8V7!z4ycr3V2Q_~o>4ABhKHtDXJcZ>%gjqih?-9$+!h)& z>?c~(1R~5o3mEmMker^0eF^=~YGLzq%5tRO$0)`>61FB2evRxuIvp#V#FiA#>I(gi z-hyn_!lowt)>QFoi*Ho9d2ikUNY*Q%N76%ob29@g=yc4NDfe%A+Xe@_lR`3aSwPp) z=~{;qe^d2KZN?c~1<$XR)FSt!T+(CI>|{CT>+sZr!bwJEQ-pTM#^P0qNx;T4*T=k&bbiONC&$1~ zR>B>ko|$HM=VO56l7zHJPrivrlH%AZk@~4t+W#wwFsBuKm{7XDhMAi>X*1); zq-{kZiavi?!iXrjwMu_`r}&JMENGT=UC{v_F(**GpypS?Bc_?Iu(<2Wt;_Q+IAsqj z&fC(ZKe?Ii74}zoa!#}BaNgGAVAm?%?^cpWwJ2GShY&hFPv&gi`B7$eTM%jTy<=eI>6E|cW&%g^cM)v-rF5v=jd>N@OrIgGm>nX6x86^j{6bV6K?PxBMSh z-vQoK*}mVL_nb7V*}G{*(*bRf0J22NO53DOn-ma1Kt@{-_W%SHf(TB)fryAKQF>0w z6bFh6*Y{I#eV^M8Ck|9l5Jg=5-_M%_{QlR~%S+NGC-1q>{oK!bpH~U}pIcbbfC?rP zf|mR1Y``d;quw_iR=G){_7*!Yjw^usx@mBzp8&HA@oOGszB@yxxx_BO++CPj;?1xY9u|(g91h<*bfj3d1DqS7dt+oF7tc-8ZcQX_;LVU|#A! z4`UZOBonM+rryzGy7_9Sa7UdTUh;hj(tn+UX=3)dTcwx1s_W|vJ)r+p@}#@nyrur$u#k|AF=dP49- zRbd@BWG^)7*JpeXm-{&+|JP!FXfjM3U-uj376-zTz1Zkc6n(}jR>iCjZlj!kSufQt7kgNCZ7{f(5hMoaKfX4; z4o<+{BRh~_e!kjyMcZhkWsXJBim})~MJt}DqK2ihR&jH^`SCX0b=clthc-X)05VnJ zf1!hoiW!4jwGVr-tucu97{A;MNN%e(U6EnW;cSIEt7(G0r%%;Gb^ww<+;c_7sa4XpkWgL>mF!q4_pQR-zD5+7`eg(Z82EZM|&GQkzpj0To(|Yj*}r<6Ji4DYv&?Cuvf8MWLDqZP!Jnm`#Zs6f?L+sh(xJj zyH&cT!905#wO=;$GVXM-J7qWO{7VTIPa%5!_&6zZiE4*zuQZF#RTn+p-V?Bt)|DUs zhcQbpdS?x+*(yI8%a2r1hz!ATHJDy$FQ4NS+;t8d&|+vN4c0hVMMHsMtNKB&>aRLe z5PAR3o~!i2;%a)ZpQirHs=vlN%Y7=J?1c|-PTV;*V=J(U>Uy`Gn6t{iK2;uRGXnO|>^;Fdj) zQ^g8wz3l9TCbDLic!cv}KEU)wEqeb}5lmgpTAN~j#w}cuM3I^G4jNgV3C8T|6vYM& z0in9lIMK*%4fXglJ$^vXe7Q_&GM%3(wmOB|>+SU#;jEK2U!!w{sdNqtm3%;GE6Qe78|+k_|U5X~s$mi<^&B=so(Bu_OI zUES4Zu2ZP3C+gHT+q8WObPjP|L%}y)nuolqSiK3Jvai*4k6uV~fq4#_+(Qjtjd#@e zRCd{O!X&lDT>~?=->l;5I>*=B5zHw5^nFSDbsQ6ta&&T7}meVsOhY zs&jWAd72-&A5!2tr9lnh9FROT4z3rv#aFw6-|CKbi$^9$b%&x$ina?d1 za3*B4MQk2z`b+U2D-l8jiFnCy;{y|GATU_MHXNSB^Zu7PkYdy#=6{oW%4gWwjR}e` z;g-B7vWeCd3C!ex@LkN7b<6G> zk94wF$*tL~jfNo^pVf&1q!BE6F=+xM8|_S|L{<|^gkf>RSc2qf|4m78zRn%2*7Q{< z4KuU8__c{ezjBtKJEowI)TpFMV2T?&?rrQgjtOWoPj+uKxMqHWndJs;*`~s#`a35g7@S=?q9a+zLyG0sC9x}Vw z!ES7@fHfZl)Zo9Zhn)>-CLaKP8PbplF!3mL?|&PXO!~UjctCbN=@z!c?H@~QQBeO# zE%pzx7-!A&fbe?E03YC!AdW!MOo*u6+%0>h(NdhD0JE$?3)Vm`&XO&F=y%z$FcSbo zCt@aU$lms+6RpyGU5Tw)?N_W9(pZd=-zQZb;}|__V!NAstx8dsRYY#_+pRg;>~e|i zBsRry4iQ*GyQ`rPC8~DWRe>^SwdF{LA@6@rEgG1 z<^022nS(8ksqX5MI=!l`wQl$TTT^!U0GC#ib$Hq=ep2UwBtTq_br%0@f&uYgL8AQxhO+{L8`er+&hy+;@QtoZ*b5!75;uBu@lP0AUv z?HFTnZGuvDmpa&z1_#9DYhc15;Y*@&*{hjRD8+C{zVf$Q)bF>NUz0t1uxGu|h?xJO zV9~YXy@2Ee4#~v`Bs$plP%w=TA#Pqka zenzI`FAuw8iWBWK-Fv_C?`kt#tMj3YqnIF3-&bFpnbHH%3@G@bNfZ*U!Q3sYZSd{i zipFxXWMEBPcCIrxqCw&DjJE(=F!?xJp+q%BcEgYztu}s^dbshjsh+I3z%TnHNi;w|i7KWY{-3NKPWa zRDY5*J&(GFn{*v|zdxv(j(x*6HjwN6l>wnG=4msE6+zYf@#HK1!6BK^X#PP-lVA2q zJz=sxY3?bT*V|d&1Z&C^BfuOSH*iQ!`p-@oZ`4WVYU!A4hPb>|?^`>yGHc1;lJ!lv z56h^2iUkcwlAw>AAbA|SV#$!%hX#cUGl6dOUPNgR1GHrQmhn(LrpGWPL`l9k+^m>Wy}Ss3?$bY`5Oki@_&*SJpxQ zZ!Q&PPIbd2yS3Huwo;<<10&(SA_*rZTsAf5lI^sJFQsTHV9h3O$y7lgW~;(}{}jF# zv1Vz8A(=UQBnp^C0kG!Ei1ks_LEJ)B6S3y?py|Bv&S#u#7s|Sf?&-9wZ#Z97xSaf z1&8>5@q)9v)SJD+FXyUiTnLJFEA{q?)ugG9o7p$@7XNrFAh|hW_}wI>XEnMvC{|dq zferTK+kiAz-2yvTuE=TE!*1c(MgwRwETlVg zJT^kJ-K`{_ivq%3aY``n2&(GFS9OFll`%Jn}K__@t;y^h(dr8i{jOtboy28X4s=qC=z^Vl3jtVx?PR;e`R8K0-k zHXMW?yRp}ATu`_!;{t6QeCj%e$@JoBnKx?G%QGxSWf(xxKQKw_`mu_t;LS*0#*7bU z0#`W&%*VglB)-`~H~l2;K~sUbOS8d?p;#42!(5njuhiQn5lhl!$$B=Jo5zPCF0c)- zWY0Ca?^0~PSjC?kiuP|qs;qzDqNwe<8e^H8Jtb@4l09C^E@`vYp__jco?Zm3!qc*_ zwn%)mTD+=lK;9*jf=Ma`U*ur##ESq)S&)*K0Xy47c8SU`?s(dX?HAvSL?e0sK$}IH zmb9#vap;$@BW6VQ^4}q`VtinqP5eHEP=_rI2kecH-}_wy215IyBC;T8#N-K z{O^S4h-}zm6?F+mBZ&(pqc{;<`pA;8bA!UXj6(%4IRr6an2HgU-K97Xu%@t)v&2~M z|LPxx?1q(_VaVcvHm%#l8<>+;DIB-nk?}(R7t}j3&o0f9M7TffY<*l5x-_88rwvZH z%~O+(yY$XhE;i8rB@NC=Hiv?i#SB~n5lCcx@F>lf3^93snJ7hRue?l zeWmz{?gr?8J8p;zE4Kx{4} zIVX%BkK57rcSop4_x^ZbrbT+S)wDwP!X=v*$5bqqEE6srU;MO9ypBV3b3pheW|?9X zts@KXA79=?5RnUWETXzY@d2W6j1AEsJ2w!YzQWGZPc`X&#-<++uHP}1g3EZ|k2VK7 zm`kehw3ud@rLhgJ|FoOGBifw%l!;lIkymD&c(R43(ClL?A-4>_>$lS-`eY|yIwvR$ z%vAklX19c>QRi=;$|8Hq%;LBj-G~euX~W(gzC#C$*~v)1GQs*mDI3vM6T=qFc9bYxLfVg>SOcut;t__Xu3o!w zghjM)n?-V^H2yvXGYA%j4%uXo`X?&v%uB-Kn(Psl#nB-vRtKf-{gVNUdSh$RV%Z7i z;4Z#}p->z#QzSM=56TNc^*AN*KDVpvYi`Y+K__0b)6hqSn7=V${<|yZ z13+Lz%9gQ-%g*7>`SToIU{rQhQRkgSZWW0?S` zqK_5Bnk`A9b2%57pq&lpkerWE%W>=1*sT{-b??6-FvC*#b<%XT?A`4atO{nvvm45U zhKU9kv!Wz1Vnsmcp*YjPWYI{?mWe~B^u5SG)LaqiRP+{g7Aa9k(DY^J21SrQSIr#~RdQk25#9$rHpm;XrMYhSu?n03%L*Q;s}GO zt0W5%asZwb<^5+lgf(&O_hTzKYs&5HVT$No6VSvQ3qWt438GtODfC7?D4o(?Dtotr zHcH7S61%HRcy^NRS)2IiXrj&S0hLX0PBV%xjnsBd45jn5X-Sx3*ec^>Pc@i_li&=* z$KQ@l+>~}3hv?mmXAH517E*kpPDI;RTDDzaR%>I(}Ntqo|;0IVIyq9ih7J*UK79$nY9tp`h->d zDQ+&!l)wjgq`@)IB)(Wngn|#Sv$5c&jCPAx^jj(z^zyxxhST7VoHcpO_Rl zMVo&&6^9iYEZIx-HWOL0H91Ji-NFP}6BaE0Efs#s1mFYkV@q8Heqp9eX_?ZI#$y>D z4B7H%`wojVD@C1nGac9|ZG;c7GY`q=R&wUfOHWRi9guuEQv2B?&kcD<+LHPqitld+mTezK0z;1q4B352 z?SqP6=Vd!Hu5$ansSV#DGw9W-x*hfCR39LZCw*R!h%M={Q||>{aXQvw4_yk zSB>Ezw_tD9{8tj+EW=SJ{r`ns2W`Z+EdgPV>_mY1{YdrvsXbTaA=#2F6tS1bAw1gP z7_7l#NJ*Ys?QCe$b(!MVdf6=*Pny$YYoIBv15HBJrpdCc-K-vg`dlUeNT$X0FPPXZ z5n-*Yf5^(_HENf4VL&-7hv`w5xGN>$sD*h!bSZoOGK=T(!F*uJr=9MQ84b6(4;9k; z<@LcnpPe>jKVBolknICR0py?HD*_|&>3GpGrSx(fY#*~Cnpu{lVbQ-~<9kwdNygNL z0CTDf5bbO8L2L%{Xa=719rZR$hvjZr<*z2mop5!_mY=NRmITOl_408s-VLVS6q ztf>_2zn5b8QFvrtYyM7`2rZm8jUz3cnG(|@$ys|tz^g|omg3IP0IEe zX7!+$>+4L2>;FJ_&I=-CFa%)D!npgQE_O4A2t8#tL`)kE!t9{1R`L9Sac+Ft5IpB) z5kK_*f^@a|Nrmz<-_?7%kGzYRKk(8(1i!|ZRh-^f^r;fO%!#a^0kqjcv@st;Phvud zXVhE0!sw|g)cqf6bFb0c&gA<41on~Dn^sRXS8&!GGl^FxJP3#Z$&Lo=maT{{-^D^m zTaaIl$c4~<+pneUx=dmeVM5~adx>zC+<|Cj(ooC&nG(3l_eDF9^G5|2kHi!Vux-*q z|IeZ$V8|uouM;HNxbq-(#ghKN3;maFj27NjBf*gU)>H&-=`Is4YAZ(0|6~V+{Lhk0 zR+vUF#xJArIM+Xv*Z;raNGrZS=~&0!Lo`U9;Rz*3CZ>$-O7L%wFe&31O_q#SQoKYb zol$KYC);P4)$3!fCo+M9TwI88Un#SOWuRz0aUs6%-aKo;1Ye z5Xa;fAAa2tFpDFr^=lM1+$Ox&0GI4gV6wJi&p`TJqg85YG(D>Xz>-M~28hdC8UjA* z7dur7oer^=yAnV?Lhz!{kQR~tgxSqlnO&C-ny2{hS#cd%>)?79U(4$d6 zKYPjbm`+#4Ul_5RVQ3F2~h(mPrSz)P;nm|F=FT1fFi zoj+M^u9vOQ`z)F3c{^_)f7#0(=6&6+X6S#IJ(@z$|lNYmX!;e+5@lK z*eeuCv9|)kCP;)4o3K?ljYjEZ?lWfr>u<%6)&qY zB`Jc47E*kT&e^A?s8qJ6;Wqb-dzNL&va~@Y^L>kRoU8*zZ#SA9UF?ROB@>S)u|w9m zGbl_{JV?vbQnxYtl|uxt*;^ydRoF0_U~LL@A2A0fYkO|zkbpHuBf9&P(hHr!(gq^} znO*IaUj`(_4z>>AYOD>SLC4#*=%xW^_r&#l23F@AdDO*3ZD4q%M{BlQ^MLI7@ker7G zrkF8};L_Oxgt3*{*&`IfyP7d4R$&mAkD?G4b8v=5y|Ue<>cv2tpCX_QYc3b+yD9-m zWjpErdjZwah!%#dM_s{~uHGB_sWwNcsLsb}L)cO=4z&zgInAlZRoD&#HPMA!63gDJu z&)1n-u?4d%3(GJVvp+hK_qX;B3${#nc;1-(f*rdub;zd9(DXw8LlzgsBBePl=R1Uc zaTB&+*a?e2o^S}~#7t+UHS`hq_~qE@nR1jVWxsobv*Hyg z3NUFU#fx;_1%1?d*@Bq=uDEM#rW9@&ZWRRPp``{+){isn%Dh`4GGmjMZLp|@)XM!FxTr@HShg<6yq>s&QV=PSI%=*FHKmN%a-r0 z*yK`V+KP^uK{<$O+-Zhp-%^k^EJ&Hs`qMsu>d#Kv?{___t(lUov`e-F0p>n>blF4_ zf_?}v&&)H2S5{pyk02`SpivxCkB*r^L1fGL%_Zi1+=4N`;*4@^zpZ?eYSvU0`!SFf zE|P6CjnZdz1?n!gqo1lPN@nGTl)X#t@v}qd8Pg7>v@vGq+~6 z5@OCX5m6`G;W>L7ZD(gn4{(T{Hi<9P+Rl_s4_d_s8g2VC>|zelc9*y{X-2oq8^N?- zQ#`*TzgSPy!4P=}4l0<-d$FDh1(LIZCdG@JZ)ZRDvB%NHf&sK@L&t3@dCOf z-(m-EtLkONgeIoFT)ico%$t z#3@YJmz`3XU_Up^K2u6#dD^J`Dn_2N^ubWWpNfCGjSY`FVa?8MC2Ka048MQ?GtMDF z0<()JnHxNUps+8E*eQ*^vP2dV7)=JZ?53pkqqM|sFGnD2`VR&`@@?tI1BjYv8ur}! zf}8Dy1#ocG?TOAL`{$tz+7^y+Rogi6aXJ@s-=PNnsVXcjN4hby;tZ@|%GumZK zySebAxGR(?{ggwp&m=xyYwRzZ)?3Bxjn-Z147-A3g1k&P1%dJYCn#tX?;li(CYMA- zv>D&qtaTjeZdV>l#;FD^y%_Hn(rJH3Beu-zg}{-U4mN`AIdIIwCd8dBr1`WExMiN=VS2r6 zYcs3+HrgzivJbJ#3ziHt*_`zHWCJj%Y0|IBuxoOVi2K@#?>Ce{U>=vtPMX>6d@xQH z5@`Nsy~M9%()?IMumzEXwx@l-<2_T7pty}>wYq+Z;R+ImMvdf#Ruc| z4P9`{=HwtkJLb)iLL5?dWti<&5MbsYn&?+;if91Qk3)@bDkWVuHY)1qw1~&1lbJck zk!E8O0>q|`W7NYg?rMWjyBa;hCo(LVq-sDH^Bjmx&XL^W7G6(c#;^EYxv)ADcqcD5 z1=I@R07MrK)o;zPt^I_1IYd`SOpE2ZBMxS1)D5LpjE+oPgJdRJWxtXA$33+Fq=SnM ztpt-x{C|zm-5aq0qhzD=XQlKbPMc><;>M(VbHsGNRqUJ4U4L3^*s?ZcGfTb*3O~qx z1em|k(Gg7ItU(T7R4?hIOonVWvE~*SGFCo_ZgrhioR!d7(n@$TU7=|%*(5wg>}#9| z(o(cSu|WSX&oEy1uY|Z%=A)UNG5edDA~jjE4zOlH#4tfNAF_&<#%=d?VeH~9IY_Ym zA|27A6=r^zZBW9sc|*3`uevj0Mlkd1P}AdS#SctcqDItW+B@iBKi9!tO%`G!*(46h z8Ms#*5?HcVWcCHh_zkdRw*;qSGS*()J%+Rl%4Uf9|0+ktF!fGeTv$-(g-G2fwhuL~ z%CO!2gmoN}Wf5t%Jn{!(r{?T5#{}WD~UsvnA| zAub;`IzLg$vXDUk7e=kSBO0*gzC_XF47-%G2Eok3Z7z&p_&X@PFZ)g+55wcjENe>4 zVr4IOL?)N)?S^1?`p7z1GWPmFS_yozRS6v;=m}0?NG33!AfeZPK;EN8HBZq$=@l;E zmJBZ01A5k<7u8_N{){=cW(6fB0b$!h1XN)mPv{TW;!@TXkxyJ zM92l!Z04-Fn^?1pv<83uMzrWb3@b}HN&npy!idZ`OfJb{R1y?CvTc?Teb$!t411xU zu!}>~-Qv1R?s3?`w#QAiIo7zA+S#n6@p;*I*dvTq{9ONcWm)4Z83mm+b(p0G8r{2< zP!=L+4bKR&byjIa!c_ZD{RePc4bophd~;=tou^-!jR34S*{`0z_YMcTm95bK2b;_(qRmUeFE}K<-E3tN2glj&3A1rZ+1YtZb{|2~j!5Qs zM1v|KSc6tfBriW{tH2e;V}^W$Vf)224oM$78$qY>5Nm#p6d;g!r@;vQe~BU){5fJ- zxXCk9t`8(JTp^e;XMLEbO=%Fgz$VZ>n!(t9(FjOBBuKvFdLOe&7c^^(eS~pN zl@!-qO^{HF1|VroshSnd9&{^Y7+Nu4e;_V^i*k#gNnPAAEn^foB)^!{_a)s`vgwdj z+Sp_+CzgB|{9`sEwqZ!a>`K{61jp_$8?J;0=OI}@kl0|z!u8_$O0mo#*A}wV(AP%krv^kWSV;~NhRWDwDbI(JSXCj|GagLAI>i!= z>;xoZph5N>a$xtQ`D}t@AZ{&^m)|FgGIGh!9-&n6a+mBwf@G;KZU1Hz zO53JsX7!1PZn0AOR^CnC-A-}EeOB?2gvEL~a-l~I8_DZK!aZ_1^xnrk#1nMGh6K#) z#ooe$atJJWqS1H7m#1B_CnxNNAv+wLp%qnG{YSX)40g$0n*cVtu}(x<0ge+KGxnvO zg<4g^6)k*#%i;w{%>bqidYC7A>_DC6aeGt7@Fy1>q-J&}-68IlO>Q#VD401M{FB2( zTQX9}dD;FIW)UTPiaGakV+Q7=m)DE&Jatg_&-x&+W+z%G2XG3ftl+?!T_RI7Qyv3M zhjZ2pUkN#YSjvIaOm&6uvl76JpDavOK@@et9PzQZ2@l-odFDKma`cmnzjYA)Y*-#A z2ff!>oDLICx9FgRAcG0nvSShbJjMSShv_+D4&K97S;Ym3g5MN2lQZWL z&K&fWof|@-mIS9hM$ADI6NgEh6%}EY&qB4VGmc(=Rj6Gn{=j_zShI(lrAOs4W3Y26 z?gAta#mQcMfrITw3q2J*AaTS+G?oF9)q4NcL}@Tb{7>9oo-t@Rb5QrkS*DU~{RTZz zjYYp?;3=y@hB=`ubDl~%!M|6-f>TL@I*>51-?br!iS$@~L8ao`%&7w(APR8;;cnq$s~ zO{L@V%z?oC9iueQy;f0^WS=XnokOyfL-L?OtO*Gh$RQZBn+TFLGMK9QaS?g{TcW}| znZcTU*@$Unj?hf4#0IhT(E_+-zc&k=atT;+f6N0)IN}8!rMQzrf&lYk9^ke*$kHS4e;bG7Y&&};MnEEXNf1k<2V$u6J3@JV zp_sn`t+x^zS|PlulpMgvrMX{L7Zj>e=2=E{ywUQ7f)n+GsXXt0EM>2j{f8;Hz53~E2aB6OW-N1;^f-Hn0?>k`AA_M z91@gbW~JlCPJ=ihB%CjooWR+waV&r||Dt%2-z>I72$C~x!pXSTeekq3duH#Wux33& zux5pW*t~cV1PAY1B?pt}mWf*d(Zg}JBrY7pE}>SHUXdR03NzvbeK|z;>wA1Yiio=d z^H0Y#x_?uO7^e*|dN>)BWXo6B-H|Z9kbx!ZiIw#RM5tgkwUu}UYj>C(mcxDWg44+% zf?MWH6yO2P3J&uAS=O{T*vXUzKEOj9qCs@)sK*AZ8Od3b{)jN@89JZdK@thtTpz&+ zC9I)Bcvx}cEZVFk8yOUCjOaiceDE6zQ=N$$P51Pz>49Al1|Pthkod-BV$B_PHn_cL ztQ!Mr}*HI^th0pV#cf zbVBDy^inP;@Gx;~lFhAkUgdI3$~jB;;|9$;DYihPrV4PySR-U5=hl8#66w83O7_yAiC;`JdRF4zBtvwP!|0{nrOV!#@_ zYX&!D_Bc+!Yz@uQhN}n?RL8KQ@De%MW&G&D~T6Z2uqaUDM+SL8m0rm%b$(*b^n0m5-QYoe8n?zXLD`Y zNRW{IgO^qOp@(gkz0HIPt%NMu&=Cdq<4{0zVR5tGtCam;PVe#cgxyiyJy!ASq!m}l z>OGQ|+%3a~J5`N5;a9Ub@E?#sTh>RkFv$aK0z(V_KMdLabk!bMvJTLutd3(8wTj1E z^z-HO;!dO`OJ!7>z{I*dMA*rS z`}C<*T;F23iCEKdnl*Pv(M0a>m$7H$bok6XM$h|EO0>Zz`#9lvOZIN$7-e0uccRYG z4&j3o#xAqZi8iMp0&4;?ZO51yhfCHGnrcyhHyb_^+vaA8r0IQ0TwEc{QUXWv!3=u3 z`lc)w8>PWb&O5+=N1iq(+wr!3Uy<0Tvl!hJH$iM3Y6}CB10Hst?Bfv8N{}g&9v)c$ zYkI!9uz$1hgk1K*Y1Y6c8VLPYk2c(qXAROa93opLB=nYRq5o6jT>lSq+5n?OjXudS z+DrOBKQv8SI)Xz2mrR?~&5|Ptoa@sV0BydS>$^EFe2znHQy3PY&3J{zJS6M&6@QPy zQ=$bVc;q%KMGg)L_L1>tntfuGgg)%b3>ui`6aPtE5MUw&hnT;jjA7tvge(s!`2n(I zHVlw+H5b2$ZQL9ZY`@4_GO%WI%8g9fCmfQYdDcWdf`db{Esjdre1hbc+2j&!!?|%O z+J1Rkg)mhq#!-H_KILVu3JRH|ah6f~Eux;MFk2py%c;QD?^}oPTf|(Wp}TrlT!Y5) zmi9_O@QH{05pnSV6D#4YxpE|Zx5?(hsm(fLpTaC8Jif#N*&3^OWhQL^3Zf`sf|N|?B%Lt;W=_Jjw$tV z8(8AI+PX9@Lhlc@Vq7082ts8Zl8t)TSEDGt+=)zCq;RRC^>Rp{Ex10J&I4AdJ0i9c zCd+d)L3<2-Q7Sm<%b2E*>Xf+b=Hl{Tku;~dxTue66NluK-j8(%T`4E@{yPrIs5~Ty zFV!+TY!u&$V>sz@a>=?mBxzuBZ^{92*-;@3SBi0H9PT8pJU=L0p0ZHP-{fsoSnoU} zmKiWu{XTOb=V|Q4TQOE}NZKh}EQU)qNAAsAF=!#AEo~z~DAW07a?AaFbkB2^AXA2a z;wQb@N{xkADC|Ox2}Uk~CbGf*NJwzY#lM)vFNr4XcurjKV48+;NdB+UJ^icGE?Liy z_rj2E40UKr`|$u1V$+$Dl5zkL{T?^YF{#6I%uC`TascL5)w8k@-Lb{s{~6qpt`(bBH!@$(~D^-@~q@ z3LJq{@^u~}3=Ywx9AM4%reaK`7=9*h9l2!ur{5P2;oBBdwFXYrz-4g__nPsmV#Jo0 z$i=*Y2@3)L7VB_R@f*-48#?Kqq49tw=>KbRf(iN`Z#7I*atUTW2^%>8|Fa7^^91Ph{>hnp-HEBaGK<-9c$pGX+`XOJy>BnOM1!-BrD z_A-{1%lhQ?<(a%&_HJ{@TDfE`pS+wt<(I*lU6i7^z6FE}&G_S2aKW1W(#Z}Pr4=MF zkA#rH)XyP-QQWxwn2aGFu0Rnth!e1~%()>bJl9rsfl>W!Q%N6%HRhSaZ*sqn96~ZF z_0ixH;3*GFW9JeUig$kLVdG^V_seJ{#kcCzF%lR`%@nmzR{6!84FjzWR#~-87?gsi{0j6XJbDn-e;9Ci ztkxQr0}W1LXi9sfNxWe$#$u~r%~rMv8)ZGVV16r8x(u*9s2213fK~h@q4N_{Udcg%4w<=e6d)Yel(E@z*(u5Y!Jk&$5HEnMJipnoNcP{)t(lUi zN~43_l%fH0wLNiVTm3&E`KgnAYm_!YDfhpU4KO=!X;jBHw>jaK9j_2nO5le)B=-h| z``RiIyqFR`pTd%PNM^>8{Qn9e4Mg!}3k}a;ILZ%@ zAc48KKCRZttd~vL*J#sxecGC>zwTLBvjf2Bj9HvIjaKpTq<)ZG5`zyQGwfW#=K!Mb z?Be7$VV$hM-zz+iPvQ`5){6><2!d0aaM~1&CuhvmzA4XoL+hyb^26lcvTh>!#LiXak; z38Dkp_>!JA$^o=vDu(!1g>XMY( zngOD9^eE(f0L-0fHc8!kX(4FE@NF6n)(n|yE?f|?D01mj93r0gXB*>sxMep+Oc906 z=d4M;%rV+xD0x35tc}=yHA@($kMCKWqm4Kx#@0m)J#505B#v7=3P`G(bC5{b54tuY z)j5SnW$7vo$&GQDh&= ze6+>;qjE;~fumSSMKf6uSbx4Y?a9_3`qv#a`9@;nsmk@{xF+*F&Z7hk|fb)E~m|TdD2m3@!1z4m)b zc~co(0Ts->ZGIG)gO%8p8#ta9n+)Xuk_a&WNEE*(vm5^b(e9|>O9yIf`oZKmBe&s7 zW4}K>3n?E&GyYr-fL4OqOlTIzsLfn>yv2QuT*}=t%^s8Z$Luz|=Wa}&NIBsyUBw}K zom^2=!l0xY z+b{6X1@VHTXc_9jcVXBSyB47-hhz)U2KFQj{lBHf8tlW+SPnDwE0v=0`nmtLVlS%o zaRtFlFT9x`L8c6!;uqZ8%P?4{?2J5XK7jt?7l>wBlD??yyPIQz#_~UAlhYq_u$H7r zU&yZEkfido8A6a0qdVqUMC{(*s}!4-@Ync(A-k*1j>%XkQ9P7 zXE(bG`xM-MCSK2a%Dn&OQ}p?@T8GeHKYUx)dV(H*(f%I~dab=&|7j)glqnK`B|8s$ z{gQ^OwM2DU75luQgF#eU?BtvGG+KhSz2&DR)z@ z$}m(ZV08|5TS`KJdE@^=f~K-d+l^o0p(jYNkh~$=?8dh(#$NJW0 z8>MTTOa6`&wEu%95Esw{S35i3dbu$NNiiTPkbS%rgI0n*zlz_7k+>kh+>|PsESEjP zgO@!fDM;le%K5*MG@O(XU*Z!@FL9Q18PqRuNRFq?;vzm7Zz#tkXqM(h3FLrH*wbVm z`^{;WtYOTHuw-Ll$s!l$Aj&=_woy2sEa_NC2^O}3i%s1O`u6LnEHkV>hlq;}L9yK| zo@llY?juxl)$sxI4 zkGqwoTMsw6uEn)a4qz-6EZK3=e|jCMvMDL^tpv#hIY>~3!7oY#=iV}AlFLu&|Dil2 zO{q|o>|dT|jh;h-K;~dl4Q<)P^?!68l2M+ta7%k1Y`<9Dgt5yPlwMAl;D>@s)I-oz z-dxFUkb_6_wE2+J1~LC%&5pZew&H&w`7ci}57v~FQO(x%U>*|Wmw)XnZX!r%Auwd+ ze{e`9rOkzp)RrgY%Eve+D8snsoPq1ZlI>|LJV21(iIn=q->*nQ+WxMY%&V~O-z3HI%@_fKt2(rI?p+>Z@E< zLxMm~=`juq+%j=k&?^V-;ILpxtwpJV*$98jE#^yC2>9X6}2f&*B)#U2l ze_iPn1PiSfdH=6sXChk$Sgw*wj_2Jnz_KW=zQ`yIYti2zvn~G%3*t+>cZjCK$xjW~ zoQLIIkC^_v6EQz5FTr92EVXmm@fl#srnaIFWH#*|0)wWd z?{ct+y%Lm99K&Hjb?nDFS|{{nUBdGFKaAPTeJ{h9-BCI#t(E3;oSLlSuXNOe4LN{w zlBU}^b?{znlbsp|e(YYaFbe%ooI0EIFs(Ka3xYGb#U;xnSO{mwDkh;u?(!+N>o7LL)W0JFs*e9UtIujC*C z(0D*xXM2Rp+G`FP)%_CiobLcc>OnU;o7soNYL_DvOoiCRj%QNR-5U*=t%x;b7 z7Rv0IEJS$z@E!;b@-lZuuuZ1CgkyAyI{(IGtcaRhGg=Aq{#EbhteNJXq_(#lc!V?O z5xQZO_^b_9(b{TzTW05Th_aq@mq9wpAwst7{AR)=!67P3o27&GM4d95@IeyM%!8$u zYSs5~NKnD#I$*1JqUqOpH&KUd!-?GU!`2}0FSC&xl6CqX_!WM(n#K7M_bRyp=f>b0 z{g`7;zyDgLr4j2?@&O*iLWnh^P{71H5Y4<=CajJ)xDNoI(e)dRU|^ez)XS5VnTi>kuS^J;L4XA+RQvfT#Q*8MB4gQ38`!%gzNPvnyG% z9QrfQnxjD#u3vbmQA|hdm&)wn|E0};9m2wh`7BLo1&5?FPn-8VY)Qn%Swkxc-=M2J zoM#Pe72raE`NlnlC-SxiX_;Hw%JD^}`~wo%ARaHJ{__9?CfGu>iF1KLuOD8-KSMU* z&Lj>d-&1CdWUl~!~Dc20=knrsn zs8%v~%4z&!9MNPCRzft1a!XbrxDJ#F4@M+dvH`c?rn`y)K$9VQxhZPd7SS%VvB2uy zr@CXnl2_W?2r$)E_&Rh}{3%G9+I`5BtxX{Bzo+z4GGx@Sla>7Uq%;F2^=Q`5)8t1k zFc%xeO)dV(GJEU)hXfzodzdCPibJwJ4+&UOowD+ne^2S-%j`GkoQF6hQ_Y$=QTvEq zhR2B|S|0P$Q@YVA&LKxDox>#SmqB36VRWu*k-hwPGlc*Xa+Zv~_LgXY$0nSY?78vV z({5R&*DJ7O`@tG%#UOfWv6meGeJ(1%a~_x~zSo4~L&$Xhn)|L`4GYUGm1Rv@4BC|*G5FMKh`$x&lf2G&}4L+d*UutI_qIdW# znIvh={?hf!Y^X8+ISlrf>i+O|sz>zl@Vt!fRBdLhRl1(HEl%Y=z<#=8;hhG_5f(N@ z)yK@@AAB(Hcw)`)Qp)=a4@6yln=qgi=f-_jiUy`591?EG*q*2rkPL72-)9mp;QP3+ zy&u|WDecvo?w&8G_R`Yz>*f(d%)QsmQkd}EMWve6BdX!Xe`PWhm)Q$>NKVYgwK`?{$2e`PASD*G3Q zWV=D^6~-41{De_hEySAfoHZ!LNR4>i<+BMtCM&y-97lX99nP@?aN!fv14lXqPpc1@ z%;Pl4i%Zkp7<41E^Ef2;>-*;|nKV6RZI_EM*B|2YJ&6mRGGxlcSCY1J1!b7ySO~Es z&LJrkT;6hAXIO7?$v_KNoU>$0k^0Uk@=j^X0*(m|jmgramHSEvF#B>yM(16!K?Di5 zU(f}+_a7&htZE)IC~Oyp1ZkKpmCP;&e^j8<{b-inYN2RlCWi#^g;`3zNk04!F&0qS!IkdohRTv3yx(9FHMSJ{-f`⋙C@W`E`}Vsn6C zzYiVk$F{-|8g|#Yfb2AF-sKQ+{il_n$gKWu7%jTZOb-NZLpGRsGY63wE*XD4*Y|fY z2T^$~cA)?xw8y^0M>SlKPnCVfTV9a^h@^0quP=O|R`PL3(2AM80-~8Cozh)&1+ojL zAX()_cWDli`}BP`O{2gS`hTd_G)~sk`&3^)6yT6d#Ov^q)8mphCs{II4wEcx0)k^) z4wAy>7Jw(NHcp!di?V3;UT9i+7Kgdy^Go{K+r zJ)Td?ymp#3v=C}w`g9mbk<}K01gx+JhA*po=Kc{qHNp^$BpLv$t#k*tM=mIql z=p)OgajRjLid&5>a=Hk|E7v~cgWkKixPT_6l*K}pEE3Mrq&X)p_G>sKr^+zXIVA9s z5gy?$7x04eQ*?*P-{3EF8(DgQa?#g>259mBW5mKdB&kH27(xtsh6hh&GLd}J8Y?$ke-B}gR|kg)?HKT00Mm6gwqS0>lR0CSW@s#XKNdn4(%&f&_=|OI@Bhhf;Q!<+40X_!VIK8e^DJ#s&== z$6lkoR9PSNlPZI^;TE%V8SNne!!w zX{(`fNEjm_b%)KlK{?mtVOrcMEr}Pw2e>h!!712)rEtT&xC7Nlm@PxnP5Dp)gQyYm4iLu#g1oBv-jj$1qz3pwor1O(T{ zJadHk3s5dy0qpnkk&A1Ox4C-7L8HrP{ zAuxCYnT40~ki1?g+!G1^VG}njBhgK8NT4s^)rLrAPlBWruk)XN-(c!ex=kC`2p4ip z_U5SrNZ>?rfuWTYp%vrfVR$QcE*1VTdJt{{(lW;vncmAog3V;vPd$f2l4Z_TL&eyf zF_W(5)8Ve=J^-?1S+@+q%$#%tjb#^wuh5pR8%$p-8@=EPaFv%tj4Npz8c`CbUu3U< znE%#D(JU8xXIb?_dR#Wk6lqACr4cP;KGmk>Rv5GF>tM=fZ7@c*?gJNLAp}W2zI1kR zNYcG6g|E(|r1C7T`CMSi@uz@f?e*1r^O}DSzdkaUE34?UC*~o+W-@#)X#Ua`q+zfS zdINpc*Kz{GzNuszBGO5lIQnMFdtAspW$4RIQTxt_I{iR@GVs~=fF_@#3#Yvh*6hz# zM8oE%ax^J^#UrkYiafxim7tMat>yv)YsUQ>+jCC#MB4hFJS1RA_CvFf9O5k5X{c<; zd&<}@jXy}=nx{!t7a=eO1))2?J8jL9v)_U>OT!1Kd6d)U6h!a=aOo8U5rx#+JVYzJ zcxBiH{Os6`d5E@}rK_Xv5xoLqe5%PS+}I_{mz^fpc@b@J1V(ABtQ2pBUxv>^l6iMI z_I#?VE$YYT;TE}W4{hz_FVBdWo`@&SB=;1hX>p7n^! zqh`*Uba?iB%Wb;C6L~|14}Csbj`%XR$ozqct-#4!*<&&F_yG8S{2;*Gmcr=emEm@6#bX>20;3@OipyL|uDW75uCS&2U$S+IP^wCrEtjT)HhmGpq=_C@&E5kU; zZ%-So?=4OnxXJNZ5TOGdic{pBih4a^ZDduzfULE+G?gO3SlM4uvtXqZvbALH|Fp5lB zVd^SMUOvbnf!@DKD%ty5g5=Dn=#U8b6>Jh`sRu{-R?{Ufn4HIi*ZJ8Iqk3c#H0cCQ zq}SW%F~td(FgSpuABW_38@qWSWo#ehkjygTP7-O(AeQ8Euvxvwi!qJxW>RZf!M8wi?DeZn|22uLQ}n>B&)cr7!XF_Jyo#aM=)CRv zza*us){^ORd5I?Y16FJk&K+$Y@cn7iwdnJI!*uNpcW4K8b5PRbthp-=a|&Ha!)+!c zMiDpCxn#yU^dUELM=VQ}EqPE7zpTG)C~`zIeJW{r$=`WU(6WSjKL=%RxS*g4ptNw) z6%?HBmb1sAVwI&(ej@4@8kPPRY1ByXe-MRKVIn6AoUpsA@GWdy@hQMS&k}z7 ztxt#7m(s6?swhMm*RM6=+ zWR2zF)pynbmA&Cx=9(7kDlEhBNWed)00H0PDJRp;(;px)rCW0cLvU;aia=1wo9*^m!C+ z;V4|j&D8^W6hMt^WOKPsHF|{u!*=iyco#dUYJ1m8C}biF95;FeMIegUDY=<4>|Ez#pUCVt5@WJXagQG1p<9MW(w- z3c@p#<2VYiR-Y{(E_{}wM()m44G{V)rv>7tEw1KUEEud+w%zi{G*J*g#oSy4S}8^O zM)=v;hU;}TSp}JrGgp8__-&5ul;4Gh{_Lk_A^C|D1)ETB_ z&EDxq+pMxm8M1^j3TX;Lfi^d-G877m2(+aQJ1vM%MnOaYMM2yX0XK>YPDI7=x=>IN z*Xs)|+|vK|chZ1=o<2Nn#vSK#zrS@>%36IlgzVf-fdm7`k{@-IS^!$h@O8q| z@#)FJj(XpDYn8(szx(;-vbvB-eQiDE^)Ka74FrXK&4!3?XM`i}nidaXTkE8`N+N+U z_IAZ9mdjJt3X8C)-m@Fo0z=*r5D{Y_r%XrmH{11%R zuZ1%*hW;XCgDtO;XGGkUUukP2k3x5RJ~UoUs!?4nRD&U~xHh~C+x1I1J(ED>Zue@* z&w&mZ56mT$MY#fhg|&Xh*2Q=weYL?)|J`0LqubTpnndC>6!(eDW?eYM%XS0}GY$!5fODr)V^Q7N0PNLP}d_G22% z_=~X3wQoj7zdr>M?57~!qt5+Fm1g1O!+7O9l9rSqTioovGo>1Y!orvHwrth)&2Bx$ zASRgzCl3%{qV=62I;E2Yl04>e1o)1!Iv^QS0XOd0+lfSdIFhz0qKA{$!~>|k+&hg% zFI*uEnN`CMp$KqLV1b|S-45`yc0WGx9l32ccDnY>F(uThE!511g*C%arEP-CKNen0 z*(%3=!BBHDi^QL-AA6~p9w8B(((EMsJ|aCI`!V3~2U4-uL5jWlRgy8&`ZAlcR%pBK z7(&YVmw#au&4zakVhj$Bk&3-KrSqGEZ)tZws?)R!ET^f}rsHFK$eP*3JPVwGV?f`@ zX;4b8@5+qfV+PX2VE1wSk9I`8<>qO+b!5y4JT`9 zTO}>eGpDe8M$b#qn&tYEN}1M)#p4QK!-TpbljdPD29l~+8TZV8Onpg!K7LF2Mb6k zo(o8b&=VK2VXY)`(FKoM3!P_hdj1FHR5(7AQp$^TnmmCd*XL|9v}%j57=rVQnwa>u znKdTXOd3+vbxsqFGON* zKl1?)^@4IP>N1c}U~{B(hj*Eslp7UtZN=}jWS?4*JF zWB9<`*{a7Ag+@9f9SF0NQ;2$XBAPA`VHj+WfV8u$uB%B?6(Qw(CJ^181)!?Uk&Fe{ z0|~LxQzq#N5ee3b^V>A+lwgFE<;-e|s;3G>-|96B%dpNuFCfAhDc<>yK!o*`_k`Hy zGL6d0LkkFnp9XJ1H8@Y<{bin`sU)%_j=&DnEa^4}q5tf~ukCX6Zu>7}hIJmgY@w@@|Bttl7yRW zDbv(D_|*$@@5uB$J&~FoVcE$2<@?Jl+p%9?BHKbpC_PB2#)Yk}JCR%^ka(G`UqISb zR@dF6nNGoQ!f~!sHgp>|Mbc5CM57%r@t1{cu%7~6cWU@=!jeHYFSb!|oJ8^!wJ^HG zM){Dj$c+?pCWB+B=8X`)0gF^v`Lss5q#U7|tLY2)H+ug?EU=u|@*Z(qM(;1heU_#d zep*i5ln1xe-)gfYM)^L7>sM;~-UOwH#PL@_LG+yHVcI9=YHX;v$K`(Uer)xoB;G#ivo7ig<{{u517^a6-Ck)a7u@*db zwi0jfI2kWTql3?E_Uz2;dVC_R28Qq_zc%rXY*j3tXG__xlbyC}5H_>!q;O3q1$(~$ z&I6aCUK}Aa@kh#~;BYrYw8?(SXA&m)V?p8alrX*%6sB8wpp_c$G9iqw_34|-blA+= z*JzUOXz=0~$y6S~I2wZM(l9IU)=2KZxYKqKZ2UZM5sNGj;+LUuG-Rjk8j~`vMQME-f&-WewGL3?Dbh+Sv_?NP7IHU!LRLf96 zqFt2m`hWGBTgo)p+?o(oH4uuVP*BQ06Jqz3*?{PE%2s)`Ky;;EbAJTJDGj@{QTyVT z@o|_?s^#PN;pqjY2=2l0D%mc);t?)C?-D{pcY+nKy5x<(rJ~%DZWo9ir@_g(R4*9E za{XCN^c;*#xtE@;rbl$@?=Gk&L2v(%quSK&?w4vnbh+Tgj?=BaIT_BJLA=p??@4V0LcuaMx8=Zsb~cf7o8sqk7qTJtr{$3(m@Zg z^?qIcaUqkRjp|>@$&mbTqPa;BC zjX?S1^5QlM!oqkxOI$jBS?Er%nn)TL{n}KtEj0=TQ5fFC&s*85NZeydIU7vlPg%12 ze48uKkflvRHCXN9#()$n(}zr&w<37mk>zE(Hq+9*ILfsVJrGqZrspZ9f`Q@F1tOP* zZRke!&j^=4iV7=^X+kz%>5&>?h{b&*o3|S%0{ti@8+{RPFMCO2mAnn4ny84vuGXh- zi>R-QWM}keEpzbCo4mJV4oIrwfs|}M%T_(V+nb)UWSCWv zLh`IHnY%PQ`CaX{9Ois5z?HHB1jff2DBj5-)iBhJ8)mCoB6OQuM0S$+n$&`huV;PDCi$CkvVorn5*W2tP=t|;b?H_f6NYWfQfH0N#4?4LaHeRK-kB7ZYm)f~^3jq-RZ zE76#wlweNzl7d-;Rr>d?likeuxrms-X<-9tpd#gGZl8^5{Cd=}fay6hV)U3KqcLot zyf3Ak#S7qJX)9Q~E0lv|{}f?5MmCXuCX|D;rB4w@dX#D97d4Pwzqv4h8%w5=IK$|{ zDMm}{;1p7f(gU~D(Zln)Rk~+2?%yK@ydsl?pE>0l-e|mm*15oe46{q7 zgcOohbvPcCD)Hi|bl=uGDmlDi%s4Q6;l z82uGnb=dixPJmwGr0dUg@*~aWy}AOAkPZ4HlQl6nA;}&=Ek>7ra^TnOz^m5lc~k5uJ37YrU$I?bvQaT{0Vo zpppA9WG|Yea0B(d*Co%7a`Lx=QG=C#+)#j1T`3qLuY4Sgj^z87V8L>M=nImK3zg*N zA{?nsXO$kNu4z6}s0M>y@H>9)N+CK#E6?{nopd(o-h-E+oypg%T?YAJLM7dQo*4X+ z@3%ENHj^detG1b&Q_cqCk*-{B7KkW*e7LhE`2c|kszJQ?s4kfM{}BzyRkb$Rh8g8k z5xUP*4%3&Ayd#j*rSwPB!tjyn4U&$^+&m{Gn=1v9ZDh%U52lcyl5B1Y;$wy!RbNH^ zi{wmlLQPEDgvSp^`uZ1NhQPJ7m99;j&m5LcBxoCoMYo7(3`4}O1`@1NmSpm>NqUI3 zT|Hmn=U)gU^Q^o`AekwUoYZUfL@*DzufN$OH449Wija8F>9Vef4=FPlDUPFjPxRiN z_bvRH6p~@fU}k&&D3FvV(hC<{N-^S_R<2owJMmx+QVL05e@>%elU6z~Cauf*?1d>y zhOn$?xfV$B$H-^5njT6a=}Sm*%w))%Pw0w<2qYL>nN&@`T-DULX%vQum(wHNi6n74 zLQFosm>-M7-xGZ_qNu)bjN0>4VV8SSNlQ{CK(bjeJw!<8^Lvf5v#ASy$<9$-q3Hgi zu`Z;NFU^vv2`U4Ui2t|R;v|wOEtwdCe33u`LzXx%lNrnPV!$iTUwmy!CJ)q8N-9mbuPqcOpP?JfrgmFZdRmfLEZ0c3K>vGXJ)mB4>=G#Qz8WWyw_P zQ?O){2$5wl8x-f$QizhOxzQk9EL2ly<5!8<`$LFN-cCb? z>!K&_3DRYl{J$edm2tiA@6I7&dTaqB&I}~={`wgFFFBX%nhjV)u{6M}8_Da!|JVB$VylG++6qi?18xix zf2W95lv#nKT!hJk3z=hwLsa+aPPz@i$H-KQC!zPRDI_l|WXKSbUAYLqc#a7qVhU2d zzq#HH-||`{?a5}{q7;%R?L2X9qxL9v0H->+ZZAFDbTh>scFj6Rj+38kwm+?t2MHwK zrjT^WQ?nnTE@=U|mc6c?)&A)!~<}HmOb^nIU}3 z!^u_p_mCyS4}UZjQuN4CjoE1XLm*kbE&H1bNLKpO(kfHV#f4rxT5;D3X^Xf!08l(222(`$!XctlSC5c2NE-U@r>uon^ z6LjBuTfK`@Oi+E<+L#WRoS+rA`4gQFHxCMbU+84tHQNvAq_9AO#3czVk4m-Hfkx>E zu|hcpQsTRHKU@gO&NY1vL$=MoFe7`&5PEZ(SsFPl1J6HXLwA4)uiNSeJToZ{<-3DMp>pwFq&_b7d7PLYu5-wqIVyqe%y&k zK1c}@{|YPgx8Q7`rv;! zIPDk1#Nlwnl+p7JM}tkR{j=xkZ_py3!9T-!Oo#!NG@_GCdR;X5qh{&uC8Qj`z*OYq zm&9Gb^s5hTi~LglX+8z=m*=TE;)dQvDJw$W0Le_^?0n2aeh3aGG)-`+Gs}~}C6!=q zH}Hhmyr`Frx76WQ_*DW6HZot?Sg@P0kgeID!jhAtn%|b69LG0&n+=;Mri|G`{{7V` zivSCMyxEz}EGr31q7;S8ORLDi9QU&8TV?FOw5}58DPAoc%+i43FbN{f413$g)OfWQt_G6i>fGl|G|r`$b+Nb@&z(xKh5^ylD;SZ;zxcN z5JEpD)PfJzP*2 zh&DUT=9G`jF=glgpX0fa+uqRi0>c3 zUR_6y=yZMd&TTnKL@;E!sQ#MuE+G1iB6QC;F8*0Hub>+9d;U4|%}z>pQS3M5yjBIODZ18g@)(=Q`a)x##$ETc9Ts!8zY9c)n}Ha^D9kY#>>4vAak z`8lc;%X9vrP}zD}d*EM4z5x=-X4;+Xu|;+-Gw&8iFg3io3Qgts$;{xXj%BJs8THpphO6Ph;-l1(7ln~DLjj|U9iASd6bXy9D3{OpB0ofrp`CDy}g&QtYN zbbV7udSglWCLsCSAJ6DIP9V85g#;TX;FP!G1PMxhd4C(fL@=2zWFnSo4&F^m!4Rl} z^sG=G*d<4G|H^`YD1>)Eg_$lFRPuKxlAE0@GcJ3X^{7A+G->8mQBmq^FB==zJe;Ne zA0@xVD=hrvvXa9l>H36VvRJegW>YA|Y;{W^kTfVj=csqFrn^v3P9pi6oXdB$J#i(! zJ6U@IEA+Aj0!hCV5;2*8c zOZK<_wg$smt$$4gvn?<*kR^lpwqT$onjSOtf&$62DI`{bWQdcGQ!)=Gk=)??#i+J6 z1#p?G@>Ek5T{l8v8nc{P3|Ai$p24KlXmPxIOYDVXgJ40tUn~!VA z+4N17Wo8RRFF1Il0oBZ4QZ+BqDeyyvY~;$kbEFz`X1nkA3y6$?M)E18w>WuSvjanw zju4^*6_~H9LYcsE!prWCtM1KGKVA-JL5%*BCu6N>r6ExuMOub{Nh z(d=SxZ%x+xp&DZV1?CMkc*FXalfAGsAO64X0wOAA%o4t)q0^8-|HO#mIFT2QW8%@o z%ss&<2eSF00Zr-ouZ#asEs4g`YPO?j$8*9Uu01IkMUBYe5zw2zQ<8H#qKP#OQDp~nm7 zf^6pA7$Jdb#Ou6KAi+vn-5dP36B2s;5UGZ~Xv$IbN)#gJ?_Z&*YR|zCb1rn5H>Wb;=R$2LS zkzg(s&IN<|g(33=7MrA*vFZ5!-{k-8=!UsbAi=giI6qmk>xhYAZb~-q4`Aw65`3(J zo_$Fm!35X3Fp`+uV^scuY4CjS;<_l0kaO_`;^B}e=Qrjd|gUN6^6K%GAx?HuNm23&+%vX+oI8&m#1V<6ktLOFx@>77)Gm}pUVrX~9$tF%ZMGWdH{R1*Hae_-HT z`&w;r?}=zILQ)}O*yrqgX;=c1tQlSC{75i2ZKk6dJnZ?fJevHy)pIu+7|!2+8_ww7(d>68-5yNH$~9|6s_*Ks8;jAB8XR^EH2LH-YslWQBNpSdOYkBEQ3+K3R@P!14z+PhJB11w>|Po-$nUMd<@DBx+s1+l7$2!`&H2=78PSOQBGu?gHR!y=ITCX-+q7NAPoU&-zEN|< zG{B+>ulVy510OJhY6{PorIV}a(t!xCi@6Mr1G@YULgf7;rJ6l?st4K}Vg#mKy^Rm< zRL#^tb4JOHL-ElINUBpv4kW56h&(Tw1;UbHSd#Jw305QLiCgY z$$!ep$o*-Sb}oVC29l|P6IJ%wHO0G~d~!UyfElxBpnYk;r1`RndWI2_P2IyD%aXf9 zdH_js=}|<j?;}WX2sKoit!h-Q*oIhF7S4P z^cJP+7aUA-h~HrcA3iVduFR6x#}F1M<&{c$@FwM;AJNQ=@{i?YIbh5lUjh#ZERBJ? zqSoVU24HcctqW|}fuVq~I5C_|Q;mv-gXbsMGjSPG5#F{qx!(92Ci#1j!V7C=#%%pl z7+}OUZ?%X4b{ZrWr6>alX14~qhJ`d@ zhGUJOtLt66GQ0M=M0%*10nzJ~FiFUnV9Y$|V@{*V6#OrQAe|dTHuIKAdUz5&d&_Nn+_Fq4$J&$H1Bmud zB1DJ*E?=LV3j^h>3T!a(zpJT<%;azUK=ghWd?7P2)XJ`=xR5s%vO{s_0*V1}0A4?k zy_q1XiJ#s^f#~A&fU(-Vs>Sg+wtt8wshcL`bA$kFe zwJBDpM&!|azgZfx3?k>ruq+WHhXY0h-Tk<*JQWpQsl`6eQ~kXnySq_-b|STZX{T&% zfrAM=5+)^GEs#vv)>CXV&UYF3Z^%oBZt&ip8R&Tl-3yQ$t)!f1 zNsj90rM86H$TbnVPgt{es5k-H+!A;*ig=;)Mb!NTlCFfLD=K9}szJ?x1*oRn$@Zj* z%r{t=NwGmSZ%m>CUngP^B(h8WY-UfjLOTxY#&79wA_>#_p zAJ3029*9aK2+1vhV^Qlmt?7x;grq5jl z1wH-jZ_KeJB&4?=@>Dag&FMlaNWe0H&tE9(9@Pw`d@|2dkA;-&UduK-zJdUT*w;Y`UQIQ zeNfIabs#&mj4a$%fy69sdsuqm@CmwYEw2As`9uYJ_x$4GgGeRt`MU!@MX4*sJQ_D< zm@8(;;Z7{bUd~2s#|@JDQqr}^Ug*KM3rjZH$$K<959o^YezteLk5Mp#oQ;1?b^q)h zgoNd{^D?25oj+d)%RYVKXBe_W0gRUUa}=4Lx&I$g;x5YO>+nW@o3vRlS|lvl#}0mT zWA+1?nkU6@p+nenR5+WpA_mAXO2Z=7-EoxohWrZrkj<*}^jwZ{nzlkEo>!YZJ0Tfq6ntsZhz=nUc*K zk5HpNe@6%=Y4w|Jw^_JH$$8tv zcf{~?@--AHr(+St2|f8mO787eB)%k@4KB8+nf=;{FbS1Hy9$2*TCsTv^J+Tb{(3&N0LzOC>r z^hjvDsuC0L+0l3)j$+3-##-v?SV0E$hO4$8yrgZ7Vyl3L5`AebcXi@%Xj%q>Jr87!PMB>XV(w@!uI*@!H=&pG7 zhs|PgojNbUEK`NQNB7uW!jg@nslx0bk_rCxyVb%+D0%Ogq>n`}{8~an>sq(eE6dPY+_N!pR;?)HZr&QwoA1{)OK0y4%A>tR4AgLl8**a`9m|8^;VuGu;_h2%v$8>Co1MSw&L$#K;D*Dt_Da+feT zxUnYqrQ}i^o5+w!zlr|Hjw9G&+r;-*CD5qFSYCNeqX+ZJt`LmM;r~aG+xn@HorqhO z>ZJ}Ln+%c-(kK4>>|Q|R5Qv7Q7o4a>mRbr#Z4Evk`lGYoAO1frs3`VZw6aD_gF8Qf z`H-DYAk|0*suQF~#AL~ud$Q(_X>^x2*w9s0>Su>raQmHzGQFy;twuPT-^=j|PpQTl zT$&-bj*?HcNHAm{(*9bOMuFsRLPGlQXOp^%q8#Q~;?Ex)?6x`1C#dr>LHGHrQPW-Y z(i|sCCTAI?Vv%8`S!8QlKp?ROrzmhDr9d*L(Ti@FD?)6+mM&Q1>Ro}PIiGnpkZPof zP)#wAG%MauOw!}kML59*8?Rhov}&YhdrGU6{5ui7R^w4|Y=-|I)x!SJtFNz|-f_el zyvf9mR)z2lEJA)sV-J*NUJ*#fSa~}2)Nz?|Zv7&?)HOmuvoK@y&>f?MsduipZOm1A znS7<=Pb+_+0Y~$6xcH{^xnd}$HF%BU+^Us#mXp_uAKBbveS?SgIN82*(mv+7OCDW zeNLTkmigk^9y0I;qZHo{wDG-C8c82stwL%eTWa*(5sJ0^NT=oJ5lN>(Ccdwlo?)m2|JxH9=}1o$?{e<7@-bDgKaSg6?6(#MnXIV9SpQ(~W|Q|3=`-}0>NwT{^W$=GduUbFLciuDV6h}p|$D2Ab&e-ce(;JLz@ zH8^?sJo7=Fe50S;0VkWn;`FK}BrLs+oQdt!%LSIx|1xHYoBx0@8x(8-r$Hhv1E-&9 z#7C!eb|a;YQiBh}UR=VhC+C#?;owsy+r)?&x}N8Z^2gKZu1^yt2~(6`y3CJ1;c$>l z2~2~6FVe$U`ni+6+UP=DJ-jg|PMGLX?Nkn)za5iGARUi*JcnaAW~Cv}klm5uq;~T+)?=q0 zgk^(*_bQHUTJ?uv-E(W)vqf0ev~9qfc6Nti{mQ_viV~R@uu8u`luTwCoqTtL{TZEn zzn{H#)R~q-Wc8}{ChUFSfAoS;N;>0$%QIyED5|T>fmtN?ZCQ+kl<($`82Di!o#8fK zE!4kOI2g=`J`uIU!6b*BLOIC?5tG(_j=C&H>BuAksj|SMC;iK~;64Q}m7a96#N0*` zEbLZ_0eWCl>+S^I@m)R}Bczj-He|#$2ar6WARA@qicIHN}>fADCf1^|qFQ_fnQ(R+~gS4@)Who(&A2;y81d0JhV*rx~hBvy|z`MBYERG-YxV%qG=a!p zz_u<&-CsR%G-816_gMJnO5nJO_nShF42EoHBf>K2tDe$XrRW|j-ws5ue-F4=b(}2O z*>YdUkvK8hEtW5 zgDW!R=LHfNvSGrIC4`ZE%)ljq1RED5c8E=ww}`lmIg#K(HnKiOr#(Pr1$qbu=BjLp z11m4o)?_YHB$Y+FeIaxJBx{4`6!_rMADsN%1{Vz3!4SWyId7mzUL=rUMT9Gsqwb%6 za|Mu$zR$v}u|gQKWb}ftEU~gN;Lu1}B~mcveaOn65VCpH#Xf3A44^(+?&&zPHh6QyZcOBh!^Q$)REEUec}sQK?8Bp;2; z+#XJwYt~GqDVGULtDO~Y!QOxTyYVEGph3(zugylX9?-lbxCX>SyQLMG`8I9SnWY!WsAeMW-m0uCYbvmAcC5soH)vJFf z&*?a_11ga}CzTk*R2eLyC^4F|X`E?gdxc7-6A~AY{4${v$w-C5xO*v&?Oh;{l%*#E z&6V1z==UI*;08Q4H{aXrm_kT)1dC(N+qC&R!Wp-l;&=`>$&u-V#DbhZ%!g9@;i`F9gk%GM{nsk}cg#8m zOSUg~U4}eyWcsFX+HA8vlh*&YTuT?Le%indC+*`YAD728c$-@=uziE2n^9XGn(SVEdIwQ)Bsito&9=7afOOEF;d& zVlU(fwjA3>{$H)YYt+qlsWvxsMdYmQ#?4!tS6lhZ0#O|PA58{JW}cX2#HR{IU1`{I z?|_{>x-er@x~#;kOBJVV<2|E<$mQnaTAY)qnz=7HA?Dno&D$5&jB0hyHL5=^cXc$o zj@emd%yveoX6AA;{J%Fswq4W!JlmXHJJqmi)hZwmH3*K(g4bdVZZANZzZYY-XZO`gsl@(Yn@a)^j7eArT8%qHTgdI<2WgINWQHz13A?EwsB>9DNxrw4=tw|$|E|C_+3a}5zFCrv6;=<@a z_Oo7&MyfiFyh5sRk`LnzE=1#@59NfU>c+CRIObZ}x5AQL=VMKc?zmq5dqQT~Hi)9@ zVq(ajt1b{o@CsJBlp12@8x$v2!L?Nby(ibrm$tg55t3JeSI1mCwB9$u>Q7qqKysqo zi#t4SXR~7%QjhQVIN4eVLzW-$lmAb~WEg=`KE?dF&TphCj?@j4E|6#i5;50r8qR!) zg{@xg>o|Q3QF351ITtlTvS9+rO1o;!I`fN2Tm+I@8_%ChNVdAUX$vu-|J z2$d8Ru+p%7e^&ZOS8*-%d{{-)!SQHtB(6dWp0xR`945O+|^z+Z1{6 zUnu59%AYtEycH0|s(6hqcBa1Qm@K7t<6YXjEw=Iw`Ubxd9lDMBxL$L~xU_G!!o?JB zR&YZ8S~aO8NKvx3B3-^dX5FngfFwdb%#-hyX0_%DB*%hlVva4^Kt{Q$wI#pasQ$W~ za~QTxi}Ik05IBg9&SWZ8G3R5r!FU)R+wkeoxu)$}mlMdkv3FH}PI zW`c!%u`>I!UoV7YL*7a2(sBAsaB+sOPHYw)Pt}*<|Ie)DFB|w)fk=V>EfkEfd*YJy zT!*R0O5P)xUEZlOwvRGDL;m0L&o*0YuIfg`mQBb8_1%!Cu}D*CggsPqCb&%?QoC5F z!I8sEnKUhO$^etBrfAxsFHlv6tR0Xueh76PqWG?8XMP_m5k-GfE2I>|^U1Lksot zWn=xXlWMv>pcLZumnOrfk|D$IP|e<$^;N}*RllyTLYn0%g#SOdG-sMY>ezoKh}!lI z+8*k1)z68%Mx*+VPDXrZ%nC%1&5%|D5M2@>_92nU-0$RLl&phD3|`Ustc1ydWafwI zLkz$}OEbDn9jTk9sG5K!kv13&i5Ot{a^iATB{`THa)zVu z3pPxCcs;i``3?nBF#Nwx%vw3hETp4ZzfHe1SM{`F%fWt%QSFx->{^TTX+253<5M1b zf&!mXql;bDVD&O%NfEyyUNjgx>nIch7%7>ldoC*-)0Tm$_#q2_DV7Ioc8I#7`7V+3 z1Iw%u>8+UefRzuY@d%C+E~dMlpQXA#vKb!QVUp|VcpT$2ZmI8uZQvTau{YKQv9eFM zC{@eW`PlKsERpjUItfeR(*n!Z$-4X-oPIl-mT1<3OJ>Y+QgLz{TSA>|o-S^Fc&TkF zSu-AbF6O*N8?cu%ZHsFW78#AuEuKb#8MCGt`O&ETSZgLC<;jskoG>~40?K(m>Nu$D zYDy^wwGq7A=w%;8ZG-8tPRE}>GCZ*iJ15w|r00!g`ZH1Y0+I@jWLafrmgSkx8+c76 zR$tcC((uc!_|i@{bFJXnPJU3ydn_~m*NN(z1(I!xGHSL-%X3w4Db74nisjS>Es$)j z$KwJd_RwRr$3|(ki?ueIyi8wP#81b)2{0*3F{ufs9n8{bA_a~GPFSq_|VG2cs+E<%EiFI{Yvq7l|CzvGBKbSENZ;leR4b5nhHC}l@CmeJg2 zxs^>2NVfaf7mcQcdbMdxTG3Wb;8Lm;t-zNSdoXDer8Tk?RUt3dKUJNrf`rEG%zc#G{7v%EkkMIf<0=43xbF(an9 zf{^%N%#tZUVuF|b9JOGka++9T8=-PyDPQ^91#9LgRz$aB&^@=Q11JlTNiLy+-lb=uuo}|qa9rus2K4X+#TS)IN&Q+aO9Qj76 zC7SWVhJ+>4BHdOGs|!Y5LVt;hrp?8cHQIBTAzZ}gH5VemyprlQ4tIfSMp$zwE8~(# zX72?Br~$||K7?iOMyaCtfQ^ThOhnFWO1P;e|1~S0EmZThi;Y(@1)}1PBV9swnWWQ7 zPkaFb&eVy9y!T}3nQnZ2b7;Ah&k>An^Raguycmixj1t-WYlln!Qv&$HlU4G#wm?u= zvq-vhcC5}Bb6{!dd#fNq&j7bHu{nDZ8M7`S?6`KjHZN4pDqD0*jq>0K^h>HyVRt$s z%b8$1*pl~#S-v?T7-5<$qVI{7)fMlj*Fc^?e1S1coq@`#xA8bw`U zVQ(zPBFjTUiHts%kJRQV!B*Pyr*M_xT4`s4m+)5%e0`;*NXfvG>;r44(eH5cdCR%q z$^TTm`w5BRxls<9w3HD00L;%-NwMspQJN67+`7VPv`CBVg96ErP!Gj@aiSJE! z^plIQp-3K(vRO7b=+;>Q>|V zZds46E;b`<$!3PuB3`+t+dz}%UIpIPF|L3u38%e8(=Q+^LNcNz=Svg+JPJbmK|-R2 zZ@H<2kEs+ zx!K1C3zf`?3q7o#&w3tPWz%js%o_cdjVPM01Xo1w&ALg@Fx~c~C8N-!*sB_@*fGD~q-4FZog;ZME|j|de!-A!eOiVgn-RJ;V?fEs^cp31 zB@9_YIGc_1{A9ji;KO6CNlK#Rj7aLpO<0DzC>CShyYGKF@3Pkt%n57{P&gOl}LHO+9nreY4ty;Tmxd({W zB$~9Bq|58Z>gL9rHXGkD3iT$>1UJu$7YNzR2+gcoOP%{iJF#K$8f zODw?7yo*9BGA{Cu)XY(GR;5Da>+S66g=VZ&H#z26tjJhAcVjg*+Fm#7E09EEc?U9e zd#ciZ8D)RoD1Bc}hrB#jH92PQXO#9vaXDVIMe0KV7LY6owT#uxPZSNp$kn;de5PAl z#Ha6dCN46`r^h0WcT@-_uTg;+ZB_iBg|84uEFxlh$i` z;ag@@cN0i{K;%$k$uuI(%g2G=GIMz@HA!C&436PhC!48czo^UW8eo$~nStcKCEe)! za4wCCy#jlViIKMT-eCzAHi@v#Yg zNun<{ZLv)07Gzns6+!By15jE)aGB;9N?|g8HA~%Z63k=qZVSJ^rr=AH)L)^e`EeVs zY4jU3@{AJxR87GN%v2F7NprJd%hjlq;Rqc^+Cz_+q(qD!zs(qmF}LVF*hqji$ zko_4=j!yQmhZ-Cx!<-QP{F8@k+GEs)o@(vbm4!X*EVn6ZOu8H$t9vkJ&$aPDEiz|M zErmH}EPDH2mh52PbXc-op;Z|JvPWumD#3MT zOwJ`lo9*nL1x8GZz9E+Vq@tQ;<0Go54S{HB3omu@_E_#~nbLDr>7K9+!~V`B%G2<6 zMXqXF%yW?u`G@=ER;$$_iJ?r8&92Z%#iL2|z*a|z$woKRFBgbl$(D{wM*|N_A;QFz zB%+sUeE&r+ivnZM_u2T-`W!f$YfGeeYw}N7Sr!dZb6~|Y&wLfiGQ$$%A)8&HCrr|= z7(I{ZL%X%!{h@63(45-LHCCQSBdGYTJ`AHVETfFH4u4J^uHG9f#4r7;^($L_eT4rX zmo5(Bk9vttr|u_XSovlnV?uw-{q z*q-yAS&GmbovUIUaiU)8d`BnM2bd~s>7cNgGUqN{c8_AY#3pTKTBYL-FssNuV!+o+E5&} zf(br^pTW7R$71dh_?qe-nwA1svKbLH1du!)I!lxDO3@#mqh#kZ{VjyV(a$9JrKHml zC{PVkx*y4sM_x)u;9E}C6ntyqSBQ%IUK>ADpKsF0ttI@gn*78m$`y%;%FW(rl_8s( zD=};N@z66S>4jKVT*)rf7UqTCm95#``DgKrwOBk(Alc$$-5c_j5)!)L=y1*J0!c-+ z;rrH5Z-HcVy1Lictj}UuMK=Bl#UGxl-MmuCx|EPS9y(Q%us%jBl~}%x23H!@F9{~U z+u2t&cAb$wCuH-!S^DBqLXuqH?_DQx{J2hnZGIPKUf6&MzO;3Y#X0hMfU0y zHw!Odi+0| z|1j!-gV|14TnNi9r$tO0-3nCSMhoA_lC8CP(2Dn1ct)-Ff7l_Wg%MU^Zl}(95|I zlJ=P4>hFbrnO<$$*Ww=}u#8PtUph9!w9MTzVM9uer^bWv^HC%WWX%qTG_}qrwbEtf z>NC;&YmMq4HNS;9n6}mqrF^R7e-NdWjGw3_ETe_b|H#QdQ{3P_aIA&q**AI^WkqXPO2)4XS3u|^9)-3nyGR;>?-bNvvt!wkP*i~=N z_hMJGC&rOAxzffL2}JL>`S4~|>*U|Y3SQ6T-;B??G@SX0Q5p~-MBQ^$XJanR!;MU^ z##;3zOGbOA!#N(xszs0w|HFQb=H!#VNl5jIrjJRzP7JKH6|i*0{}#mnXv*S8EWCSd z{uz^WN=WB18=u>liGKgx$YunhNl~D4WV+d;#$1g3TQ(Ytl^qXZa=m+JmG zc^}Ho0o|p^&0TM_Vo($rvumkqMzc(h=Oe)fFDMv0Tw|^bsMVYTYY>}-sZ9!c*N zj2TZYvtx2l2ZauvxSONjQy@AX>Q!rhLMv62s~k#Rn^B!ntGY$W`Ufjx)!MR*{H#)N zIGT>V3+9RRuUa5FjwzUm`9As)hRxhhYM1FG>(u7MokZsh+50~)EYOUW|d7PeRht|!0YskO| z*?TImL(EU1_e@f54ds_lyV&(}{2$1xC?^!WpVIsHG2GdKb!B!HNwK)WmpF)?^I-k}`gUeMVO5Pfy=AIa- z=A504ueBPC+#K^c>)lv7uN%FNJr!_7!&g|^$QsN31pWR2_HIizIGB+YR8{WlWv-aB z#>f|h&2_5?$@cnz9jDbr8#AQSWolO}xZW&H3A3--^0(XBck^?O8KmdOlHlf|12Ig> zKkjCqG&79B4b^zxrfz;qeK_rPf=)kJM6g?pV?e?v{W;!V)ROP8$nQsxo4}H(i=M1O zfK!Sw5?vHnGUI--WL*cD)UOCj){)PKDEaSZp_>{<^6j(mD{J%5qJ=5n<@;^Cq#?(u zk)JBzD{D=st^9gn$aHS@PGb%t5)%EjZXR6Y zsU<_EE^4T?Kckg;m$RWt?h2#+6NQk#<=59*^<>iBiS_l_Sg0+7-r!dVnSAf$-DB<# zb$n}p!{@`2nZzQhP)YBYbFvY&h5YAR`DGUNUc{R7XUdXYH~HFsbTDM@qD>j{n`N4C zEQrXtA*}ghb*~+E_S1Yb1{dBb5H;KQfhs!T=k5frZ)VuNB3$ErCzF3#=~x*~J8YE9 zGk}8k%vDXOahDpUug9CVh7ER$^xB;60+GAuNm2L5`uk%Pw~uALPKbJ3Y)b!8Aj&CF zjZ+HW$&x-1c@R{ywYKn2lQcMnK$<^`5xVtWsOI?+ntx*X(aQD-Ms_#5vcZA^^Vj9r zsn1>Xu}QkLrtr!Q`9QR9ROUN!;RoIL&3m$LwX*jWJR*DS<_SY~ zP#ChILN(>-!N+3=njFJz7|#LUH$6dNSwRgUO1NPtr$3{WdzbTBN=}Q>vL{N6xP#qL zYcm@8n3zAi-ik#*kBam!iRdiW_ldcnn#)lG2%Ay!*F&KdZSi<8r{&p4YK0hO>mkTi9laNR+ zRT2px={AGOv%!Z> zmO%G3>DN)50WgBqSybS{Ae1`N-j#wKa5t zuPecz_h{_!)u5v%^OB(sF-xwKr+1Out0(ZdE!boYW~NIq)DT! zFl2oN64a9u7>*3*@@939 z20KQ_d{=JlI5NBl8R?c9`%?+ayDqk^*7<>4bVwvGn6F_XHS$}0%sFKkkZh?Vy9Sj! zBvf*`+MN(g_@Ty(aC+#gT0CoxF*d%8Wa7cbc-hMfg(Vx_iR9-n-=ySkG^&qQ=L;n4 zM6KO!l-gp2z1s~~I1u#Dz-2$S-5|nMS@p8cclD z$|qUa<&nY{|7FQS4F*`UXwgj>*c(`VS1f-G$p&$H-v{j~Up(`qK^ifZbOA)^)yM<+ zIf3X}Cx5WU_gbcXK_vweKvX*en&AC&ReNjxkE!pDZ=(MH@4er5+2fLHk|vint7+Pd z4q7Nn5NMm0LMhPZ?lRhfpx{7;qNpW+>?KR~7LX+%Zb8I>15r^FR0PEdDn$hm1nKYf zKH>NIJ|6y2Lz^4V_iI02ua~12OD`948^+k(9PMlZUmGAw#|nOngFN(v%Hl%7=|lP# z3h)C}j&hUYk2v^Bwj3{7FKe<(jR9ef??q_8On3}tda0bqI$*($(V1XuK9nK43PWDx zx@Xvd(AZLd=y)}hWnu-tnCL44k>8VcbVKr;WQtytA=(1=zl?A}@QPfNYO;VPgCG$8 zx4yUXsEm;&X6`qZ1+jq-YgGmM1bCvhS_@i1zK(~5#0Mt_WT}Y}hz@Azt5IgLkiCdZ z#enFEqihH#tacXf6urOB%Q|PKs~d>F|F8@Zm9|6p=RBp$i{&9Pn%PdwGrSqx;6~4h zcEIRp%(G@PmLS1g<7;obyI{GR-rn1IQ1n59IkOQU$=_wA20ny;Hqzy?ahYque)2ii z@aRr~0%GBZlJ|Wr4|O#7@MD%VS}YTu(b0A&h_$lRpnb%VKnFX%^VJVSqGvg2CJk}u#a@?=7 zDw(|<;O@8^u=9dgZ`M#t0?EXJ zEP*+o$p*sGaly5UO%s#5Zcb2X!vhi)d5IW+XaGp=mzxe|+=ApsG5d3!Z)zSgPI802 z|4&L<+~}NWAIakQAkR~ia0`dl)cEec_CJ?w-_IscWQz*ct8r_E@?X(A)lAn8A};|Z z)ITOLZD9X}I`ALS`&kq5Dhm*^iReH_;q3yoGz**J5MX+&^|mW9)#oh633x7&WVXj0 z6)f``goT191TQ=OA54o1n#i!Ao(t{hN5L6DhUW|Lt}38oDw-1Hg_n4#D}onb`mr(R zy%}zRDLp#j_L}jpvg`c51^qP2pjRpm$v6RZwM8x$^mU-K<5a+q<>9~`SyXTySWNP3 z{|W@$Zih>g|N$}qwC zw*lp`jpQKsCms0QSeJ~`qJnM&C+~tNb56)zMN*US*1QTEzAusKC$2Ndp#Enwp49-} z1D-9zWVB;iavs-t2IZllQ3ha|Ne0;9kr38Nmb+QpX^?B^Bs`Qu`)a)HZCeU9tJ8Q= zh0-CpW|?X0ApF)8;{hw`Etvi=;zAPs0TlwL8p#=f)~EpjwH!(@anE6`=js3pC#XMz zE*Z%>U$BgTQcRo&NDQLSCAfkdO-pdgAURuZO3rdSVnl}@>E9{9Z&bOV>_3IHAg67e zyhty4Pw1J!v1~Lo=T#0bOSpYzY?SigvL9LSccV;NCG*-XNG1vpW!V~tz2pBj052Q1 zENvefWj1`8poScC1A!!s$HyGP z82#Xz1}3yr1odwN@|I2{kgRjyx5rv#NVXKff!(L^u8Jxc(Y=9H42V$|=Y&9;txH(l zEd6C2Jdg3589JqjGMOhsVzpzJ{Bu#2q1a&CM0X@$dM+P=m3*X ztK7g^-kTsVw~v>Kh#)5Pkf^Ks#Q9iu3zA-v4G zs!FnsX7S}p-OOm-Fj9&c&R+kYHXBiw3EJ$Vf{ki)xVOGZ@_^@jexQ0w)Cm&>3dfl) z8}WGg$$+i0oEV&NkVoIm!a$RHBo016Xy*W~m!JcwnIZRv0u>`YBhEwdCn~xG!P$YM zpCe>T!04l!7(w#4y9g^G3~dGYT$QIMnME)R-bTKcsuKN>1DHVCa$TUw&Lq4AW}GSa z8=oM_Op95mP?y3F9PH()k-+n{B^_vHRC|>O0rZxA1fFwRe^^$1*I?3&;QNdTas;E$ z{!IL@{3QDc*WWdb`~_SV-`QKaChmhDcE%i=#$*q)qDRI+kr@mQ@d1GD&_^V}%ytKQ zcdSF^`hQe#LSSCic>6|`qUe5#rB}r)J7;#!w4t98RzIBo?REACCu+}{@!~4tAgz-z z%CX~N5`RLM3vL-vbtYOIL9|d0HySNvjRFf@4>DFZf&+yOken&lq{gdz>mQYJL6P+% zGY5vfWu;2T+5ZJ928q<6?v7s}5o|~vB#d9kf+y4=;6x=m+Bhr)Jiq z&}$qvCv$_)5jq%-FFr-;{?NG0+*S&|%mHiV9!b`JFwgdnX6?TQynHw;jX6{Bvq|}) zEH)T&TY~Q^CWH#nUvpf*Ld%wjad{^fN{OzyL~2N^aer^+e%ZLZO^%NHziE>-L~6iR z+J=JumLYl8ftQVgMbZ zh59MU2~yHRAmQG%Qa_E$ybgV2B;>$*Ecj4b&MFj;E8v3!lfZ}CqPqqd9~2Z{v(TUG zh0nL-Q18XF2C>XzqHng~D&+9U26&|a$zK2ovG>o~(Ks<1*fAMFoEgpTW1?5ckaX}; z(?tI#dgf9?*AJ%J_i?yO(hZQDt^=PGpSB=tx>*So%$O`DCP=0dOl&Y>u&y}-kZc_e z70ka1E}Ime%3~LyZg#KWJHh1V6yhJ|7=hwcEkp7}E^38Bt${w)SkOAh@@Q}6xj3<2 z-^Q}a=KDcPK!x>Hg=9#qu;l4sS&=>Oz%$b0K$C%A_E$lX2=?C9IciuUx;C=Rj+m?4 zwCrpf>XNiXSo~lefNTHVO#dT8vR8&AWXD@1=jS^2BQhjf=*AiW_m4Zf(Jl$vYJi30 zE*xVV!@;?yUi?3bZ0}AhNR2x9lscU^v_iRG%2{Nlr{2N{$bvMB+hmL&=MFP&;X7eU zy>|*eBt!I(wxII>^(sMmnuWTj2mWV=qp$>f|jpqV`B0*v+$jfH=cyafKh=s=SN-)W{ORERFmDmVbICNV&AQI?txu-st^eqV;<18pcgfPPw_zrXcsn{y~G;b>qL`$g|&!CAu5RU|h7 zkYwM4DI*47xZO!gk+@RX#l1cEC$BmcVv zmkVZ6!IY)OVZk3ufVBrf{xhi;NQenksHo(z(PImmrSUk5U-dO21xP} zB;@}!7p^b(<{20d>7-FC?5*sWfFH1h@Thz++Hk^XU4Ip54x-6m!^6umB=16iIWDuA zNKJO|0FfGZ_o)7;=-C9_zcKailfw}knw%u%j_Gx_X%ksU%lKqSUgJ^wcD|b(e=9jZ z)MfvXhcw`S=wKUU%JS&W>~3!KyOcSOr8iWV`wHQQi2VmhN`kA^kpUITe}MI2rk^9V zU+$=t${bfDLjo_1gd@f( zY@+imA*UNh4@uv|q~sRm=%#n6<>X`0YUbm%#I~O?047V#OdO5G%AFDGA;%F{k1rUF340 z*I+&XQ0dbR=(~ZMt&U8Q1TRAY{g+C}G6@fs572h^SH%JBF z2avd+W_wbGqNpr~x<6huR!3NSFD3`@XEWlNAPV?2XAsYyBSa_CypRcuxl z$3c_hbcPipAm1rasOc>#bNX!!lB^p@~-L@PjUydKK-D5l4I+FbpLUU#7n% zfh^rZa1nz8B<2l`@B1oMiR9V_Ov*uU4hlQkkSb;E!Qv!ICT0H$(F~!!+fuvo0;N`>N94y_XbmV1LM)xGYlP>qbcx0~@j z^=am@F`-Ya)Jixgw@Qr`?s%s4PPg@lstSuUv{rTb`ZdJIdiu z%3lJTA7oL1aftas7P!iLWk`Y++$2K+jniHsKpE+kG02wP8)VFiPl=_#We(&N-N%@G zfFyIOufaXwA4K2ROz_!4?3rXebqk`j5!zHm4;UPHK@%qP|Mph? zAY-&aFx@jTvl*ts+^+?(d2kSTO|}V;Ae7*?`Cp-#yont`49+BYwftcXM2DtPl6O0+ zI5ALhAj))w$y6z8FBY$nQ?PAjysVK^RcCz7qx#J`aXV3_CtwM;I)Gw=gEi4-W2O(c zct*L=y13;Lm}3>Qwg{oeIdn%1x|Ws%m#Z5S70TUl4=f1iEozRA@qK2cW{vU4K7bFN z@B<58ElUmXab6jVu4Un;L=8Z4y)PY=r3P+r+05WikYi3bT3C9#SF1m%#??!92SfRTeF8+ahLm*bt=f?lA>~}1t`*> zm-xRO_^u|!Frvto1izD*cQwrZD%B#%yOU+)G%9zy4b4wkqfi|tJUI-5z+Y`llR)q^ zk2-JSlLQkVVA3f7qkx|7f8vSq=6S7hL~T5WFU_wjYDd1G9}1cF0JbROki&zE|^pV!};b824@R%egrJ#g$CWlhO!Bhi`{*cwji$DnB9q^Dbm6XQnNpp**$wN-f00SVGF^u~Hm=2-0+4xdWpR>DLUIggdrTJcoD z1+MeaTViug)?~XKXpRuMZcvVo9e0tmUy;2&mR%zAJE>cP)H>8IYIM?m zKTE?Pm^VdNIn2qwnJGIOTt1lnd`Gt%(5))LG;GuB!HgzB5j7dQ%aHW*QeR1)Q+hgG zpN3Oc^c{z^O};8K{S_JVf=yPuS>VC`{~|+jJ4t2^10;d5yG;mFM#dZi<8m~pGK12G zH-urE+HTSP6%+WQ5H(KnL&@``3`s{ndQmJ`LR>Q7KDzq#Vdlt+EKhW7o|rcQa<)R+ z4AD$%kpA*^2MkI5LdHbL<5IyZi_KADT#jg%ja7=@CGT@A10Bu)NsSHZnlk&|3bn7B z@xO9J{vC|f+F+kx#|K2^B^~VuK$K;6nP@JCXKnO9;6|ZD)(mLI@1xlxlmjG94e6rx zwjYA))Mb!{xh(-L(0H_{EP0~ySEPdJ08M6UB2V}kgbM<^27Et{_D@89J6- z4)m4~Kt{!PjlhoiA*eB{o|dKLUI+EA2r+;7Vj(&;F#sb+uF81qizhy|QJPb7AWiR=M;9GI#9S!|L zm4c0X_5eGEkTtkU8|v7UB|}2q6UAWL7%M&K@TFV}rOEJM`nclrJ7Qujjkg^X;*mA30!5 zxCWY;@p29lAo^O!fl1g@83Cu_7DOL7fGd`tVN}2<;`Sp~g0HjM!6c5w4?EC#G41)B zDZ5gLHcTwnS+KW(7#k3q^P+#bf$lxXkw2+)K_B`DdAj%*QW4CXVntVDnIJV^4AQRL z$}h6uY!XTFIXu1=%aNt#N-#SCii|!`#dH84mR0;h%H3SG4c*;j`~MJWIVfAFiAwv4 zM;F$5XW6kuQvRspy9Cf*K&ms*onm;>`rte_8lT9V!P4jI`13-yX&hS6P}bh23$0Rj znGRlZBKLhWf&4&gRru{Qya<9_pUC=QzBm$t{@a!*cP|ZpD`b7f8(|S!$|oL2}%IE(rw;*|wDiOmv~S ztj;XY@tWm8S}FG=Q*x#d<)rh?7BH*?lCFMamfWihG(X6GU{d~)KD3FnC-IWWgMgO|-(?cxuIE|B6(M`xn1a4w{}(r9 zf=~9E9FnsfZY1mu{2PzXukkFjLxNlRht6paAg!3`Gtt#C+nwwDi`{5r!ZMR(-m7ye z#LhE0w7a2Wdz(A7Qk_4mLb)s9g83S>pg7)I_Pv!_2WFjBnPo`6vEch;DUmDIxC`)a zO5@rewDuQk=&+>ulcl*qB=1|{qOwwsR+fH9%)U)>b>-*@WT+x&GIt0@uJwDm9MDL{ zfmCLi83OS`A4CK%c* zVk~74|7UQGw{ZC$-ad4}ke!YIi#v2LtLY%avfP1!lJ_(d`LYm|r2Wu>^neUYE$nTP zJZp)8F_cg0_;??>bBfsf-Gp{lI>(B01zWue*ALd#Z{dN3GMv~qz5|a-gxnFtEpw*< z7v^IP{Y91Pk+|nMR{3B(_t==8Q5(1m#8rNX*c%M6JP;$2@;i_IS)IEAn%*VFKRQ=! z0EHoeYoeuS)`+!%C2n*mVVT3y+v^;qB6!MZSk(2$|50XRi+!NX%0dg(%Iy`(V+q&c zv>A7kl#jO-{b;2|Mg0m^y+xjXdCGzplCjWuE{{e>osgd!5Z7MRx<=Iy58)Ef2?tts zL@m`Ws!u9w5=+k&9g^hf!O`8pIEwoiX#*1dg z{nyg^>?i7T8ic$y4*lHZZ89^D%RI4MD-aOCb*4MZ+6*d-02KV?&kmFi&16RNeNj{U zk+M(=tG*ylon7ic)e^X6k-rPk?5N#sK~EA79k;;1P|3F*BGQ45RnhEOedv+0YdUS_*I3Y$TNqUc&fx^3GJr_+iH3f!idh}^>|<43NI|jNARGFn zNnZ)=82_1G4lf|x2>3FOG^=yg+wnn3c}?e86hKkvh=NYhCgMN_9sfYy0r_tQ(Pp+< z*}z=Uf}*pIkTjspY6Nda#^9t2jZWDCl4YWMvgGc?;axI)wEa|dC|l%z-qbOdK!Tmf z{6Y|=Q$lGC$+p_4r;T7>cE|It>vQ{y#n20SiG#4hJe zueXEzm96iC7m)4GIFm#zrE{&QS+IcE1S)lqT0Zh(z)H$#6byrd|69nV3Tnn+EC6Dd~(cH8lEhjVCQYp_o117Qc!G~=>1EEgl6>@ zVsMV}cNTn1X0ESuTs zlIidPfkazqA^TUzEdnM_NWSd`{8Bx^x_6m!Un(Dd=p;ij&kBmj3NgRFL2G%+y_wXq zYXOo<9*+{dBZ+}YhF)pVf2%RRQ>FMZ?m56J$BIy6<>EGEZPY;U0xB9v%T5@yBHI^@ z6K!8!@`62$`M474eT@M;Q*`8+@GlMCd8>k3-KbB}25f;rb^KznXf`Bm8#*n|7=+6= zfC>L*degE8{h-N4hc>9Gi4~fhl+fMH__xNKLxg2P2Z^*Q~=QfEt*=VW8kMm+S=MOM6+K;-_pL1WmMvz*vH{tWQ@#CM6W1%!w#K23QC{T5ivMj9;@dxWkQxCN0}ox>KEHj|f|)kfO0ed)w5|RyB33Lib?O`w1iy1jSwHg6meQ zxyk;Gkt>&n_+5hJw@7YpE05A#iW*_ZH3{uCt>0Ut_*9}nlUdvkax_Hr1@n#AR# zdN1eShk5BlYCJOo=q-^Co3NrWuysZ7IX9Y@wC@JqL~r&(vC|VUf}ydny=^&xZBi}&P1ESMtvU3Ic!W@n+I#)wl2dsY?0jGOFZ%kCSZflNNC%&nzzV=d3=?n zUle@s!+aOYZL&`x)v<2ZCHEi>zh6%@Z~Lj`p%bFz)%D$gD>*{~>IyJffhy~Y5lG-S zN~XiGvIIy8XqU`)go58Wbh6obuQ{z;PFT;l%!*$ZJ)p@RFGDkyhA=kN{iq*I4oV5bn`L zT(ZBVn~)q7tUXkbMAZ1_x}1Ho{v%>Cl!pM^+!qH2{V0JP%lq+RNAQ1vB+Ly<^ox4 zuE7v@86qfS{~QZXu%lxM?cZAbdbLI$$A7c*2^pg0E>zz{qz3LeC+=?KXxWDah<1j4 z68Wv`deu9i=G+E^svpG?&dAgb0*H2oU{K`L<$kYIe^9u)v8PUh4ST z4*X$dhF*Oytjm*fA|~9aF+Y7~S#YNt{gAW+MpycKSgB|phiV#u>whrxjGDrg>WfML z7iQWaLT2Q45Sxp!&>AD0Xd(_!JRBoyve&^ckL6FX<9`ym3>|)>TH86UxW)pI%%DC%Jj;BS3O69WqF|XV!LZbfD`Jaw7I}5Mwbc5V67Q*O%PoMNcIB zv;o+q&MQKfzc|#Z#lMqPliB59ovj#4UMR!7QwI8!n{L5fWJrp67<5#WWn^3gl7k>M z$}h=2=-@sFRTlRGVfk1g&}8%aTS)&IxfF=aZSmX}4RqgnM}bgqPe{2|hU974O0GJbad_!=KAT#6-hN4x5vl{FR?gS z=k6etg4l?S!1ezuv|UX(E7gIN=PNTEB#>|_8${&cX-3oYa$Kpj0^tu{HwI#X0}42H zG&rei*P@quo25AZmu2piNB`}1p)F00No<;k$sO^WksKa&lY04CsG!RH`kEfY98`xm z^ud|F5275=C7GDwD%0+DrK7#*69JA^#A5AEql|Ax}|I{5>M`qTB*}A4&C4A`|*F8tZ8?45ER*2Vr+^kwf$2* z=up2yhDdLt@`T7tA~odT7_4}YEH%f#{uc^9$TGavsG)TD*=pkhaRei4r^^_<>Ox;M zIbgub1i>;V?!KGDQ^~0Zu{j&cYRG(f^=>e(&0nL0)t+ z;iG|5S?8<~%PxZRd4xmTTA&sMSPX-EsI=nSB~PX@O<(8;r=Cri zd9v3rHyW0*KF{K3dvjx?&{7V~YXq+UHDX_SSE?UOdA^6H0kYnRGufz$w9sLZF|(wS zK$B_3CuGrqdR&#@1;+mVr0#|mZLT(~jw_*?ph_NO@SzLonlsZZ^K;C)E$+F8!|QLt zaxK)e!SLp)+r~Ml8F6A@BH@gfn4d7w+Xw5PThrklFG5K_*q3yj>mD%xZrO=+i+>NR zxGab8Rb;4<3ugQkb)vd1&R=Cg-^k0efgLhj%6A)K0~bJYEi{hUV0aTHUpfG~;a@TN zj~An%LOw*KUKx@;u#G}eykvm#d}y2y(ucJ9^5Ee2h=iAJvtnpcg?7J*QJpQl%J;bi zMMyU=zmkVPaE>CPb1l@l348$kD^(gxGWRRc8WMH1HFum1{nld5VRdT4XTg3BE+ zQC}y@TI|6N{CPsj=y7uZJt$=tn;1dx+_j|q3pbjZ$^yxGskdgn6k5qqn~5?rhPSIx zdU&N~W6J+C?5vCvOgI}Q36WJsQ;`gb#fse$sgt#l&ZWFfc6=kL!#cdIT6-|ASDENL zMKAp8r!G|740CTllXFMop8GiZjhm1d!@XL}r&mT{gVt+tG zey1K7vc~Xu0tuM3@DC)nz<I9q8cQHChNm|v&XEkJpi-j}rpx7MFeJ zMz5x9FR*m_hj{rjQt<}J5H@<|p#SfeH6>3(K%4o(yVOXiRDF>0K)- zra_ze!mTab*%h}GUIUx<^kb5qHqzRtIox{Nqc#*9VmWVwx1}7llPlz4 zcm&Du#+_(ddZC|n;GRh(*5gS5^rqwn*Lk|&J-FyL*vI}|%C?8axWXfo8D_#}d|3V8|AN6yr;@QEOeRkr3R{XZ)hMh4xJ5h%g_<^wd z7-`bAB_NoQ3jIcU3Xz)f@I+Rb_L61sg}=*~oM3`=MKFB9uQ$8*%JP4kABk}We1Mgr z?`QpNG$V6NuE5hyBfp-!!y7 zs+ybhU1k-Z2<-lJ`E(naJH&dzs7?0};G4|F5Y5OvpMn!_To80P@YE#HWSax%dkJ>s z(9a02e-@UXb0bHS^%>a*_*v?-heQ7~mbACkf|R&BmT3Y_j*GYE$9ZhjGeYSzM(ZkB zO1xG)N1j%rbwX2X;TcnSe~Kuw^u%g?UIH0Rc%(@3P{&OE_nMs#v*fIFO?XCfv_r1A zwx6m6NK7TmyDo50u>=L9L$3rgj)>tV6CH`sf34`)$BT9*{eSBjXPy1DnBNW!RlT*( zvda3w#I_}^Fonqj!OIh!P-!glH4EA$Ly{iGqi>}`5R*IWA$wUHp3Eu^ir`>HuE>y_ zWb*5a@L?fOVfG%ESFlw2(e60&9Lf1R-xZ2KH(4(<=ff4gj1eh$1)vvU0#)RXsD8{c z_pdPCM~3809v>B5QwSur;g)8_c@41O=@*k}{}q;Ti-u>@HFIp}z!2-3Mh#Gg4cm=C z*sdV#GCb6Yzk0&!hf#=0NWjs{0*H=hcZ3n2g1=;8&o(#e*<_O;0Y+)z^Bm%1MMe03 zitL3yi$Re!hj*x56GF^@rfgWg3*QRI+-;-YP78(mjMhP9G$f8#>67xf8iy0TC*=NY z3THHd{fA#Q#uC^Fqj(39`#ELG{ihi?xo~bdG2sPGb{lCh2B~QdH#bIdm-SfbKuZ(U z^E3vCeiJ)1nV4aX9^HzLU~4{2=3mq^zw~$C5Ch6gv?1MF{Q~I=HvYK{FhZ)hA2wh< z+X+3_m2;$ z&0!cX+@`_dDD!>N`wz=xiIzd>in%tlwMM(msA(m&5pze59wxKPCOeVhiGqLwt5OhP z(mMhuk3htHE9Ax&bh!rOeKL&CkcgZqjfeJgRQDKU%EpB^sdLktN_CGkSzr=B+#kF| zuZ{Xz=u zEw;KGhm@_%#GXFd7g*&qq8Biby?k*GOu{_e30F0m-m}0KW%x_mgFFm63Kke?8!;~9 z!cV|*iYnclwIy0on*ieym|KKy2!WXvTwMi!fT7DklOT$0MlAQL(BW&7qhAY=nzTV~ zCO=@sD#-zpN`8py*FEV0vUEp6sNmn{VW5$78i8aS$bYvB8eA1su_^C0mMN4oWs7X+ zjvD=9qjoQ`{~XkAC&`e^b5i~1=XQW;XDLu*>gNKeGVX>MZGQ^BgeL;T?0aIq7f zF!xVWe)lQ|Kq6La)+IC!$i)dcPqqdwn2LH=aidv7hnROy!abIw$I3=h9Stc(j?PjGf$T|PsPV68t%W&xRyQamXs(}EE-6r5OWveEV z&)1||_<^h;9&;a0xW)nRk2HpX*sKgc6jHvlxMhz6bx-0KXyuPV)K3b6CYuscKC-m; zKrgCF<^Q7hY!S^cp~sksSJqmL zDxm$X3@>I?X-9*3@#<0^kA^ldrtawT+ZEoU?qCd=6wO&Gj?NcA;JFeTRV)^qHkvocE?EyN z?khvm=tNz_{J-o-)vO0d()U*@&nIxM2{%Z2AGCr>82(<1y#s4j3D$oSJ`kIIWM2+I zvMYRFNOx>;|AP+du_StxR$dNfjFG%UU8i?IbIWp-bke1oH~aYOJ#ih4gfR@)uc~Bm-lpJa`y zymLd?zBs72;-fMwCwM$U%AP}D*%h8B!!kTw$t+I!U>xjbxm>o^hNgwotBsm4fhD_! zqtD82(QYSN9byCrzL8R1*ZIB(pl9Qr-X^+H%&ni-$KpW+%{Cx)qJA(Fu>1f=y&QuU z%s0ck)d4DGDsMIzZ%Im_jcO2sXN{~NOG;JRinqmxHUlpM1|h*Hz4~U|buAuSt>%(+ z2ePTk{#vW&HaBi>aXMIwN#MLm&jgO{R|hWwV0jaC!0@Y!YTkpYRT2!0;%bnZEBOHy z`22$0@eD99cZks6|7LhKtL)#BxpQSFXx};Bp!k-F_=_Pl3~aLC-y5`W|B%4^QHJD! zI@?qz#N{jbAp!WjCJ7Q<`l%I9mn?l$=7*xX9*ex0R&-H@{XJ2NoF;Hh7;C#pl!}fB@H^y{7XQKNagTf&QOcHa)i^D6`{fh-QLLGdHr?VY-D; zM;mpw7`|v^XLgmTFpzweX^wX}@dU9Ti$vIg>xAo{**&S~Xu?%=PbPTnqP|Cg@RdZ*(h4q=v0L(wAP}W(7Z&#_fg*FNpiS>S z6EB5cP{7DjYXpqUjmD8r;l~L?7?zZo%JJQ`_Ma^H>jp4{wk16JI-U_UGLs2J$HSXg z)$|tg!4(~Q^3>G^1xQU^F$F6HG`t5E^D4! zqPwKkw^nOMB-Q06{DqM7UTb!v8x0@gJZA(^)=WrxALU>~-+!d#b77R^s}|OLmUf`x z6u|^24ev>=VKP0&vG{iI0sc(|f7QFxiNceTD=!mO^;N&lDo@LYeZG8s@Bw<4<5PXD zIx~b$L~7Ra@Pq`C4WhIC$hq)lR{dIw>HFm!>v$^CNFeD^jGqznVZiw-G9*IUk2)ur z17uh;`F;4uvm=}_ze+G4 z#bq5Dcr>I@nLf!B^eM(4i~ju*} zTeq_6_P(m>L}%zcEf>mN%>OjmOAE_ElbIvC)R7NN<(Hc|%m0DseKBlgAptlXuG4JA zPs={Q15W&@m#2aM6p~BA3Bojk}&8nKE;vM~x100C%TD`2HsE`CAxmv!Q;~xT%{^3Lq%!H9$y=$7m{uf*i;CmCUMiUI?&E7n#|5v6WZ;O2ssT4TJB?=*! zi4m#Ei|kbweQN3%Zh_fh=&l$XP_CPe`d%#JSi=``$bSde|6#KIf5-_#ko?uqJ>O`& zs&(zDroTwi6((FIx?9p&hfJ+8X!m46J%#o#CM)K6Vjo^|Mip3Bb<{c(HmtpV~@A%Q%NyT9U z-A~N(NJY2j|JRLx`9T`RR{vj+q>Wn#tC&=^F2B*##flgKFWFkCNIT&la+VNHmKS-u zM*pjZo?WKg(3E?DREmh$ykJA0L=8ucy81Fx-r5|1KP2<-jPa(I4L1u2LsNQl|q;n9i&RccgxSqG4G zjqGPti-(wJRvE_g)I}mC`H5l}5fnH|f){fCr~SaVVvZOTQ^fqSpHH~%Gyx0O-D74yP(t9J zBv|cheN}HIilHF5Na&J2^nWzjM${EFSzY8sHF0X^wy0`MiXu{);_7UaODfD`wX;L2 zX;m3x;GM)se&$Ihj!5~#9B4s^x}tTJR$B8@npzVSGr&q<;Nvc+(LP~>tUFhm@;%AX zM{hz@7rFZmwsBsSDa}*9MrIGKd^?o!NW5S?XtG*m;EB$F(Kk(@fAvfNk|=S1aVDBn zt^bNuUK>oR=NqjkKp?`?%hBnYOwNk)27{|;JI{dhSQTKL>Wgt;3G^v-(jXA~g?M@p)O1t#HC#oxITw z^hk)kPG6W&f*x9!Pmtfc^iQ6azqPhDHX&^@~Hu$x}O; zsJ*meUYJ@N&ucX)+H2uB4~Oa{+YF>~unohXj)wq}t<{=uS>;f92Z0YQ(1 zv}<5bF7*1Pm`_RjrS>tY7#dV3hd{H#GiU7IR6yJC>^M`WVh&d87KQYUuoI+#?zy?x z?!+77+)@I`(8#8Kn)4b(pAcQx?EaG&GxEX?+0fHb%~_*veAHC4DhHB;C`l3f&w<$F z(=R%3ss-x)riy&rp77oe^jImkZF;{4J?QtAtbEouy|2QYEIi7g&jsN6j|Y3N?iAKu zYjF&|1<61gH9`s&vD%?gQu71d?oASxY?Tv_l6=#MOE&zv*40vp=cK4gAQHxX10bG=vVsBNI(bZC~Zgc~uX1 zQC9+qqA*T<9M217;_s_<-?7S04Z7P`;oVlWlt>BlemPdxvOp<+VK50?pxwlfqVy074=MKRE1fzBmBhYdh93U~a)lNeM0`X~==O({P$Kv?Ks zEtNpK-GaWLLE$&>ny2#hHu3{V3QuCDF|0m5@)TE%IBlXQM9yszVMuy+x(cD~j@QhoomLtoIb$ z71NVrJjgx7ZXmu@cIRY=qa5{@P;{^2e{PxTzV4vRW=CFDqthW>;SgKnEtnc?)NCnO z!s?!mvg!Oqc&Zhr4tjDZgTFyXyY0EqF+;;PF_FqenkO({MxFh9m4`=khfHkj<}0@``@;*AAn z86uFJoErVKT9sr)-!_=i&ZkO>ocM>hc?l7n*^!gghBF$M+H9KHoO_S_!>X}l*)nwOfrZLD^r49TZZ_pjEdSi_R8hPlhLA$L0} z`Tv-@?(ite?VbI;nc3MkWqXp{P1%x7HrY)j+Y)-VB`A_KZ4{ zgr%*tTt#F$@w|rAIFC=(*naJ8x;G6iY}J3ps#Zkt{SA31H3G`3g%!-5IlEx%|> z@{@>s+9KP#y!~nw|Bs4Ftw|`V&wy0Uz)6`To!m46uWAuv!s1w9_ZbQkP!7$%SwEM138+gjfY1Xevzehu?Z-BoFc9>C0kM&zI=35yRk>SLT zH>CH8=j}2k3cZu>Nka!(jc>8a=cD-L2G4mI#ncw_(*Jp~V)Y2{WQTHIkl|_Bs&A@r z4NtYyNJ_Tn%`iy5pOh2e6lX&GuT_$V_4xP%D2C0@F8yhe6P8n74D*AEwCOG)*o1~4 z5?{CPQ_;O)`Kzq<3i!W@rt}>!Y5fmIhjLCv*?$&{{FYCDyBUi)fD28mFI)^HxR~OR zg~79YI&J|qM(X|139a>+J}qtzYkn6q=j=+*bqdJmVFq}0>`Ya$^llxn?U?X zGL|JX#sPupP|gXCPMe}#yfknmSpX#fz$j~49@5r1f6<}Rdg{Ryc$@>ZHW4R9jBt8g z-d}dg9Tq*=x!RQY!&%P%KtwEysHQA%Sk=zgYiYd6e}f5E)h9h7LUbr+cU19>JmVy< zH@Bo866fh6MCU*mD@qwS#t_y%|A2LlMj+lC+WB^yQCD~7-${6KRVp`RHXlLd&BOS_ z@qAAUKy+JG(sQh8UzGTwq40AJnq3PG=2JPZ$nc_UJhO_f=c$`(B#v$QvkXA`b&up2 zXP5_KofkDl)Dbb%v;ibW6Z)iqghwPt)k4jGD(5su zw@%USTjB>Gz8#2Q#>y)`2v%KdO3= zRbGlhSvc%V4SG<7 z4_)Qc%gS_n3G#jy+F0*e4Ox6S9Ud6<4R0G+rcyI}cC~&-ecA{uu8QcOp?+7Z{KeJy zBRyOwhfJ9?dC`4Bgc)k4ioqq-gd~krj3sXnTV%Jg?fNyGzA=-kdViz=mw!5F}N!?4O8I9i?G!xui_@ z&xU-MbUa?4{G`Yuznla4NAe}P`zu~oQ>Ja>IGeavrTG!mNn>;l$6pF*XO$%Z{W!Hc z6MnGQjKWEHPO@#6*e8qmZ#XE~>QJ}kQ8(Q5Tqjgnbg(+-+ifQi->fX%9EiL7qsdg>nEVrlFTZ@-wVziBjNsN#-uG(_E-WJlLpTio&(+gbWhO&gSdi1Mk zHe`wynW9Xk9z)>^5M`TCQKPY(C8yVdDu%>;fsXzEf#xjZI?zP53qhTf11 z9l~SvmM2BCk+}IN{k=SYnM<{|#SV@oG}OqtYCvPlDKDqK)uocH3O~V9l|yImgJ$$Z zr#(Fx3ob>XiWug^;~LYuc;Zm4^>|kcK-BAESF=ztDw-Q}euDUaUNjq>8_edzY;L(r zHAQSD;-?-P)&o4hy6hOI+#TkYx|I9$IJrp@dt7(agyz=SeoR7p!g7FQW|^+PQsRS4 zEj5sO;jA?DTuAu^o75B1FwN<^G{nhzD9r&9om(3uy?rC*Buids5##@ZE__+2cWmX! z`4!Y>{r>OM(Yq}+jsd@ybiF<^ti?=(C3*T*mx5n~zl4&a2AieiNPwi%HbIZ>5DQ;J zz6sSgrrf}i4~Ro$o%?%6u#NCZ) z5dWX8brc9)4ZG6NfQ#A0vJ=LtmNe%74!eFLB$@7)WyD}Mw0Pw(sq&9yw?3K&+v>1* zSi#9Z3UjMm^4Er%ha(;$;_xnl#=tbU38E#3r7A z#&@&rWetHvaw|ZR=@!VK%I1{76!>xrw8}{6nFHbX890X=R1E76U@IDI$<#9=Xa=n!gMZ zdypvSxN{**+lq|sJUL>h(hHl>EFrTLtOPt(l1kU$#9JF7CzHQgm$|01;VIFRwQq$f z@mS^VMp$tG2|ZsU{lAp#t=C3_Co6I9k>R8qu$T6mhl0(5Ek&IoM0g^nEERLg_BX}9 ziKOV!v@cB{e&l46aYt09P~vrdMOcJLpl=iB@VGV&tqU*7-A++YVuUE0zO#>7fMRpS2^j-S|;Ygq#B>C z)O|t90i%m`;u!Mlm@<8-{2yL&u~H5Y#Tq0()_Ech^1dO6pe^;nIw&=d<<$(qR813C zqN;Hb9avNlFf z;M9=Fu3Vn=0#D5x!YOJ-KgXTpl2JUY$W*cAPW*mjYCkW(Q0F8%o8L%7C&Th*SY}g< zxY+2qrUBX;v}VS;_sXy#hZu+`XNZ3#;;u)$%M4(lxRO)mM3~xz_-|ghsS+8sqzONp z@V9l&losBRhLRxhZ#?*1yK{88?BF&oHehIiS-nu(Gxw&!t1^hT7unPXDJn$&8|UeLOnDB1cX zt~H}09kv|y!zPahv1@{_@tH?zk#cjI)Qt1$GsYyN zmY7_t#7Ft`i=sD!dO-Ak8`2OPmT9@F(BGusV8_wVkJdy^$|suWPn z2xnX%fRynvIOb+@V{dSj6`g8zI+(;g;*nrY*xV16(TvZ$^FO zMPoZM=D@C*xY2C59Y|G8d5t1OaHMp$8^Zd<7@Dm+^Itt)q$W~Ou0V7yr2i}U*?=O!DmhA z)rOQ^B1GaRNxmXaekL0)tXv*IG=_*5&AHz4u*`=oAPLwt&3)JKR`n2T+l>F zxs|7G389-FE_fKY{?(FZPIWrMS1!Q+@R^ru32IZK!Hmb(TjA2?(Wop@NqowiwJnl8 zoT76`mE*ZIWDm=dIMaI}KD#CT0}ZjTTC^Hr@a+BYNj%Nn!w)1&W>x8*CCJMzD01xp z$>wHC((9|WO1i4jG8oHy;|;$xq%>&J8`B-hywo#AUa}NJzrict`p?PUQ}BB~|*pJefKn`Q~kSmKiPU5HdmFMG>X* zRMZY9zP|~A3&BkyBk?wzjxr)LDF1-Rw4%u+*P`3%p;NZW{fHe>MWyf z-Ixzk>ldmeEgbhzgnO_bOVr85W$m(u)2z@`s84T6M!gksn^Jy(H-%d8B2KQZw!xzv zP6J|nLpni1`%0?GF`ghG_O-}$I z`7*+1FyN{U#>TYCT6AYe2|&_0MRv~;tTo_X(MrhcUi@%JQ4bJyqaq{&CbYiEIhn-= zYN^2^o7{4q;)Q1Q7n!o}`Q%|`n)4)aHV>}PILE+fvRs^+e8XEumL>ng;Lj&$x7Rz4 zIjHIg17E+dm785=xaYrC@@`D!?aCiYb-?^p$Dq~Gn7U7dWRrV!2mgnh%n8e`RO*+p z+!HmDwyk+Kqhw`=bpgj87JzwKWqh5do~vO4PvE#2ecs_-mki+EP^=<0Iq^$PVu5*2 zE%`{iEioO<45>b4)g#IbZ#3lsBx~wD+y3LpL`U{oZx|fe3-0|g$C)hR;ZpV%o+>Pp zPTx@Qf&rw&03v2^sMYuFP^zlhm?5~#_=$RFdop@EqA)7CZ+Nw)ETNfG64h4tpr_N& zU12txOS~z>&nN>GSdg;&7or#3vn!;IuHh$>(Z;B14?(K3vA59%5EZqMuXX#bS<$YD zK2@yE6Gt~@PuJo%J4V`g>HaCQj~3&gTJ=mVN|aJUf)D@Fk-I>TFGR#4^J)`1+LYAB z;?^3tQuYF1B(0dl?Z^aMZHNEBY*0Rat=?G5dYtDAF5!xJBMFNmfY)70wk7f+}fD-Dz8}FLRq`L!)>U?#TJU2E6H~? znrCQHR$K_=icw3t#g*VNpr420zuAWi;`vMTs9XF?8n&Cz<)&PaLq1UrowB#wp!`h* z#ni7E7?5=|#D7yh`ldbuww|=Xe`5%6c2ikX6f%zM(OoWuWYuse;@TUN0h7VKZ@F{k8m`I7d12sNGiz84U7MQwn6JQyB5}AQ z$Nv`QdtLI^d9t8MLOzbyn$f0sHZZLwMr0)_yuyif%_&e|rqmEsLfeRR^kqo?Ez8a= zGh3QH010@`!7FFn2V|aoz^;0tR13ic)|Bpk(7PY#u{Dy(u;3XKUm_$v>+qC^JR{Bc zk9r4$FL{u$Da8rj4=oZ0$8Bs78JgGAP)ZP_A+*a~1kq|fqaoy?00KaA#=Wva@vBgJ zHCggzSOo)2S2k!JSzqMkms`l*u0TYvp*1cdpCLw$)oy51-z+|y)jI^qtuE|_?ei)! zO-g3^@bY-!Y9Q;1=4;q#LU&dsO%db$#K9wH+EZx))dAE|>6VfHNO4J;GpxO$bSeuR>pJo`xLBwe1R*e0IMm|z{u^v)URa$Aa)@KqxmyZn!H_vVyi|lp=XKFqHOWGHUEFRqZqkCh321oXOn0hwKJjNOi!CKQ6*GMD$0@+iXjE(S5EzCT~Qz=!_BU|v} zW^|(<Q>+ktetmKlAFTRRqNUTYRWq z@I9d<3e!ll5qSGj+BP z?{nZ8t)eGeJYMVBp$OQKVd&%}T_ou#*6>bfj2%_rC!Fzv6v)t!tARA^>8-U zG(n~;y;_X-3%+LFTxHOCz1*%#JeaAuj6lB@sEnN3|e4xCxG=deuK z=~Tob>=K^Z9Hx8L6nrBXB$>66nVe>IOf>pTI3`#pnYz|~iy1%I;COmy_*1Av&am#K zR>@IT6{$&?w>>GAj$V%{XK_hUU~c)Op@e?>Q#cc z&m}KuN`Hl?mJ}nm;A^rWDy()f#H}H#c9VM^+~56M7$1XnSya)VCHqn2U#m<~>QNu2 zJByyvBiWu3p8KGM`mWo%$t1bA$_SbB4F%}AhAhzUy{m;< zG9Q2AAnvP5{D~o+94+3F z9?_Kgo`_Ml=jx3zi2@h6(0vj1HP$#Xq`vZSum*AfAN3-Ph9a6J3!KMz>P&6Qu1(}I zGrFlWQwpuNh#aiu9B(IE(!T`bs#e;&+8#+qWLTES@yB`Q;|H)+i^?m(YDRd3*JR{E zC%+ZQR6MmSj7~q`{>~toRtsihNRL5C!`TKrwJKj&)2o=B|Mg}?UTRuLZh`>?B5M26kq$Gyqseqk zgk*%L&qtC9%myKJPJt!W&QQXcjk&Ex6c0%EaP;wr_H4iVW1f;tGH-hre`-eWbmqxT z`17dTuY$tY=5H~t=i~*|Nqt>yyVB8MSSdI-1`b714`5hvm@Z;c31&jP;baw27A6Qk zgeCX^-!)*z)JkS>iLVSFW*H>wO;VJusl(ucb!LyZ~OU2~#9nr8!K-WS%#Qb)bd{vYE4W69t zr_aPoZ?>U_LtMIem4dIBlQK^W@8|G|ywuVxwP%rk^GRi8GKl%ek3Z@R?gxp#ihl!) zWkgFZ#Qa1Nl1k4cUbN|LUBh5kD7!%gkUUa=`Nqs%J+ib?4ZZkThd`H3c3uQ}%mi)! zR_-GkwWh-l-!pHD{O?L`&k!WjK?&1K?(fKj*>`NjpP5lwSGL83Z>~@U#MmNO z{blkyI7M=G*2S*2!|CWoXrXcJSG=O7%$}!3>nbJd75_`iejhObJlQnQK^eKR{~ zK0A~H%queiM5jbYmb@*-tGlq@fcsmaznQtj48^bwqS><@`Cv7h!}_-)35QtfSPe37 zH7^oGv#~GWEXfhAq)PWYPhDu#jCo?j;Mr-OuZpFTcyxkEvY<@|4d&BXvIUhK)M0NH z6JBBX?NH5xpui+c%hb`iDRZ^xm4LjCmlie~&p2_r0govoEK*A6$2nbvhxNE%2qH+e z#+7M6*R^*7keH`=gm#`EUqL9Kd^e$mu7ooraiReE8=d`nbXzO6yGPdVkk5~D7sU-3 zzWs5{U3T##Z0p*|{ErmuihyOfgA5Xp;jZZ^N;#O3eYD{InSN2&FwX zVqQp-%}`@QhR5faJGHnpplF6Sq(#~1l+7?;VxlZnN~ZbIgI)P==}}>Y$bUBgi|+B3 zBDfx=5HXqSxr5hLS1@;U4*SFelvwRWlK8j~O>WFwrAJ3wDOr!I)1iQp@d^W#jegW) z?9Vnb9QObuGaJbjF6PbuT1}Uqx;>tkY=E5*$;bDPm}JI(H>G|kI+F3h4G%{H)-U;Xm0gb_1s zbVZnVG4lIEiMex%vSmb`!fQzc|G#ZzC$+zNpDF*Zzv^MS!>eK>R&}{xl#AK;Q=a({y z)GwXn$x_8-R$m#CnI81TjVRks?dRyLQ7&_S=J&kxSS5Y(K@#MpV%^!LFaZrJid4jS zCoOAD0cEC_t2x}$CbgpMpdvP8C4DRKSS`9-DJfO{&yhKwt^`N6#Untl`O6^(jGh+D zhuD@CBLJheNs6f+fpqvyN}E z9!y6E;_e-sd1-{-7}fj)?dm4t`$r*b-r~`Er3xWB--K?9fYp#=vSiiG7Dz77gZ&Th zEM0ArS;d@8{!E#Un4NyV7XRv(LQ4Wd&UYEgyA62hM6sJW%a7~23qRAtT_%Y1h9Y2X zx8_e~sh#72>%Yb0g-dmlwPixlFD76hit#_cQ2AV=3yA4&6-zF5DfAB2*0APRMsdSf zdHxnQ+kqs4PmKSgYZJd)SdgTaeppG~MB_v+1!swD2J}ZnI(1P{qqgg+m=hvITRbH` zTBWe=cgi=F%CE98a>Ym1_~#o@zK=Y>$#Y{&e=n@W$Sjo#_qqbsf_8N0hoKu9WAapl z*(nRQ!U-$oyVb5+dZr{<(dMX1sN&doDCxQ7xKazf4ltYDU^e8wOwA*46?iiE4IeHq z)fpv^Pm*+VX11LFB#xU6_|tkcV}<9i8NbnJhlLR~ARDQ~cSg9}u;vs??yEGs@`&x@ zbTr*B-3i0Xi2k9d`ez{WS28EJlntKU?V0T*Zxbq3L;UY-*X<*SKY3!HIpq*fo$wJ` zIs>C@vVyQSmyxgY!-pKUREs|L$zUo3Iv(dUc%UIjswk_J9Pr~E-Gx8uQN<8Dc9a>7 zYb~0^N_UNiqolh%AR?UQC7+KMvu4m9(w-;DlLhpbjn3_Q^z3A+qD#8RE`YVEuQG~n zCg?LB(EvR*Dip(K9u*_K3q61FhP71~AbF#hyi>@_0xOC#Pc01m$!iujCw(G9vfFdB zPpVL)KI0T=DzNa{{1Q!{R5R?M1J-tG4u_xnqUbd)3(z$Mo*@D;}4-8qYG0v?b zPGktOiKCSgk)ObR+|yWKMNEvH%<=u9`QHj9<- z6j%G-@kBLX&91a~QJPs?dO9bFIhjn^lnKiMcnbAmC%fD(YYdZD8P(M?E_t)zwG8yU z5CBO0F}iQS^F5yd|DHUw0+IylOiPVc*gjoN`>utr;>>% zXb}=TxO(^sBRb)g9^e#NG4046CuBN%T98p#haDC)s|QNo4>G5k@YgYwM@8<+pnn;~ zU{0D-qb%-iE3={r)01xHxYt5SfocPcJDOo0`v1Jy32hB{vvXp=`8<;!=-^;9`bP-) zmz8B1CAvC*$$X%k-P(a~G2o*Ok`I;@T`=R6CY#YD;Nt;VP>J4+Xvi==$C4Ln?OQiF z609f^ppSBvH>1+o5iPAYy*pNVZ1c#$v*$c(yg0S99I6Z=!oEz9@A9b^o6|n! z=Uadq4QA4D7$%i|J0eSeAay0~;Ru@&$l(i2|YBj6uo$MhyT_2`?X4L*r zBELy(h`a5%n!R4`-eAIyd44?i}bLvMTW9FRa z4L`*Sij)IR#um{roNgdYrmqgJGoqD#ctus~W9m)aj(>RSjw*|3tu)_)KJLl7&xDsw zPcBeVof-7{(F%f--caM(*xS}%MeC<0-OX|7;iR{!lBR0W>k~kF`DZaLyCsW}btLT_ za%Oif4d)vrH`Ga1aOT@8RCb{QgQ%cv3Q{cd{ba^vO_|vyJT53LRpOMWIvkdK&Jxds zbk98O(pZthPo3f{OjI*9qGr|7i?!7In??_w{n>N9nC$8ty9d_YBZ^lE@&un^ZgC#w zRPXue7rIJPZK{!BO+LeZU6#1@f!wFG_(Pv;HZT@irG{8@o=F<~KrwYkhcC~JMnpJhGRIxInN69m>CyL1azSA4u*-A8 z%Fh^Pd7EA>B`Q6kp|QeRoyQvDE^wyu(hNN z1(=^bkcX%h)+512^Z|a_w3 z%GHrsq>{54vdqy+lB41^O4a^VCsW-T(1ibvs06y z6gAvqM#mxmi6SaOLghAS@I7Ag?GEoq@qb{zN@lurYnw7)SKtjleq2y1?LduJf5)!u_VGcI5FlgT`af@QoI9SFafuPdy!( zUX`5BkX?u=WgPu@4RQPYrhY40)nV=9_@&{*E0rdznh-n_QWvQHmzQOBP6AJsn0ru0 zbY>~mc9ln;~39i;CL zDZXdn&!v58Lr$?3edmXpWkwX$Hbr@pn)H?#KiUYHb7HR1ON4~3(EBEdu|oAaL0;ff z^UCPS97p--d%A+gart5u(K0HVtvLn6Sr(0p$+n4WE-F?NYu0eMmi;>!+^^f_kJ~t_&+b zViZ{+C=GK18N`=LN&bExlr`!%kxsWN($)c}zB)!km zFGdnl7LN=Y(XVxqhd71TOX=cxi2?7Pg0?L#PPE`-O^TaL_$x0J0Mc?m*%#7WVW~)n z+4YdK%8GjZ#8ocU9##Dzgt;s=Id3BK$p*;Fa&l(`@z$A*3pG}VQdKB}Mt)2V@o6HJ1> zph~{eA?pOP94C|3+M|7KJFRGV+_9O{oe3xQyZ9`%#8?e!*+>zRPlhRL;)$nu>S#D& zqsutXh}2ce?VO^@OHGaA2Zn0li}#OoS>TzO4ikRYrvOMs1emU{?pIbS$U@pzAIzC% zg}f~CH>XwxH7|tuLbdexMAZimL0UF4cX*JZyQ7y(NEcK=_0sF4ziG+L<>Vg+sF6J- zUs<*8AZuWh_qtf;%Hl&>9G_pfSwp-!jtq6;g9hB?l0s~GJb)I@9|ot4za4_)QAo>N zYz?at3dX`^@{ze9S-ZoFKZ|>tMf=fwL6QSmN@sKSMLlZtQ7?7!U)f}{BlJ0jsSX)3 z=j0f(a7F;SkQn&8Gv~WgjksnaaXXFs15#sm;hhG|1y$EG(C23Sb4%(eRyMeIWNxPq zsTHZav!FD@rJ^H?X;%s(UV)y!kNSvHpDQNT2-)Do^$nhbE8FH;P*tz}s0sdV)>4(M z&jG)U)p1gPZQ6@{Z3nGrLp);#$DIx*-4-=@)o66JB!~H*BlG-S500!V_mGVEZkYa= zxcWR#-4{V?7qvBt^Ek;qPUiAb7lb%oFJdIgxxd7sw&XRd=bP|HK@vRKAAV(SSpO$W z$3u$y)@lSRlK82AI2bM}mW9cdg3kx^8Jj5nbSZIfp#t}LLk3hi zMf7C5%&0$XtYYP(M2M<#@6+HlEvkIMd#f3(j4Hn(sc4q6vf1{%9`*aAY?p4gjXqnB zKW5lve%80XRFMHDQzJUEgoy`wbL>M_GmFL#2k4IOe9-N^5>+Y$r~HZ;XSP~SvGT#a zRk^qOXpJI8nkD-v?uo&)HkwenV#KRPRN<%2aNO~74huPYwe(1R^4}{$eHL`E*Zrvp zU-BzTRmxn4^3E`C;HdiAw50yFFRbX7c!@5H**oF(Vc;H|4$|!}4Ny^?>X` z2?rz8xrGffwQ7H*?j26{VX?GGz)u)JWI=N8qLL(as=12UY{FCt4e@`MUulPpGFH~t z!auoo^ioLr0u;^jx(fBquzIYTO0DF7SRWcZdsFWCp!D7DkuuofiE^+ZljxK>MzaN+ zbXP$7chAVLteWFdt%XquH-${X^1v}I4)u-P21ggYq+Y=9gY0>#X}{2M`b zatIQbL#ZR$N>*W*2%hYw+%64K>qX0iVgYWTMCq?d@;cAWZMOfSM;C8k@9HuvwL!R| zK4D;S)qLYRM@j~D)+Y`%zM7U`=*`PDiu`X3X0tFrpY1LhDxxy3XHXIgZfQ+9Ekbfr zuE$Sn6=|j{rX-$M#hI$3lG~P-y=#>0^T{r9@^6c&nenVdHT6-wBV&bhtp(-I&;HSb zPx_^P6`Ss$r-a!gj^0(7ytKdVA1it?K=0?&_K0D0#8jll!o|v@!7Ck*lVMvi?-G)s z=LV0Ix3KJUp50cZzR1b;7gGSq?jcXMd*Nsx{O+xi>^0#^pM0c}`p!wUhBY#A2a*0^ z?eNE~Xm3C&<@viSWZ{S^q$ao3%C4;&H+U9C8VQEXo)D~6>tp;Y1o1_N?BpmxTFlX$ zpP1G={5z}mdQ_)pm=&R<-OK#PwdmEpvS&0zj+dGj$FQY!IIIFIdA>k?x^E;LX!&Uf zl2c~%RaiHPl~0`r1tu_=K&IV`F9`lcX1E%lyhu`?^SYOt)352#dqMh4m#*C=d$e47 zj^UU1)26N!!Ur?(N}tHl$eW%pw|W59(m{g*u>gRLX01`umvD%F(Zfn7{gkcGiY)fIY@(S|Z7}g5ZTZ@rkj9kN%%0Ynjmm zo@}|8Ha8S&-WL+TAA;zPfyi0jWN(m2czU8&_NRakfDBhTWQQf6^63Yg(Mbs6K6->w ze$uI|2&*_wepeX(wI+9u6|D(MX&xLIrGovhh?@Mg7OB@&44z${o7kV#*b~Vxqt9Y2 zVDwamtbbIJpOY^S$d2}o{==%9F})DtKMrftt2L)UthB%6Weq+i6#vqJzZ4yr9IWR4 z0@<*B{}j+W3V`!5Tri{Jn7*22?hQewYVtB2WSFGb~FFx(R%WB-~lrA~CfCkC5$TJYI!_t^hJWC%*1=_%MQ{@RSPok2uX*T!`=)<0X^fbqJM06`7R*jl?Z>)as z%43iz<0-}3)J`Mxx4w%?4lWpXjyGh3r{n05mmJoK4;zpsmM~%9hOc?kugzwN5^n`% z#Y)xhPT9R-L7pTwNu$SC@h6~O@{=^rF%`@sC9)gURDJQ?hPtNEKsBD_O(+dp@s|_b@uhL%7;#K|L{Te*CSb9qbzHGq3 zh%8Nt7rW?p`-`9jamf#n!SI6_4-dorU6yr)V88#d+!Y$U*o&X&3_M{*TvP=G<^|rF z*y7+pfhRz(=;o7biq;tY1!G{tiOU`su{aaP(PDtnwxYalSGf@uQ4=9k-a4Mq^cFm0 zz<*9o*w~$)Wx?wr+y<5z-1}JW%l#=T1^HZ-vbbZ|EH3f7FhxQv9ev)24);!h0N7)y9)!HDk! zKF8UTWgn^yhACx|OyZSrLMq2Lf|TE?>`PX3#t){#`pQ)|mMH4gP#3h{uqHNmb`QK@ z+SA>mVrDe4!}AhBjLndKJt}b&C$IHO4ZWoqHr3>gn1NB%gp=~CG#9lfX+iN@8hogj ze5wP(u&yma+oZTsaIx+MZrBjLB);H=-@u!NbQ8o&9kAcOCwHBO==5TyE3ns${88Ok zB>6S(8sCy-fmLs)e7iNIO-XH`@*I_{#V&(=i!6@HEz?dIXlt;E3HA@1hKcI(qQ=>3 z40F%f?EliTb#J$TGdn8An-#^dLLsD(YI<*!YU?li31}x}8E}0h5|lDs;7#y7v4qS0 zWxw*Nk+P&_GcNWiy-GUEr+h4&;NqB-t-9_q4e(rZeI(@SZP*3EH?CM<%KUubhW!25&D;jKD698vKJ~XI~WFc5tmgoqst%H+SJ*U`aNXP|!aH zzP_NvG1rWneKN07s`aVXg>j)cfYa|-IaX&wbA6PKXGWK6o(W2)s!5ocy;?>Mo;{!Y z#{zrF{E;`C(Vrdp;K;rd9MbhJ8JGH!UFv5G70V5Hj##N1v=)>S)&L~gq9Z$>`=|y6h2+~^{*OhwmVQZ! zX8USOdY%FO=A&Qh;VxMf*CN_4nY6nEm-^S0RdOepHQxo8jH-~;b-HI7F%WpcY#y7S zym5Zcy9V^*6v?5^qH+sNa5YO<)!^Rqx!i!&rjT42CLb9uTEnHlH*a_GgGPyAz&?hj zGQ4zqyre{Y8}Xfs?UyX5dmy{YjCXsb`6{K_F0F|w^EoP8s5FjV*tWuk27R=YXLbhI z{o%wuHEyX?4_^6Igye8>(uOXnR82EM8PPXpt5I@WqeR0~9|mN{yYOEIlo+I!^u^X& z@arw<8_g0JlmwKt(kH8oB#hv=+g;oXE4_I(B>3ngp50QRst%GjL&@*rpISA3P&oT5 z*uUqo`Qh0>efQH~CeJzOPM0Rk$+#ds)>ja>DQ3k-r!u+^!lnV2Mgj+f2fQcXv}af9 zo;Xf4q7Q2*hm<&##rGD{8z6BP%R+n)@`w{Q1tj?!Z@&{smcZ zWKTO)w~ti_qYdb>fYjEj222uz+&7FF1bEFWL-%En3n6O~JsEjGaLqB|B`zAOmt7O& z`{!q!GT^c{Np@#pBcx?6*%}d&UvrlZm>mkq>0iDsa}bDQW)*8VbjWJVwIXcJuv#LhWK-+ zm~k3Gz)oh961%gs^@a3v;8%U{?S=vidMYOHm8^M*Xg0DuSYQ8fzH3Ey;3tSeQRrp@ zGmBA;RaP1h%ogtM)m^kgmf!w0m`x}tydnaH3fU)4%bZ@SK*;VC9a%dRGc^HecAp2> zk9}>DRYJiGvGt*Ukkt|cgO1b9M_^>AeR0tk~c(47Z@u<*G?+`Z_(OsZ|1^O2rge0D{mBvc5{jRRMfq&=_;=qSm*$euz0a_rZ7CF zhS+B;Tx9=+*M7DzdxIJ0`V8R7R@&(Fup-Ej>sr)LENVMyLtlFp9-evI&klz53)PAr zCYlDXh z2=A2Q3p`8=+YcG=F|P;-bktWzxh6LKK0hpz=jFWt0@OirQV%q~QEN;N1!k60GkcT_ zCa?_wYV3UOidFeURQ)ZJ))O*5x2$|t2Ki8*$SM22m{i5H*BUWwL(ZgeeL%XuFJHKB zz>9^9yW@omEcjGd_B_iE?#;`)w$PFRH}i^>&kBWaaLM7R=)-}k&v;wHBKriMNcGZ3 zgwhHT5`51>*J<81VNnjyBOdfqxhmx?HW?jOmU7h57B1)hwr_0cZLieFGiJZ)u83~) zkRvdu)>7W)cJO3l^Nz}J#G9BqURtKbDKRvqXY5BtNmrA^!J8X`vWgy@GgNr} z+|zc}g4egE9Wp~}nJiK&b`~qb)03xi@Mg9*E(@--p)NmJz{{3YC^mN#&Qnth{sYn2 zyc+`2{Jy{*Gn(xe!^H1`odS`C@f>XmlBfFvmu$*%Ka<8Z8*u1wzJJXNq@f$5@QVilh z^;d?mf0TBX0i73fIQ+L&aU`a>!dQP4LWacZw7)XQaKAXcTvsfe+mX3d{G75oXgnuC z&FlBbjCgH;x!94v(t^J%SMC)H%&~d5E=sW}@O#AyRj2nTmv}6ikUUUvk+6-&Jk&Eow96M6Zz3c0$YphHbPU55vjjf40!KG5Lp{hmGDKC1;iHiZU9_I5_% z`cY~D`jBO!wPLkR{(MaT17nVajT@^{7v}MM`^C9`qn8}h;d#!8XP1+A)A%(%^>85# zYpxRmz|}0=V8O1ie4m&lPl70^uqueBixszZ7M+kRQ(Xy&oY3v*9@ zxf%_^9_YZN^L$S1ewXl}89(KNzKlN6CVwQX8pDyZs(^WiO?H&&r^fKA9X{3T5yK`m z`ah<=J3flCYdbslmg%!I*~ylW-3@F>A=#Q_cV>YUN(!MvLN7@a3u0HqWYT*ANk|Ay zDHa69h6NA{(o}4KSg{L&hz)rZOTIIC-|zRlf3hLjnYrea>zwPHd-?2wq02W1-Xc&# zL|vmg&4dk>XdLwueza)r2C8ssc47*j`rGi#)r4VKo~f_=-HtvfG9O7oS6X5|n%bU2 z=T;-=iB?ru-s+ZKaVgl9maKbu(pIXU1Ba;z)TMdYn`|$IL>jYj*N|0W#JK4;tMY(Qm8He9eNsFVTXfd@+k#8>U8C&^IyN`Rc5P?daJ_ z{9zTAn*+6F`jM1Y8-e7(^qmp<(wbLWru@yP+}k;_T;cV`7=EcXw8ezgln@JA%f9Ec z-tG*3pM+LLi2!5OyQp^yVXj4Y+fudl>33tcsD3g}Pm3}S7FoBb-7)XY{D0Fj*ZVhs zGph?6C(vUNbpp5Cggrf3(^xm@k74iS;{ypZp!9`i4gXW2>lej2khdt|P!gKfD*I^s zqa14E{ixX(|4@Zh+nsa9gaVIHl{zF(lN^U<~L`9o*x0-UUWzP0E=6820? z4HYeJyreL3k-7ke*0vYqxhaE8rn3p#iYya~xl9p#+?hj|&tBd}krp^r6QkrE&OUn&aJn^ZlA72;SX2LF)h`Us*!C4hhxPcp~ zaFM#2(Z90xCkriu>BRJa!QQ5(Wpi@0Q))6l8NSWiaP8~@MQ;hy*%tIi#IU6%=QxnK zLgEdM8amJ)I6Fu0rF3uR=)3BIe;Yw_g)L|b^aZoCoM6dma+;5 zcA_hTvLi8yXEPR10Xahb})Bct;`7 z<%lV#Nq2)f`G`tuiy;?Zm2QginJ0!JSvhPbAJkSl9jH2;+LMIx+hSqb@JkLIu0b1& z!l`ANzI3C(jm>Hcui_0k5ySkN>{~;~A{=pv;+y;-ez^rYm4EA!zIy>k;Tr#TW+x=1NM!dtI6Tn$eTP zner|>=8jRfa?TaNx=%b7_(gSO)ajj&4^?=$wj)_D)Vf z1QiV4hj6lJT227gM@p$3Cp6texH-jfT7&t*- z|3u8sH^twqPC9 zUxRk49ZSn@m|>qsU{$>^!64jrsN`))Wu8vCC0?C6DiqFqD$35y6u|f%$zkQ}#q{ z?q&lFqaMwPb1D;4tyo|(U%VL0S3TN1y55e_vIgohy&f@I2-8T|tHbes zFGw+zoWEI~FS3p)8S$3i(A2KR|1nXlO3AurLG48b@MNRr82UooJPZ0z*1w?S{Aow4 ziuw0dNZt>0%rT@=%!nvEWjgEN9cL!9cQlS!X~ll+j=x*s6Gz4H)AjPxDkezZw6xlR zEn1V3X-CtdWRx*q7)8EbEG#kNZ_js+Sv%=rH~;h zYVB(lRu2E6H8qn0RxEom9HC&6Wqf}#>b9TVL74il2& zUNYKlTpB;MJ*Ui#z0{uF1;a`ptW~mqP`^RU>zF-s_Pan&fWSLSLH5Q*2?c3hcL{$^ zvfg9Fw*~Y|JI8gE5RToo0F1oHh@_z z=m+2;3e5IFxpp!rmbi!2GR${@p?DOO*$vH+4m(yT>(1-+i#*~`i4o*A52|*BPP<4Z z$_%lBqsaP7apFq9;aa;&FjvITVZ}#U5nrqY&fglqZwRrKP<@JG|0t0mJ9@c@g(F9Y z4ty7QC_s2A%8d+xeaMA4?oETjY~Ql*rhe; zAv@Y58S)v^FQe%2a`*LWnp5@M+Pp(t9uxLRPTW7$Qwkvd7Zn+%@ytWR`kp}x)|{iMsaZD1fs{fM3}uKNW3!+w z6QOrX^jk*DKTCvxw#Z#>EYuNM!yA$!7z@TZ%+5}{%&GgsmYVMDB_V4DL}mI+ZUqxLo+sN7jVENMW- z6yfOrnQVc=lbYE5X2*<^#k)D~Yt@te5zwknrpnSRKV-*ZF$((rqdg*7WH|_1_lIxf zHy0Ega06#7Dzfe`HfQV!H#{Cf@w$bZ%2a#{WR{YQxe^4pg-^ zBioL~$S{5>{xgcae|hRkBSloO6MH87_kqT$TnN$l*Ev+N6o1-i z*->oyx>bflbM|yZH}Ya)#E@AV`4JpZ3G+@Hv|;Grk3QYM9mO}>vGFmY24Q!&#KuB% zgOM!pp*c#|MA1Wdp-;`ygv6y4F|*VYMT*C$mqR5sqSuFm8$fc-3sV<9U>HEn0g}J% z(4w~9$FW(3#-S5*kTk)q>#^3nXYJSwiGY+0^O$E9CcI+CN@A+jaBgCoOz1gbdr{(s zBD3t*|Jo5$<3Ff<>uUpED=I9;?!=L=j5UR*`z^>G)xJ?1fwbrAV#8Oe+0a4QUF)S- zAxd3paOLxA&Hujo1wB@5W|^^rH(wXibB!6tP0$t9*c&Q$I-XDld|6Sup%@;(RpcarHq68fN=4$;Jw914QLH%9Sru{o_Z`h*+v zb>?h?<;M|ySFQZB31$oE#5Ty1oxx9h`2C%w_uDbW8zowiZl+6oxsY!$(jR7OKkmww zVIn6=jAyCND7&(Vs}Ru-Ya<0F^j!pc|tVgXFQ%-jB!q(}qlm@*q?8sKtFWKY3Dtj_=?a14jGKmp=E>d~t{;Xyr zQ(Ylm*ISh2!2+$LVU;N#Vd|^X?Zc2Pj{k2;mNs)Gc(QQt9Rm9>8eiNhz^srz2kon# zQ)PvNgZP_y?GLj|Pld@>E$9&3NKIvn109}ZI-+Lpr;)qNm_yS^5$cjeUo?vP#V$o@ ziN4{+8p_$tynAg-cdj<;2NQ~vkk_})8#)^f(tiCvoyFaD>;{Qgi}X1zi>`=nF_OP! z!b?^#(?h03@rf)wBg#EpBwQz=ww|oXP+)CMhP(dw|HE{TH=)1BlVw5UWHl{IabWe; z(-k-xtWX$IPK1M^2|Flje{CIm+78141~8qy?!;K3?Nc*$x>HTd3f+WGB6*HIS7f=P zIQ|u%;kQne%^Zyxf^~uMRxn8|c(d(g%z>b;-GVx0Lw#M&I0vi=rp~D%rf_hTPnSZ` z??$M-jpli3sR%{u7CsJS=B6@cfTwPlk#MRp6Z9nTgOBRw9&}*FUe9>DcCanHYB_&J#UriywI*~WN29Bm zd6yMSDJB4x*Jp|6!o*P^S~>bfHI?ffSVh}`HisSP z!|G{u99yfJPGN8aC~MYum$l`7XUAG%`inYUom*T{82_Cao7bg=g5_>VrSY7Z>6O2%?bW8cr*#*IRpZ1Tg>3i&$HEQTnAxU_*knbMOPo}KN z@AVKXqK0CYu|?V2i@B8|*4`UlXhPX-_NSW^^gm@GU@tjd_PO44&{Plae=!$0up<)N z%(49{BnyHmCKyy;kF|~aj~xp|(T_U)b#BYLLgNq69UESu-r%O*j^ZYcreHsGvE@^r z{%V&R^I>Y_@48T#71?9vyP@vy)4ICl^%lsW_4)Nmbg=`uW7Z$lQrUuFzF+I7sOBi$ z-jueAPhL}s5w-JPvtn=eChXw#V`s)c(v*7MgeH{6ZLeMWkpuJer9o4=uFYM_*nr^P zQxn^6WVS3Lhx*2?@?h)R(q4fvlL*sNGd)Yx^c9(PrvEy#drsVzHl$o$89YUx0*QRA zjoUtKe|u|Yw_CA-BE7=1%V&!phS)FF*H%L+mCrelp@{e%gbs5+ioq|9(nS)@@q#hN z*EMA&c(7o%?{VIxnQqkA=Rl`8A!c0KTsCxeWzgrVy1#qUOLpwLD83$P6I}_JG24KV zRA%^eXVy%5%7gEWg6@faKfDjBzO z?5G&AyeR$`AF15ht(whWvSD$3c)1llQp`e;d8$vlzI*g`^|ni%sL#380Y?flzo-zc z3{LauQYmsl6#uI!_$|*IovgW2DgM}sE$Fj9&g<TJ7K z)1ES&iGRRFo~{W$t}4Eg)~y@Y2P^H_cF(IYES$r9TQk)MjVD#>-w^zOK(i!rM7w^s z2|b@A7tWwJqEAD%wX9S5q4@#=zbB6Sr=GgLKkH0=VruPRcio9?)3=e>)gwrJR$)V zGdDTVpv0`@AdW(%Y<(~W^}+y?+mY{cVDBptJ;eL(T^6#?6mLO01JI5_U%JV+B7~D; zM#!wW$kyaDycSUNwMj8*R71vnRy1*PJXnd%uR9q)Pg&4~D7C5~(&<3D6829uEn6R~ z^68Q&y(}>gG>^H=`9E7q{i`82PK%G3|d;onVh{YsAJ`b0`K1H)D#yWenbIEsPZqx< z%8rckIXtu&;#(VX?f|n1&+>Q-ML?1$K zmwEbf_ckMu>cejAnaFz$`j)w~Stb_Y4p;kIMC|;!@Lei5(OO!N+lu*R93V>eh(E1M zSpo51FM9!_4GwfrqIx+ty$A^A?jUr@2LieS9eHCN*tQ69NvGZ6GUpbWl7J}&paO(6 z>NrHzD2^dyF1tu<@fjWufQAaJCatp}qf<@E(7m{JgdaZwXEa&Rb5Y`phRC1;T`Xb$ zRjp=s@GHO8Mk)GsiJRIYU*Qd7Bifg%r(d#SF2C+|-mp++Zfpr~qBb#tO{rNdIpLYX-bQsOu(GQ{GVYAb(opzBNHw5nR9Dn^^?qwL2~ zV*zi5f1az)+UUW)EHl2xQ#Zzl!3L)wqWz1ow;Le1yb?U=({5fn^`ae{B^&NWDCjcv zEqB9l$VEQw)t-s67ypk$m9tDjgbP*&*NEtz{!G}rlq>6xv?wUuiY=4~z=ZJ#js2dx zRL5EcknD7zQ!*UUF5Cli(kEUCPBvkUK5eu!Z;AtZErS27(`|IcONFAxf{v)!IABU< z#IzocO_7;5ixMC48CuuE#%TC+`fCmTjl+=KhigCe;Rn|GUbdj^GQPY~3GZ+qVloFa z4MPWB310AP<0)N_1j(iZ6Ur+ihOyPlbT({#|L9kFwp+&6hbck?>7?dpb*0CN{oU`m z(~iFGNLj=%f}6x-@-rj*PVtC~1JOTVVByT#G!z`#RohE9I6obs~RPZBMPVUDO zJDF2Zno=ToOKsT)R_sbK-OguCEHe=y%w|PzMl@g5R>nEeC&h8N9fixOJX&~3qMnoJ zQq@YR{QB_A9_-sP{tF(jiW#(xSxF*11w(qnf}yjgg0~fr={-|^wqxJ6hx zE}Sbo%BOAYojA*D_^V~^5|$Q}2v<~{JqYoBz}IR*n5->qMNuo(1ubWY_ij__fCsqv zOj-402OKCVif`c9CsasI1?Rwm6QAyd&ivU9>@FGqMW?;lmGD}jDPqBX%v3F)z(cN$ z8q+wIl$l9Iwr(Hp=us>B0;PRTVtlQUzj#AxByO;}QnXY z07!fQi9}p98hekC6z3BFG;saiwBJ7b`G)L4>N{Ml*_}`rDr%&$&Pj+67|8M)q z+D_v~CbUVVg>yf%V&h5^*6{x4%gmn!@sU=PIVLWzu5yGE-B(C}^!*l}VH_<^l&F>{ zR;Ef=G!NHhUG!*2ma%7fV#*e?;o&pNHoCH_=s%CjJAIkfx~ zROx}=t4iaHPehr;MW!2k#P%Mw!2D^2@y*7x$A`^k6^_33Yftw0&sb0hCd`_m?>W%+ z>M*R~8#-`4xYn<~LK3GWW^3z+IKhw*Aum){x^39^1NI|){Qg>A;pn4VQJ=43~JMP%Huw z|FG%Q!iv(UE|a4VMwyi25x4ma;a*URqOV(NXH&)t|Le`r6~As#Z^jo;0&2B4G|68% zV5w0ER`CrT_$#UPO0G#EUhR zvz*w;^=X^!Xi=B7lA%_($$upLA0xZBH1W`2_AOrYUODjtZ%vfg>bg;jMNMHz;?QL- z1OcYZ#|?G~mrUrItl3>x_Lmi#R&46y;Ybd4Rgei<(ebE8Q(u|uRA2rqJG!kmm`hu% z5_2}{Q10O48%iy(?1=Rm?(I#7k+hPTrrf5eJPb=&9aJ#6&{V(n&E7(QB-)mpkFZvk zIJPG846KLnYtz?F-0Rg%Yb&`93YZaQMorFc5nWoJwF%-~x469xEwy5QNZJ&G{wBA; z4Z0t&ApKmhPV;34dNE2Wk8qSRMh~6fLbrhG%C8M|7u@H-pelD+rz>-b+9F|=1x@g& z70gFHw7^7kg` zSAaw^T8+@asL# z&>xRa&5)0Js9jMa%(1hg^bJbc?hO6xJ{6)A87GT||#W zbQMbF?M_VG;D!;i%Vl^aLqF^$-jr~W=crQajtz5ndQnX|`x8&z9A#tmwp;(VfteHf zgg`I&i1uz$`FohE-dR7}Vgq4R{3E>KDIb*?BqmtVv6$vaedT;7<|*N(4yR?gw75iK zS4WNG1#M^wldps)dG+i2B3F6VB5Q5Uv3bK}W>hUSFmpnG=aU!u3at*{H~s>IK5!*m zsgYkW;#c$V<^2V8ieYT~MCC@7;v$Se$vz^Yqzyi3&2H@;(cO-KW!x%(uuP=fY;eP< zJr*=HM_s#QbfO<3<068-wfn(=ELSo#>iplX!MBA4(mR`J%b)tvKC zXQEU#$9^55zpg2MGXwv+Po?~zI={Qwul!&|=KIL|aqtaQ`gNJm&^*+Z{ARN(IMHV? zcxi;Xe@^I3K6#QPrUneF+VjkUVQNG_Q>mC^!>-$4`h-tdH^=M`(`h35S7u*QD(`b* z`!?90w`&)d(aRa)xSNEYkc;Owl$x_POxWnvrj;>qf<8UUt*uAOE&tn#DGotiX7I&Z z))gSEJVZRnzVR@O?Py8G}Gp$hGi%V^&yvd18FD5GO=oz2Bl#X8jxrt;d z7SOt7qhG86SE(PpF7hjHaX^8xS(+tkUdhpQDUg;GhmPkF_3I}29oQr7;XH&cyOe}D znSRAcQj4n2^-q*j4Ex&)R7jr&z5}&b(MOTE6ocg#7k7Na zsC`g|3BY4Bo1Ey;2m_G3UJNn6IMivvzV;bjS|dN`z;;KeT}YGR;xr}kH&~#sqDuX6 zFZBnE!E?+gNui2riVHJ!x2#jm1e1v`n!|rsQMF9ohojqMOr z%*#PRxj1wvpL&zTO9Iqi?Rg^wJrglhDwRuZSk7YRbDmoh0JU3{Pfg2+zm>{vCpKfF z^N1a74-nTgB=B3Xl1$#{FIB9io4hZ1^*iAJ20=$eX-xyOdKi+;3I9#YiterkPqrv@ zmO!I@_!BV22|ixdXE!Ve*s$+P#67$=)lcmU#4Wa>k+Hb74VCpy?0m6l<*?Nh)5b)J zNtF000-6vpB-aEQy!zMHNx$*V&lOqsP_ulOsDUZlziU7)vnZ6GM;iN!BnOt*5zI#j zcPH$Z@FPY_yQu2!feGa)`annVjVxCbVP99Gr$w}IWAKn_#Kf8o)MG^_BKj0V@&_)a zd!yqp)Zznb-{0j#MxJj_hyISOk6OD`F zBUFeMh1TR#M@Yl1e)6`CSel^9X7Ji2_t~&ni^(r}BB?B~r6W%Xis*|7UR_(c!-*wr zGM})cM*`$c459asFGg|LbDLGFZcP8stA8Xw=|JffWvd$a*8jDd+tuJw;Uk_6(2R)q z7`C;cOtN7glvwuj+U-8_cp&a}tM;B4{%=F&dMBudEsb_m=`&2FO}D6Xa+8!90=y%J z-snMVbJw85dUuveUMA+=r4*ounipd3u?jrT{4BWojYYW1c?@yAT);c~m76K%Gl>tv8(x}J5>uP)-=|Ns0_ za-tIwp}fcu&zC@Oxm{I2F7@N5*2bXwaV~~GfHVtS#{T8uMhhzUtMR|oOLa-Q2^_7J zsLbk;IX?Xp{c5H>Le?K|30Z8YRMy{%BWXN+tlw+3!csO}LaRK}i59|Gi3-W>q4s?I zAgPb~iSIjNA;BO=l(?$eW%V|!XA!LJ)?Qa8{@oFV)CU@EXKE{7a$;8&37^=tN6N*U z8FHkDd^$=@QkSX%K}O&SwB?LRKs%!3sRnM%|3cCXDVet42XEbs5h9d~FkR!^8S1g4 z-q(2TVITYTTC`ft9@8rtmu`0|=&|L#b*hS9BR(fj~U1>bwKZx$wg?2+q?-j$HG)#9{$Ao@eihG>&v;j zSl%4r?x+p?EMhx1`GD`fQ6Aqg49VjWt=Hh{a4FR8O-Y|x(2TioSLQKJbQ{zHIqGx? zJ9MHswAF;J%OmIaj5+SWK9R|-NOP0R6s#`kv0&72aJkh>UTYay2$ix3IlX$uW*;FB zs8%A%_`0ycZ9_FOU4x^=;|&W2ybde6IEU|Om9BH5y)y1p`K8hv0?U1dG{pOf>pMf) zg5DD`9IvhHwqXw~HeTaVUs*y!XP{6--ZAvJy2_87*rd(w^LA8LPT$Nh`5v-3iqBIa zG2FGqpPGWtpGzbPC?c_A8xz-wni@D3$^2hO7QLwk9NEUu8A5y9$BgaKD{c|(n1S8g zSiDfh2))DOjl*}=Hk{$V)mXXLiOsFf-v;UtA3vEE?vQ9tD}q^DCCBwxb>w@mu5KU; z3GNmdFKUfch}ylXFmTz>*^QwkdCYqQljb-uYZ*Tlp&Q)^CnVU`WPB`-m@t@sFh%!l zr(e07HDyNFv$f%?B38cH_o)fVe#76LXg3sBCB4^>Qs$y}Z%hJt-W2t^%(tFVrO-^ zD?|I~fExdU8?u&$NhM%IRWc6ozjVC*uK{NiJJC9sPFBrkBS0iSP8tsS z$n%}qxq=>?cxv6UT{i5e#oWIMDP9qF*+T{N1kI&||rUp({MZ zR9RoaLt)kM;}%g)A?_<(PxCQOgYMRO8g^ zZCJwn(ixuC`gNCj5LET{FT;XOl}DV|p6cu;?Wo$Xokp_*61}|@-6$Y)gx1%@3@KX2 z`Y0*5UY^D83gb74+E_%_U9)uP?4Ho+0>iEACxJ5Y_c=rip?bF>J|g3njpi$P#215; zzDm)zloR)`@nsP@r!JyNz_2Yo;Jd4Qxs6@upcPd`8LuI2q>IkmlngD1l3_?@I}tz4 z@)}2SNkKn3HU1N>sBN#~vQ9?_2N5u_82=y0a~|)`^;;@uSp~Y!5&}Jw)nj zee_LTVOadJB4+4k7^nkw&8btgF-{V>`Aa6AqNnYgxgNO&;Qn zD0GFH6{U)9^8>5x(5Hm<6Q6NzuQpqy8fbh|@$ELO zZ}s?-eEf5H%*tN0$*O(20(+=w(T7fK`)cfU7!b{;X40fiW-hm)Th&>c)HyX$QVKe> zKARGp%4}vsn7c{kyyUr>ilMX0p-|j-Jw8};s{`7Ix-h~vyAzUR{tu&hc>%6$7(bMv zeXI*x4ILxwjIb-pY^}?|V14D5%&$Rb>eEr(=&)+3(G-Jwnu~g4i|0QU^pMI$%-1{7 zrYLcYV|0@NmP4U^&@%Pwb$#Q0b6}AQXAjaGaha8|HPfHBV4vivL*rj~sl2w}G)`C; zp%>T8{%SOB9#p*<6GLp+m}f&7QC7jRj>$yUU@8y zHKLpEg!uPpj5^FQt7T&7#F@|`6P7&Q(A_uYF9)1Xfd-J~bCt*@?zdon4!h-FyxhSy z-wckei7?OA%=>9H{p27_c%X`I{2|Nr1(Y=ZHSRa>#N+!m^Bj{ z>41=2btgj|^$?>Zs#U-SO5=wfOy873&FxD`7cBE6_I#7$h^QGj&D~gxnRw~VvSDer?jQdE<0Y;S3K$8hQ&_4lPAA#d3 zb4R40zXyXhfwGoUp7t2@y#6DT8x$~|i=odm3{y7bHi5);E~FdSx9$WvDwufdcNvBw z8*`ad-L5%t4KPa4e^DV_?qu= zqOYRV5svPa$e|M#L$87CsX%XES73w!m89!Lnkz2bk2Or>=P-;WHGOnonk~+0M1vp$$8S`=b*uzdVSu&(3Dkc|0|7K{r zNqw@9{HZ%!K0Md=WPRo5HWZhsO%%w_eL8&*-K+YbU~)s1oQ$DNEHDhoDu%r1A%YUI zPC(Vm9J{xUJf6b*)aUgJ)~iu&YIEvqq6Q>YLzn*reyQv9nf~h2%@)y@Qe0#6v~4y_ znIQ8~j{Bmy0#C+nlH#DDax|YQr^)dFvaTJ0rXNLM7IbW83fi(E zJ6+JHma_xxV>?9H$ZYsssT?}{Zzw6Bxws*(8)E(%fTU965wA)HyQ<4FS8ghhQgsDo zwt6-`N#fqB&rX2zcj4*%X+p<+`t~*GvK1YQ>e3AE_gyM|gB13=Om$+Q!->9&!r}DP z7ZOy;{tX=mVOburcU^3h6LZVjdZfALvSurVXJKc>FeLlZ&{OUHaxP&;gsxPkWCG{k zFmf0wrZvPavY{VA;DuxMC9G03=q|UST>*S<$Cy)2)EhNq7@K*jE4ef zuAtY%^zjXq-vA^a{1l8fKlO0{)rjc5n7+HAsvsG=l%dIUXs=&a(7;f*mrRxLO#+Mu zs`2it6smEZH!O_sNXD0&(*cr?bK<%zYFY;OuO1wC?^|u)$%ODH1pI%)mUU=>h-Sq! zzc(*_3XUF^xUYCi-gx}Ab?9X)`b~}v!na-nfWw6AwXPhM@<6gp76uU zIA01HyU`aGw3`C7*fDOcN>_2J7OX}HzmQL@->1EPd z3bw)g^}2{QVSD<&ur0XX6BUv~iOXpzc}dh%M8Is^;m-)&E+6aa*HwuyMy;)Cnem(r zyDIVDsy!BAazA=qC3tbiS}I2-gJz!5I8awUJ&V?@_mj7GpjPz@2v@B%Ck1`EF=dR( zZK`@Ya<_=+g(&%~QVV9|4nIGh@@>k0)PY@B&M-)m?=e3a6|#pR*||AyeyXmh%(jL# zeEyl3Ny^=Hj7kH*^AS z#6(ZXBR=krOJLOtToXL{*l6@fhhr|6v^2tG)|P*hK|Q``c(Fyf zd2|S`wW0T9eJzd|mqGw^+^VJ>RTDbL{^msMp;MqbGI#inZI%_J?p~k1e(jw30{e#? z_jyC*UpCab&EgXH+x*OqwRycFx+#`4zp?UWi2q-18?kWMleIF`WG~s@Qm{)vTO+#n zx4TEC(!2Y;V}*oViF>Fe`H-k-%Fzv7j)uP^3?KQ}m-=;(NWCGWk6J2@K|fAnFYw}R zD6sdXUYAcFG2T?B~N)0&y6`Wgl|pL>XdBH2k$m z5tilYZX1whIRAy+JNT*{!&ZpwwvU-0Rf zkgnSXLyklpWXemKtc{};kp20v7dvyXWK+x?E(N8V0mm4b^lCibhN30lzq?=*x@{&xe^dju;i_lwkxQbKh zaRZ()g7Hqt$hVFM>h1ybu@(I)#XYRFRzf&yl3A+*y|+&q%@)-g0~!kgci>srrsGdM#@$ zlemSA*Q~0h;MU zCrZN?P3CXM8{*c>RZc8(E`K+QYj?*FNF-s!&gMakL*qv4-kd`&taUSZPVbu5C|D7lh})!}X-@5VccUNl#N{Pck-chx;CfcArnz!!QG0@}Ab{ z3j#=6@!1a%t5S&%2Ry}su3zGghq*UJ&A13y%@S~A01B+@+Uu~taz0v<|upyMzfOx3S0j~jrL zOftUKD5WM~%90(K(3O7Eua|p~*M=s`2H4d2tjl=Mj%1Kbew_!d#{7m8^|Y3K&hg7~ z;NUp*OR8?p*FU&EdXE$PVh#fl9HY?$-^oUZ$K4zZYX{TXE@)y;>`r7a+{ zK~W!ZXIJVTME8)V0C_-0cl?LB%F!H-^5$rCpBdcD(rWu zh84YugRChgCHR`6nF-iwG7d@*ANsUMdJ&XI^mV~BgZGk4_==2!IDBcC^MB|>#3R5Y>F!6@J~Og=MLL$#D{=9!TD9Mfdsj+1+ELWb|f~7-xj#F?WVPAPwat z4!wn^dxLif{=cNSrlzH-iRfKY>lchW^Nh!P(_R!&RvY@Osq#QF_BDyRhaFiTLx1We zE8E5%7tl93Y764ERKhgqT`Yk9P-34BvnNH(nW^y~{U1-pU~9mWwT4d<>>nBW=pYSY z3x4t8wpl|qtUCs!ZT#m9-LygU%W$Pk-@f#gWbEcx+$*GE$ztvTX<6k{IrVM(5E%LzV62WqZkHEWQhg1@5=u=dTTEqKDy6u77pB-4U4-r86JPB)?7GD&!2T7XQ z%8_aMKYEiMU`35&>}?8#6R;B`o+F|ZzrLamLAhjQomwCG5Q@xkZqrFJ@g6H0HSEm3 zccNxkJjhuWN%#=x30@)fXENy8L1~i{8<@-70r|Ja!`fx?Rg(KYL%rUE={iT5{zfkO zCW*uA=R8LeY^LhvM*Favy0gyM5G?Dhg*8khWzQ6zu%g#8^+&tMPfbSGOJttWGIXFd ze2gS#llluj{e-^ERYIs~Cix8fo0pW~K5-GIoqKJ?KF1 zuD7jch-+T@WLwcG0S!b9-;?yERQ!cOca?x@1K@+Iz7#bYnI5{l8BB-%A;WlTPz#X@ z6jtW;8B`+nevEpBq(01`#tx!?hheE{Uvf_}Hd~I{N0JvZxO3!)wQ6Y^JuRT+G5vM* zO77#N`Co0xqsdXtZI}UoP$yGO5}M7Nv6j-<|01 zw!$Acad`wRN7)>HnItY`;I$hfyPcT7Ea`R>r}J}RF8`OTHZiP(MxMhOM|r19jrzVu_Dsgv~|G*^6=j2$8qp8{dpV)Gya zUsXA^ed0#~;vE$rM%PuBgt*tVu>I+vokn znL#=+;pxp4K4Bv1VQDDf<*suAJQ?@QOdUQXZ5jl53c-mRbh zBnfGi`uQXI%#Q)=k`47pG&nPOx8QRi2y1-$V`~alC8H0c#8jhs=)hCq{bWKONhv3M zc-1;zn?SCJ#hqwgyf_hinlw%ju!-Zz+I1;!0`HRWf|klZld+dc%Zm=}v3z=fp=M?3 zUT>fHg@CA~_ETiy)HHJKV)|Y|50JdqF8(BHUXSRjZU0TnCex}jI}BDsUGkCKM(r*U z2$jvyq0C55#QuzN@Pgd7M1VUGZD@0VzqO+RLRxy1ex6Lq-5R(`ilcnY-hg4Rp#NSb z(;CJ@AKmPc}=m{sbEg-BwaXyb&D-$o0CZJ_-Bd61~4+N+h zF7Z=|%WRmlha9_SYZ`nW@EeW=FrXxdV#Zor!S<5#zuf9MZbd)%@Upe}9m!}wqGqUR z+2Qc>WM+h#Nh-gGV!Pb zJx~A;(IC$$=ooWOKp*5lIJY&W5gRuq*9!FF06DcI@tUYv5;YB7Rz8AMnH~t}pW3K> zQbZ2~_@<8X%tY)}nR%I{%f=hdY(&X65dE@WcT_%4ERe+BI` z3YqlrcHvN(p{PH)lQoT%jAboyQ3CcNX`3x#bMu+4{iw=@u1W|vf2Nz-PgZTQq6x#n z#g&YzI_Ce)S>~x$^HKO9Np2l)TC^z&O)9SsUxwmld*Yvu8uyaWo`RJk=YzrMB&A0fVUNz}m@QoF= zYYq9&lfuz$nahR5ZomG4wMAD&ZEj3IpjyeL@E+1gY#*nLabj=xPxu4V^m-GXYsuBe zYo8%i8Zwk-__BZ8W2~u4;*Yn;lT}EBVi8&M=#c~HRvVHUximxC8n^B!x$=xRQ-vS-|`Wc0aYSZEZ64qQ@`mkg3k z^plwbX*&d+U)I5+SKwG{lAbSM854-Y0rv$FX=CK3)=J+L-ua7jITG*Ipm>Rp*jZ$=Ewlb{}cDX}fC6ZYnYA56|PYs|t8=5;;n`%g_b5n=Os^=i~ z4O>laGHA76hduv&jvD{tvQCiN`42i@-yFH-#1{BhjIkdws>hPKMwk=W~`^$!Os zSVC-O==4n8i=FaS0hS6H&XDHBbp4jiBin=o*-swsgqW%MShX5c)|Ujc%SS%CS$kAO zkNPwp{6D6?1H7rK|3A6sW}Tem-sC1XZIZ5}i#D@ulJ3$02rWxm3W5}rynr|mUU4Du zRT*UzXen)hLWj7JmO{%GL543IWXY7_9w3S!qW1qid4KQo{(X3OHBbe^No)w@3dPiS87t=hhY;jzjzBXHVu~ew@K~7Ble} zhvGa?`%LN9(+41}p4et#KE?=M8&s&D-O%T*5iP7V&8nU-(#D*?+%YWqN0sIsjXKLE zf2Gp+P>-M+;wlynV5WbweUV=L!c7Vmb5>DW1;vY7$-b*94TOKAn%P4}bkwb`OH;mV zVP4Ntxb*lW291D1P@nk2t^9Iv$xm_2*&KFD47!LVYIW2{VV4X%jQ!a%?;Ie_2W4+t z=IGh|g}Q;YnOJ1Mnr}Ee2MEi_zVM@zJqy(LhG>uyNwS%%E{+svmIIzGjC0-CkiSi< zJDANkWJJOt;)k*H5SG;zYM4gozkxk53b_>tPbR8QWA-?fUkr=M_&AhZDR8{{1qw;B zZ-7w&F(!1c8RM8nH#ZSUt|x+U1ZyJEB?>*tbjqHnwJqmJF-YT_Q30>=JcgzLbP;Io zwdrOHtX2(y3w-1XX8w#s*9(cUt|)XP4mql`gEZ$KUWpwmS3@1B(YZ?xRtvpQUEW1M z8a#y+!wZ#~#uQKx^_B9w)#IO}N9P9rjb*P@kyeem$R&GZl$H??OgVt--I)B|9ABr8 zXmsOKi&ZJ2G$TiT=>Jn>FCAJ6iY%1tyQBhVR3Tr3fNnS3t(%&rnrC5j!&P3rY%8YQ zVw4%Z>Xua13&jYiS@PUJ3V@F1ZkO*^+by7Fy`LWv%ePV&ediL zBFfKYvgVHHy^>2II*aANO#Hqf{VpTbCF@_UE{+9=!v42pW2)-chODhxfXWVtlRy86>VYQ5sITVTa6G2#l`!N2^Nri2C9O5d0S*+Tg4F%?0-%um&!tw); zGqJQb5v)WKU6QVP&Y+q|aExfcGQ%ln>fEb=oSLnDd(NQYUVJb_jUD3q;X!p7b_=s8 zoB3B5qf=O~GNTDanz!qUZ^Z#>X)`DlBfOG0toX?(v^DnGqK8ft=`Ypek5h=me`D2U zr*>4MUoKJ&_uPVsFWZ=n4)G(b_}!`fK!X>%W*uG01ZbKS*%W<*0heE&33Yhh-R)uY4NNHaHQW(oq6040D4C7P&>Wb zlpG-0lL+c4xC@gnoR9)ARmY(LqeNg9eMQSKLw&=InhjX>=;N#t@&lh!SklUoBq2$> zKW7+ply1i%+V3~g3ERxs#^GVvoPKWkYhKlU8nPkLqqtO;=CzFS3gA=i`lo_vaF`WkM*=e{n-U$Z(EpWHVAvL`o2?stHHyI z?CX`x^#v1aY)rc&5+d@u&X9VeMl;_f+g{_;3TQ$uxFtad@gTr$&~w#p&AA#)z9^lO zrR=@+r0=AP-++nQr2<%t9s{2yYqv19S&>D0btl#dF2!UsByshVmJCR-p?9;4XJAkS zSUq*b5x44i9lEba&*#ctnwz^k1#QPXq?jT9Wcs--kR-B&IZE9;pvXSyTVJZ%i*@y} z%*0~(&x|y~qkeut-!y^!vIJzkP+08nWp@hsZ=29gGxO6( z>{pnLN%HuPxNX$&r8;mO*!)rIKD;sv%agv*M$LN6Wwa!CLvc*Ci+vPH1}2%N&K=MO zZ8ezM{5)s)NpL_D(#@G$F(6I(3H>rOwM032xzA^TTSrjA%qqpZab%PkEiBR;TVANM zq2&v*-ryCzJD>E8@6ab<*+#eW^QO36`uMlJl1mFl{b@nNI)sn0jw$ATZ;CU9MCkcs z#x9%)r%u1=i0ld9@g@!bf(s;EtD~Y~dbcyK6OV_Ltc57mO-h#-OGN3{xr%Al|G8xe zAJl<1d(n4HMLxvf>jy6z(flIenpf6ifz#=6f4zD=PKWC=&FHe5`)SF5LK_SP(S&}8 zK^<853tQiD|nK@SK1)Kbo52QNcABeaJ3~pFOI2qD=Ls=W|Drz z+~My>GFx#LJpNQC|ALE6VCL?#29XMVb#* z3Ko%F>g7%@9K8#CfK+ZX=HF?tb!fzYxm4@Cd}LUgE!!Bk9$WXe#BI>C)7{!GFaM}0 zjn3Bf-dgC}ry?70yAP88nhSaVg}y1Js*kZ@ zTP)M33g2R+H{9f@g+=)S`^_ND6)dJW(8ZO^AuU z$h@J@<+};fm_N#?g&fz{oO)}v?umJ0Q5rmY2V93>W?8*&h=p0OPzOFh&<9S|lzcOD zx+tW+Q(u^2LyH$?FQ%9*^gZ8UOu(urk7Cm}^I^TCdsM{fh2sS)ldw_PhgF|WfPpB+ z7!gRv>heY7kJ^~8Qw^P%Jl<;iP-B=%=?Z#_fMz{u!CgWJHoV+wgUU>WTRnVf@G((Z z4VLoO8sEn%?Rre+wxXXyMwH><*DRg*sfBrZUjH(^0yG@l@jNqv!NY$p9q^oushU^D z#-dKFm#X9c=~k_(M~t9c501dRqLfrf`w6S{nioqn-SxhJ$j;Bv2IoV7xyJWb8QzNx z2VlcgS@KhB+Bg&?cg z#|?B3_I{%Fy^S$FSb47z%2K9t)D{Q-!7Hvn&hO|N-*h8H>kt}dLdmGyEgOU+JCejL zVMum_ZHV4U(maYEIPz{be_~$cz%=<`3y>?NFN7bBK%`6l*dYyALGe`%xF)M z`mGfu18oQ|%6*4wvNgVY8--{rM0)ViRlbw@l*^-}gBO)2TN!nia2U%qPZ-Usv*Jbc zoLhNj(S*x3#^6x(V1=F@~!|)w#m0sg*&mz*T(*7L{ECO&SgVCw=h@d*`Cm&Zmb^NhE|x-B^Q2USzgG7 zzMqH8u@LZTRBHbxZU}^tOyKThtFq?jSEQmIOq!`T8Ckj_P%N^)=O{m;5N-1Hl!a7~ zdAk(L6jZT4Fw)g-{P?26GJ*Yl5V?d6_Z%p0wdRyo+2GaAT$Hy)WU9Ly$1r4(x#w4- zZ_KFLqsmmEUK-5^5E#AJL>1X@kS?ioPvsRUeIdZyRy2~f-pWu**QP|N&6a{-T_B>5}Z{X((m3H6!4jK=AERFk%w8 zWx^@UJh_t6YQR1ilIz+=i*|UYJxeaNrsIn zUaI~T^PghrYt7y-v?|7bLv65yuQKCIb*m%2H{ohkXHE;^CF7b{Muccz@v( zu{r$v8RXS;(DihMFBYnQYsh%rf;NnlflGG8Pgi&r%dQuZp^XL4+fY^|InKjTz88Hb zHyh2^4$vQJj{BC<{A8ie77u*N%6zt24{R~0&VAQx^Uys-hSrRW4@0spmVtD@HjS{` z$Z;>+{C|q9@}ovjWVd|lRnmZ0eF5l& zB8u?Hj@FIX5A45N7SGy>l0ZueMUb0^(vZaD zu%V9Hk{5YJe+tnp-x4Ep=fgfHFaZX{qebd|NHW)>o>x8iyD&tNYDt|#`A0+UZ=9?l zhg(-Y@!S7G^t}@oHfFwILG7dDZz$0$Kg~^?#Om*zA=Q?~!q;u6|0r^jhr{D<`96If zy!_-HSgCX=?m?TLC!(yTY>t)L(`|T94-Swr+QsIGsIQxxtr_j15JmRHqQh9TLnAD4 zMu>HJ1p-j^07F#kKnJn%tR5eAy*hA36%vc0z$Kb-IVnin6!S}K3}C8(-y7;9zL zR;R%zYY1Wv;)pY5q%4-~t;@S=V|uF56VRA4rO$qB_}Zyo--zsj<%yb1yrAHGD!TEZ z`v6w`;M5*y^aVxqOpUmnLc;iy{n+Q=p^Es6Q};C^ec)10sPT*!SiTgLY;Yr1^*YU8 zg|wdz7JL z0WNRg4`EGf9J8fJ-5*INdbAI#AN?&-I`S!vT1~ngu+8BVRoU4b&a`0MB??I;Je!+N z&e-U01pA*^Ng(E5>zBQ|A?q;azi_J4nlhVh$TmuQmWPAl8UK&Zs|ki^io5Sr|E8C1 zcat+U<+WB2V_lb?>A_m!(mg_Bes0K;(F4PfoQS27_b!e2iqp_qmord6ujkUFz_$J>oBHCXQ z6Soi`5&bECxy7OFqP}YICL;y+A#}QuOcL1TrPKm%#F|BG$NvuY-YqaovQJS+98dz> zge{lXBGJNxJPOcc!^6g9I1oc=t;#-2k37=?;k2{Sy%d>|GA+#(9HV8WJKs&MFyk7X$ zt?9QM)j%nx3spt`&n^2|wFo zBa|@{-)cb?s71M1fN4fpa-glM11G?zCfg9>;el`WH!uc|rug3t+ndmCEFO$w1{9H8 zBu((}-!B-%o0)`C?mpH>I2A&bDC1=_ygXSr@}C*_VF#sS4l7c>xYD^Ew3$~AMP{pC zUealS=G6JE4454VcH$D$oL?Gufmz$qSHo;8Y2h^AR0lat+vV=n0p--G-u zSJa8p%dnDLdHw>qR|{pY)aUfEGcgO% zl31p$jEuyl3ow6e)=HEqphmCZwT1Zw4#wZ<2Hk(DSktyL<5iJu_Nw?r07;(zDShWoM|HUgwA`;POcaM_yZJ7!?%OaVmyBp5whU=S85T6(BLh!) z4xJ$@JYxoj7*bTGSvC}c(Y!T~kf)gB`L`RHf0pXDV9R-kW{OBYk`RyKsfDGHX6E}r z+%H%xb1E~dR63q~;8o9CSiT`c`Ew^o4k(PEWtDTE1%2d|LooB2pH1Bu2?bnFYxKIN zyfZeq&VET5vU&cT8S39v4ycWlwe&rgJGnLPMG;v&_?M-l z=YZI37lk-5Jf;I0Lxxj3u|9j8Kzr8UXZt$YF08w*H#~5wpRPv@qO>jtV*cTNxSxY* z+K=$Aatev`?fTL*E7LMcsMZVqQtbhJfVD6Mg{-h5l$CF1>KCFlu}o8$;xrbcJ-BI{ zw6B1+jf(hfVPLES&D@v-q^xTtAf~qYA`3o#9ff4LKetqQE>*oX?0;Tnq?28E_R@k^ zX##U1JlstfZ)s&>ImKIU-J+#Mzl0&VVT9BI&$gj#3rGXcMw zKFo!D)aP)5)Y0MoZJZ*?bY&5ME{AWFCqmU?NG5=F!CmwAEMHckK_=t>jb!ZP> z_5{U9;#*PXu`>Hc@nwV?P|EMc!#E3yDU`LY$bZbv@QY9hVT!sO=fQY*R2x^J5&`XW z>z-efTT0|(x)P3Ig}X%YaFu_d$c}Zh+Qk4-(4S8v84hk2R#&x^Tw|mIU0AlP?`(k` z40=pr+J;r38Et@({DhlCEX(^_M1zRrS0hBpWK|m)Xh9Lh>I?-so&;|f-ZDdg3uel+ z&IZggb`kGN&jq(E=pRUA31t`*5Rg>BbA>@jC*0!5MT7bhKAu8k>~TWqqTu=DV|lt& zi)3)lT6fofqy~k`SGzAjfa&JIFDoEQc2mS*EPJOd`uCLuzuM4*O5qMAl?D9+i2SxH z8EO(I+iZdm<@2atT2=+d<`E)4rB`pm@*mqQOGUQRrRZH&(QRi&5ovZDRR2`RG{*Z5 zvUo-Ia{|l`0&f&8p^8lPtKJahQHL5=pbk+A6ZCp-z3lhPC8yGurM*w@Nz z7^Uq?z|h*^I+T&1@i@OB>sdSV%qVGqsIxXXZ)5JdTUEOn4W_xc;E#(6GKr~hQ~XuT z_AB95ul6>I>~)YD3dzfUAEB9DSfr`l@&yx;+FW??vZA>Hn@ea0AA$p0JB8$|o2*&p zQ<(sFo- z!Ky=8r?D}E`Vkn@(Bd|cQ977ulw8U`#D-f=*_f(G9Un^Fn#V;hPR=04`c1a~h|Qf< z{$DH*d@JWGSr<`X-DJLorBAj;tXP$&u%l&_x_f+7@6MO~xkR|7@8k-BO<;DIqxgvEQX3k+IWlgTpjt12_AM!E1I~V(*+vht~;smeiM=XsN?4K2CSJjqYu`=mIJV!H7 z!5diep~$us86xV&T(L8KL&Q8KT&=r+xwQ`AXhYx?fdRt$5Muqr37R|z>849i!E8Vu zi_#&L{0IM^CL6VLEoib=%4M)s7fGhZp-b(1${_ra(Db6dUO<%yUm_1D9gANOKSk4 zR(~onyw>g890$}_a*2_4IZ1nMVIv&$N`QK2n(2a?xjLSc-E_k$-BuGyCrL!48|oTH zuYu=W#Ahj(W1h$ilF;^Fh;D)Xzt>RK#KUANFgC4#k;d((G7OpCR8W0LTIIG}T0GE2 zJbw(Lj}N2}jW9LkhN-&+D&QsWp-;(iZ9bOyV*b8N9@REx(K1GP>@7#-WM}S?|SF3FA@a}9XC5QYO zM4j(PuXJQ?4hOPeTts)2XOtm8Oj}C9h6SM{0e{EwX$RaIcFE{eVxF^wLb3%LbS`PK z6&>}c-c+)wgg+7jhMfgGDWRYxZZUsfl#fhN1+kCaPZ%Aodt4^4KI{?Ih=X)E*d zNWOqXuJl9lJ7z1b@I_8q8Fk;z+#V@~sWa22Tantb8H39ioFs@b9@Wex`EZjFTN4<; z*bPx!OTUvMdl&jhmI6dqK>l?vZuK)ZNT@_y0Q(BBq32`hQI+Z*wSKQEJa+F0#$n8+_1!hW~Q?vB33Q*v7_x(G4JuoOS~}O z=ZZg@D4z7QLpqZ;;n>6$2Q;7cx=dTVvK+#FUJ4s}Kxdel9M6X`X1cYXc-a6EW^SdL zYzubQw|KLx%s97l0k!{R%T|-Z!fb{7z(w5W*OvUJ?P&S(T%rTXx#IT|@r=rLAq|}5 zpjY5fiRAL~;ZisqmKg5nwTnw}Hx3>X*`tN*#QH%g@eDl49#CeTmQz3^b1M6XR;Jeo z(1~gsNvvfqnWr;qKZZd%>QO7v9Z|Z-3&irD{RwhOLk2N)LP|%wxfnzxFw4p`d3A$` z4ooWCG~}!%6zi0$VodSO`(9lxQAuW4?qKsK?0CNgJu8^(Zti2R9B!K5W>*MeH#Qw@ z@m&|$bs@K+gW~eDKa=1I+x!tWD8MJ3VWh*Hy1UE!t{2!GLVey`H~$f~Nt9b;WP_pZX$97nxfmpead?b{B<8dkPG5{Ps&)PC=&y114|&rPFT|HW`^yN* z^UIfXI)TM{wZ)l&B%w1d<2zn%AYuQcS`IvKDnQA+>zKl~u|LiM(^07zwaoYj+3_SY-z8IT zj5>&k-Gd*jM1P3VbzVj9Ej9pgkzD!L|9uI-57@S!qKY%x11#MPns9O>9 zNIbkiub6OyTIOf~u#jkM$ zRBnxJXqI4t$vXOF1@J9~9afzXxf5&S+Y;`IY+o4fwhW{uf_&CdbsozIggsCnJXo-xr1eUuw{>hnG`Bkl_(gghwl0UBKMba zI<@XGJ1QS1{g`LJDghrLB9JJ`3yAdZt`zvPF>PKDn+BKg_tJ{hW@gy`t%O!4T|AEV zaPiB=EDk6~19DWF@Xj{RI4k1Z?1C^vBZ(BUK_6jlTzlR-b`%R4)hHd*X2L7ktFmUL z({FkVqOn40-HQGK#VFX1D6f=K4fnmsHWnI_8~Th7Lj+QIyes-DGy^$Rd8^ab3H(ww zU12^kp6jxl!?KkgRln89WRmt)!YSB}056xoamjbOz@?W7CCax}_YJ*ogu@DW19Cm4SPd~K7g z(xZ5!79eo|B$1UwHjZ+573UdgtW&>ZMZw;1TIMAp$#lbSDDyeXOpos5itNz1FebSK zpDiWOhjq*%9aGEzBoEzSjVAgDE-lqYs14KXNIov*Fwa8h(tFeqNEMZEF6U31Qh~iJ zwmVXhq}&y`VA+Uw%uF7&V?a@4Gujj2h~wLCZsRh?xGd#>@B(4{*lX>s$yQ`=^AKN# zc8=EcClT2eXabYpY|rhsqkAi|`skn(Lsv3!uS%v(R~-!Jl2;c>91R0wDI}3OMCln! z-9Px#Tqx{sh^_7wS z?chc=Q2W52oAIEG#k?tRjQ8g42E}d}Ao6R$b5hDK; z%^4pGT!kAnsym4o_G}JCX9)afSiZ6u^)X3%`Wsfp{V!Ga8}}|~vhsi$vhl=lWHVYV zf-;j|YA!fpWd_y`yr4&J8vdcTEzBXT7_lY=jvjv;#{I-e`w;Dq*fPpXu3=`ifR+|% zx@wEox&S(}U7(TN6^ulaOdoQ~#?=8v<$=}Znrxz5947T1Wu!+PrrQm)gS!5zH zC3xt{{*AdY9zoNX^%8~1o<;=Xhb2OQ3+hH$qL98u$NC7VMEq`$&Z|~KptJ1p*wZ|_ zw+K39$^#xz4N>WtZimDUjjp-`Bn@qJ>e_1`-Dj4j5=zB-$^#rrT*k|R#{~a`gKK=@ z>yUdrk2UkGi~`2CDrHUOfL-)R3v*(U{W4~6*wM8HzfT7_|MI}sv*JtSg5w|Odw0ETJ78rLR4`&4+It(_!( z*lo=e^gs;iw+01FP}x=W-kKDEtWzR!z#TS=GRTj7eeNenUJaIps)esiLWJo`H=Lhuvk`FxKXXu9VvY()gR)=6(wvSLx8MM%TV3Ar89Ager)4xKMNn%G^ z(1ghm=dt>s9o?zo3#img3XH5!E|W_tGN^6Yi^)YNN1BG@QAk3DETUQ%pmz+kmoJ^9 zsmXFAEH-@z|8kGDo>Dfe@zeHOtK={R*)}|bdXI`vBC*l+-Bm@&~P2YJ{P(prN zKsSo<`MQE{TqunQjyz4>r8<;&%Q*&ywo3iGHA%P^?`BD&z;AU)o;FPDcQn?5Arr@HnNC*^D z5bpNlvB58S{IVOOmsbM;Q5Hiq|K5_~w8I?>;IVz;v>vP*e1Sqjd4At`6x~=H!n1cg z{5N%Z_AFI8F~RkQQbuB(afZ+LLOEUaoo=5vtoC0*ZMIE^$%*pN&(0~%v6U+1ebU|b$ z<_hRyDHPsf0w&qDVhyPWuX#ye%?NE45k9ps(>nw(HgQhwKvT{S0{cvbvXbaN^Pt%s z%udKXdHBzp{Gp{`jB*GWKqINZhqw#?@v_pvZg`+V1|iBasxCL+#Pwr?U-A42H{<}8 z1d2p98KNvnpE5gm=W+2!@-JuP*yY1-nx&xcVTH+Fn1CZ$S6di?W1uXiF(Dt{JSFw#3>;jWmQF$P>hxYS}Wv>skuE$Mp%_Ls0C^AKIb zR?7%Mza8iOqXmsLNnvzg@2&PwKq8l<(-04x5TOLs=b{s_QA{aRfbCK(wQY^#U) zvF(AGBh-0B|AUPw=rrwRq+^}jGb?lM39Pg{qLfY-PZf?nEYo=l=PV!ggK{epm^!^*5EL{RHC%W#3;gpGz)6f{X? zZt%;t1XOYuObs7JP+tE4Yfm~MFT{-YDF4uF2ZnwAD^yan=US7c2~3WMQQMe)gpsS& zJJTRnssB{qZx*ZP)aSnBR`e(AAOVdkBRlc5p(fdcLQVDx7*M_?AeO5_r9}I;jmg+( z+{Z|lLzl=n)1LxsD_2e-dgw|WxRC+U&37K{o^ks2Ff28q@}W=Jun}?&#2!1ce%V8}$}K`T02jOKx>OiywMuCPe=lv#IR-Q)3S`8eYc zowax8mcWJznOQDz`IK*W824imS0ejnob%bRr1%8(dB5WHMyM>oCa^>MjXMm0?8|KwAJ~gzz`aSp|?EnKJ#OOatG#*wxVe!rqiwd^8eFjQ@&dd+U#(kS0*V8 zfWbr$M34~mMyK2s#pHVMA9~&47y7{U@52x+ZSz_am__wDhHz;YzWb*%6_9iG3&QIq zA#7dI_dU87f)zwIrA)a82S=M^6@}V!D`4#6;XwXK`ZS&UP^Q1>;ZCp0>@h)jY_FxoyWsLJ$YpWbHlQs?C(vd#p~8at(XbHep776! zH~CbjCj{E;aA2&++^hiD?Az?@F3iD@w``}$vf|MPW_Uk^;*M7VU9J;&3y??rD@N4Q z>N~w29LycSBTrhHl45POlFb@Pua^-ZF(#7`fJRBHZPVUPjMMSoy z%e)`U$CM~1tse7Ih+?Gi3$kp&ZtoHf(P|z#zuGh)jL~Wv8APNLNbC-*db7>(oq!6d z=|rD-lx0LZMF58d*R-M8aK^0%+_I|y_=Q~o^-#j7Oc*%Z%bjdy6ioe8_v*P7GcDzW zd0?T`*GJovViTChR-m|$jk+FKZDiB&r&xASh!|C<+`1y~3p%U9-Jhtplu>LZn%I?v z{4)*UmR$|>mQ!a9N{qL=s5bk3hOb(W&}vagq7K(kcH_Ru6siN=CQVk-}CN?RGVE5JRvgEE4U#h9nB5|fEcVopE-uR+deQL#sRXOyg;Mwd7Q>m_5nVe#@Ov&yHOHE&* zK2oYXi}^M2=*_Cgu+&@)%&Jg^{*Xx^$gSRF`U0bVC6aGe_g_FE;raK#V`jD!6-PlDMky0iV=7dke8M3sM9YYM+nJld{J8=-ZA{9+)CXAGHyy*5 z!K$hYRRbIH;Ftp#@0Lf%gED|hcM(f(6>{oEFfhLaQb*E_nohK;&HBR(lk8HE<{X^? zrH`bsfQxAO&CFAre6vRx-|RmSmXZ%e2!@1EXfw*QGE3Sy2MdWLc!t9B7VyYHrJ0iA z6;HRLA9?o$s>yx{Oonky6{LXZ_d`7kGqFf|$zdGXFhp&UcadnGf6AM+}K5HW9gdsU+Q)Ch2WMWD2sF}A7 zGJ^u9qruM(^~&LBw-*FD z0ogH+2%fORdlW0aDdJW)f+CY==2QSg1#V)vyP4n3KsUc^M{~9o&LNvx0T`K5iJs|Z zW^j-glO1VJ`z(ynCJ{FlMc(BhElTyRh4V!6aA(zMEfxJh*za*9DF-OF{07T$wBZx z5HBk2RjSvOnj(6nsliW#qh<6un0j_iS|!zF^31mRe6(DWK!j=CmgNG34rJh(erv)I zJu1k-kA1V7uQI`&)?Qfyhm$ZLC98h0fxl`PL#$IgsuNhHG{BcqTk}-NEAx_wSpr(? z1%fx6z}I&oPO*ne|oONAQjZ-IkY zZgxX}1pG^w1gnfRpz&0XoB9yTuieZ{j@^!xW*52?hGehEI7!hXJ*dJ8IZw{cN@qD? z&j?UF>qD~PQ%}c3(~;^9pK_N%V$OU+WaQ4sQI^RisYLikkNA!N?jM)nV!OkTl!H4%__um=Pnp==m|wis*qwkrN>)Fxf&AM; zV@cGz9u?HP6$Yxk;b*6MSr18>O-Xss387zaVr~>d1=E%JvrIBPi@@MX(F7qu=_gp2 z6vZ4X(m4dCb0kh9#uO`55{)OZ=B)&Dtr5LNb16v|uy})}i|l(~KR9)+rkrOeBoUwy zQwGaIW$Q~|M9;TQ;rk|Ni*;q%!(x(3v=@4G+ZZXdN&ev!T(nkpv1f+_lO?QuvPxQh8C9ceBk=;E4 z#5(FHdk9rbwnQQ6pN{C1rbn_Y%(ZgeE5wwauGl?AvjgkzI+dkO17_sG0w^R8O1Xy{ z98j+O%c)qPv|g=%y{6Bi1`K2zVX|iTh7bvo#%$qVvK^6yk-D-kO1dT`fSEFD|VMLmMu9m}h8#1ko ztyFge3$+R8sV1}zdY5Ka7=Oa1mos1~P#zXL3pEFuGImmoVu}c9@H2sq=p8ublOk@x zN;m<#DD!eTz+d1bnu}XNlSx0ok*C+@r2H2mCsBX7g_*_4pk#G(t?#$6{XZ)*5XZs~ zJa1)SPK||?_Jkqo0Q;XplM|*5@$#Km_Zx4S>V;EEi!y6O+4>PApF~0;Gcd(uLDG0< z#P+7*z82}1<*HYS_-49dSx4j!962@(Uu!COjm~1E5bf~Ek9XKNQv%S?1<6G8*8!)jh)PXp9MJHH_VKNjtpeO}#4RUtAc|35!s7*ybLBHzxfv$l zUq|0>(cMWvUnW~cJL4ysaU?FutJ;o@dINv0m_E64UZ5WFO@i`n8nDq!J57voT(I}n zNUF%b%pzGtA7x_3mO?7YH$RG5RHW}KFb77G5QqUN_ovFFkPmz}f$1G5?V)b61*^sB z85Da63vU-|$E}Q&d6_v!V}=pM7-%r=v_koKb&=Y;s(2Yu4$^M!OoW=}t`;&^8I?1ZJb6q%gs`>KOreyG9uN({WV{X< z$wy{p&*dJIOCZP{yG`67uNM~N&3y>0LfFC-^e5bveg5LCdCwD z-YkVe*u)_bw$N-;d4 z)V^Nkm17BS3G!ur*~5+$h)3=$U3lgkCXo@Y+POzX!tO5yKc4#lnwWEn<6h!wKG{rvV$WO97m!zcva9i5^c~< zfc(H^x*<>rP~WJb2^!PYyF+;5X%qd9v;Utqdn2$JwAt*;uVj+eZ0gv8cbiu#-HRuJ zm(ft99W9`Lm%|-FSSWp-N=`&`0{W{;`h^W1V$20>oaUoZ64bvYmvFzXaxU{SNhhLS z7v!ye>CYPzw_$v_HR{dPpv-26GG#O3Ky(h$t`W3>kpgY`uh#5B1L!1*)6?nf58Ih} z9GFxUY4d8sF#Rafmlt>Y53Breu^UH;uF*@>qn&XyW*j*DyvPs zP#N>y7f@;`@R3JI{fU=@-4 z%LMvFo!YLLkSL#7ur%mcZ~1JxTB~=LWnIQsxw_yn5?zBEi$ng&ho3xygA(tkeskHMMS-ck#56^ zPuc>-22f7a2bh@7jwZ_G9PI@?-sX-CL-LbI7XqZ;x2<#vBW9&ZPH+i?KmH2|N`S~- zVb-xDOJIg*Wk54yyu%?N^;FWD6FImS2BRC87j ze4kDVqM`#O#@9B*!vvde+sHy?)GLp{FPmZ@-Xz-ln;d&Ei`qS}Qb=k6lK25~&;ob> zi8v#0d$4?#)9`>oqN)~{H5FW0hzM_(fG8)w*3P|K3%Gr;IG%A5T5yI#)MxPA=itIa?>qO9n{ncE5$+3?lo)b|r) zyW1^qQb^wUKV^2FMthOx1S9zW!AVX|9t|JG3&1Zc*W{Dv`P69%zWp|;NkqlT8nV#5_tiEQ4?~3VW zq&*((DXg48rH1-fdcs_I4UQM$sJJ~K?%La;ta!#{lJ zg`oH*wUVfeLK2ZhbVDJ&1^xRmj=bd5_ujgZc|<08CXY%3h!p%?xM3o6L;dI!CJJ0{ zIb8{`0LFwNf!gQqPNOphE+*xw&CaltI1MmrQqa4YgcxS~CF2JI19aG?9`ny87MLyH zu7#0)H!@$FZoitW`qQoif@vos4avP4NSKeK!7nu~Wf?$))Gy;={!CZygXXa?B!7$S zsu7B85_!hTte*_2I_WhB6zhcuE3>GaTTAo<6BK_=j`;`+UpOJ3d?RxkOx2-g-IPN3 zqh)$6lJ?M$QTT>hBU+ep5E%ASv ztjoO(G}*n(Q!>f)JPHN8x5h8kbws_3IW*osRnSbM8FaW&?Oea4slx;fGqOts(4vOqv<{^r zU5FmYko&X1*hJhCBC<;*`>;8eLKLwTk|yQq%n(W0YGU6mHGPVW4-(PeN!)q6Y{e{o zAQ9%LtM+#!!FZ5$MfA~Kpb&|Jh@#bxw{*Zha2m(^dT*(+4$36Q%ji3biE5f(Mmn7z zVsA=|RE&CM5fue-!{xf~ z>^r!kB1-`kq&tcWDk3g`JM?>hhxWUFo<2P7Br|i)dCzZOj@$EOiGpTFIC~eu1=h%e z_3j~x@0SczPg;7IFqErgH5n|w(FI8E&b2G4<-kNgRSZmQsHA1THCm?aGO88p+c#u_ zY*yG~i=H{-qjbE7AgQAGrtz{zT4OI>@yyV*eUOwX^0*B-cZLv(&R!sAa!8C>8Dga( z@7oZ!L{X9#f0`m?G?8?a6kS>As8#&Gs`k{RI&^i-J)2{)R<+HX1e-B$iy_z5`L^2) ze~f(q03lb+b(UCS*p^pa>nRpK- zfOv92hw%)DtRM^q@Tf_XpqM$?w$;B+Zgq4_$7LUEd zjr|se;OKTQkSRMJgId5v+JTMzr6~56_JTK%>e);)$wtBTx=O4;@~CQ=T!$tobq$=8 zy{p=6lgKgoiD4-nBY$l74~U8TVxD8<-$svnzcI*m$BJA;h%OvS!x=P)h^tc-8%iA? z5xslfe}--UKa8y5o=sq611lhFZUaQv|F0Y7yi#%3iUDY#zUbNX8;~A09dBfZGQ{WV zOm!=BAWk2DmVL<~y1>!zf-;PgRcI>umy6F8HoCzmIAH$oPi*yFhV#S%T#L{tN>68p>2(=xE)2fvw3?~hsQx#EWD3LttDy$heKeYcNlz=ol{ zt@UUqOzrnv?Vo4#%70uxFSRN3Xb72F&OVGXpCXKKL#~Z5ay?HD=7AN{7y9~JOrLRx z&QYudb;A4h{#S;@XZPFRQ{}(WRM3<>OR=3f#<|0;SI5{#F|P#~2qyIcCH+jram&ga zbZTlENiM(}IMsZvG8C>}omvScgH{_oeNAHb85Nz9X&)z@)dq}TY17IgwBi{3T;Mv@ z`%QBkUp$o|o~c;NSLujjPI-p=O}RYQxR1K1X7X2&8ToqS$zG*a;u4sx{EjYYk% zu>JMeVaYPZv$oFlD-(_-!1~m?GNg?S1Q!_N_LVq_!XlIamNP1T@=ISdLs2r)b5Ypp z0xUQgV&`*1HWMtg4p){+bxO*%(vuDq`n%@>Y}Eh9MLk#XycR+tmGwS3fUF$o+etdb&!IB+SP^_q4vMQB}u-scC34xagm#S}7R5y8=RxwyP9G3GdAoB~y5;xmw zAY@>DdQ}nn-RjS4&8l~MGn^+(f(t;g=dBLyLsI4Q>~~Hn57>P>%Hb`v*J$>wcIl4i zi}shWtK0Sc(3BhWQHqftK)aumRP_QpnCDmA(3E{fo_%u;*as<2_ZK^nE{e*>`xauY zjH?NfG{m){gPdp$+DWOm*@F!>uz?^!lqfMq10;b$3{zd4VQy%|U1Tn#!A)JjOERZ3J0EzJyL4xdMc|=q}Pg^ut?b&>OMfO5p6#1$(*hy|IF&>JlC@WcYTF-2OJCSsWdFVx^9;|y$Jq@^#z4hCadpm2EqyOfE`Faw@*NsuDe8#T z?A(CRVmDnM`=46&=!rMM&91H3BAFiK5bZV)TCm@xCymTN11^~)=pv##m3H{`+(p~jeS_kaxGy*eFQ zCvo`pQggB5TkXjX4|05McihoOHBzIiR?$8pAHbAFvO2tp49vY5Y-EEvLQxu{?zAiY z=*rTw`Pz!3i@b4*>7Q!ljBP1(0A&u62jm?py>Wkx-U^g50Fy1}Jf182u3ddR=9x+m zfiBaFl+chhIrnKEm<{-vJXk!VOFgc_Ht`Q#!zKsd8$nl$I|-5_9FjJI#5H%#z@jiH z+Ht$;c&IsuJ7XclL{dJ-+DK_kdLPY*2$R?a4)5>^2R!qaXjtdu9((Yu67z;O{gBF* z*IUb#&_H5G$?xs`^eBd7HH&rKo94%5#Ll!G;giwS)=wE8?CR53ONiyrJcGSTlE4{N=YTZqBlFJFm?} z6n9`16WRu(ziXG@NXHTrB;hi1iITt06GgrtJbw%OAbGk0nTUaX1WED%*^?khoL^_K z3mVr7|Iok-Tj8$MOp9?D~YZK2oH zfqsxls@@y(&d8B2nx|i)7=;R$WMr=9fKiOERSae)I<88HmzEl3Zrd{=ML4CYL4QAvJe99e&@PaVT|%*xc4$P)nT7np}=1Jm&PXC zQZ}Ob5>Y&_L@8Wah!ZZb zu=x3i7#WVR(aTDml}iV#Pf-bFcAdd8Nr<3IHKT2e_d6!=f&@tT{oWz6@+-v z#T=4DAyK?iUL^aSDNZJbGuWezuHlMrPSkVv(%42j`ufvM(oqoUud&bE0bbzRIofn% zTt^ZwAVIR&mE>FS!dTAbkSwzYXU2T#5$`>7^}ChyII-8reHubeP>NY@#BzV9dXmbu zeFf{-%m60n(eoyU_MhY2$W zra}E%N{oyknqCHKO1a{F%XSY48qJ zye~wZS1gNdw&M^Pnn^n3|CKfNw|4r5D$4j$hVHj(X<%*$@)?cTZ0<_MX{&RLT8e6@ z+UsLpJpxk7zEKIn{TpAO%6U;kaUn_ZNW`4qsaiFPWAp$iTW^%-~78(=h_>osph#Mn2Zj~hV;oX*rm!pS!Ulu@nH_j<&}^v_Nz6vdW^o= zp0R(B{A8;pYoHA5C!>FW-CUPKx)C}~%d7Te zPs^JX9>X#7ri_m|ouB6--;Si$%c+5==}mtv-CXq$HZ0pw1}~}YBTvrtgOGcfTz@9% z6S#gyy)sfU{tAg-E^|C41CKH+tUF|0-RK&rxITy~qn5`InD5z46G=x&(bjWtn|p#H z%`CP4EAClAd&vE>DqegW4HzYw+s6o*%h)oUztR-*&B!rtoTK(vkQ5?G5Mz(_JU!9!+IwMGMeclFkrPur_q-4v-6)CR)&QyP6r*e{enup==vw;~n>SPV6 zWJD&Pm$3##Xz^sX4f`BL=($rTRIzv#Ud8GH&i-}&-ah-llx)fWcE{8gi)nK+RLr1n>Eu#b)Jp(@B@RTBm4a! zP4tpmI$0eM#5(Ak!Jh7~dm#$v+RAUYHHqT6gY56D7yvi#X^57WTHo9)zUTIwDs{ZK zEF0AffM|*#+ouyxexASI`Z@WFaf5nmhP7Z0Dcg5OrP&)_@qimv@Vo4>9QqHbm}%^2%_eUEn(&P`X4mxZd*jHcOglP2knT2PkHHBL=(FDrK9uEi6blOfOb}5loq&I8dPajy>@B zV7737fTz5GXQMvU)>Y@;YY+5v|3RA#hDCm^vi)|)O`<$pk(aJ4!f}WH zEN*q9S%SQIW!}3ue+6^6!H|C9`p3$Uc#h&bNVXzzo*5bTSLR?Pji;lQ@rrq-7af=o z_y40JY*-dGWxUzpERJI5Hz0UV>hXFu|50I!S}hjSoUwp7^DGT<5>mZTJjx+~aZ7YQ zA%JRo#63}$XU&d@O*!^k=BO7d!T*#wMk~IzG%7;H*Ip@Qi`&((#{MXG4o3trARu?Q z=cuzX1vPoW1fa~0b21r$ct{w{aV`H*otHO3EoXB>G?NDMi;D+Vz_S2TibpU9J50rt zDhI!V`>r|_W~2A}3pI8oHLXQp*Q<@Own3Tcc2*)Z1z2iwaRa+Tv?4F-zpDzr z)>5STV}U1^VRGz!w;c+~3#(%MV)nI$)X|)a>)S%`?z%b{%rES8by|ik!h>o%qsTn9 z-Rw2LZ)ZI%&dPxXyS6EEL5FiN!Quxj&lablt?kl2SRNuu(JGXFi%ONjyk^TotV$pe*rosy1oN6QuOhn#!iYaOL2R@$y6G|^Fkd^qoh z04>Ml{Qq&YoJCu~%`z(i({T>dpA>h?hQxh}-k7{kbv1IB9ziN#qdHniYm3oK&Dqk$ ziwb_X2-A2#2Q|T~>f9Z6u``O{4H%%oEVKTz)mxZSjM8(Q-(pvHXI6d|1qij1bBRRn z5+gZ^d%^0WpEcGN#axXo9HJJtFJDm~S)C^Z*^g0k%3vFsv+(^-LgGM0>tw>y1A>1= z&Hv7j&!0<_^JNs3lFBSERuaw1GAnBg@%|?Nv36Hul=W-WQaTe47E?Uy>2!1VLf8>( zHDLrxrU)3}`o1W39zj$^n<|Vv-Gg=JN6_b&&JQro4uO-f#%%3;<;e5hAn0rsCXB6?bi;nrFvQhRi0(AODB7Z@=TXS*`!7# zjS1N$V4}$<(`{)Fk>T?TL1Hac5|{Fn*lvdcck` z*21{AE)Q>xm1@j43G0t60Ap4!Bxe!*1Cn=h%`eThU4pjOif{hf+`oEB+PDG7rgn<^ z+*+>UpS?B~=BKp(*I;wF8|W)Co&s$M#SA2N|6m5$KSUhaNQUZlA7j;`?mE%S@wao(ch>m2A@b;%3|t29!kEuNrSoPbg%0lh|o>4=DMkw zo_ApYSov11V>|M|S4yVm*dp`PMny*kN1loHe^IJD$i|r{mHct<8F}Ciu_2nhyV3Uc4i)TnC~vIX(|u8|un9(dSI-mg z6k(yeXRM1`bUgpE(H8vWqIm6DKyaJaIRPRSKNsm~B zd&UC_H#}1PVdkyR%jXa|G>79xtPMlBub6}o+e;9+r{!Rtpqh-z3RF-UU7B-89S|;h zqfFf1sy1rk+oOZ1lO8_mNgVpW=J<|OOiJCSp*1WTn=%i;6C z0TU?#)#ODS&&|ak;WBn!yS~7wWB+k$=7Dk$0z2q75{iB1`e+G4?K6SoP+TS74N@cWap*wKW&W}L~VedVq&x?Qxd z&pky61YbyJAenXVTz|a%(g6Z zJgF*=UP6=nHe|_c5XLLU<9X)c%i;4UNDf*|i^q~4-KdB|OXaT$w7;o!C?LVx)X}@t zvlMf2sri`|aQWZOAxW8PyK>oxxzfEN;trN;HzW)lcVOv^z2)YW9b%_DZ78hh4LQZs zc#+4HiXOb%jD!$P*P zbHx?A`(Y1#u_253;3=b-r2j1mO%q5ZgKdq^vNq<9;E=dAWk*vKkGPE%63mcoC)V$t zn`3@-k$*-?$v9eJAFh}?H2dRYFmpDlT+~{%q$Wn{{O2p?BLShd&cF2kaI(p(c7l^V zR=G+tUBw|vaES2m@5AB?V{Ff=&eSFJB5PQJUeKhNx8$)4SFj(lNTc}NVmdfB4WGiv zfLl@r3OsEwBAZH%(M!8M>jKPID$QCstf%`ij*+SMk6iPvIo8D@-Es5AxS@k}Kz4Lm(4xr+(bVj!l@;t+l8Vvof@K1nod3e~wF z{~xQoj#PiPFJ^9!T55=skv_I>MbUzE`#-q^b{#=vC|>u|HNS8fLHEeq1KYKzi zafonB-eek7LCF5V9E<1U@S8Dv+s2?w5Ya@^k4wUb6ZFeE+$g%jw=*{7jD!3K7FNx% zxCxJBxA$T6702k#9CPy`<9a21bS3CF32)Am)I5!)%Gvw-)hjhNrVbkwMX0tdP5sIaJrQ=l<$Py&|!qW132pQCfS}Inu@3K-hEh_A`m}H!Gn1$?yRkc0cZxAFUG0`7obLX%JMR8P_y-pGQI%EY= z%_SA)Z`#Grk>^+8MBH;CrApJD z`n^#(+W*OQRyq%Wf8OwdwXT!l62{0E-|Uw2okHy8yKe8KUoRl$NCW?`@T8v ztB=z+hG`-w5*jlZ_ZmeZ+=7+P_&sJDr#Mv~5}0Tr>0hTL;lKnEE^|00NbF5=vaxB( zjHVc#hv@5y#^_aw=*`Cq-M8~dSqkMJ9Fh@=Jcy(&d!}5Rv|qhS6W<_6rl2He(`Xbe zy<7Q$WIBWDQdxaK-ouxEpdtrWIbKt-&w@n%rD5|M4TMRB;;dT5I*3e0?68;?jH9jh zfrhdftW|P5r;>4+?^}xMGH4jc#cf($)zkehK@yIMm86!k2So9qGQ>UonSGGlSz&&n zUHrza9xZo_RJ02?Bs+|ZJDLX2`$rNcb>L)g6l3VH`OSAM^lo*T-zP}Mlqvmjf>=+> zyOsA5B;E}%*%M=%D1s9~L~rG)_#z4@)8<;rA#r*ON)+e%Rp4UyN098L#L$wD!eFpa z)l8R8#>|buT(%5N9q3)s9)R2x=09SKJ?3&WZA$dB0 z>^9+i#Wyw|F99TYfA%EBv#rv4`&I;L9i?MPY5$x|y{hS&m_3H51S;XN(OP}M|5UQW z-|p!T`M#rsNXH8_jy1pi=Zb3SnD3L_U>b5JH;snQS84efm)*&R6+%s(6Tex+4b|F$#)(;9g{%b}#mR^6eog=1)gBStRO;b79gE1#B3Kapz) zab}1*_V~8kJY=6wbF5XJC-`+=SSloD=0LyXf7Y<~C_5(kk;SxRd>X#LpD3mHTpY=m zN1NnaO-nu0oQV&P5hl@*>neJ>|0XhV#Dvdt&CYou)Uw6p@H^y`lJ#Od5i(;^d(<>y06E`5) zI2l|fdD;zgs>`^MAn}KMaKq3<(l<-OHT5K4mTAhg2ACF+hdCr^8t4v?q}b+wbA1D% zJKhKK@wfY4?o=KO4`vnqj8rSm;ia_H6Y}tX6{OTf=MW?V6jyDX_UHfMW<4)|3bo8# z^|EAgo=bR73lNPA-}E|*fOh8NZV-xGy5sEmaWOcPK!NZ6<*`q z?4X9KRejRB^uwe&kGN2C%xKoSI_>`iEbyA-tgr6rcEgG+f^qRpE(n|5FA6`EJ4=41j7}?6vTo%Ni2)!$BU%ua5)JalOwb1r{SzkxMvL5z0eR-%W8ZhL`6a{6;t&@qePeb%Vm%cEM5<3cgtY@>k3j05Ott5O`ujRM7HfY{M^}Iup8z_}zxt_e8$O%itR451l&akFbZ!v1Ydgsv90ENK+3Xn}Xs`O7-CmP7KQ z)wE;+S#5u4$eH%luMfJ2Y+@H__TQ(gsZP5b#P?lU8~XKhXZJ#~my{#RU7}cDfp&7i z;dD4XNxyq5&6``rU)<{CIpGkT8G3$&EifZ3Ck7+cudM1Z$@K1d_$&oel_)W?E3;ZLpP1&~sDhqJ4h7L;fHTb@isit1 z_6AQXd(&dtFagYh^=PhPiacpUI#Orb z@%0MV2t^;&3yJYXrTMbfl=!n-9aoojhGN{$F;N28#{|jJuz5g(bte-p9YpeeS_X+2 zAUP?|yzX|fUNH|Sg<4itb-%$5zARl9^V}X|>U=mlBB;%~WkbP(eLnx{YUZD(W_SyS zD?(}mCPmotsVP~VDgTg&h<+_2anS@8Z43`dA1$L^OGJDiAr@%zHJ4ypvaJED)F57f#%~;wJ2)f`MGsdCi+4qGbg{9N*u~#5 zqLSH~tzxYIz^)X~Oa4CC^mP1xdRc11UU0Iys)r=g%JYB*Ojm+J-aQcCeXrT}4mD6D zbp0Hn_T9iS`P~NgU!IDIO}AnKmVuddk}>r-DusK>rc#QTx}n4F2$D?7+f>@qU00RD zVa(WxyK=2(FCwx*EFT{Z)j`-G8zWR@4!4TO-0G!uSe)dNAg*U4#r8BryTj(Q8l~;b z#EaL}=@|}3)Yj}4XXlx(-_3S=Sy?G^%Ic~X8f@3g=Cfn$*_hdw4;~!3ye#dejnVrd z|52icv8JlU-E-7_-Z)-z|3+dar!hLvl>c6be**1&l0Bz`%|# z44FEDXt^ZhHxkusA!7zZO`ffYXC>rfO}_YXEQYc-AiY(OwS?mfpSrKiA^OigOHoUz zg|qjB6S}By`TrTmXrX3(U@S?Dx}fBnhQ9tyRf{FlHF*Ta!vQ4y3Y+$1Jrseb$Mh~) zGc-a#VxLY5!b|z=#76d17E#A)i|P7_q>@>5+Yb%C^U&d%GqS5RTk4gjtP48q?jVQ| z_YdspZmP=SknG7d-?g9JEecaBT|c}(2;QMH6NJk3RqVC>;&Hd{#kzFd10(2#IExU~ z(3Ut9W~&=KTbT*zu)`A)Ao(NLb&Z=noM+y%hqdA~a|QNgQ`Ljq}22bQ%)zzDDvde?pMp2QksWmvP5n%{qDs=RZ(=p5k^PkM+B+%drF~ zc$fURT6o~&v~nHwo}>eFCrQ;SXsI)fRzsZkJAZmxP5Gv`acBEY_G#$duvMUe38 z`B25u6C_61`V(Due3Z{n?D{x|WQD~f)nolq%&J>YG#KL)?S(vG5SyX7<}~G;Y`13y zEy+f0iel;MZmv3pd_`03PD+trw~FG2mCA$fmz5}iv-#{_sWM-+Up(RVju;ccI|nK1 zxVUTtNbAS<*M!*>jm|C1lu(Sf;^sRth%B#mv;WfWO|fn-$|sGUmS%7=yhO^6iQkZ# zOps)h!};d>Pah=TR*SB=u72Ktsm>UVI2qJPH8 z=HHrYYE#am?Y63*S(p{5LpeqFoGO0;8=>|?4$+;WSX8B4^Fh%-CDaiIJ25_wl6L&J z+k4{}{L&9mqvp6(4p>ud+|KwQjNvICGW5Ak-x{~3GHjhu^|)JDL+)Glz1M=oz@C;l zRre7@3XIqvV&-e-X^TYDZRI+$j8lCO71oG{=V&=zXZL8WQps8$$DjzJ=b9p0+l}i9 zB35QG9jE;SXQq@ovXG7G(5gwX3c)zN3>|k1=VX6IZO*XeZ4Sv-`LH7$r^)7Wi>a)h=r61z z=IJk2^uKwe>;}#ENK>%1-3Axr<&Bm)1*w=zK>ye^wQuLr8s3eWi(iNfDUlMhNUG+BK1Rpg@JVXE3wxT(%l*MJyFHx5#Hvo z{N_bB-~67IB~@s^hVNNp;;|UpIoJEBX!@+&4?Cop!_pe_UsZ!ISc|-lpGIrNO8Bil zSk6sN)@QYAb2u(&T2(?^&H(AmSR|fm*QXIIkus&IXY-P(R};d|lJH5C$oepc<@0S7 z31wt;+=MiMPq-Z$3R*`sSeJZ+^wuJL?Xnz8dsLofHQiccI;Tq?OR!)`*s+-FNYwGJ zCSIBvPy6y}!lk(9=<=$C2*q4zJ`uIPA7G0)EMG+s^@;5vwJa&btj@6X0*A%iA1Ttt z{489LJ%A`4<@B(8UCe4w2PqPQU)loF^gik0+hI3)XG(n~cMg*8>?bq}u7 z5T|w);(J6YkxT7zd*J?vSkYj~#5p>g#g_A+@{8^MJ2@n!c**AFRd*X0>Xh@~7T-fXEF0*F%7Gt>Pnc~1R{MWLYr$=|^%)6H8}5=-yqWHa3B*;c2c z9J`aa7D0rc``i34MdZdtYo0~K2?^LYl^mklcKyYCw&ZrBQi=6!-cmK2`XrckbBIp$ zs%2om+UffVByj#Di+tQ( zO==rYh}|DV({5MK(fw76uystCfb(=?zb6ySj7a9s1tfzleAnWaYx|?}#P$HE z8mC2Am1>|TRqE{0dL&Y%{kK1;JN6$ANvzF&UC{paBr}3+J>B~uI`Qn~RFZ!JsTSVk*nXexM1a+Ix52~!7KYxxGHiWit{srz^qC(L(skTZhS8;^ zBA61$CV&rmTJ~3=1I^KuxQQ(!B`AG?D6FV}T+pVbo7b(RC%sdHQCLTLU0>9}Nt(Wi z*k~^#1#SLy5$Taesm3B!QCYE3LD@03Z`=Iu7CR3+=osR2dnpn8azfZG$HJ%W9 zB#4u&&_DKY)qQv~Sz7Echh$c#5zE9qSl;Bi2gp1zaY!Kl*+czVg<_qXg$0cLDVbap zxMgSSjJt&bkpkjm_fSKaz=y5&X+ih3ji3?;n8TnF&|B?C91<{sf*R*PEm>zN(r0}3 z8F}=cQ*O`2V>66hK^Vnz4f83Z7n0Y*mfz;s;QtX2-8Bl$SM_0n5eDapr@UBRxM2=g z?eVj}R}o8`7d4+;M359$`Vo-5y04f#ZwMXfVpGKtN4c2i) zC0I_Q8k+J`;@mcWXFhx6b}co{hxC}kRnrU~vX*fN)>r!m?@5t z;8FLDO}}(^2(4ca6_`)-VYG%DxSJXFYZ3-XA4GUhQk*B6eDq6C%c-hQWgvi&=(j}K zxJ7=vXF(;|t0tRu_iC_L_WTfRB0!|scr4^Z!g4%L^6KW)(_*UC_%$LGHJUH7h*!OU zCo@&g9r^X08yvr{U*gRT1$R)G?P)QK{n+HddXh_>BT0Y zwL=@nAvx{v!}Xq!xtnK~9pI2Wz&&Lk**_Zz>`6K+=8buG+AQ%nTcl}=5ixAF&kU-| zd7q=6ZngSrnmUXbF&p`NFfhd-uIKjTzS285+A?gUG>gPabDb9uQ_jenHX6`F#ROYWGasnBwp^k3@SlO zt?)~`p1POZQM7bxxX-^`(}qkWGJBsOLASD4^*xelR3aCbSWueXWVyLRzmP-nDpE9P zhV0Lf^m-HRCYeA_K9q$4$KFJ*;Yrw^>|)(~MVzjUZrg9071Vxc z@R0q}(;cfmfm7^EwL5ZIJZeEG^2QZQS|| zW$qIs8@QIdf(bPh%GS8$vR+1J9Lg8Jn=86}!HIRqj)?&hzk?Q&T^(gR7pC1Kif31) zh=kf@y@7-ndxm3D=klK2eDi}K0OycsAIQhTa0v9f6 ziho?K>DG4rA)Pgo^OJ4lkhE#W#)-jq+X0E>xt*02{g0DfF|iYztg3phWO^e`^ydpo zQ<|)5hmp)=@7`{EUNZd=C)W8_NV>hr+|j{C6tHnyS;)rbC4^Oy(3YZcui6Ms*bzwLtvTJs%q?SSaw3g?`Jb!s0(_Edkdd9LX8=^qkCRn^;MSAgUM zyOhW#I7bx!Tb1$6*8H#JKrx5tV~Pk`CwToW6fLa$Jz;safQI@B8Mr0M2(7|oi#RP| z{xB{Th8!JHk{*}#XLGvTclyvvrmA{yf?bSRo7itrErny!xS6NEoGD&PWJ8=xj;U2a zZ3D;X4o)_wAwov*!djuKU0p}FnuGFv zL>=mMsARXZ7bL+?(wV4cdy_!&|Jnj}>qqP_xgWOKYDw5lhA*3}ixV5H(QUTtZPMnr z_>AV=#Vz$agHF`Y;c-3P;{Zt!sOFtqv5VrNQzq5AW_M+5!?ELB{+sf&ucGd3k9hm| z^qpNscA8~=Li(CR;)uE5;Z&0XCKD?N;!855b5~(XMp1up$z0Lv^KGp|`Q^Cktult2 z#E>o|l`I5DwzWDqVO#c}vfIZY*+nn6PV^eFv1wJ?n7dGVuK?7Hz%DqPFFQiBEwPB+ zLgr1F2ZWTpWGcEJ@6WyC*BDIUT{Qo)XxH@Qm zu^B^UaQNW?|6~LA?71%cC$+*SZTgG4w3l*s*x&hB_Nq2b`?)@>x3l)3rFs&YlV4u_ z0OHAfz&{17!eoMER%VL%8iki6(?=YW-$T;#JWuu?K7j*rXtrTnBMI$1wt0na9^L4z z*{+n>#o31IInDPSr;>YujtLETCm^}J7n04?7&>{gDD19v<#na)(b;R1@uYzwTAb)cZ4;)aZOs5`N-b?k8?(;UPkt*y$lHUD`kHXOS_ zm(QPMyLpFJU{_#$y+FncZQmz}HnBkf(~Rmo12j~-F*k(?#ema@p|1Bj!yUSLAQ=Zn z4yk2o)FaNEkj=URgVSiMbx|rG9*|tiAzH_TGb=EsqH!4(wh9Yiyhu}I1wQuEIiQ>w zw0Z})gyfV%LcXIK6xMH{tlmIYJ-a(EMWj>j4gNkhux1Cl+h(21T{##OxLJ&v7cs9z z%rUGl#I4z((<|-?M%+_6J&zMaGpYv|mRST5{#6asJ$stP%6#!arWiLINit>tdD-nj zDV=-ecR^P(Y$BI8KRV>=hNev6HvdwcjjmTG8{+#Mqc1eAnM;F%C~=sC%H{dhP+#}( zr9aFexwp-DA`@VnpOQ>I4%M+fNdD%Ob3)c{G)&7;f;N@J&rP~Ly-{DW(^+n}&otO8 z8hAKy&rQLU`5tO^2u$WzhYZpI-X_vvNUC^ysOy5x(D%BOO}-bSJdZ4LpGUiQLceD^ zjge{QLc_YT7m{AL%o-+as&JJXwzK-wvOl7>jjgQA#~vF4s+nK?n`C;K^MD3!U(QL1 z!Z5U9GXx#2-!*`l& z=DI8^hLQrYN@rKpyT=;hzyd5_RhMRL;*cB)ij@sWEPJ{dWl2zW@T70a$Y#*iH)fjs zjppZJL6QZ=PLT0Suad~y$9m+9q@lbenI7Yi+ze(m$$BK!q67@jjXM4RfFB2p!ce=|@7b^u^SgDUK9^>svwLD!7n-`>kYv*!I;O<#ogD+;SlI5p4 zR#_CqwVvLsdZZT;yvkS0WxkC=VoTT(eUJ<;kQ?R&ULr`IuFf&s&k-ag z7~3G-b+`$Xp_=-MsSMuU{j~MMIfQuGSL};8D>aN`oRcLT@`<6Qn_BgCx)g7)o@tno zN)H|78_jodBRQ4LY2sN8-q{2GrauAGcRke$mj>R2DLO4LKDR!t;|1{G)qrvf< zWD?1b#eNS_{R3fis(=<{zZ|^8z&3Zxno2srU1SJjH~7Do%}FD$ybq!sLG!}7038sm zs?H>1v6pJFQ`Qc1KiLufL${|Hw#mA1dmdrx@pylokg=!3xG+r|U^wq49!C&u52xt0 z?=fLdrL)BFDmFX|?>CO|RKgk`dtnSX*{bRz1QCt%yeM--O?QeyWC$?HdPQ~?71ATT zdDy1b3%!A#D3Mg0VYAedMo+h3(f38@7eJI_$eR=P{|`}3LCV@SH~a=+vh=vy7-CTCC&q|ZC*OMrh7P+uh^LDBS8QN{4K?)NI7D{ET|La?Yt=XCj&1ca z4p(~5=8Pp|Ky(|o)SYR<^^I!J(XG{1CQMD(#Dt@phyAC+`28u<9GWB}N8@*rU+h@# z{$V3Y%V3-2e7-py7f+>?yjwThrq>|W__eHF61T0ImGNCXO-TG`bz9oGuGxkuWmAo~-CgXtsL&!(;hyi)Aonl3E-&OptU`e-7Ogo$I3?DcY%d@ANDj#?&rjel{s$JKIL>ik{<6W=b`!&PMn7n{wr zKQ0CPAX!m>TC2#L1PPzXGZxcp#M9lAb@O#i?(&ZGDh>(iSS)lH1e-}z!WzD07jQ`K zwqfzIHAVjSFpMtm9o@R6k!;slHZgTkT=|_ex&FAJAPr^sdjEm{<7Bfu-++@Ht?m&8 zU!n7vgl$)V^1o`>V+b$yKN_h8D>Mdg#g=xDWy*sZA+P3ZAO;5~4Ja$|ewcir(pIp#XzmtOg= zTI$2g+l{BwFvaA11bHpKzbs7q`ZH#FlOUS%wcPI-?m76JhowgQERT;xKe?mTU*l1n z1g?s*ZiKQ@rpTmPOv&+v?D>js=aM|n6H!ajYYd%WRCKeeWk-^8INT=1#QzVG)rMgv zgM8Z2n6RtB9BlXR^r64cQQB;;TVRnBMAzx&^C*c-9ZnFPi#;)ty4&=L67&#`hH{E zjc3znQ?2S_WUur>B5bI}9!UN!dzvZmX6)s5>GVRCDf@qFvZrdr3X zU9MMU=YP0LHYU&A7WGW=`j2u>=CfOL^0HuPqA8|#aH@fp+*EEJkPw}mY63Cap9SoN zHqVEYuq@UH71qZsr_De26*}8NE=08+@*faAE19m~bbbxT1vg4M7_#TJkm#8g} zCcWNECH|U{3OurQW*?R0kF>9E3;nIjqsuI-{5boSMi}(?&uqy4r7ie$8iYaihq7Zw zg7*FET(-0@(`VJ767@&Ce6A=#{vuK`zM%_Qwgp|;;f;~^C|h0 z{WaO;mRFGfXW{bxGMz1*ES%jQyOqeqy^MT|v{2Usv5YKnkj*D5aR+Sf`G%{7HVh4F zpU$o)-y$ow_nT{YMV|46KS!q#5Bd22Ffz-`Z^6j=*ZhjJz75l(hV&+-`X{mf)y#;! zWuE+)B%u7^wYaq-gg4^hEI&dz*gJi~=FcSU;uSiZ+dOb*Uh*l~f}^zF?B!%hJx#u^ zIg?XO|C;ZKVbxyLM>Q9Wv|P{@mi*=^WtPwULcD-R9PoHAXy~^j)fRX;4G+###Is=zdsq@8 zhW+)pbszaBXxyO)>05WoMm8NW~Efop++55oDFvmFQq%E^=sTVHDPodh zg?4Ak5bU~3`4_G5rD@{Da{}5`0GbJ#pJ!q7=N7 z4d7$mE$eB9^O(hSG)b2FUP3waaGq<5&7Wy#dnxu!$Q>t02$i1hi8Uir71mP2Q{Rh; zab%=vS!+hNUp%W!3K_yXT=IrJ-pd=aI$HxP)9~PIjEn!U7da$lOxQwgIMfxg??UM_%})B(Ue3KIjS=oIYZbX*?qMU@aoDa-W28r&dp{N z|4%I|tUnBHHnrw!Q7{ZUYUMWfLDb0w&ZCl`8;;t9ysHnQJzTeWTQ)#VfM~>J^qx<2 zJLo_AP@ertn;xMVV`XXRzXs*-L!ftHG!^^c%xc43*9Vd74AWVy8U6j@_%iE6L%g-n z=8W4iJo@g&?D?(1HFRQSwiDCi#>`V3q7s}rMvAcdUpeDU9`_Vtrx{sV>i9U+V@xHo z36tf^Uga1ep{{F~$uFm&C^^I-I*9Dl za2fp7zX7y) z*x8(H@XH5Nz^I=5tZ# zZ?IX0v?0*TDi4xc#uiCJ5xTP^Pax+I6;z9@00!K(e5;!r7j)p9AD;ubJ62xX3aiaq_?v-I3zd# z z9?dj=Gu!fzBrL%Ber^P>nCnFg5Q_tLQyXDLK5*6^%PGJnEO{8XxV~cc%gR zYz23uIGH>eHhZIJC}VoA7E@9e%0@kL2;;37y}!4C9KDz&rT=+&AU+)4+lr~Y*W75^zYz^UYO$y8y-u#+d?T7do!Op5bt zXYF^JRA6#{&5kn5DT}EqVO^4N{9C7}AcmBl#kQAQK_!zD*7b4A89|Jbp85wDE(c_9 zATBP2=%XzWart4@72wm81W8p$SBfqp2w&%rgi8L$$f{FYj)0RrThlEH_uEADq5A(A zoyas_HitbR34h6Kd)&IeS2tn#h31BP*!z4F9z}ZGrSxPZUSHePe@C9b*mjzWv22RB zutl-tT7*3#Co$=Thi!U(Vk)t*ueJ6@B#lR`HEu%Pr^rJwATu@JbpdBouYyf zMTMvA*_!)DSQIP!ywD80WttxOl$zwIUy`s%J}%*WXYYhom589!)%*ZIO-f71r4nlST{4zSKQ;HAUabGY-fY-3VOykVDc{&nM3ji-rYwvpV7?O z9Ye7;>PlIElBAsRLCo<*)KljR*&5-NSxZ#osURikQx3_EKGWwTuxT7iWnXcM3|Tgo z7@&2g*O=1i9n;Q++VLmJ!R18fC0!g6m_$1X65}`7|9BijNbiXH^4pz0f@E#Y_2qW6 zRs23-ySu=0qu%cWGN{y}T>k%8GNlr((gYhFR9bjF@i-32PFZbB#iiAf>B>Ck;i%v3 zcfQ8GBvzaLW?by2D^vd^9gceb-3!U~nl@2z*(Y3XNXt1S|3tmuWEkfHNvI@9*j`>$ zogGWNoI~=ooE|Q>Y_^yjT>m(%2RxH04AmlI{y?A2O>s`vN*osJ4>H*fd0&K$H_%pb z7uDYxACrPxJJD~8kl|?**?kKPbHt;yl5e3%OvlCSzwjT2G95^6X#L^BQ%p8@n>WbU0EE>#tKHgB()Rc;lm!r6t=rUEHNVVEQy zajXv#lo~Y0Evd0VybT|)+c+j`<(&QrOFye=9toFZz^^>aA$eGqVUg!isWyI+vuG!> zE&qp;z5dQoFtYBN&;B1%-vQoK)&GBUZ|=?a-0Y;yZJX6J?JcEA%TSwwG#w}kiu#HO zqJm0L!GQ}m0Yn+1hzxO{2qGYE+#oJ+Q58{!0~K(-`r^ic+W+T!fWN=z$pg(za_>3k zbG~~V2pgQ|V(AYa5H^M1E1lh@YoMC{}Q*Lp+wPCCqgDlPwE z6efz?Edat8Rc0}DZ4*PpWZt!7#{q~+L^aOt!u0X&^&ge}CldOKH-S}eYV#~dI)L9- z;|Fz|ah(1J3XariuV-f_Px$Xve4!Y=ok|X|GWgj`wE(1WLMVLNNl3-m(eE`~c{L}7 zSPJqzu(VS{$`2BvRa9mog^9$8aGZP zft7y;MGm)6x}e;{Dq+4l;=fgv+K&;QCd-p%{fVasw>tjq+Vdk*%@x9#w;cCNs=)(( zu5?~BU4#7pqbNi_OaI^iCfZBV;8;rONzM8?G?S60-?waGr61W|(I&9ewJ>XiB&RnR z5)2KH{Mb+7Q;qU3P`7J2G-dg_i{g&*VUh5e9lSwfmU^QlG6Ae`1E}T*Nj1Mh=Phz< z6D6?>F4FH&($3R>?DE2-J8eaq~ZVOhhI>HR;cmVueY@;tEOHVPN{gQ$~T z;K?A9&X4`B=`e<)^|ED5we)GFte4{+366dG@6eTU%XLb|9LRou9&`oY(tjPngz#7{ z^#O(@Ss%gBtMKXBqO8^``l(_5KTzRZcN zCAJ+@mA{qTY%L{S&F*&%WsUTi|H1~QHhjAl75Jm}A#4{3*X#eve16CPz~U8AoY^U1 z(ej^`kBk6Eeg&k7+pWI!D@66+lvDM4T049J!gP5Atg6(9zOc4j~!|0#2A?IiQ5JTc@xvIYt30q;yg;>h< zr5HU!@)rmV7EoYzxi zOfHt(?A$~C)ytgIe*iZtYuSu*+ytVx^c#6A=7IBuyQILGq2upDy(Qi~2vNF`7wQR0 z)a117fGF$oX52rNV%~5isg?+D&N+||fL}eFRbKr6lvCVM28>wXBt`lHs}cjemFvRt zV;c^aA8{UPP9Bi)0xg^TD5e?b#HW(6x6a6i}eLEna9>Ebrcb$ zCfs|Ega~($%AxfnRiGXR5Pe(=9Fx&7LNjG8H@DM$x>{!$gEP(>OZST;hG=PtHy zwLw{E&X^Q0Rc{GVaWh$UmV2M!SkIYc$=-alXA?etgF^KOLeu-n28#l2mTBo!9lJ&N zP)q%p%K1*v?zl0h^|D+8dF1>$UP7{(qVsa@cMQir`Bi%G?%k%H zCL+(|)Z$8A`A^pMc~*aotr;vDxLKxUJqz*tMrj9OH3xOW7zPz0W=cY`M3`?ek1r&~ zGbAk%lAl??Fw4Cu!Jy-HRy+LU;Tx&Ef%BWJADL>j(?h}a!y{dtnU)vP4L?_O9&4Fz zuwE5?D5NwD@cgnhcprIAX?DGDsrR$O=$aPvJU*GDqrNp%>WvP?@we`C3h9~j?f^qUVt@?FaHdAk#ZlZ$&64PcT#h{+v2 z@Kyg7X-Hyv?R9uyvNeLyGid$;wnd>{I#WhhXt&G(B&{u*RL4+`oEQG2%8gm<@$f&A zN~WVyCdXU;SROeKyC@;KgJSPA(Hn-t+gQ|305gkthYX9hZPN}Fftk%3Ao)5&FiW4} zs#x$gK+@WBrCkF^{!1~H^#tp1b{T<6=s3GO-tLk9h*w~rNl5w~l=*l#9((ISD*3UU z8QDS((crpuVYedgqKyjq7Y#>AOlu3;tUk+nS>X+Vf1|I5lnn#iXK(edB-fkL!0p%I zxiaHGpT=dw8eiY4jpQiU0Z6{fC{WAFY#oZj>OMb5By=Z988_d_@kbxPr|4eC1+YQtjHRtey6B`af^s|KMH46VP=e*xgO!m?w3lVM9NYH{dR6y7r z2hRDCH2(%yIF~ZjoYS&Vbvz6CkFTt!vKRTo@Sl~=;d8X9y5kkW&m<9Cm%;L&0WZJZ zPS)W$<5k0fGXqb~s3PL~$mZb34#I-fu0qJFL4TrNf2N#1;qL>Ib6T$8FkJpEs>)`a zr)rK{yZL^#W78te4RZE_MKSew=FIzbXL`J2pIy;|kFOAj5pT#b54%HpFEM~b|I!Nw z8V^wNgeFF^vW`C;8}g4}NX}__9*teOLu{ctTO-l0L&|%00+2jK;(BS8^=k0y8FNn1 zzgf1KTFi`OKh+eq@~mfP(z(@kzlADcZWUp@NY)r$j_CH<@D4j#9!3MXb6SjA2s*(-Kh1cjc0ml*AIjuQ5MS4(}waU2XB&NBiel< zEAfT5IH#m9s3x2(@{R*0XWa@+u5MY6I6t2VqCHO$na&Z0%|GW>ZHn$#D*(FoHkCXf zlP-7L*j8-w_sSXIWZ?#VXvPf-_FbDbjK7FgvSqq*1>8vW=HulgyKw=Mt6Ta=DtVJC zU&-i$iyA5?VH<{TifAu0R@RAvqpK@)bHEtK&$hpskE=-U(v{LaOdq!$fJ9r_AI}Ld zr|#XG@CEAvc6@2$LV-TRYr8tHZdr4Xtd10g^E3MIOeI(Y_bp_8#!zYXraIMf%_#=M zU$RD^U1G)$Vxm2liS0`2Uq~_;RRiL(wonLF$$(^QZQwUsjfN2!ySn8EyK$xNINhYv zE#ob1|lzkrj?ZrPwZ4mWwkFHn4ChS|9)IoUMb(ZAnR_aQO1K{hvI({8EcMnPcG}^1 zTj1$2*>tx;cV=AMStUCT!Y0byp{>U#(w$?T(ap8Ifht(o%x-D1jfp(N!ZDV1{{gMJ z@82nHvh9Yfxw5%vARrn$z{v_T86*E1ioVh0!lr&T%VKM41h?ni^&Da8`r?m=Ws=Qs z2~pRcr7f>O{>wJ=YbgFCFIe~wDgP%+Eg3(!okI6Yoxzq#EU!>J+pKRi9BHel-(ZEx z4r1~l;ekvx-7NR8ER&7YjRDEhmTNenD1QT0XD$CRsOw-zMlXq=RXgwhf~aV*0w^wU zasGNEAi2nPeFj;RGly8_-7=)mxXaC>C%>}TGwfs;{j1XoMc(?K=d-aFQr{$>kuwK3s0L>65{k&fMLBU zA=yr)H|AXH498il;w7((;C>9rHo{wm3;x{r(0fA9pAExScCfeyoBT@2??mA zj4gHT0rHPU>I3}W5PW$5C|M_T7;hPla?3s0DyfKIh68XNrZpg0#3rFRJL{BG!gKE0 z@pQ{*cJk#PBP(hJPS%w@93sj;9&zoL_h*Wlj1^pro-7iQ(x^Dyb|FMHD@TV~!8;`+ zXB9n4(~)I2+0I)jHa2Hel~J;emFP=CzVC*COrCBr4Rv2TUrLLrAF|GPSUG+WSdBYm zcxLy<^R;QhJ=SvH74&T!1EHh+$hs!asKT;lWN3>tT=4egYWN2}$JDJSs61t1A4DIo z4I=)Rj4>`xw~VokA)4a`;Y0fJ`;^2_a37;etFm3FoB#=-@9KBF-pqX59ER|3mT`ym zhGSR*>g^npcpoz?$Frk^VYy3M>Vu@sKm4$N)v`sI-@wc^wroKD_0P;rv}F|8k^!n5 zo59=bbVokVw^~I0qD+?gFRS(1E#w*7&H^WDxyD=maD;^w@{m3xcUK2O(@L3TT$3>$ zE*Fcr`VBB`Z277N%q0IN#j32}_b6QMhWqB9jEE-4nk zV+WkF&8`+Je3ukB6FkbcBg-zgwd*PTU=wPTf_>_kOfG4kGL#qEdE~z` z4Hp{1N?)!BbbAf=m?L<_t`^$amVZ&uw@PL$Mg#^W<1Z=8tj>y0lFaeoTUt?#Rj}@* ziW+v;Mb}AdCLS*BTC=fbrY%m;9OnyfcT3&QP6XUI47E(R-LeF{aEKNBj+hDKHB3VE zCIx*t^CeR18$?-#Ci8;vx}L*oVPD?=>zO>X{TOxa`Lt!7>Zq37>^>?xf_;zS&nuk{ zTZ5*&tc3^p9;41r*dfdE9wKos3k5sd)!TKY&T=k9_CmSq z^c8%!t{tDYJiszHznRL5hgk0aB5jJtlz$@PYL+^{o7AnZW&U9(-Opf1{86#kHr~~h zetn#StnjhCblOCZGI9XayuwWsJ|#zb8TB%0XjZ=>Ul9SFGthUa>Yrf8>#(ZxsV&80!l?2&xS|L^z5T?b{w8xj(zNfWqc(wcW5?iqE+ zP;htFls|15Wz%5fubSaDPOK^5E|{WTr46;k&AL*N(@(JU-`NGn3wEc3 z3_P2-4vp@*ENE2wj(gH*b4c9V-~F-_Kc8kO6bY`Ako?I4exi0S>3?(KUwBKUv&wctbG}+? z&L5Kh3JKAx(hstdd=GYb))(11;d&|K@-XkzVztUL@~a&+_sD_H&+2!V3*!LU82JlW z)5(7*5B)|a+fMd(=3k9?KjBOOYoLf?mG&CyQ)~M*Vx0=^dXnt_@-Ey(gW(JI97O+OF`H}%qe|Auci83t zoMt0{KgW#<%UQV&|B=#Cwt3S*jGm&>cV+78*Ie_7R1AM(vsg_^4N{ge=9EbEQ(3&a zl?zMyB4hCDM(17iu09p&CpL_k3P95FsH7S|;?Ej&S;wYI=a)7ClBCSq`j~vhGbAP- z*9LJy$OFVRtS{+^$@Xu_DrSU9&RMJ7PsUi=xJ{00Z^nI>wE2&zRl0Um7LS zj;vUh3l!67lSBU3Z5+2)k?+!#wX#JoG82w%(9aDkPt|GP+wlv?*dkMWUBa`R*?8gD zF})nM6&J7#$L@?V5|T~{3F3^AYVSn@!-#R6-UPIx)9QHrlZP@U75N^v`&iBK7u%+Q zq#pf4Fr>dyT0h$a*{qW*xsHOU6~v7KiuNE;Zy|RbkpQ>wS_~e9p}j!y7AM{Dvp#4xHMIOY2$5=0D!84Sr(# zmQfUD?#sIKXQ9WkjtWU7faFGG$l4ynA_6%zkTqvZNZM=B39}&|sxjvc3~ZxnN6vI; z4i7uu^Djp#R!UQD8=q*beam%^8PI>D5ydY8Q7+}vtCS&#J98Ipb5^u=?l{$-b=r` zo{;Ll+t%)DD*mgJEt&Q=I9YrCMb+^Hx7L8_tX$d4ac;)DfmO1?wYp=vJR0f2gAhH# z!e;b1vb)=2gRY$=57PdU$q@h+zM;TLb`V=9m{Xgw{@HBIxK6B9yLPnazhd4n`eWoD zug=jws@h))o7W?W%@U&*s3-36wV`g!V$_XY6}V*@5RH=&)K4ieLqa6iH+&sM1grE` zRCJqYl}`)d%TUSM^WZ_dYk0Hu5V6B7WolSi#i5154dio6`aezhileeR^1pLq08Qat zGA^~N@q?TBsHfhWWMLWnZCld#ne`CW^khRes&{8j)*Qy!e(m|AY_k;&pxMdA5TQ(S zKh?C_o|%$i;C8Dh@+7BOYrP~yA5wT|&Tt5&)>4ZzEqzJ^t_R*4+gWw&i{Tt%X+PAv zY*w4mf?;U>In{9@2f(!+2C~b1Lo=QirItKVcMRYK)1D!BhO4Bs52Q*qjlzdAB#tvo z$KjTimW&LaZl%C5+Ye)AezUW`Wy~lSpno24*N&n2XBd;s&1^jv>t98h@*ROiBN(E5}GkW>DnRjLs#d%4pmU!+x?IXTlq6l}lJooC(USpv4q;az|B}?g- zqXAZMmxSaQcwhOXJ?lQII=2b+Uhd`Hv2w|NVRXe9nm^oj_X8tib&VmpmzO^LV@kW- z_8gQg+S8Qk$JdLRw;O)yUr!NVf7i#POcW@O^G%B&q>#dJHt=5W`#6q#v&?6+M)H7x zIX3@1x*khTmNgu4%RsTms}hoHbVsa)k+_`#2w&rmH)}zc+H8tm%B;HZqo~9Lzv9pe zsHCWECig!zeyH#N%ek_a_c{*Y?T2J+{+?1ievN7 z>B`6Ql#3lyUWT%EpvNQYeHD3z$fX}HqAAP!plhpyST%(m0;3oS6Z&g5imylO#6t5w4mUnbbibWXKhP4*u4XItagyfv>fOcbveoU3(Zu{4^>7e;p&?mUVMUU0S}95ABTktqOxKmg+~`SLOr@iw zS^oidiS<85VYNSPlrf*78692h_rvs)WM;56sx4zmR+Lw0bt|Bj&B;HhI<#uOk!?6) zMN8kE@$M%boW=1n8^17LVBj+8tmloO-Au`|Y|kXHf1&lTXcsSk8rLr)-#;}W=m3>D zRJ8_o^1cA6ftk(8pDdZ#r_}AtoM)e^9s(U8>v$*P+rf3V)?~rK*?UOYSmX`Y=#Wlk z6y7~5R}*Zqroo9`2l*42bPOXkPzsp$$p3h~XHF;-90geBFy;JF!^Hg&rC`VY0n?oI zSoahv*&`+8Wum0Fg#e_Z?hKHgc0Os>OD0D-*s(!$#$x*$+-xig{uFBo1=2a!D9g83 z48?-Cv4EMAf4QCjNjuvi42d_3g$chaApzxdmoA`(C_Go@KD@>f*?$KmtNQDmx*is0 zBrE1e+#A`1(0-Ge@>1LYd4gFZ2xf-ockNl0hs}QyXHjS=Y*1x%W!6}KfK=3ld@dl) zgu;!n<+KYD0r*WmTO2;kuC*&2k7xLAcwL)mi5SS^BerNyTqCo|W$Tja2bu)^(w( zJlqWf43iN%i|gU6n80SF1)*RQ3z%hjI8g4bVQ_a4zF63&Iqqq|z}!p8=#*@E5kp@< zIQ~(o_!q}lsTWDmmp5Tu3Y(J-=oZU$rG?cp>rpB>UmCKO8N4H-E2C|NQpZ@!(bb5#L1>Jd~a4*fcmT)+ciL!_U z^ZncmUU)p;ExFl`|A(8=MH;x-v#bOBM>;+#86uEC;WY`-)w=pRxBmiNvLcH=W^?Kq zph!-&#T6JMU*y-r(gnSgOtM?+k^8jVkNve3sR+aW%|tKgSZm{@fBq*;Nl5c!^wx z+rIrSJY0Q(dd=V@E|ASz`9IQF`uv|1z6=e=RMpww{R>?mEv;7_9*XQ3_G2u?SJ1XD zBYvnbP`e1n*G$Q0kjZd#gYzoYv8_%YmNhOU^>g0q)^2oX&KgTYuFHy}qFtSD<-vna zt0{S8pt8TNVOLl&d9%1@k#7w(!tj!3xBVS*`FbKEB{%8-d%HeS&wB%@MA;_it8mO11ISvOG56Zz^M|F&-nx@ z|5AiP?L%MGwSB@nGOMj&MV86tCK5~ShJ_f4Qur!kx(-0HGrwAOlrl37MHmuHA^f<6 zr0k1R)QszI8yRnspnh87^ zknGI=BO!T}%DU&o@2VPU5Z7eXdQ0ykA=yN=_`z~gN*k2LnZTFK$VTJtpUQIpJ|Oog z4bIEh<%!WX7E#DH*8UF`?I#K!&5W>c%P6E`>}25*stMmPQ2B&nbxrQ?!l;PElDH>O z@FjVQ@OuPhmbs=h5V|{_>0)4cSf;j5unYzGF!8HwoX(mVN|_ z{GIvEhN3g0IbLJ`<^fEe%FxRa5*V2ITKoc=3m;*u@GWAm`o~hJ#`Zq1LoB<@tok;W zI4~r&qV!bT2hNF6#IuC17`QmU`Cql{(hrd8tPPUy=hc=sg!pf^$9P7RZx%M?Y zk!LCKQcmnLpci0Wppx_O@W(oyb?>*Sd}dK58otFR7g%$t1! z=EoVsPV%2>hrwo?Cj5JaKXKrMl>gNFxavrm?rZD<6x6$O%0Nrmz+y(bMt6S5f>2vY znUk6r(K5EQ5S6LV+TKxyHdvaaxbhyWiduyb57?po;Uc_!iW;AnzR<26)apoA1Cp01 zwYpvWs;cLkuJ`JL#VX6Ar?GP_$$4NVDfN~yH|zhZLa#_C5iWa6Lh=}SdswFfk_)Y)p(#L|0K!|u{^)=2@?=5vDQa8sEj)mJQyG3ZYWhj*t7}KBb#GM> zgphxgsxNQ%{HCfG3HxTtkKpqkRSbz!RN^)_5|`!~4LYbKl#YT*o|2n;DfyC?bv|>l zLOfk{F@K&8Io9QD6Lkb(-1qk z7?Ox(KAv$soYK0bk-MVQNJwrZgsFLLkRdoUotjS-r=kD*d%9z+K0{cMsQ9z$cFl3>e_T_zF4aHT|0WTF5x@n zpP|%89qzvwA}gL1jc9Qt4a_d-&74I@0QQ}g?X#POO#x}*?@71N3<@Nz@CC4cSTYsP zqtHnbq8AxDWD6*wcn0Kuk5&kq*^-leNwE)_^uNQ(F>J`X?3O+l|>NbQKS&vp^R#j<^1naO2k!9&t zRxds&g$*$JQ<~)W5bD60lMuUQ3iGM_Lg_U*RroSi$u4rW&CBA`v&anFrBKNxpqZH^ zKBFdF?Ap`O`WSkJ3(w=WH;l(170L>~BO$p2k+L*TWDS*7HRJq<5vH%vWgO~v4sWs-_g28%KxXS?5lR;7gdFoSDx|ov0OK? zT8a7~SkLe!z(3)-HS3Y`zkuN7XA+Wo$kSkX#;fZ0e2&WK;+KZ?BU|?B%5N zlEP&d`~zRgiiAaI@5ZnkcbV`VZkhk3NMs&I>z0wIu>Et{Qg`Jn*KTU-$SPfXPHu(F zpIT*JZkzj=*|C=RrqYSRnk!)QpDVf9om4WsSs874zZbMB>-dH$KCUNZ7Bom6gnJuu zbW-_}{_dYu^&GRrn-zU5LS6}0;8*E!LjnA` zjpB!l?-Qw(y;nq=PO0E7;*7PzrF_IJFUfd{zRR|VwLjSQfUX{OMnzZW$*nJdkxEJl zh{Tc2SlZ;T+2GE4xclf6?$nKRjIyg)Db~Nw>L+G>M;??f8)bvi9h4x>{L;F(&xKW1 zG`fwFxTN4JXwc4JRrzG#Qb=iPf8K%&3*HVvw3aEwj{(2VNNY=Q7YT5NZHvM}D*xOj ze7aI@+@DF?J+~2GgOR1#LD;(^WIXgusyQ-ieD?pDS@DL`Px!zMZZ@tJewmDLJz~3j zSO69vg>q@hUWv-3G{Dv#qOwlb0SdQe=%Ea93ak(6T^|_ED-M+QYF}h9675WKy0a)r zQ(XOdoU14;``&JMxD*CMk-LWD8@ zmEr!6F#nu~+H?=PC9>nK@FMlFvhe#)YF&j~zbf}sn~Z~y1VyhUS?2^@sh4WmO;q|G zhph?|MdJ#KXs`>PrlLcs#|< zl~nUJm8;Fh65Uai9o^MAsdX)~Ya}GwsbptPUyh+6Lk9T)MWUOy@Iw2AeAUe~la$}G z{+BY=l_^|g_BEE(yxuz~nBy=WvTKJ-jZdR)VWFG%S?u?p)Ve(FN@|XBHvh0c z>ThMoP57~ckepoYzGk4=*U+p!49O;@8vpVl1$NeWfC<_Y$p;o1r6X;ka1FJ?aGCBF z7>M-}9kMHfs_1Lifs@Uk(D7MxoHQ1vF?(y6 zh~8pXuhX^fh3lAXD~N|%hOAuaudocnIw@xLq% zC7a7?+283>#DAcrC--#F{k)sqRtBBu#3Kz%xxZ2QaXHtu&@CGD2eQU=wg_0jyvkJ9 z`&}w&laM@w8YHD~J@u_*-6HxGMFwWI^SL4h4@nD9$+2v_^aUghm?IKLne_#*=Dn*u zcz#nKL#@j3jmoc5tH00OVxhi+JL@RDFZx0wdd3RgWu0ik&Zmy(>h~d!uEnrV=gf z{nAi+vU0K?qr&=(-Ym3m+5*{JDWhtu$bKTr6X@Epymf7rNTrplsmx=C5G}h{rpNph zam{0DvZ_VdCARk&UER~{ZOR&NN{HUqmE)x5{1k;+nq7csO{R!%hbL3zJ(82XM^#_s z0?<5%WL;gIcnEZ=^obbK4zdFM#Y#;%&vboN?^;D}kvuea;*>Ya8BF?_ob^%v z2wUFaXHx3zDeqOfVwxhU6e zl;!*`LQ_+0yuVC6$JimnM1L0!Bm=)8A=w1_`;9{d5L2P?IVKyytUtVhO5f+TvOcEB ztek*-HjN=!!cKA>pd4%(nOW(hYMYR;#Smd@b%Zi;N`a6e3nZMpVk+&2qX zFpY_6EBSW4XH%$$g=A*soD^IU@fk%*I@l!_ol4OxCuIVYHLcgCu-1idsxT68x%vm2 z9cWy%Jf&Wp3S6cuzev{KXs8pK>3mBZ*&U1pasR+z+jq60uV$f@+>UdUBqXI~;Cb7< z5Xsrnd9sR*{4s-^vUge^g-VukG5tpjbxeQW*L$ejHJ0ZBFqSHgP9k;Da|A=u+jQZ$ znmZ}}PgQ!ip;WTtn<0tG{v=UTc+x#?KrBOU?ps-p#fk!wcUn(O1=H!i(Ym{ivx|3Rv-UH@Pd)%qn(L{E~LuQIA>X z(yXv5DJ-evi5l+z*!xN5@rgoy6YL=xR!&Ec|{@*P3@)N2Gi~O|3A6 z46N0Mo1M*8$-^n<$*CZWmp3Kr&lu`eP3jOUw4yuk^Us9Pvfbki=Xeg@FqK>(Gg-gl zNDGG`noN2A=|URze3r6@|I5ilMF5;^7jv?hOsa?)`?*qhAJtrD`6uY=GCm?s^BDdn zh7O({R7pA>mW5rP8A>^;$^4U$#Zi@7skvaB$4MXLWJ=2VVwV5AS{vnNyOm1c=8aew zF0!^&@&P$p`8xK0>TuhCHYz%EaA<^oBXfYB)wzqQW=)zsWk^)K;t2Xpb6g_IQLA%DkxE>302K-6*3TX8+ev|w zZfDk8&AI;ABb*Qhh?Y^XPBuDQS;=d+kYb~GE5HX(nwH(Ry4LJ!?VIwKpqssjJj@fR z$B+A2rO%}FJ`$p*Ia;6rqT8GGAyy<`k3H&tut<@8^>n$R&SjTi@@>?-%kq|TGl}Qi zhKz#kfFWP!Bq1BRbOCLT&g=R;Zv0~GD2(H8Ir6>UTBrw zPUX`M6Fbm$Q93DcJ!biS$>{KT-~lthe{`uy-3V{;0Zz8J)yo{Ku$oH8*?|SB_P&V0 zx9|=HN>Z4Zbs!FERYW@ZPNhNX&< zlX9NLFqy%UJNL4dyg40X`rkw)>)YMGXpVZz*`6`s?mS5rIDJ8pPf@u_h~VmzvObxi z%#dtieWEuC)Z~D*J1cqHAiv>%d_B60B0ab>8|wS_ww9(sA#~gor5A7jhankYg+59- zy{XWZx>67!etw;yE^1arS>g4(YyHc~|6#pzo}r$>VW8w2C<%~cW3Xa(99X|0?TwXm zTnkw89{=BT0o7%Y<{XX)Vbxh6(166SE67ASt5H6xY09l4)5o_J>l<}Tgtt#Ug z66-pue4AYh(GQ4qO_VBitufo8sj@K0uS%QGlvQL*@L^gQ<*Bl(!Ngg`)aniO@Mf%J z0oh-Gfd<#+|HI5ij17UA zCEDPc*&x4${D(RzZ$6Rq=h;W&kD0=Eb;dQHs_`kfS&xIInaB15 z4Hq^rOrvM&${P$2!UN^4QfKMfk!VY&Fs}Rts{E+NJ4;os5qyj1$QNh$toNzHS<9Md zE8A^_H_(3Z|ysH(DYRZE`%*+rB%tzCJK>J(J744#EIJ!vPkugs`*t}#u!_j*cbLr6!smjnw zmOs`FWWOl&vX6P&6zA*F81l0MiJw4kVQj3m4s@)_zE zOd{bOXu#5-Tm+(HOUvsw+#_Ttv0emMWL&pXqEPMl2z`BJ2^wxz+KUxTA1ltaH|okA zav@REzg58so%uL{?TR<#+NVEbS`y~?%3g*VA} zBo0FbM3S2=B=4eT9Xh~wGRVH1yd9EsekcElIS+~p{>}oDo^9Y}L(}XnJB8BI?14DR z{9>w`i?(89KFe+)G>i(5wbjcF#~ZzjYqEiNnYUm|p#O^GW-ACgx$uap^sHpWXHn@{ z%$B1+QOMJ*F4oZ*t7n@?8a~a@is%3n-2uwkL#fA-+C*I$E-44c0lp?HsHgA~{9jQZ zmvOyqXz%i-O~RKUf2)>4d{w-L>t)OscH7-OrUUs9r#&OZ=jOfP}NTE z-O@XLx(L=3?OxXy$`3hbzpOc!+q+;{w5w~(DFaQon@(vKt5l`55;Se0DsTZSm{`&@ z%5xX%XuEhso0-(X&FVxY27eHe@TXL9Si%cP4wIU4rJ>%CWA^`3*8C@)y^4H}M$EsU zK;)zU^V5t8=tUbNxhcGtd#Z5>anE6IWzEa`{i~J@IidudYzKhk9;awcnG zF1epPKsM#wZS#CX*_YG4&-l(_ZwNzlGjp=zo}!ZRIdPAwe3Qgm1mnWbFg2mDC-Fwk zxrC`^c-tQd&96CrPvN=PYx}7NdThlXaWN6k|Gf%(54m942{J5yztHOvrF*Hwn~t9* zl;7EnokUhoKiRi7VV0Mr>!DXRF)3i4gTBj}U3<=F9bjaoS&^>P423$FY6=v+tigFM zyyz*bCLIGL7s_%0pYT4HDLhMM(^8(T(7#VI=~mVywP)B>h{%FIJ5>fqd{Xg7|H<8) zD-TG{Z+oc{`!9bbg*t3-GVNok!P{NBE>EDa6cL|qyDl^I3r#Sx#&vLL#~mL4A!(Z| zCAGOjJ6lD8o!1q2!6XuFgA`F(ToUN7-GMz|Xt?$yF_d40x5L6HFerw^V20HjO5@6$xJy;uNMg0ETPUHr9D zEX`^6!nL~Q{I+-EhF5c32@Ws&57wXDpEvQxBIPsolqH|%?o2FA5@xMCT@R|6%F#;gDjH&2I5TE)8_F-{n^cjm03`Al8n_25 zGgdjo?-wPSMIeC7?vj`8=hy%($6Dki`DSGuy5Q*x|R%)o5hH_mX%45h{w zsH`dOg!6J=RX049z+b612U5s()Bo9;MKh4f%sUbq5^BS(+{do^OEW$nG z&WFkGPm6a*`7ftLCZU!DEyf@v0;OqIE6F^;lJ&y5! zDnmHK94#1vDRwYLJ;GYstS(}R=C%D9^9MCYlACHWM9ZYY^f?9oj0^buw{Q{%%s=lM z773`7R+q=b-7*ZP3MC=!OE9uh*|(^ILvDq+;D09{Fr<$yx8N#U!SeqP9zy|Sb3Chs z;XA3N++q#sC248FWZj=#a=JjEUBE38PkG)qlrw|@cLSb$OU~6~mF`2vM2hv}&a}7_ zm2c#}q1kn+73tcsqHUUlBr7U@E7rTmsOq624NSnRzTker);LxZ3&@H3iCM?o){W6InHK}6hrd4Wc{yDbZ;y;3Fov*^UrIT@3%7}yGE4GjfJPk z_C8OM@(p$#ISOeNH9r<*U=%!?m#Bt z^X!jEUP>kF_&PjIfnMxSE_I|zp^}{=Tp^i4e@wG$pcTB1T<#RKUu|8QPPEMtWR5L1 zi7`wjYuoY?6SQNwqaHIUj1e{GA$lK4DJ_iB zIUO1x@igjlW3HPh_E$Hik|!wG(BYReLUYo!ZLoAi3W`AC9*S?S34E`q#iLFCah7r? zPAEySuGU56|E<9apqn2fc3T2}GbAe|B#%=`rrC9;stn}vCF^!7y`J-_qpB!M_Yh;FCKo!r7-UCSAF4AE!YKG^z8gaTRRNyG68J1QC>;c=JGbmcP1$lOLKT&wy$ zj?v_v9&_DC{@dAJC|W0=%CRGWq^y6)(bc)B4SM$Vk~|)v^gA{FA2i283B}#yxltN@ zib)^Wc#67uJ{w(yYZG*+tWlpQ8QIfRS=lV+tIDZd^k>~okudv#qkmAPqglU$sb*8# zM=_ThJ-G!%i<~i6f337L-Xi}8F$3cHs45*zFcEYdVOL=eh6tV&b1z|I8^;tVz1d5X zd`4HkYBF9*`0n94x4w(mn*+EJmhLBVP{}@LM&^;h1IU&a*(}69Qomk6y)kIm7UNiQ zYsK3rw2tfZHCRfpipNvU-wAyShhk7|$~Qb+c8Gmfx;F534zI!Jg+v|AcrIZ1yzNlt z<$2^k)p9aT-_ryJ%>rgZ0t2;1nxa>B@Y9AP!c3xZHI?TpU2tGtDq$&l4bQ2z-{Wzd zN#4(sNNkU+U@m8!NU?RcIt#i2!NB~y?Hyg|p914Y+^O>H8s~pm2f%=jn}QQ<Df?D<)Ys#m|q`kj%Wl43Bak-6p9^Y&LlOrp6 z#cv_sLsBjKfQ91dtEo;)njadDW2^MxJR(ijd=-|WCm367+B}|rVIG-xbD9bu`K|4j zxN!&=9o!C$ybG7}lH|AJJP2;IX~j(@!IuoJM-BIXYFr9qCa!{1CP;2Ji2{wbFg;LE z)hFXl@Fw{LYZAHdw2!}DSJwA}_3~TWHWV|aSZsseK4u$B{cwolE&9g93c4s`!))thO=4j)ml+DIp({InVIitQeF_|$btIfV0t;% z*o1En%a;hY)U>pA?m&Gp9dmfDNN4B&)yoFXkAj=I+aYk;Wz9|(WLUL1XP~}-@T5l1&Na_HXC0<*IRx=w=hDgaho%AVetT6VAD2iS0HQ0-)k1~;G3SR`7W^pY{FqCKuy)!g^1W4K z2#@1hVQz>SXbC@qSKPXc{8>9NT~|)e0U~!hAo{hEB_7H?;IUukS5$$}lKUp|eV1g8 zUYtr^O)8Q{NE3_3=3iBn!01Ve-k&q(qpq67u(*2>g^3e*quXR?cpg)YyM1m# zB^a)i-l}vjK!h=4icgSdaLkR(GAC8in9h_L8Y(jJz*B@?8uPEF&|N9@ebm3B+14p` z?qQTFH;dtk;Ge<`Os7J1mICKtYP+Ke2gfDbA5Ecr`TTW^=5rcq*|u zv~$V4N>a^7KZ=V} z66ISc?M@>eh1?5>kUSDDm$4YON`$*CoqLFscdM}#8!x1?L6z#~aPXwOhoq}6qS8-l zTuzSzCq^9|({G`~4NM%?l@zYALs*CzIRr41?O(u-O0lQxQi|Sd7sYwpDF;f7`x*+3 zlbh}nGT*m7V-59UP7~Jl#oZ^w8LPjmY5)m3u)N$~ou@j!PWW5n=3KIzXvXy zV-C93B-JS7!) zmXy0pqmNzsgsyyo+VZ&bzan^DsuTwDStgbgNtA8BF(>QYz7m?UY??=g<8SOrCHxX~ zTO<9Bud}74T|}-CQnrLd$$}hq&tdBm+B*hj?wu(MfM4r?|3%ThC-HrPJwP%=8Hw#` zWq;fcko0a}7Wd9ii04q`md1tzBuphRA)S&+z7@Vu8rm4Tw%~z{my`Wl%<*4c8JW`i zrn5!z|5)QvJ&s0U_lh}Tnw%!HzEJ0%wnMkTzHBZ6liuy$;NZAQFdgkm^1WT-yhe3M zKN9Nuf}bU@*R%^v{V>~evEf+EDTdnSxHd?(EdH&k4v=8S|J(uIGU&C0=Yp8IgkpQE zFxco`3e9TQaI#U?n%?bq#|=|+{3^mF=|cd?9==id)grmij`?8j4M>%z(z&>yeIgZE zzX*3l%^_4eJmpd8dRqTwWanxL zFtPy*(MHK~!N^Lb4zP@>N}91&?$_k;O2uc%+a;qd5ox-wpl<8qgf>j8WmXC1TGOAk z1D~*-k26HIlK+^7b5zHEPBx%@w`I?Wn>Wjt4|!W$Qm ze?vEYCrZ9ku0p!J2)%GG3|tSo>crA91izyFQ$WI+PGyI12LQS*hY03?_V0D&NeR(< z3SV67-t2c=#3r2kRPwj8C_r+(YkhrilHr&pA+iPakq~*L<{UF}N3|Q%Rb{s&rp8=% zQrUmlXo{l#%e$$)yX0g8+Gm%Q0HZ%RQvxHd@6Vew{5*yJ6Z3(mR!|U^rqNw{Mzljyeo3|i zg)#F>TFU=hsK+~e2Dtk!N&m};TvAnzh{&3pvWlwq#k`|+49@cBa82?;98kfTunp!_gJS{+Os%Cfuzt*E3X7 zo(j$-pzqD`f%5om^W`m_a=YO+{bVo(mb1#S#;w$82LA2wmAT z)j2Or*i&U2^~X`_%0fp=h?3Ckh%76~JQd<0_^6D@7=MyjCz2VE%=VhI%i_1dIMkH~mK(RLdb} zB-{ly)#$&u9hZvIlVaYRsocq%(L(;=r!^(8gDd(#OTMuE4;-ae$-?C)O3tYd6;*Ws zhoan9qb`(X80tkro%QbL42Pc$J#A_+u8m*=SDVCi-8*75|1#AvBsum^h2NyI{;@DdvW)%a1wir=$3(Rf5&k_Ed>lTv zRQXg=kT0LN{m_#0&EmPZ`>~=(m!}foWSgoyt8L|Wf~+d6{y&^7GPV+&Y)boTRo%-0 z76g+Wt9Y#8r>NJQW&r6PDuvDcoPTGiC+eI;B zA6lL+*(Azb}Pj1H`vlmuqI;9irYk=RRY>91RuU;jZx;m${yWv)nR1+78x9W>@ zrK(P17U{l-0-sAxmNeCm>dj{jWeTUGYE{CyvQot#lO@?y7&W3+fNHKz1inn_tH^qs zmm>;;X@0v{$UcB6?We?@aLa^EFksf2yQISO9EA>v;carJH2umAZI~_lzxqWY9WySa z)Z(~fGAVx(oo0Ji>B`KUQ5SckgBdUZDfAb{6ub0(ihkVW=-RWO9buR=6YgFKSg4MB zB-Ok^J^spJzq-##`p-ycw;~=ZA^C+BoTF}~nk_M7ysnN-q4XG2*7A0-3IFXPUw?Vd z+L=|TT&;5(+R@x?2V}DV^53{5X5Pyxy>`6nID(B_hGdPjWJsnWY$rt?e$cp_!q>+P z@THk4ED2PVz%1MN&W)f-^`59Pje>XaFySc+&ang2bS!GI(ABx1eJ~m232;Kq6tO55 z#}wvCvbl`BCrTr-+N29I0=|U{ng1Yq7&=Q1_}aADI}4*6?Z(WRsxmJjHYZ&x$zI4% zMbD**7ww3YEeqNcF#{^uLgw%c$%pKA46iDZ_vfewyJG}%G7Wh~FG~53%!WwJyqXd# z;&eSA5&ph5pU5z&*%64FOJ&A2d=}H$n}d4QXt!o(*PaK!Eeqe0YiGO^RC1G~l9#D& zUx$08uJlZLHpI`IM>JcC`%alAdrOh3H^k_CU7N;^bZE@qfTXpM zk0I?sz7AL(XdjkvofmU2WHUe;s-l}T!d_vJ_3(sqTwUa7wga_&q`XYdF$2La!P{J* zlmQYJ*fO(i=NE2=+jJJ+hz2H7=`Sqyb@1%}5Czh;!`bDlft$T2Vd*8x&QF?1 zBAg#LQ1r8j^f7knqujelD~-D^65gdr1+W~)`Ch2mFM;titnFX5Z0wdQFtc^-@BzF} z=K8qlM~*^K;&czyEzAWU)E)hkVo}_fOTMcmPBJF})eVW)W3KabZB7acz})N{ZU6-x zBse<8T+t&lXD=uHa2B?<*Ph`eXp#xA$RHo=2X2ju^`3eT}#p)#i(#C}Cks;hHd`w&X3 zjh7?Z6B2$itrt{|mI0#kDR_fazrv!_p9Tl6Z{QRVhxXLz9HE zrKz&dNV$ZK`NrERaz@N!;6Nt{$rCIXn7 z+mEHvhvOw%6X?K&Gab5}p*l=1J#n9hlnu$Wz7RzJkE!o~lA_wWo(@%YZdG;es_L10 zZ&mm7OfykH5L85;Oh7@AAVDMuGJ+8lLAc~4v6mt#;W}jll00QQm^@&-G&u4t| z?_0Y5_qkXs8F8k&Po1>SKKqn&GgIIYD*e&et}?zuxTJMrDLbIN8}uCCY-DF(BbB9B z3jm72DJ8rgzL*NN6?d6RFfR|&g%yW%w2DJ1RD_1|%iKRH{S!yv4&Di60@3r|rfLI} zWw}Q=T})yinmNR3la8zCcfgu8Ml~(1@ho>_V51$Y4XdW5l)9oL)w_M0a+B|+y^|l; zF$$?i35!uovTuh8-2G4Aj7a?&V4tc}R~ZDqpGN-oG72y0DKa$g#+M<_o& zvXrSUH=e1q%kcN%CEKdQc9X_u(6^-8g(ZBaA$L)}f5id1T2rE#%~srG%Sw*HYDO#i zE?}6tKR5%gJr&L!kEGrC^C{70ZXQbBD=LF~hm$w7k^^KoX?Il0+lGy%+BGuu zn$R95|Cjn!WUxKef`~Pas)2W96Vu4qD;#I_P-0LeeH!ZTeRl`< z@7G}yNq+1dgdxe93M{b z&(Lj3daNh3QGyko<_-v?bu#^`9(i6(bb5f&{%4r+fY9PBbwi+|a^4z7hZLp-oxuGQ z9bm{-7@O(GElkV8vdq-k@L@EHd_Ay_5Of74D-C$SA*gLv_w2|lprEZ3Jw}VRgfwOR zhhm7P-cIZ&p%Q$P;#l?^MYKujhQMtS9hOY~#O)VJHifNWk$Hz#vg@>(hl(_(IsGCv z4lC86DduJCs)~Lbxo_|!qIPQ#W@k#A(5fRw9>u)s-8^vu<%?k?D>K(>%L1U94~@?) ziH`lK{ybUOC<@D|cK2pB7U4iu5->@2zc9I=O2P|+0@wV|B+!i5(4>r>E@cjCk1i*7 zc7@@>&%LTAW0znnUmiJhT$%LiyEqFRqK^QDhNe8Mt zv6j#zEv)c6$1-~zP9fnZ3pI)kfJX7o*bhN`1J%y(4fOm6s|)4eH_+rxtY4NofG2N~ zEGf-|9??RRFrD=qmYYr0)))QcQbEgsnTPrQIZA9BmY7R<$d}?LBvoMU!8cnTs_NWE z>`;|l=r20#0@Bts{#7ZLI_f1A0w~e>mYO7b6_fR?gXdB40D63yp>75RP_TkLUQd2xD8GXYdx6c&2VzhSn^Yz zz?GX{gf$f-3{}VlAAo^UiM_>Bn85xn2+hkKYElqO>-xnN?b>1gza*PXv%&+EORo>s+<9geS0 z3{`cWqRbqj%D>HFBYZq1wknM(c+J3$4rx_`__d(_mr!7Uf1ImcQOThu+fnMX1M^`< zZ6&$fsQIEkHMfHHB|DbGZS`M5!1@tNzS^qiQZ*Mb=T&Zka<7KFg(Fn24=^)PABKuLwULZpdToQ^zs8!R`D~MV%)vkg27rLG z2HH~5nhqozZk|Zx(8sZk;r^#0Rw{Pvz>Xb71{2Ine5+mICatf85A{Y$J*BGVU`3Fa zaTs$2wao49(I4SwVA9Q!jhd9w*$ z#IFy+hwu`j9R*%j?5eQII-7Lo?~-h4`!R{Yhja`$3wVcu+%OR$|M)4{5#;El&ywt zb9ga@hG`jjt5vS$pAcVE0qA1%uHUO;h=^l&Ip4RLUyB~(@vyA`Ddcf(T#1=i!0wW} zmG#)B&?FFR`;uqQp=wYg6Gv*1er9fXdtcOK?Ul^$+_;wPpMv-bWfFUE`#zH>Ij(|| zY>M)dxiSHh)aj8!RYw34)(+V|{t#+j@24-2Iurx`(q33j`THx{Ih6W0w+@G_x{C11 zB;Pcs#wB1ZCGfOWW9KP10d0*v-3YINn@s80BFx_fyP4$0ss{3E%*438-g-8a>(=8cK@-!ru&I?WQBxHmtg|iepc1p(!CDV>Y4)BeQ5(%O8v@nppO4d|v zqI@|pplhpAmOzgSZ34meZ@9gJ#5=;Ai=jcd5s%IVV8}nYaWpI3DY9o`hd2aj=TPyg zN@94&|BqzTCM|14Ae+~Ll5CbtuanVy$bZLc-HY1aY&2SE=eK;;DRfZ0E(inJ735Wi zRK~8N!dE7SrDq^gnm zX6vmyv50Cfm3ZJGkBPLa27o77(?DznQ9SW2bRtV%@i~9KUAWFz_l;2`J*+O3O#fFkcy}cBi8FtBLIydd@v$PgI^0dC_N2a{EFGriT~+j@ zIt0ag-#fkI4Pl?`>(^5G8d;>4~fs~FbJ63NhW{xZpXl!Rz6JZGO$JX@78XJFiv)9eM^H~lF#Ua_Lv>WGan zkIXA2o67@MQR6d>$pr0iug|6mi1?+B2|J+w0HUn0yQwiLEF_rEDSb)EQexqve}-A# za~0N#s$4@Knw_V3*a&8;I(jj?@j-5ozX&jtNZy)OMdrem;D*WIYH-)lB@AUCU+GYDN$GMcLp`S+-UZvre(hUdjQ$R%$U$bTZjf%XdUt2dGZLb zb$oV2$WECVCY(K3`Zb=q3d8r%YnBsz(};(&3LCBIcweNq@;Gprlr+ag^`k?~E3bpg z7oX(E-zPpTNI8stA# z&LiP$QYKo{F^#+-(k}`F8Ddnac0x2Vf@P;vE7=vqawYa?v;7HWM}{b@%Z%$Q_WKMe z8c$IS7DNz#iQL;N3|fLe`ua;eb0n3fD>HD23V{K>RMh}$I<7|77mMu0qNl0;q;)|U z$kMttk6Y8J={2veDy%+wd|;Sw?xUn#6{wx+G55rQ%H0$#spn=0DOBu7c+xPsP_F>~U2COqcq`CcO{TuuDm!z4js+XjSaJspUpLxtYh#ru@z-Nx^;c z*H`E<2!snZS5djLqf}EI+p9qp$S;unRaGUJ*qb3Z0V>8xiY@??Jl>I)iRXCY3JU%Z z$%#?@`LNStx^_S*{-glwIy*1W0PlsMVBd@`3t_-oC9R@@HByi7pd!yNWWUa}sU(|2 z5+`o_;0=Pvdtn2Vu^#U@kb>&BqAnx#S5Q8b3j0N)1DNc_HWWG8k_nUG0%u$JPUbMa zx&oNncp-F~UDU^`7_wR)?WAaASSj`#rxQs|4De%lKgOPsCbu@3=TXE0SE{|RlFHCk-IrRf_l?&%o>D8V zCW+|zlfO2algUpBV;=mk$JClao79Ik>906a*7aJ=DPiLaBKZ)7+rlKTc1W3glqaiH z?iJ?fs6JD9$sUFt|HP;3MDkf`INH~dt}apR<-V5g@6XvtDlV7y=fZ*_dTX;Xb(`sK z;Q9>WmxN_m^^4H3NG?Y-Bzw2K+R;t9mql@`Oxz6gvQ)oMG`h0hY^tP}kV|1C+eign zC6}7|5Vw9qMwWyoVG2AM5MhZ+)Mjz(CYA5mDO4G(K6c($^|AWN$|SFL0J%V=yiKNU z33Q;QwIj4iQl}$%s)q{OefEsV+)AK^tD5zBN^j&zFqTFa;|sK!Rq6%rfk1M0WBOH| z`Is_8gbf%*6p>lMko6C*7#DT^uPobPPCo>)&pRMovbW4U-^4Db$bX8ea=nJ?PODZD z-PC82Z@$Xy$&}27TzOysxE^*76@{RKwVK=fBo^WE&3_H+kKLGYmV%37OBMP6DNeoL z-^u3lj*&9)EjPeD>J_OeQR5`D{x1_f>}QV=sIBCmVftF5M3MR$x*S#IG=d8ENux^| zS5RWDqMXJ0nbyC!HIGu4N|eCfmx}w@fn+nh0qYo_0|O{LBI;(y>_xctTWZ8RX<>9q zB{h?9tqD+)wye6YHZwLwA@wmsap4BsPl-COGw+G@&ZT! z?dMeNeW;BG`bJI|&wUg2XMlyjt$@^7+ec&$(`p{@&0RvT`Ijm>p@gk1SD~7g2dv_Y zxupG|ycu5eN5>Yw_IIAXj=XP#Jvpii(`an3jq9iSBLL#kcoj*dM+i0g)8U}g@ZRFm(~U}n16J1Qt1`ZXOl>6B=MLk za04>4r&h9)D7~AE!z5o(YME5F?O-Y}{s6xYb4zuDZ_W2nC>C;Ubab=^?C4?Knos2? z!{o9nOL^^er>f-gN5>sJfhu`DJ}~v2TA{##mwgN67jrg=_~*X8i`34hXxN%!Y>*9v zzKAjrVWGclQT=UjjaIW~W8y}hok?Vg%%zAwUxXA^(0<--O!sb2cOu{KDKmEp?JP1b zR#7f@7B%lvNlc)ob4uD>oPoL+smJ3Rdla=<1x&`;6MPeX8DV(aJ^1?bs=)^DAbmbh zK8%gnz-;jgXOMB(-zG_SzU`YoadQRr*($2$zEN$3nIGSdK(NO$%-BTkSwOZ5F325U zO3i7HPbY7kt0Lw>zLuBPa`Nsgv+>cINoL*0OCP*-j(mT=Oh){{c;07+UUCPR$lM%9`R;&C7SSc7 zJ*Wa4L_=W%Yc_eL@TrLt)QGzpT#1sXG2Mr!*MZ(BvS(>EH;3nHP9(mjF}-Wo|00<^ zct=FChE9mdl}+tT5j}zEa8>Z4E^peU!e)_JR5I^S@h9_^qK_e)B?ng$kAa=)>$4%h z;p0n$qW&jRT`Kx3Gj8Xiem`mgs<%`~@gS zhUQ?RcgygahRzO3SDz5|+qjL5m8yzWLBccu5RRjiDN+wK+c@|7@35O(5^77dn~^=Z z3iGc^wp7+WMYXIPJtA7u8EDV))O-@V72#b7WZ8T<8k(q~bE?bWHCIZ5g-BUbJ=?il z1F_CA-0Z;pqmO*OQy^`}FIUYiTEFD)O~!+i|BWYlfRLGqkB25ul6}} z=4%6}HdCrvd$-t^lXqPyc054ZGDb0jJ5lU^DEKElcRLkVDcmUd1}DiYi7P47Ph`=} zOlGMcgtEgip;?4U-C;EQr%YWX^P4DPmnAN5yb#!T^28J>U#_IH_%_m08nc( z@Eqt%>;$liY(u0_rA-X^JEu@bZzC$@k)7a`&BS<5mxLb zQuf%;RbC-1Zi2KfFY)bTu*{~w78S2+%DdrrgIP0qaw;_7w7dE82Utq)(;7DJ5?a$kisI*~rdrlBVPz@C?*o?@*~BxG5xvVwTz_ z00CHsGRF-knG+SZ5ObLQ4|UinwqDXy#qD>fEEh#!}9T*r`)B1)hRAzTokwek7n5x(x{GVXf(>nmcY&S5fX3w8+Q z_XusYp4x|2k|U^{2k~t@eKgsBhHbsa?9CPSAbB5g<48qyp_}}E_~yT;rPbJXls=N@ zN0GaKVBRR8)R5HGf-!>G^v;`#>^YtWWOSdeij1F`mMeDwY`soYQx!=EGI^qc{Ax}w z+Ch20xn%#>p`$2sS26xJw^vhk|IkGHn(<+-aU2M|B{rfZ3wG0#l7VijS!?cFlMSIJ5f`|OCH@#pFY2)x6{`OJP z8fcNc#M86M|H5m6jUJ}De<&4S94VXL+1It9icw;zZWR_=cQ2(zmxE=LTJ2`R*15|! zKjj1nwktHzMzR;W8H{`Z-vI)CpX>ul_19yEp&@xcH#V^3ZM>RagN4N~nq5r%wnhlb zEa(KW%rK+B;9x5SdYE9Irur``>5;T!B(Of=+R0=#htX_b#x7{nvAu>C2d&3WEPYvc z*Y()2Ec=kykvuz(%Aa_~I|8+NZoI1KVUh)%2Nz?nadttK_z8vL%xL^_HMhdq>zWIS zcFNb!VfG5a03#fw*d;wEFh6s!ee1m{^nY=NOxiy*Ns;;ga1GG3noH)$mJC){b}MNM zG50S6yj;*ZgmOh$_ZBZ)NgN#@SU3??f?|MZ8Y20fAAh$>$ye0ayT(;udhAfCd7;~^ zlk73UzyiYH5~cE9e&Suu=2KyM0nWxR2^-lHHHeii=p5iCP$@5v>3X4>nc5H@hRp4? zuC+JukA3S6j@<$(hhPXI$7Gl7k4d3$P{+Oq{`syY0jR9K!LD`V`>-tXH!$b9;WGKj z)ckTA*fD3Qod2whZRO@Xs(Vj0zfchHSGHn0)e2DgS!;({x*`Nm)&}|}dT$Nhx{JSnYqw}Redz&XPCwf_8vKUkMS!#OF zX`NP#*un;&-xvbp!^7@rDb+sem@_cm7slH>c_!HuHn@ip-J#xa?er3jZo!3eH&@ES zOZF~OT+1-uuA=8ZT;U$p9YnAB)~k5FP#{SaVfHeI;CJ6-W@wVD zfq97JTFR#eB@RdV=W8$X%n1}6Bdr?+=C0__uvZ7%|BTKZ-3)U6KV%{hdGsBB7Ey2Y z;G^H<=0{R`lW%>%)5|GCC0EVg9wKL!3uaQGkI?WC-;C|?QVAw88?1jhso$7;Ij_A{ zt9esZPdI5&JECGO?fzd`wr=VmM6%VLXfPjku5^Cq(2;Tn`o=gc-73`7!YesRSWgG` z9b~mDM5pGnkPsF|p`Rz1hX=?AaBNF9xioLOz9 zJ_r_igY}-1nnghVQ)@Bq^HmRUI=R>!?A^Yu6K(SglpDwi{n53dNxq_BTASHT<){4Y z^_(4m{C`bolQx$5Z(HPAlJ|2HvGP-y{I7E7*r3pDCNuM3o;#A{+Ca-lx{#b})z@K? zb)C-#R4>>X5;>8Y5RH#j$~JqTEL#F`Hj#LlnZI!xNY5D66!%4Ge5w;afNGx?>`W0~ z3ID&k96LCQ^#$uJZcQYwTg1k;TdJ($v7Ek zLI}P6TymF)+|2=whvhV>9?&n8NtzFo_9(8LDCN@|!n}u)H;t-DX|qc#q&VOQf+joD+W=hW<+^bDHDe1DsQ|U*r}JAq@>zm~p`Meuv#b z{2xUPaps#adx608L)n_^QZLamPGHvE8uI!P4$f6$m<=l3LsO(bw+g0_|#+`jw06x_g5Xth6{XH1Lt3V92q2}_Q^ZqSwuooISq^^2c!8@G*C zNNs8~x>$iOJ&-rsUF0_e<{Ok)r}iysE>>RG1CyNZDhnMa8Hj+FQRb4eRmDlCPM;1C zi8KWZr2T?0FH$u3;CSUG8#)_23z+|0Nw*5f3D>L*3#7%+Z*>yz-?_!;Lp%d%mk=3` z{Yv^h4tkC{Dn^gRB1}je$J>6toH*Uh^Xja>Y|1Xj~{pik! zWN&oh)Y9jErj45;sqmeonbLZM`t9DPA4ToZ`?v?y7bW%&y{1+5usv8ce~afqQhA3Z z)`VWOv|c5fEu=Y~u^$D)12#~ibK&oVfOzkFZ*)Ey&;upoD(HU#k{K0^9mn*0h8ids zH^{_Lk?6znZ*s*ad0e?|-;>GtB5$L(dqmI>RY|0mmg9i%O~$_A5dgov+}^Lndyd>M zLcd9JAQ2|`B3swAybxHe8 zoMi!15wu8=zK7Chl?|9^f=`zVt-o51G9MR-wUoJY=#Gn(iQecO?x_ZIt2Cwv^K!ti zp^4Bc4RhniQ7RI!$2dTT;Q6p%*-YkHP6C?%4>qMx-8@-UDp|9TW4D&gi`>*tl$y=+ zUuw~_eRB`V7E-B0m1JLa0xB!`u}*G{Aou>Tq<@&8pkp0G!&U|Q{Twuzj1zi|&qTVc zt*814E<*C)ho$wHP{ufVZL-#DFIlf%eM~@I(W*PqLI}{qPA#xhu-bID&I?A`=*ZOkXS2?2c@}+N=8{s zpurdW@rP7NX7vwE(#)J>dEjRBH?Dd)m&y3jznKj6)s}MWx0F7QTlFlOQnmfb8<9 zNdCx8{BdKr?{!59t6h;ZRfL9)oN&grICuho7pdd5YUDWOD!rX^pix`Qe$112H;&B1 zRZe7fro6+IWP(nW_U+HfJVeA%TO3v@6w57RWIPi_Gtg1K=DD@F&s9ns7OnY*pBU|8 zjnLV>WW0(UF>+2QnF}=tl=pV7apO>0K3iIrP-hDV!YtLA97<)!P0gT8T|l4l6!)h=2Ex8MkziGf?Ke0|&E2;Uv^*g=te}dVH zLw7?k%XPtXlFaDG%>`&xedBDIIEC6`<(8?`_jo^1eOAqsPN_vw$tzjmEBG z^6-)mGfgU*!-R&V*`GO~&>OEBEz|(;`RGWh+f|y?s7NfO#H)(7gzG_6o zl6^w;Ce|@pWWV}!@0MKGbaKWNvtRNQn7D1y9utlBE9R2rL0~~$DBN>o;wY8}y#&el znj)Z~wkFg3#!(o+M}pqq&h=C`sgyu48}3_Aaau-or%0nZNU|lAn_P02XsO=yxvu+p z97cIVf}KhU zNI2l5Yc_LR96-2D36a^qC5h|U8-)pz?4!JS=D6ucDg$~V;T?C<0UQD^~|1yag^lll_HJJ*Z2Kl~12U>WnG*JG% zro0Z5rNknUn;aMshPqsp#)lM@{?V-QGJd9`-oSUl+{W|gVv1GD;FR+~KZ!;b+Za!l zs7q)|$V-;WiE?&2I7lDs1xeS8{7EIUk2FcsA+X zoI$@4Js1WhcT%R0tOZ(mQQ7>gS?I(1^*Kb+AdBB93a?ezpg<6-QlF3AlDM0V#HTtVW!k@JJb{0 zSWINW$y>usj1o4gPOI-tL_5jIX!5|rz|Q4ipqxoC_iF~0*lliX9(j{Q-T0Oqws$kq znx{qL^^jrOuM6v?iKRozvggu*OJ4dB|XAyZ<#UUMsXKM4!TW^vj2h8ugZ#4$X1G;!`H zz82cG)Nf500P{>0$!1B%;{;@Lb45my{jg>-0tRIPubmL>G{Uu*(70Gj`fAimNGqY<#K$kg5u#r0yQq^-A zi|uAQ%}hk%FYU&zhAGphFSLsj&5e3 zvYqu%VdM|t?%}l4&oX_8Or1nc7h|ZjePP#w(a6CvJD$fuJ2@sW-V}-3sn7LgSZ}~B zf!0r0IZEFswKkE!C#Uvb?jgRPXSG1M04wSoHi`YL@S+&5)ST>OXHaQok=-j0n+F`L zrXBE-h42z%iIaE(dWyn8S@wF^`~q2B=IL?4vaB!<01l`}KAR{b>xixLOpGzX+5zT2 zpX|FubVnQ9-t-k!H?|mvn8=T6$w5lwGm!@KbZrSdzlB|+$$va>ewM&J>aUaJn`7y>Im4*7L|0Qa@T2o`MpVlbM8#Za?{o>N$dw!!_K#j1Bkf zCy1lEd`yR8m-Pa8!dRg%C(yhsC-WR$JApdBmDIPWUrD<>Stft){{^zkZ|guHJFDxT zP$~cw!!>%STDxnYy&Ra&Q2UkT8_ zfL|6B($mSji=EUw>UVt6yh(t>I%HQREdUdp)s=TMs~xOK1ot)pi;v|L>AnXg#3o@B z1(*cMTR5AI{C}J8jghsN5W`&LF!Hzh%ocFx%p)S+-;SPIN*(0Hp$=OS&iI!6g_OQm zs*>!i5=yeOy1FRyW>DyZ=_-kXq(T`_RKlzlG~}-=#_o{`hhAbUC7Et)Rr&%AoX zTuJLVu98*@t9%`!vfcc|51irjLRJu_;E#|CxZ_wY*}ML%t~NK0yFPP@v0*$pfoe8N za4#}zDD|0#XQ{3^h;QLgd(D3q>Ik5Q1cLkmHBNACjBDS-p;)1A`8`x`Yfb{f)Vp}v zcpCqmObwI9DysH>unef|s;-Blkpratw!=Wc*(uPaPuEZ*nB@CXWtwkyxUn{}kCco= z>UPSlAL?VV&GB%r$h=8f?}XsrohnpAH8`Dd^RuX>9MHkQxT(!ktUZ|Is;-=yxYc2I z(T)!^nJATZ2L~Vbj}c{W6K28739Msqh6eLwpViBzv1GmKXt+t=P)vN?Wb6;26cO9e z#!yasfCJ>q^%MDVExEI)@HR%TTIB2!?#5jOlXzQ${BthO`p9uIF*6!#GzYF9+UF>8 zPA;bIk`ReVe-*mQ7U? zuXGk_xaD_M*Gx}$6{#%xNnLUb$*UxWwU`Q;XLzWlQ`ta&lGh$V>3W}@@a-J4zsR$P zsW8U10KXi_Qdf!$`pYv)b^BL^_7kzw+{`{SX1k<)g?=gxyr5LqyZvtECW|Ed(P2}_ zX=D+k-}9)?%2I9;?J(Il_jIv>>de3c#dAx^x}xM>k5b74W!3moW?u|Va#0wnuOXws zHTR>k2vEr6=TPvu0_9+mySu8xU2T$=eu{$iP1?Aq_Bb;lK_fO|wtD7qPVy(pEaxU* z$mPEEzHqL_$v-DHm+HVsw?*Vw%6O>b?dX}z%D8brgS8?*y2U#J%g2Ina&Tb@>z8+T z%^>%|z}?@^{FBOXYp`%x5MMVmbr@OIWkm~vjo&E#R>-MZ61vHr3`l~?_b-U(Z@h3e zW!FeTzE8Tw(Hz_NiDqHHkNO&&lFTkpJ^$TZn;nMcvdGf^sWbPYmP@5^x=gR6%xeyt zM+LVSdxksc^ne!J=WFkg{dpcRj9VS;g6&uH9_edE1_69dNwkRcn@|FF^ZU_(Z%A#Z zupu4;&wlFvM6&78ZbY)DRY|r`VsN8@j@lCdvbL{4)+uGC(q1R|nW3(EH<_nMJt{IQ zDSd1yIf`1YaIpXwJG)3JRW(;*)52u)E7^TqI-H6vfzcO?OB%8@6w&Q{@98e)>L2Be zuc;se+b^o!!*VzHDKrA6Yu@4{ldOOu@9L@|dy{^78R++IZv7s-93ey^ew zI>#!s?CGvY98bm~E=%M%JZE6_T`#s#TB`}TTjp@8U+=T8xIUHKe|g#s{*LdEvnHQ~ zUc?@5@=k(6Id=6-wC3HVY}vIYG4EVAKY@aP;X{KR_v%Ji-u`yiBZ`h;zUr{??X%vMEn$)-Zu&XH~XBSxsxb)w;TUjTK^@xD=f=WA-V2wlkFU0K8TWAcyblx zFr2}+GhFL+$5=t7jIjF&x`=X{MQV|jtM;ycyX!S4SsRO>=C0=e`rE%nnIf$VDfgR` zgk<$5-$V&KnzEB+V!R(Mv-+R%NgR(I?c!aHdzxW~$GTI=59f{&`k5?yyPN+91|>4p zpisFHjU{mXws$?I#{9+!j?qbVTV%YKyGyCPu~f}YriS@GUCZ_R30m#?_mbvQ4zy-W z(Uv*!yC{M;c54`~n?p}|n%MRxnnrzp_TwGgo{lXI^$fx!+q-mEKhZ-3^>}Q#Jia8A-JLWL8 zWER7Hsoo})U&@leA%+mNB`pNAZymaXR{>4uMu{}K5FlFHME+>4ws-yZt{lM*I zxqTaf1Y8(TgLd;X4|2MUtSur|5e8I0jS?WR;5-N1lE`8*?g<`un!kGS7v{!Gw09_&#Cb=c-|@3HD^=ZIlk2@ z^us9mvy9L5bx`k{U2`jCx?KBGVsu73JxnLQJAkgHF}(om7M`)Iy1=gZhAyJoCe+{p#u)cJ?VPHjQ=0Tffs z=>`=sEpxgTP-Sf3Omnj9DScEa33Z5*R1s3eEGDD5u}9p9W*SM=;KoAuCw7L6UmMC& zW32EbuY=nF#spIKk(2w-19~Z@0NeKyw^9CmW%@q7>z(dTJ%%gTH_J@D5`*yHlx&i) z?x*Bh4{*P{(>H$g@ib=dE7FsG;uB(5dsX9XlKXmQC$sNlPK&600Bcs5)Humm%sj=( z&Z35|q>inTGpT1oJ&>~I?q^i@!X~=fev~`7sK3LrD{1J`GDsDD4)Als{pcLZZV@am zvL{h(!q?VNW3#J)b&iAS^TOQnzD#bAkuS+=C{#^+o^Sc7Zl39+-CNb=VYo?i_ot4< zIkqn9&*u(GwGiE{2~E1s004w-)IqAA&JS+lk}& z;lnO_oU}E};vxm8qfo-vVG{dzHQ#K!S<=nIIF=4rUT>yG{;$Ct@yy-`WJ9~3ibf8S z`GZ_z3>A(qY9H|YdDMJf8HIH71V6clA4hBZk+7Jg>T{IK`R3^)e)j-EM=W1El+(9b z%}X+MjcmS|MX&J^V{rt)H&>`h!Qk)yF3W~?f93!WN~#{AeC_(8Hob*kjU#6Q z5O(aR0OPWu-Ln97x&CA)c_Z{xg*`eN9pZzQfCdu~t-01^TbOl)nrXr&=GP*zDao^5#M0{8%#X=lnb>t}R!M88mpZpV;8UXH%*}#@|pP zExBzlFaUdDO8U&Fsg%1-(jBt0l?G!1jUC!Dpj?h&{w|kE_&>a6O!t6*&2m8O zmgC$6N+n!NdP3O9|8CLJy-d4|ob93+=wZIIv*JqCJuR!i9170{#sz-#QZo0E25d4z z1!vg0bZ1eU)#6=4h2PXxeeB}^TT5fQkD`)vYiBvRTS+#G#K>sW_03EGlcXLN>`FJ` zne6Lg>^9YrO%&o{R4I!wey74gGkc-K#O)i{XyeT1`|L-Mfhl90jK zyM9dfTvsKR%Vg>WN1sS-hX%2fz`m6^)q^OhxWi`y-1t$TPfO(g^c=D+$NG%&hkEQ@ zqP@-ZySxr2d7+q$ID9m-TsMoZ&+%!tFb<{h&-(~uJ>4kDl2y~P9U4OoP-Xdo6L$Mh zoXw{GwXU(zi9rhJT|sAx$a9psQqoCO9^?X7hbR?0&bRiX#?_Lom3_Yenn)Dz zNBpJHl-d@scR21jny1S+q+oJ^HltYsW#I|eI;5p=C%LbO8!e{=$oD~Ww$I?&mfJDkEMBVr}4hcBx`BH2X&p$xO&e~k6 zJnZO;De@#5a}nR08m^a_W8|=L%)Z!zW`+NnPruhC4y0B)^cv*<$*`A;|Y7}4ochlwy%Kd@Ox zAAFyy9igZgsaHa;SrXtV`SIQ3s1R{2$BS<#7p2#}(dd^_|HiNOSw^D>Z4l?uBn0yM;Aj_+=8 z_2yUv`W6qnaY%0N>4QJ)oC11`W6Y+^v%bEUo9Lu;yRUu1lOvh&s8h`xM%jgqeK8Jc zv3x?LHUpb4+7rF_m(2Mip8>eD(#I9j>;xM0r9>nC0tQ6bGy=TenmXI!&Xcm@H%BAa{L_*dO@$M^pKE zpZaljAnmlxYYpAzobIWCnR1MW$RC2aYZN0J7*Tryq~~J7^DJ~(m$`{UsQgcv2>m~I ztOHVv^JKtoMXQ4_A$7pTulvS9&5%2DPcB+Vw&d<3&;4uI5ddF4r+W;!HB~q1dbmAM zyPYFqMuCf5>*F!WCR}!)n`&pZD}DP0z2*}y`JyltU=iJ({?Ji%U31a=g$wY{zVuR{ zW6t!G&8~f(BDR{ypbt={685pZ>(A-tFm5bzmSjh$P}ANQFG8?oWI9f+I-J~deDfim z20Jk-_3ycbk>!0J3QRG`)ow8LUnr9msi&|*UrbMM%^lF@s&2UM5n@MlmO+`BHC^`SlWrE1nS(;J{DA{b%@`upu6410-cop$ zGPA>EJj+DRzovT>Wi8jvcoxK3E#abjxt^M_#(pBCyj*jNn{87qy@^|~NBh=w!njr; zPztlCFKX}lxO9`hF4Qht;#(CraRv#f$n%u!SF`rvKG~y$fIB=i;m1SSuHVVP)-tG&0RB=!(A+ z&b{5|2kebJcF2OUt^%0{vFx*go`HsJ(cI*L1m`{P(q81{!ZPE#t^H)vBNB;{x|DyoG(s zW-ReI{e=>p?_GaycbA)Kk40Xf)I>Krg36vu#IfaqMIr|YL!RY>SZ3}?nYh%M$SkCE zuagHe<3O^@?x&UY7(#WYXW2^2YAN1M|Z?E^7sQx(SS8*0RI~k==+5-Xa74Dh~&I z$xT3!rp(OUL=v>6(;Zqw^4WmEl|Ke~t%L*<1q6L`v$m4lqXav;C36=g+)#S6Uey2_ zyAMHc?vyU{tOv=RBP`Sa6~@=8J;Kz!t~S#(nq_nuH;<)VdVFiU(C(4uPA>4znpjY@ ze)bvYF~cOyj-oG3x4VcIsSDi1fBYomnB2cjvawsbnH^%0!(lpBcEOOAm!)_0NPQWrN9c)bS?^)t$&OQb}ShR zKHS)c`mgdKAop(f=4b=}^d=6)sJiF;%zHd_D((2bNY14GpE>MVkDW)>vwmVd&ptr8 zR|PO;Z$A%<0g*K_fzr5#nlgT74{;DK6+9whhtrPh{aC>5gQ)rEqP|T=df$7u`_#b9 z6~JSzHf(f_@t9z;)EB;n0%b+f*y352l03y>gIR7jg%V^Ikvrc(M)iLbG~6+8vtmj~ zTb6)gOYAfU2Wac=7RmW7xv$9GNmys&l#dT~%)8ywDDy9;F2$V>aK0MDnrPH#wRa0- z346S&w|ihdRdXlv~M9 zMI&!J`om6q3W+a#>j$1+N;^F%GBao()Hv$BC^ppI^64>N0990z##L1OQs}cNavP{M z+#E%vTHl*0yq&9N?P?D-NZVsRTfog>RR4aFE|t6WzV}`C^1yuDO>L#((D2Uue_3IK zkVu5Td-=<}!eCZf%oU0xUXvw1hZ zuqD5o*~3D%4*J;ME#Gxlr;>Qn@!NT3Gv@9*g>{S}(t0h>FQwFpuJ)R1HnMaNqCPdx z_LENuV+^wfxvHDV6wO^+CA-)m%_E~Vr~1k7JWvj^n7nBs_7gCGP?4o~{de6RZmut6 zm}D;MSR)C#MZmGrXHfEchpMRSX8MG8vJWLc5k^{=_fh&Jk6}vpgA-ptb)K2rjf)wS zdO)Ujb3iOF=!FE@%)pP0<@VtqORBOgK730wa*1@Gbg&H0hp5dJ`*iYe7sxGr@yd5` zVn?YVy?z(Zt)%2C8M~MoN5lV-{}BmHPn!k?TG9Mcq+g);W-o<(;~#x`1(5?-i?okG zk?~%9_|*aXFkkl>`Db|AjA-l)mKh*&h-5~AzV?!rQM$hqJBzFvi|iPYo=QD|U{pYQ6n8w2LQ94s~((#N+q2p!|fj%EeRn8ie!E1{D&TpB3JF80%FU1J{g zfl2IU$hT*|=W4XjyFNaAyOV_1IA+y~IKWp6T|TUqsZ#DHCq0YIvP+M-NldpNgf<5^ zq4PMwV>oa6gQF?Y4by1mb>qo@NTvoj$@Rn{1p_yD(mwmG4xLJHlq$&z!(V{{l63y$ z(c?&V1=>cQ+8fu2v2RB$)BW^o9u}3WDb$;1sIgggs)#>Il@Tt0^vDe|yV`}QVdFkB z)kh>(%E-@Nb_%tv@fk>)2T;R>(%4yMdfzJyKQ6HFSUrY)Nhg6oRxo)luYFCcdCXH- z+L>hT5YTk0|GJ1n9|_Rp4sk#+EgtXcJx+W%^xtX(L2@SICju{p<%-9IbxKR_N6O9d zlOS-u>?64phL6W56x7W?YQ?o-UQo$JYQG8XI*^844Np&uxpUmaBx>a>H&&#uq(3q= zNu+3%-P#*a(TNn;v6uPTeVX;tsO||@$Bl-UsOo^v6xyUP{Cg+0D@5a612Xt1MB3{$ zF0hSdU*zObAf#Ol|I=`Y2$!^bdGdQgBLIqVpZ6UN5@3BzTj$B)SPqq$ot)Hg=3e2k zGb!_#w6@ooQ)x$%_D%mMkiC84I0Uk`;nf$Tk=4+ebmJ#d{q`XKyviSKlO&jhEeHFi z>&DKf%&x`Q2&EsG0DQ2Sf?YkF(}+}M`eYYLMf8(qBh-kQ{jryxh}yxYbbyC5SRtVz z2d`-xepz5@j*X?cgPaV8iv3yU7oG<%?G8_?KH#xuaB0m+Or`oyi^eDwLu(IF+YPyc zSm9nJXqPGonh>S;B@S0+&Z5kJ9Ajxq{spT2e@$I^loi#T?pJU7-CEv$Z@qrEZdJY4 zEd82Q79lE%s1zJTP#RPg1*M@AP)9;^1~JbK6^JYbBAS?qwh|Rh)R_@RBtQggHU$I` zJuOi|5)^}WB`?!m4rgwmc`hCx4LfZ$V zScVwD?aX~j!Br@aim#ikMObc(NKT{bw;|NP_9}fi&xHB^E6*A#fDo3(s~E1$Ypyk= zs^3n9_xwbEx9~Pb$TCFax;FL>8ik1?vP2kOP&)Rk#9x*f^jq_|3BBn5@}$QTP_^VWaHC1bXhT4}eg!!{SH>`&p3dT5;s4JMJ(E$BS1qA`|=XsJKZ;#h`$L2>IeZA_ke>cJ)B!FLOli)TSn4FOWmv^5-Sn<{n#wY z)>FFCF?LY*l)xY|@{CIL5CjA-tJ3E>@mCqk6{8cWvdcBD;mI-JKW*}Ll-pe$&A~IC z@gnEHBCiL4Bn|szs8be>!*aooJ!YFni0uhoB{D~R_ETxyNZFeNjmM@V0!gqxh?lu&IP6JT8z z5A%G$Y)7TrBuEsMg(~~0$ZRA%FEF^Ycc|R=Lt~s?(CLi5;-6*NO`Q`F%~}JLWouO) zlffU5__>$pa1rp!Px>ec)CxE4isS-HHT&_Dw6>Bp!U^AhFA#(p0NC<0p16+6Jro{f z>It&icnZ>Ao`wF(QskjIt&&K#Q)cd-y zbZ!k+5MS)swy=OIA+ew=gY0mTf+?Z-pl=Nk;j-3u1kI*~UMw-fF)A!Gvl`x3{Fkr;jcZ3Jn-%DUdhA!` z=@MF%?svH0l`Rb3*COpI*C?>wL@6)vYMFjQeP;P_6mF~CbVE%f?jv)QZ;p__{nO_= z`caaD1j2vhMa4cAG?s=`l$Uc-U~8`7nHK8zw9BRn{W5YqWiEH@u8xJl8qfG6&#Z$q zlG7ATtLVu|(*B=t7Y-@g_#Ksw*~SzSPf&6~7|e3;xqb+%#kkR0vqK@_E*YP$wMa(5 zF0uJ%F;-hQ@zrGiLYAh`v^il7urT-;HMM(ksxbFa{i^VWYIzj)4jzfI4E3JPzM%Ye zp^u`0jf{17v_UL>4-a_*`#iiu^)TbOxg4FP)n%D=p^be*^-l`z(wYE=uDJOhb=kt; zAh!py=%+mPlpmP@gB&;0b=Gfof+*fg*`;psKWr!^v+b^G33G8~hQQa8SJ=rDl=utf zj=Ov;r!ojM|YJ`DfAwx z*b*B0OE*^*fDDcPzJ9Tce-zfNbc~892$5jgN&7K}ps$~<>dDbl42^I79P05)SDzse zGn!62AT!{WEDv~50}-YT(nxM#u-L2@2g~|#cth*7He3HaHT)<%l1gopn;tLu4=J4r zSxdzZZXM+y-KBR+W2)Ao^kSWDE~e6bwzaycfVT|U=vpdIagh-Axy(}G2r@v=(4z@bY~a6UdPrc*L3_XbTlK*{P2~?4#UUB8hjkO+iNz+M9OR_?q2LDRaAwUJn1e8{BB;|BGY~ z&A0}UtS#u!VDy;1tP0A53wP3socK~|z)>utb62_60Xqf)Yj>aE@o_bLIvsX`M1NsP z)~lwh+c>JXUi+LLf0QZk4qo6Hz@;l)eWK*oQuk9%>{5qyb+iQsJma&PNbe$dp^X9y zC}ZvlSsYE`U1S)Zd4=Me?BpcuSagZ@B#jAL%YH~ogoPy- z4*&vh;`@nD7w|OewaNusrY!&|Y?W91Gl#TM6r3!Y8Ku)4CkD|H%*Mv!{>@?VFEA%k z(|DGQs`#I<1CobSjB`YCDNppH{GH`E=rRY~)CD#c5gBhdfDUv#ody4BFx!H04apcY z9#xsAI8+DX7BBk#S?<$q0^&Sxk!w9`hZEB|KAYeGH%)XC7HmY~N&~`+Z3G&S3jXr;VE12f#B<=I}x8wd-yndyYpj zq1{gw5b`M%a&CS`PA%&&B(c7_ zd7ERP!FRiFDXXvC(+Y4!1Mb$^ucB)Aw1!kS1Fd!-6`aq>tjDs##Q9(RSDCHcXjLzc6$0rq2EIdFF6U!-%E^}G9OTGyRWwj^CFgb zS0-;HS=NoIpwD3BTm>pzd>F0(*bh(USP?@YtA@l#tPC!_BjQgt6|lAz9Vo`GAUs3g zzdKk?-YcF;gru_k8-ma!*|1!2N>JZ#w&MpyYzebwbI{)Uf9)qekmh&FXgyn&;h-;( z=_kkrxgTZO0A>xg!QGR8=80amg+;w}b$kc*zHQtc%&f%Fr6ECoB!Lg74tTL$vSuKg zY^|C%QsFMw=*Q`H%0K3^XC<`9>B+)^0qq4g@cL|$75`1-$C2oz=p@grQ}Ig#;3ogD zO5N-l&C~-ydEXi)(J{f`RXz+;^*{KTStF)MM2i>?Mz$xqVnaut>^;++y8fwMJ zQnH5ni922MIHf<4`Y|dmU{Q|?15q=Yq*3O$tB$qTnJa}Zason3|2QPcs@+UvthrZYI9MYgEi ztsF^A*1iE;DYTW;6A|li8gKyPK09?D*lgWpH_T!*uwsZ40RC>=R)ESk~IulHI<3D}t1)lf{zFpxv?Z?WobyDP9ed<|u z47j_{5I#^2*UBX~w+^8ymsdRLiXMSoAHq2VaH zd%H4ca3m7Hw$VqKoE&v3tjYL=JhOyKTU=VowZ+tUMp}>3c^)%oRcRmJ@40Je=BJBP<=|(?|}|Y&p*I1ud~qro(N?j&bV@HbQ$?RIclG$9}v*o zsS`W}k#bLE?rE&)S5od|_^fgpzz`AO(^UGqY?f5bWPDf!3%2yI2Xa5~U~_>06=TR> zu`IY6e-22QV6QZ#QBrLY@xJ8r43kT8)UT=jbx&-t6F@bWgHEJrgLV6aM83_Sad{q} z3&a%;2(NFX9DPLAa+aIu40(o8wCb6&vzNGdZ#GS5rzLxHXPpN_eZ0i_OAt$C!@!LKzO!)D*|HtjaIgY(YQ9_ZTl!kNP3TZ0srM=VA-bqVkq(MoArd6TEdB5JTx7jw@ zQZkc~5hCh)K7QBly8m!poa?yGeeU~tKVQ%16$?-0%&?>@uJ!pU*C;|Ld_m&f>VUb4RkXN~um zJ=J@>>{Ww%4#)rdDeU>(^#6akyW0#mi=}HeEZMS4cuQ^|?VPPZhX2!q2V2^3`)E_z zx#0xJA8N+=FJ@8C`f4s=GNU)A_=4hcZTS60%=&reQq|^8Qu#2VGZ>7Nh%3RjSn`59j68F|@sqT=h1DnkThryH}4|m`>o14oIRG+)ZGu z&2r$+3fSphm#EdoV=!c%nB9!bp|hVAbA4-!m`aN-9xu!yJDWu4^|g@HFR3A2E2{A( zYEy$LQQV|%RTi5bMdzMVgB$C_%(0{fn3+}!|V{RVhMy%CG=Feh{+a@oa`-t+=oKqrQPyl@o=U+sZWp#p4QsZXU<5;(r; zJ2v!AhJ~MAaay}G>GCmcM9aqzcGwG8{kDzNeso8|Z?FdkryJfEE_!gj;KAWd=xw3cVN&z4iG zn9q{nW_46k&4C?nRYCWIF8}?z;qWdyxcJ-#gDzFvR zR&?X>CT>SBRdzSy5qnbL&Y^i`RTdJ=sxNzcnq?DVTlIp)>Cb)DfH$Z zrMKgQ>rcQ^u|J6Bv}5fHQ`+mH7Vqw%j!XCLgmH(QAlpfm)fQc%RS%T8jV5ZiJGTN( zMan}?k|8T$I+*O6#$C2gqDy}PutT;Gys82(<;22?1C%MP z$Km74Rt(Saq09dM;H+~QT{C$u97)iIh{<9$W(T9m#U12Bk}AF&sX$}qTYxoP!q%_e zhC2txbG6w|sET_45w98mpZj#-feb_HlWhjwN9yra!bJKU&X)pMR*($YBbQa$OZYqX?OPOBWQ^c3>Z41NtF%CKoq9i53Rv!;xvr zVb}*nw%9P72E-nQdB?@9cOIiZe-?AIuNyPZs7&bp_sLuVsyWgHm~|tfORQfpsLUvidUGh6jNP%+^|%#QuQZR zKez#Y8O|i}c{!doP@|g@`tbuch|%Hn7C4%#1$oT^wlV$!4IXlo6K@jXn9CJlJpoC) zoDthmq=mYk^8BQf`;?7gAiSvu!Ab(QVpawm6UIuEj$1REOw}QX1Qyne7Zvu;^ zk0jq)m5tPmpid`1?>4pjxWJhIp@{5!=F~*JaO(wMi6?eIEcNya^-KUG!WA$N9+g z{_0mDyqaMT!wl6?X@U`T@=PJ#%H?P`D;lP#%Jb{gggDd68aUq}@Kh?#ybk%&bHOE& zkY7SH8V#_zKm~BB3412rOsyaaeAHG|A@ znhD*?Ef~h@(82zl(wym?xbNmH8sX3JAKr^mfr|#^`C@ptNX!<5GOD0%&IJorQhYMGCcUYZDCu6Miy!>sVEe|;DS`p%xEpUHD1NwQ~fJgsMLdF9{rhB{>Rqkl! zE?pL|)srsJgq+Oubw|Z)TQ;Nn-VEg@HwrMO^b5?m*$4KN7%&0R#IN7IxiLHJ=++e@ z;nH3^IP~i`2E-&nTtR5b(aK>Ud(xW*F7&1THxO_Gs4y8Zb(kvwEwJ zkE^O+oj@73rWmry6I!^`HH{niB$4KQ%7FG78(8qH0tfIH;BTxmr;zAL?MqjY-8;15 z!z67?|Ktz%wnma1M@!rrtw3uAwMq4Dg*fHC9*r*T1rG;QAUEVZsL(Uq`-y3k*DoRu ziu-^?t33OcF_*Uf)`rcFS(FHl!0>5WP;PG7$XzPJQHk*^KjPcMVTzZ=P; z&igd;)Ge61)c`CuA7vh~q3F^kf&#f3jM9q$>Keocz0gC+8hg;2^^(>-xA~bZ%VY?MgjKr5#pnf_sB4bJ`_lP;RZ`}`fK7ePG@}*9U7h;i*0Ln>L4O8U<$LpkR#7!f1Kn~hY((^Jjh!tcQVBir$)(quYUsYsH1 zMt~!dAAt8ZMJSzb%wBZ1(GPduS_(S&DoHj%1m!H^P8VR4?pMv3DbyyT4pgP|^at>w! z_O1L3{m{bF<>SQ6=QE+%UxxCtN2uZbzn?*(YX$vB7_!7qVssfbmAiJ;j(W?v^yu5{ zjNjN6dIh@U`a{bq1$H||pME`T#4DZ<;;zgUU_W3moE$7*%AIHEvCkV1(Eqy@bMmdB1#Tsz@SGYt9@3>2cD-P*S2^B)83t1OGu+vS@@!Y%*_0(~!;Fzx zbe?lykEXp|WWXlaH`A^Ysk3NQDo!CJ*5Z1u%p{5@WY^FBL}-W&g1`hATS@cZ>}s74=f*>|1% zGHpYZejap>c`au*Jd!n$w7-{>&o&IjQ- z{~XS8f&f2kjwY_px5K%?nK)nREfimDCf(Up*zdCoCB;HMFG_^X`QdOmXCQ1?ufvv` zAUz%x=xVWDj9V@%&=+6iVT*GhJC=D8ch9!rTV9Lstu&Sh)eJ$nJP+61`vjj8?6@46 zmm3!^>X}d3J4^JK8xQX`TqB`pjM%fU>R3>fNtzuEON1g6TrjBi!@;mh^tm8`3c&0z@@B*k{IfNMG=rXxuVl zF)iw-9WBo*d!^7PN2Rc|SP!b(m05aa6dZkWP2zvsnmLy_Q{9afe9Q&|JSM*xTt?Oq zcMAb)(h8vw^YXa)1?pIs_89c$M?%|3F}pbDD_t{n7kv6+%r5F^VCIGX{FxjTbl$B& zue!Oy*Zgvvw(1Csx$%q(Nz9>@g&)X(BxA7eufp^iXVLTLLZvsO)N$IT$6&t24qSVg z$?o4a>XhfkIqlM+RuTauSK7n3{aTntjc8uzBjPu{42=TYRO zKJ_mi6ilLzr+t*nTq(fIq4xoYDT0yCVD{2Qgx61HbHiPd>5sf?u(`k<@*_>y&W(L> z+a*639V@^gpQ6dV`!gZ_Y!ikSD$?Y4zop5uf1u{0Q521a@bZqbYrr=g-k%jhpXq*7 z{njX$Vx9nhuUVkNG(Bqhzq+x%XbIU z$@(mP-WDO=Zu$iB>-)j7R6}+{M;-S)p33RlbYO917_?XShfmiPSyQ|w6*U<1mJfvJ zKhhWWPah0guT@z4lVDn6tHi}93-O7^C#W8*04t9fGP4>HHf5x8Nw&#U-|jIC`eO^( zI+fVx`(D^l;LI5*dD7h*rxD2yEl8->!OQDb!anUwa$~JKd94aP05|zS~z{C zAr1Q{2TP>oIJJByO#j%6pK?Wn78N@1G(!i{{p!)|&F)+EVhU zN3TQ!^fBt435*+ZgJj)rLkk6t7Dv`{F%6kC%60;z%+vuZu?G9J;~~|do#a>~rRi45 zJ$hAbewZ22{;acP;4}la`JO8NET$xVff&P2oG0GVwd9@fJMQ|@2-0&= zT-_oSW_mq{&P`PTr!E!rrUg*#I2P>M4A`D=YM3{7p`@&%9!2Z-!TQfbN#n^n+;p-P z6n@z8{U2-K28D%S)S?ad4yv#pIYHF(LLk?8r4QwWg=FTnNVsOHi}F`1!12U$Vm!r& zjXo&EAQyRFDo&+CpQX!YG=2E8Uxh`F2!XgcF_K~B*35VGKn z$n4uH>~muf?R_?vo0X}Czw7V8&E|7p^UMI#bdzf%K5UNd0oA7!S$%bOa_36*{{5#nFp`@m1Kg)a(@OzD^!-Z(R#YniM| z&3`F_A`FB^Rb6zMXG}e=r;{l*WvKFY6PWCi<99o#;rx{v@ZQ1+e228+xR0(hz^XuE ztfGez4glb*32r-vFxQPDoICO<$0C#I(&Q`9p*awiUo&FE2lvKbi`GK!Oaboh71}dn z=DlphjJ6JV`KMjlEUCdq7lzVFL!9{CY3k_c5C%G`>JYugn%!)8M+cvD;RYUGPmg2| zhYNo3Fk!7WP8_X7ZDu05{$7ANw?awfw4tyx^(V#_{)Q`Sk|cLW_rvDBcfgai5vjfa z<-Qj{u~86=Q`Tl1OBHdq`$m`*p^L=+G8yQVNQ6tRnb!k*I&+>euh?6K^;sH3tL9>Q z_jfh?F!3GiOt1pSZN}{UDG@ew_;9-%I&e*5V2?&QO)kef&9$(%Scy-NWd)Cq%n|Q@N*lNi;Yl4Wgdgz@D~B47Fbl zB?pIbcA=iMxYU!Z^wNg18=W|Nw<|p~A`mV{YBBZSCDd%iXX0a~hN~0AbP#6_Mxu6% zmioiLH__a-i~+c==pgJo%Mp#$*>r^b9w=|qg2g}e*xJ<5ko1ZW-S)iN~kAJqVfn#6^=UQIy`SNPyj9H5fbpDAPC=gippRb1yI3 z)3(4kY2aB+Flf?4e>WZ2_TxI4HMkBZ4~3jd{u~uMptrz(Zu}yB%Or*o9SNe#2UIbGR+LCjTip z&}Y0lKW=~sx5b`>q1prCjEfFCapw`8>lNs_C`Ad2{p-PbTnl;ac!YguIF2hP*z%`1 zA+F6lOp3krVPbFa z%!wA`1uW=;67`I9=YNHWv3%5Y`1U{xMAKE6Lf%n2YJMQMJGu`}{nHM!Uzd`nn~a#l zGF7Y_CC@kQN})#%KZ0SX2b(6Vuw=P|u-Yg_67boYS$*nDT`yJef>oNB-#HWRIeZ~> zj|%(Lc$8L;$mOQbX`=gAMnI0oVOZv;&h)L`(R*P#z+kKZJ2XVp>!K?Jh`yrfxfw8L zK@NAjNq}nmmBD|w4^-ak!kS~FsfzA#>GI(k`1(=`3>r2Niq;Nd6qM1>e=fImj5giW zCJ(|PcHq3k5WinFr8-JTPMMVBD*rifM^T=yStrB~bpj~AKLq9_bYb@4(X?#ydx?%n z5AU`=0W)t+7}Mm$3O1@@)S*1i7Lus*oT#2Tv5gqA3G!yR=+$aiyG;e3S|23!&!z*n zs}Ti#>mc`hyR<2`21BMg(5ai9_6rnCoUOv?ne$;{ z*D%iajVE0r8QU`h)`WJTx6??fAj^K))nAysZ5w^j+QbP9G?}A!G4-}CCNN$V70lJC zp_>`(x2!;=4RfLE&KYj4s~pRp$I--Znox5$n|j3Wf)Uo*;JI6m<*hBF4TWOKr2j{-eaXUcIRk- z`~4cSN?MDjzYU@(k8W_!Cdjm;$_f6iG=&wH1gv>XJe7~x4_C(`-BFX!GY^XDWan*= z8NNzBFX>)lPw%LN_2l{A6Ps~yN-4bSdkn6*w&T|WjHW!Y2(i@a4N1 zw61Bx@7058X>UE=%vBv{Nsq&W=?-wlNsIY*-J>U#1h@{DWlb(kwGb5AN`5y6GV%SR z=vZjOA1qeIYR{D<`nfI)JXV3KkwxHjb1YY!n?wh;c9NJq%VE|CeY8Iq2Jtt~l1U@< zS(c9?F17{Ywp@(e)qXu*D`{Lc&hGaP>gA%ioOUI)`NkpYKTsL!WEoEPi|3G@?hfa+ z8?kVE6|^3@NaAc-hf1-YpucJeNeSpi`s4?6^mpNdibVK4%L~dXG~kNN=Lc>%OsC`q za{Ui!J{GI6P5Tei!S{2yG~*^}{o*Y6X&;92x9y3pLlnVxui zOsaEG4J{wthGmOwz^G{udv#F};n!S_T58kG&Hu=Mc~|@)BYYodLW9RKGDD#Z=UGW$ z>=HRXS~hnSJ?kd_&45+j9T?W-MBfCwk!*0)#dK*J*l*PUr*bD&`bw6mP0iyLSSHi4 zy)VLISw~QpY`|I)jIg9*B^aDgL8+V$Z+bqi17#bFV+FryKh__IRz2<$8EVph$D#vdQI@YS=M&6?ryy z7`WOB*xT`)kQSLGIr`cPU);Y6X5U*$_%U_Vozo88`&W@uK@GSu*{dhFzvfYchr8dy zjGA}c*`uoLXs;u5`1P#xjmL#pEqM(mo%%uO7!$SxWjzE;=k{LcPZz(jgRviMq06EZ zO*i@g7dQaU?<&J3_Y1&lni3z8C&U9D@K(^+Q9d;DttcE5%M&LbGKqW=$RLTi2f-pF!}NurScBM*f=<*SxO9f~i)tqht=ZT$n^V{`G_L#gk!!OJ7WF&xTQR zevnJ6oY||#%CZPjhcA@P8q(cS;G1Ot8?mWO7ha84i5~qqOYoMa0+25)Jn+?&MY^Bciyt+R9!4>f3pv4ZYpDv*>^bf-4#@v zjM&T-Mws~UykvK!9sTlZw{-U}4Tw0|gyy{pVZ)xI;8)a+ip>LPfPWpwP0yyUUylTr zLAo$8PQ<1xxU zE&T+}qs`!2Wi#G5X+s^`wfQJ75x)C;xW|u`_LuqLqD1;*T!3p*l^QlCHNc7WU4#e& zS$pAO>=k6qpHCFw%@-4i@f!nBd|Zh>Z*yTxtULE}Ym%%pY$TJrmx0l6D|Fv+2}U1@ zCH*w?n1Q7n4i1!()v{iA!s7AdaYrT5y8Huo8oYpLmuSu;REf#S?V-L8mB7zU6-QO) zLRg$TXsvyLX}F>c3hXXlDL|YL1}bYcVdt?X zG`qc=N}u|1{zlq3@9P_Q;FCvgMHw@jMkVZ2QQ%|ZQ>b)NN>4|5>T&~C>pDQ>?-0qE zkH1jq?;Ci0>n49wUmLA#yx{%yQc`rOnd*%_0}BccL;Geu-0<`xY)c9t$$7?%H&DjR z4qN_6mnz<5s&r@)2Qx2y!QLzTfY;A#ZktGe3C%x9xpXQ>FSp|Bb^U4Az(DES0auXkS%Ki}55YR?dRYa~g4iZUKCp-!844UV-iV&FM8y2VOT{ga!)( zA*ode=WMmu{(?jrb+I=$KYty4`Ntj_!|p)&Vm-XKT8;+gXOXI6H5}A$JXzl~4D_b7 zVAu5`=&Zdfp{@Ej|MzK#z4?{+m1{DYFQcPAu7_E-8ZgJy0W365LEK(zHo8cwXJ(ud zsmg484pHs+tn{)*5ia+B37J{ea9!5D{y3?OQMadaS4;cR;EVm>fLuTDyIh8xWj35! zq{OfD5TRNh9=5z540X9$%uf3R&A%&_`7tqeb-x0Vt^}^@jM>s`CH(03fD@cbq7%m? z^~{VrtvYe_G%NVK-II%rcc*G~eM$CfP57$!8%@qzQ&R|l;GAZ>y=V!w{``~s@?4V{ zc;r(f@`)^R6ywfF5w$vK2_7k>czmu7T=fg(0^UBNT_+-mM`1sxTp-8d1@@G$(gYoG zBMz7K%U9Ow@vbI0^iS1VsBqPWxbwQ~#;Lb-@e_3km!pm)dLlY!UngOlPPJ(S z2pu0Bfb#G5;5k`~abIuK;8_8#7V@$@^UaSQ9b4LH%x14L#M#}*^_we3_3I9#F4_n_ z1ygX|b1lXx)f~|i8cK)452j5=H znFPwZMY}gWnOL6&W7fM}0Xv)&c)y|)>RNKQN7EEk#B7Gd0p9h$BT;_eiaGjuFn`J| z-mpyrZ#cNZ-iamT%U%)dbtRA9-?$BmWvtP&4=O#{W$gO}YZj@2d0IAi!&e2n9(^M6 zx4q$yYb&a`_o4e64@+BG)zD*g4BTNhvaHaBg@!8OSFPpT6f55CwN};Tl5R{kW85_8J1+JO1KVUt1cN^Fh+usEw0e#=`-1F?^^@ zqAIV>!qoS65SygO*eD$gJhTj6ZjrGo^K6Lxq?xd#<|keslL_G^ZPN5-<>>avfWF8d z$T!-Fa9_*;=<6fZ_iSKV*KGH@5$RicCKLPb7nm?qP^ z-$Flxtb@XoaHi`KhEm}zUha+!me_ieec4%Ll3fjEW=p{-;~iJOP{3AQ-$~Q*Wm)}u z5xQAEg~=zap-sl~JbJ8v<`;ap@DF`yWgad(84Nj~1Q#b6vwMCDxX=0lcOp5NzI>Jd zJBcmy3lg#t?VSthgvLA7%;pYQ-KBBamT+wJRJh`&j$gg6gX_Mh* ziD|U{lQsC-^a8II*>@zoO6iyVaC4@LO!F&XU#bK$#+fiTsUe=d5+S)+Cu3z*2KR6m zvky07p4S7g{CouNKKhA`Uk&My^A+5sjBKi}I2b|}=|Y!+kXas&rcZx2ldLFb_Nn6^ zmHXkxH>fJ%#=_4qwb>Za!(f!xx5PR53C`q zJ4m8@s1^HYKLHc0B<>OO#f%%8OZ!p>Zb60?ov77JJhcbFnfHB>d(?}T4$LQyCYR!G#d2bi z^_MF;q=wlW^2xNtPB2PAp3T_Nm)^`MmfThBgIi6WK#MHPjg|4t(owlI<8?x6?7b|O8y2p!Em8~ExGpsX8B}ETAo<5iDReJtu`XJJwkO{?Y#?b-^(YJ&Z=zB z_9$BYFPIDZrokNA8tC%(YoRjP5SJY>CPx+SlV?-E<0PHC5MJ|^Yk4GK?pHR`PA)V3 z`x-TDPeiag-4~jl88d}Ta%dFe!$D#{`uKna96MqK1FO5RrS%`V<7*FxpOxXdvUn)< zQ{uObkg=C*27|?o!BChe$6WMRQ0eVIk~ujVxM=iK_-CyGFO5xD%V#-!-Tr{nG)kt) z(YIl`sx4F(RN*FrJd$HJoSVAWonFrple(I(N}*Zfe0N8q`+;3*8QZs7wbpox2W?LJLVh z8K0cHG>iVrtKc%Xrcia$v(VX~4|DyE*}oPYEW8>`q91%kl?_kG>T7|#PM!#L7Uq)p z9i?RR%o^N%PJ`+{jpJ6`Orc4iWLce;tV=afWs6-SX>v)1`w{d%A{%2vdB!@e|o@mq^|m`+-~kiRt<9ubh`- z4s|FP0NOGpRJ1rw22A~sCJvst zlv`x4h^*?B^rqEDi0ShOUyQp8kBUt}tFQ{!QW5pIAmmfGtK;+DTY7T52qRUtbZZ2a zT-xS(>$*BxTUJB+COJ@)W!E223)?FR7y4Q(n=!vix0)EkPP{d^TXwcNSKi~gd> zbv_OFw->JNS7k|65mc&M#D&#bV55r?J#*}(^u}0i47I3~-j#1A5#<%=cIPU{d0pfR zv=rI(x+SzqQxR+x)$pgC6e<^bKxu>l)7sNcR~O8eykB02avPtJxHCftcknl^-;e}> zD~9r)^JO}DcmPPGnqVX2nucAUNb}~b=H7o)r_H&SdvtQBEc4f&p9OAzGD+xHV>YFv zi~gsRGfUE_ ztm8te|3Jzq-B8Dh)0d&&r3m;|s>ZZ^3Eenl3)~Y5aC(s(wb?xymL4d<{mDr(-ad;v ze?@@lD+qBrHVqVAn$hH@4!z|XAbrwOhXx}i(X-wh-?2c16V0P~G;`cCG21;XlMZ;` zz=ir~Q?2}l9uGM?p%2ajZyE-tP^mP_16vgMZ(9J_B{#}Faoo~1kZ7OU>-0B|oW1WmoR6Uao`OX6%NMyp!^y{Vvi+nid*N5I} zF@bbjORx^^#{BkNGU=5)c-6=l@6Ibwt*OjAXQ;{e0c)7{zyad^$+0~Pe5sCOm!#pl zItHI+@O+vQOzLC8Iwo{emC^^?g1<@BvGGRFygaC>0)3~1lLMEXxj9+x^lz&|&%C_O zt{wOH)t0di0g&6-iluwK=~~jvaZAK(Nr=o|#lIs7ON2NrS%DrcGlz?Ar8w&8Y4W&N zC}%lQfd6KukfSkM;A8w>yfsLluD_-M6{8w)&g2O+e7+uUW1CBlS$t`3cUvXc9q z{fWM<9S+kS4#C=XOSI^`CtLscPC_?}S(q!ObAl_lT>TVE9m8OJpgx=ym@v=L+Bn+i z3b{6>6es2$C%P?x{MJ(%czu34*-=_SUN8EN)jI_=UMr3}_9%s#zBB02%(41P>_$r{ zedxIZnzxHti58{X1nlOsaGGP-K)!B}X{IyKF&ZQI zW}zA$aw&lw!M#D)-;mjKh_OzxjC-;{5pB+%mCn1g5$g8+!PIRra7e>UmK!Lrk{|=B za@dUbDiEQW`I;WqcTcQ<{na~5<8NHQC@xUxb0&|>;m*nF^@#101fGb{y0-7tswK|k z;3xh|y9hyLvHaF{9sHKoA9i_{6VDz0(5`(34am;mcD1PCq)X>v?WJ?@sa}oQ?|MSr z_${!h6==?cRH*-;3~X@;>WtYFNm3w6r22S}Z<4*xCm zpm+5+UPntE_tr#!kJbQ)Tp(tS=CbcM+=1&@rb9P**O9tRJIKf~!wasubkOGii-ukMTnlF3*U4v!ZNCW=8q(=3>Jd?zo*Ty$Z(SQfk0cHCy7HUAFGcI$R zs*~shyVE_pT45PF>`;Lk{%BhSn|U>Kw!I`RG?@d6r+(rbauFsiYLm|1S&8xcWL^0$ z2VQxy7$xV|!G0HYNL?dfwQs{|SF}ENy!Qd@+-gsk>p!BbUK^uAYhjEWl9}~J?AJ9- zeEvd(KdUCfKlYcUvv#;ZfUH*3yq=wf}<4Lzb!GsT;ju;YbHq@u3|*L`|XT1DhqLGA)|_7$Dd{8P~7+o zt`{@iAwd7#dq+NNQhH%oDlFA5CcR_6;YsZSq(&}`n>|{#L-#0&%sH|JVj>w1d{_#j zTR)O_G9EkT-x%t(NsI5JnM;j*=EBHSZ3ww3xQK}c>-aQJm;cy!fjw#0y z|AS<-UoXB>_KZFzP9<6HI$-vuQ^o>mQKQu>xsX%Ew71G|2)=p$lF)J?_D8j z*)3)xJ%N5cTft4eoJxn}hV}F&pF)k8(L~Ljd34YsGtdiiG*_1A>=!bbcyCAdc?rQ5BU``qDlX;d%X&?uMs$5?>g2tAmtEMQ42 zggX1ylVP&+V0t~B-f1d857&_HH2Em_`524%DS!2&)}}| zmqfQ2vr2yr)LDw$JXK9hXc;f1vR$@L*)ufx$uSsLFqVtdPNrc+w5KEfcHj>t{+K|A zwC#d~d9wXh^H92{R{=LsQHO~Vs%gQfC&YQP7CJOdl+M4>NcAmYn!Alnh&6j+cv$Lb7^4KB7z= z>+DT?d}c~`9r~9_=&PNpxeBQ!Wuiz@G5Q!Jo7&*4g(YC9Tt&QPnzriFJuvFu3j*H$ zz=FJfiya)+aN_b^c5Wn*X9k%49lvdIo3UEW(1}XQ83$ zJoGnIW3MCAXm{Kuxbg?6E)_juCmmekk;h!R$^7kyvf7>5^c8_L9=5^AU?rXSl@;daxt?Hg`<&SJ% z#$=>2?REG8VLIg~nPNdqo8)*uS+_p@=rz*vpZJf>#C|&Op>eL)C#Ei0H+i7%#%I>N$|@;|*_j%Xp84 zC+WW_b!62%HN@t(ke$*STCd7j%`y@Gys(nnPE_z+!pV$1G238FR2M4690P*~W>D)? zjyn$2gJha2pR-DY9R_nD{f#}Wx~RfB_MN2T!ne4-TBnL82i^d=@tb(dv`GGp5as_7 zt~gYTG8dasQe*^e{*~CUVmo+@bmxBTO{PmWKkVsZ^w;;t)E|f8_w-xDIZK62ynT|M zGtcKng=(|-j5508_+#Qj95r^jUyj4OMTSD~a#hAlotAF1=nhl++z9!*Dl$Fj`{8 zU&e1w(3$0RJ!_|qzbd}wio*DdrhX$@%`Ut`vWfId8pav;PKxKVa z@d$Yq^y`S!v+9zh{aF>d%NWVz^2>a^l_qM$==bz88Cn1EU%zoQv?PObA&K;ncqpXs zqv0C%#mJFwpfxUp9LNNkeJKe%WIV>2#b5CG;g!<=^2r%r1gKOUMzRX0!HnZgIDAhR zXy+c18rs%jUg>apbBBa?A1Py~xe!oDwgClGj;&2-r#GbQxPTM7cw?5z|2R7Dcq;!W zj@z!iiDXo^DB9fTd8D)zskBSlOG8toBr2L{@1c@aMuqSBo~N`WKa@(c$%<&Jeqa9g zdU3CN&vVZCd_M0(d%V9-#yzgWF}+siI8T=qQkcKbH0&r@UDY4*$F^bVuuhO0o5$s| z&zG)n7?cJnf!m%W`llfRoIlvZuqGXGYMBBG^X5Y3Qe_OC6P4YSf%Q~v!I*P9;hETx zv*K|xl7l~B;=n<|fKpAAZk`MG5;P!Zsgk&B+yNRtU!T9W*_S>HkihNK<1km=0LL-E zM3=r?{m)1&UaX1-a}|ZFET@pIdnlWj4gvoW%3>IQ1U^JO z-8^UtFDBv4w;49@0FA*YUdPx7&&+CMyQWQ~^120T?Z1}oyeFF+cwdR@&a8(4xvzNV zH-9kgD$7Gn$;j$$tc{!KeYnnYzR$J#(7-MFFm$mcG&yQw)BI!E=N@|y&An`pq*tQrpUDB`smlc@Qq z^Wfxb16P?J&wpICThEGtd_R3pI?ww-&XB#DaC+5OoOt>>oVMNt<7_p>(ztXwDdY_a z%%F4-%ijK;@t!zAIoiJ#+`Dw=(d>D2;!6a1_hJK_eeeg(z5l^SMdnSC*5SbrXZkc= zQ{b1WqHRhP?3zCgoPO$xr4d>5##J>=W~n-QyzGR!Ge1bfiAuCd-{=1DYcD~L`5a!H zi6A5HX~B<;?ES1$q8rOM^4z~9`s<(qoLKJ-{Y%ww>9=UOYw?8iS)WFYWA?+X8HUhz zzo9s4xiZ?CpC&b1AKk@81YYNCEqsJV_Hl-^i{mV7d=a(aj6nG zr_l?}7RZT_C->0AV;f-RQ3+NZE`YT?Jiw{Fhj@Ck3c8$#@ z=Pm|E=Wy8hxCUoVs)En2-|-2H)NticA81`Z3BEHw|3vi&+J9;zS$2_mNQLDMd-m3pyk-LaH6aB`;%Bn@J^vxf?XSyKK3>;1B`rnz_Zeg@4oxZY(B ztD__N4l$87Rwt0*uLG&mmSFYTTX5u{ zC!Bj>Aj;a>u?jyE zK-21%@L#8CP;TQva`^ooIKRLSOK-l0_{w^6tq-NUEpI`SrWq_9+=<{Lm1g%o!TBt% z!Mv2&;NEyfpmTK5;JG$D8dgbe1}3K9Jr@P1nfDC@?N zfepa2N(tSyZuIewh{ZP2KH?+ZiD$Eb>29L=W-_FOx1rG70%ORooW2JeFj%oa{a`8; zIOYegyAcJZL+#)nwHB95E2Q>u6ZyLN`c$s4l5}M>dSw{md53C-hBL}Q^BlECBb*PDpn^?a@X89 z1j^Nw#i>oZ;N-xE++R5xF=B{ScOQ68xfd=-UIAq%K9Oi|C2{|}2`wWJJ6xtSu1_AXKJyRmx8UgAPw81F6`22ULn`cZu!eyf zd()u@bU;kBfGMiX^PD}|{rWB`iFi_pL5?#)eVT%>Ku-;GV^q35go|sxVteFJx=zx{ zd9V!cne;4(d!P!pyDPv?wK0F^J06)=~%_Ge7+Q91JfPU03cb0n>(@B3J`|Rx-4|^=b zA!CQNcyL}%+8${pI3%g!oT+1=VT?C?iBS|EyxUEO>}?>K^%A`0mj@$$n!#4)Bi;X5 z8O44}c+LLGc>aKcbnv>3EQ9wG@2&O&*Y74^6? z64Oe9rw3^7sKxz1J%QI7 z#RpAHq7ScMBBg!{A@Tc993C~0KI*?2;;$-+wKZY%6y)BU5 zEl7Rei2k$e>E*~J{P3l!v@j-utW(H;OLW;5VLG|jzw-WzGv*C%U5{e zP>?!C9Nh;OhuDMqFm3Tq{B3HUF@V4IM3>6;E$!YPmZbK^C3Cf?c~%}d>sp1qZM3l_Uhd2Km0Y_~AxQ7K3U4;22qWI5<}6ToGkI(QT* ziP3s{=$mwXzJHhx^?fJ{>aXL#yGRcM(?7uZKO*Vb!$chTj4=zAC<~_U63qSRC>=xw z!lK@)qEF3oICS#~_tVHmjA`lF-3LyK?ui*`^TA|F9Vr_48Do8y)6_LvdC3)ZaYgfg z^wglmAhlA(wG*7BXN)hAMZL;UG3zgAld&*33ic@7fhe4u8GxHftd(AgaPNoUl*`7Jb2I|ID;)(G- z+@#&Eyrg0zJ#Tcfdr#OT+m0DcZ=vAoPB>7~gxT5FRAu@n{#>297~7mc6K56^g+!JM ze%J=hCwoEL`f^M=?Z=Jf4)b|BtdBDCB^#>N!_Zn8F?>@koF1wTyIAkEQff=TU(^%M zGEew1mvF{=7zb#oExx#vOiw?Sa0SU~tk-RaUmf4b?)(}YUND!NHPAxP`@!;t2L41S z*Mn7NHF(DP1+3(J`I0}$baCD{(r3pc7!qoQ<)_Yp$=N1SuqKUG&Ikv;zJ?Goz(Cwp zEQ_Odo+R&%SD^Q!d0cUJxbR>E+h3JVCi6T?$%zkaf9vxcE-$^vm+wuZv*SBSk9(%z z>c{eKdKcl^kh8=rl+7%MpTd(I0U{W0t#XS3-gq3#$**ysD)a8SKi;PaTE#6WH?Kb& z&))-I6dG`mR~~GATE>53I#IuY9$@^%8(Iq$#G`2;bco3(GVP)&j;VhR1IjF5M-=nj zX)B^d>mvTUnKBOTc~lzVw-N5zRibOaBN%-~S@@4-%0otbK-(He5It1H;={Y?2$fAz z-NEX3-0dYKX#6AEawekeMnxIs*aq-7_dEZQW zE$;%Ed&v?)GiAi~R2SN71FL&CI`CZfQaWwPPkv;C1Qmu|g(Y$$K||I++-d)w?mg?z z1#RlYe>);M;So<#TB>l7uPvOOVI@@FRKp2MUrEk9O}P2D5l6r3L$94!!Yk^l(<(lk z3_KJDwpliq{refn&8;PkM+b>R_bH+zr-$%!>V5iT%SG6vZVWdUenR^>A>8<^9TMnhJ0>h{e6$0I5PAd=!)Sv6yOW8cOtL=0Cg} z*6m%49Ll`Gkx8`w*#Z2-1RY97ye645Se7K!2KzA`x@UDE@oK5XQ)yecsNV7d*r?&O zy%UM!?13;oOoHBF();k&wXa2=escuD3Lo#s6Yc3CUq zygo;z*Pi=7boGRHf9jw?#%t(e+<7y9j*+P%PA^ju3U906z3Le0nv}uNIA2AKsT~Kp z(T};s>Na9(gf87QK+QwxVJ~b|oCRJ78pxPUpRwTCLh62MEB{9{Ksve zW5Y?QX~Z?MU`iPVJN1Qs`(E(OSch+?^`o!)-^r2*YQ^Q5f%MP19>TvB>ge|Q23T*l zhU+6;#1a#ET=aJxZ=YjHb?nrkAk!SyCUm0d=}1oA#StFol%ZsMU(oK56*8DtJo{}M ziNELs$2(hb+Grbk$FPx$-fVz3D$~HBN)7JoB~#tI$6=F!4a6^~#PuUjb1!0Dd4oXa z&v~#r=ge9ym=oEK^7sOl>4k#Lr*Al?+?t|OJAc?;U95MHr|T9Kk&<}kw@+$@OToS1 zz~Bm;^7{-Ik$sq-HA;d8UtGI;!ZzDZw3}E6oT>)2o%@EXr&`lXGChP%Ix46(eJ5Qw5Jbb|Jlgmy%$e8nj9vus-}EKWT=nIDU8#4Gmulryfc0nc^dOEb9T@ zuM9<-78#7Sj^TdZvZwh=<)k^EG+@vKrd|FpfJs{65H+I#Hw94$()!5vuw*mrpCK@O z`b5y)tROxN-$1Xq)xd*CSm4(D9tX9Mg1Cu?D(A!;ATxGwLzD?aM70or#=F1Ckah8Q8 z|9XfyGvv@^74XB^9B-%hpLFeVeOSTrq*^-CC_+zIPEjqRlQoXfBs~)dt z)cQh=vITl^IC(Ka|GIN?gU*}apDcOmF#G}0 z(Ef`T%th|7m$oo~aS|paI+82Q@8^`SEGnsegyPy-uCvivwDO-z*X?!n7|F6B166my zyQ4}l(>R&-+!+GvJMAH?R!g*Y{YtCO&V;^ql<>%#JZYPeAM>v^;-L+C5LMikb7FE8 z9=~y)El2waFK20?`Bx5Bb!tHTC2eub_HddXXwL6_Jei8OzY#y{IM{MY7roXOLb^SY zg6Srr!%lh3UalruL@la?Ggi>1c+OYbhC%RDy7l78W3_NcDF<6S zipXm3Mm+5}gBn?H~c@1S)m!<}bbn^K5L%-qD&OWs6LQ0l*RSOnv zolVa!F%rZb>ey5MT6e9x7Ccb=XDWv}g~9yX#TL}{x&-RI%wQ1nF@`VB=e++8g{x*| z*fEfKEn{Sbqkh+t-E${E-7{;v*m@F$hfc$@D09168b`iyI&CvIy0O$T)zC;P4R2P)SdaT+owHUFcvHPWYFsr@Uerm z@WKiWF7=!VTqyd9vNvSl-Jz-cBj#aiX$~h{tYg*GALx3;j1EcL2nNR5;@8X1=>XkK zGS5u|b2h1Q`zJJ#l$?)PvaXgKNsi+?Jb_xzJWAZzJnrcyBf8w{L$x~pk;DYHSE-pv zQwIIyH_TJTPY2IK^?ENjBBw8obSR(`YNv7M-^q)=2Fme!{Kk;vTk0qs^M(Y>(1MLs z4QTe-fCkN9%>S!Ur=bQRWC7!jd9+#J53SecEBd#7vT_@E13g{NkECw1r!}mC({wmFy_$2NSE?vF6-;I6pq06JJ=1fAjok z-gH-wt>)?&bZ=`nFEr0*tGLxy8>5`n1fQwNbmEgu-Mmn*VOrvrvd{GTsu?iEUJ)0B z%5(oE`@me%h?n!fkfq~Uf4IB~%jJ{6rcXa%X-^G|RvHL%Gu7Y*^ZbA9xr+|`X~xgp z8je3d8B?cfpi$-Q`xyEJc0RdJ%+_n*vm`ZcXObJ}s?_4XmL@VlJ)X*?nKycg9BkVX&GgG0dfrZx%w_nKIO4Y$V4=FZg{U+HpX? zo-}$xQr5%R&-loH8ufl^B)A)BqUr0)P~>R~uFMbY{NH1GcDukg1ofd~K1jO#hnr?A zi>DJ5`LM8|@NsD+?soY^rs^pOebduB`k3E*vwJR{ z&wPVVUOc9w-(Ta?4U_5Mb4P)eSi}BbnRt20D{jI!9saeACvCg#*sYaV_B6%feN|*z zpDSdr`&YF1YD8x)YU8hdRuyMlI!iCB|3|hmU$OS0T>7d&DwMcMP&2jyW^Xfr6`tjI zWRwiw+2=4nL`@L`*VgAKuUHM=_84G=@mpd#(1xsG`rX?kO*+qBQy^^TIcLUt*xka2 zcdOWQ_QqwJP$uDy9%P=hqgC+a+7}WPt0EROnej*7@`7Bo2BzHa$Qk`gA7anfpsV&Z z*l@y^Kht@Ox-Bgxu8+pU!%9osyEqyY9O_7q*%I-T?=dUs+DN zaxS_j{$Y02T$;URH53*|&~qSx4MhTMNH-FN1HWi)ehhci)`2#RoFrZ2rwOKaS~0;= zBwaZ^hvFJ6{&xvNE<18VTa00<@h_a6@sxD2 zls`UCq^f&1l1aM*fV265+ol-Nc_te{bkq>1tb0H=@^^^$cs;y7*M+NI_LYde%kg$@ z8tLjGt-mAvaA+S{)?yETv^wy8kv^5oY9~cgKV#{vNpxRQJJS(V(d+zaxIfzqIA0BM z$h8O5KzkyWGEh-;nPkZ?Uo?*FPxy>R6Or^P?k7BVW_hJIkBGEL6RN_R@ak~wZat-! zktSU}cq5rPE*##hx4^)4X^<@`C36mGh_8P=pz#^aym0vry_kOt&JWcCzoQNKpRy*e z6&}r{r`6y?&wHd&=d2L=Ll5Uv7LZjts>#d5dVEl&L0dx;_)o2GY07`@&=$?~fF@<} zcj<}l-qI~VL!6QQfLiu25w^N1jNx4h5k+AE&# z)r!x?F$PpwXpYcWg^8W2bl&zMLZrxYqw_X_z!?4!@)B{=w-Zz<*zg){Iy6h|S@%pm zuSy$J*0jLEgbX78?FV`gLq0E1L#RD0LDg}kIbA%`vOUV;_n{P?`_*zotF6Uh2gcLA zfvz4_%hfRK*jk_lO7PlJB1ZQ(N#!RW=QD$n>6XfM-L*8Uk2U(GN$4|42q`mC#PN=n zoOPTJJl@`fx!Hs$YqaMyu*{Lwl8f-ot)EcO{3Zc<{XlbzIuz&2h)x6N(Xk~OymO;E zJ-+oEDGnJ2v*j4We|$Er{K9sxCym7sxt-MFh>}3r%-g1B&(%#C4#DH=u<*crV$%`N zU2w7yeR?;;7B@AIHL1q9c%2(89bZj4KQ=Q?zBhHdvYD5>Qx(4tr!+A=0M^;*WA+MH z?qfwF%S3%d&8j=(n@t}7K>7uv?&{GsiHTVUBU|zGqRF(6Uk~9UV>Hg*a}FBbSc3uc z%tz!rptoiV{HVO&cyeP8zV?CxEVr-3f~6T`P_w)+i```i&w4<*eBJR*isJg!y=ig2 zEU#6~JY!!j!Mi|ZFkv?r{LVa}?bojHMRCcrcy+&6CC1|9y%O;0L~ zk?-z5e<(QM3!^%s`}_{MI;$2lk4tD_Y9;T(_91QKB&;5@QCgB z=NNtj8PA>&-B^xZdwcNfjvnUaniTNIi{zZ7{;T2FbEf|udrBs4w;=)784qWjgnFrK z3fYSp&((hkClKan)XGna9Sqe&Ou@rUQ9 z(Ne>WaOs`_xSHvSx~89LP*WV)_wNsu=sWY9PR9uk_v^De5;-|XCbbZ|8PzN!a{|tM zzQ7-!pFzXnb$4BL+Npy}+k;_SQUqDg81LF{_u=Ul0YVrm)K@3j<~ z884maP?~IKBGd&ip0nnAn6=jp3Su*`^0O@e$o~?bd7ZHb&s@$~u+P+$AvfFsUNCm_=2tQF+Er_Q;YeM2DD+WxE+&1J6@GZ6 zNWG`MB18VBYDRhy1*fGw6dWI5jAVj}%iOc2o_g@!ncgIXQy*PIC2_ za9j<|1DALEc80TAb;P$A`sPU-Z#*uU9;;f_?cq^R(-gC7YU#tN{*1Y!j0chguFJ#I z#(J~Z$Y|2#;rTwR3hQlS!C$qX;3B7qr_Nb*Yd6jxzM;;DNp#UiW&RRTr%qc>k)M6X zfxCKN{Bf}ic4odIJ9O2sciSlLU(`@oA5@Dg+9Ju}De+tstNHf7-vRld>M`}SA*Nq- z?&d|bvA#WWHRJte2J$v+2c95 zwn>Ta$Xd@^$tt1TsPj2DErQ^#<8Qq4Of!?-P7gqbIGET@+D7rru z@_d!W*1a+Gq@4`s7^;EC+p8ff;3s+JorS^#MgG7kIYD^F?s`~V%h_>??Jx^#@aLmA z_@3j-mun?c8;2Jp$i^G~GR9zjNi@8%ZX?0_*i9KRhTdy^%a0kIMn7CUY$WtO)MrlC(NM9 zpfARY`@l!`B#Hj5f_@{iK%6=PKJG9UHD~{zZ-e5vOMRT^^@WF|r;D_~tF;v`q`8o) zFX8Zado>O+-v_EQ-||09CAitd2tq8!!3;M!(RRud8gE+7m^kVfJuC~dH2T1rr^ce$ zoDS-_c@baC^o8X|XLIwo4KP;a58g?1>#n66*!!t@G7=i*Nd)UjDmZs_4|wp}4(v*m z#H`|(6h^F*_MD`PDYHZG4N15Cx6&Ohk=GLgT#OcP5ZmUGR|jNyq~HGb`7MD4!!Y^U+_*-T>3DFE_6sIa~NyuUF=#ec0&iDhszNT zS(BN=j`N|6!<1TkiCnZ=1B;Cw;O%22pto8i3S|v==O9PDzP0c_V${&bEfx;ej)v>I zHN}caIW#BAo6EQ@FCMG(=d*i{A?^We#=K@roImvy6#KHDmx(8n?`gntnI~wiT-K!x z@ivuebbDt2S#A-=JOt_(QxFRooxpZMnxe(cZ0a$jg%7@zMtg)Eg6qY4Fi*1qOYRAL z+wf>k&#eJ}-0w#g*<27lh{kv->Mq&Oy!Y4C83S;ZEY(a+;A;|@4}|^Bz#Hz69w{%L zzYs;YzFGvv2Abk@l1*nOnh2(>NBvg*8q)f?!SLeSsOzD}>nWY*pRH%SpylIox;){7 zC$oOG@u9d|)8cFa9p=uB#?Kn&ON;m9+24=@93r zjGAZWa=tZw5bDQR(7F9dWm89vI@8=w`bR>a8b{$SyIr7R-m9D4>b&|pn$j`!T5kzo z8Kgz`&N@j}Hco^x=EJxC^8sYez9%`i)o{AjV($E+VPM7fD)HJ5q-z(t$KFO1&Tw!<1F=qHJLi=geQh1gADNRv8xFd|oWm|~_PmPtyC8#pT{|CCKe4%Q zt{2~DVKnrA^Z{{uU!wQ>Ilr(;#P)?HP?K~ZYxfnF5%|Z`pJ*U>GyhEf)R=CT{yt+% zw$J`Yy6WmSrysa%)&%~svmN+2us(c;Eolu^5Pk=;{CnLMa=)%0{L+7ju8D79r4n#Q z5`W_imkIRqq3J@MqB?4(#e&5>Ie3|tOz)pK(5(j@oS%-;h~E6E7A@Y%X(TPx9FQG3 zLW^-a4A8{zIvJaEhBUMJ$mha0aBHjJpWIav^`fHbxWMNmB3KpAFM11|iKcLFO%8s2 zY0rN=vYu~aUWElW>#{euuLXSl8zo-RpoZ$O)3FL=N43N9Vm0AC^Phg~HLJUp&aYPz zCDGCJz|?=ze$4YZw%1$eeYKtF%HGEgYRh+K$OpBM zq0h==iTwOK*p$BVw1a~)}a*Nf6F|Kx%NeKD#AvpsV& z$k-EAXpylA&TKB>eOONp54FI4_c-vFE+X>Vu+1;1^1ygbT-VQ38 zwT!QARYHwLA)K@EMhGN-a6o))&h9C_z|gM>YgcRnS!ao0)1ZR;=jcGcD8`LpH#JrW zQ>f{{b<(43ucGjP&BFSfBw;wKIeo*p#&t&UzOo9(emsItTflUOO0GLEbKKAf z9Rzduem|DHdf9@qif*(%JCpzCpe3dl+^78Jbke`p5PO%${f}~d#sE&IZ~OPHj{zKcMZrl4Wa8lwDA8{GrdyzP&aq6QPdSxDWUms zeq4mSym(SQm|xs$G})q4g%=vba}<*L3O7?&uWoUYblrpN`}{Hb#{CDgMNfWipbEV@ zU^-!4HAHc0XxnfYypjnSCYMInEQ#u#@n7(Y;;-Rb__6<8;M&&JqIN?>PTAqJg3L5i zTyJxe%$wXsVpHnz?uf5Y7LdR%WZs(@K`QWQs}%NH%ZuXnNcvf25qs7sWA&N;ppp!S zO)V*Sc#{=xG~+D4MpuGUcU{Qtn(M0-n{epbPm|8wqC|A+Kbd~vV zxXuwsw34_%5=GAqv*N8b>CpeQb4XyQ9SrTGk9tOR@N~g_(zdk%@0I!TN=7n*O};9Y zXI;+j>P6KV+jI5tV{j*+mb?1hS}g8#?%t6O+QaTN8O{b@8D%&`mBi`NDB5-;mbc!K zOy3#>cGt`acMWl>StC?B1d=I&B7S$|GRa*sCapFNyk&`*ttkvvO@AbX67BS?H!ns6qn6<0Hl`hU+tz+bGv^UptZ*G8A&N@Bo}eKa%r8L7Laf{y))7^{P2 z+{*8w|6DizPu40ve3BwMoj5T(`{QcZ_Mj7!e0GABhX(v7VY5I$EiiACuu?}AEAxDz z&~Yrp&QTJn{XQBz;IA||RSh>Aya5yPmBd}nz^7)z`H>I)@-Z4(IIYi6w<-lg*uA_K zjf0nf?BFT1^H65eA#Iz4cDNw;@s z#WEf7Y~n{c?*n7k-@A<}mP7cXvVOwVhdofG>4aNf{jcN>+l}07S^#UOo#&k-cj>Xr zdt~z#bJ)4Q6FcQtM9pyp+(8N6J(C0*CkU|HslOP<=AReSZ*doAIMUYjY2CHag|S0t zeQ|Nu&A3bqf3W}cLx0HZQOGZBmEd@$1BQ8y2fKWGRO|?ad)p0&2WVkqMg|!5vWAp_ z&f+68CEUDkH-CJmGR`lH=0^721OvBfFwe7t` z`F7p=&!-E&;_=E37-6{{RyZ_cfQBnQv^;}9c~(p89hE^%Thd8xn;!btp5iiNzY< zA8~sRiS*K|IQ|Y}W#4Cv{5dUaz;cL;=u!6%E->!ub<%`hSuWHey_KJutb$Gf2f&SK z2|r@=MVr!WD%W#5mo!>VyuKuoU!>?o{y`;rK2wpFtm`Z6Wp_{djoD9f253WiM>~$( z&<<@sSMw3Sb&))e0oegh$@&U5M{L~R-A}4lDu^>J5AZRIE^wpjE6{PYinKWRl(1w7 z+j%}bM7lV%cF{HHtzQGHRc`RlCnnR|{tDfG^0tZc;^n42blbp1@b|t1uTCw1KL6Z7 zwIBt1S`OpAJkRoG>@_AwSh;sGw9VHxVrA1JD31%t85vcHfAlM1@ZiD1%uHqUZkzyz z{`G-n4oaeJVFdk?*q2wFs!c}+XA);aTR0rTcw(#b;rNW3oMb?$6UtoP>Q6vc7LUQGnhv3@ik@zTJta7XRAYYZdP8oG z7kkftR^ZO%o{%?PS!n7n!2&NCcr@J>rab$LFZ&Inb>{-59@h+T%;$Shx>*@|_g2Tm zz)PIh0wWlvRf`LW3fIN0_2`#ESIq1|CT?B?t8+W>&w*MPwrL#W~Mk}kHu z{wbZrIJgF>2Xpei7x!J06;(@#N-t35P5;C|5t(Lla;x}drt`;l+AG9jY#sKyq)m=tWGMFfY00O{13Nex-0W9 zG0>HQKg*1#w(q1Wp9A1L^9ElEcma-I-Qb~73ZBuPz)!w>hM%}cf+M!{k$R{5!ocSZ z*k5ftEGpZU)7oB-lb64T5??n#R-%FjokzpXNGlLhl*9)Sd)VzlE56-Smu}vl-aTuN ztI@;d)@9&XbdT(F%)ncwQ~1eB`TXT|66_h+M>^_df0({WA_gk01m72R+*eB*asP^5 zlw0fSVd|=h&u@E!SA+z9yiB4A17?7)oISYJtBYpwg;ZWL6+#pxjB9n4yEkDP{8Z}1 z&>BPT-%eRFl+7|L3r2S9=~@@rT((%Td%nKCuG*+YK4HxlHO}eo4Q{g4U!4DV7QEkED6Dd4cdL~Zq3}Qf z`Lw19)!#VK?2L{4!pjoz>BAc|ZR1?9{_z<{sU6^hE26;c-A8OwVho1rJbo0@*8R+D zz;a+xmL|LRbh@)2b@n$BMks1vp18l86=}h^*%Jrfp=XjAQ)QSreP;ieD9$p4DY8FM zxO0eCF}DK;rlor7O1Q54b-uhRnxw7n_E^qU_=2_VRiJ#XkxL&_k5m4$Wg7)ALFs@7 zuJk(4eW##>u_6zB3G415Yer?@&aLzLkW_7c`Ylho;&-BZ*WS`!tqmJKb1>9%I}~Jm z!mM+JFetl*k7hg#-37a7iPAF?)~JFLkG%jju_u%typN||EanY6*6@YQ2b(y5qqLyk zI?xUJjc*=|f)yd^(AlF3?f<@j3AfdRHQUwD%ah%{>@^)mhPn%RGwS)PZb@1 z=D}K*4wBU?0}uEH@F#lw<$ummM`QgkX;%ivt%UX1quE`E!&CU&vLxCu>ns_VJ`t|W z(L(F#;~<>vRI>_|M2oy#)M{D@|3@K%juqy1b8*i^GG_btVmdeX7&+OV%D8!R`4fGo z2#!v=Sde=_I(kn72^K1lUUP!z8|V1Jeecs>zpjyy?v|i;`4@WZ=}%*)E(1&U`6uS_ z-MWu#iHX=OTSI+E9p`3iI?{oc-gVc;l{G4OtKVU%tlvqJJ-dwE)3kwMs|)$_<0Xh& z+Q{``<6wnER=hoaAbp=vK~@fGL$BS7Y0Vu|;V#S3%-x>=0TzAWh;)#s6sm|W@AvXb zUds5OI)UrDZRexPZm)=8-F5Q8?~mAc-4+u1C<*Z)+75FlC1vl%sz}LB^QiC;$ z#QEuBc(tYjmG_l^mf<>>(oaELkTR4yxIE`yUeXZdTN3EB;de;UDK*9fOXU`ldctoi z$KI*SxvsgJza_y%MH7i(W)K7uIkD_=9eizE6QhI;oEwQB2g>Io)PLACH@%JGC5gITxxdzW}dJbFb z=JRe_tTES+F|Te_k$@fP^kH&1^y{k+o0JsAK-M$1oW8)#oK%T$ZY6g*=ale9#vD%t zuOaJaeI*V%tI=`!Gid04ogbuhkI!QL&u{mAO`UXZTa-;z_lajFV99jPT#hBe`E z6)S4Dd?P>6R3iQudX>%#nFIH=8SiE92|l4C3Wgo}i2KPhZt{gZJ~*Tes~d~KxAs<+ zEqhKaRq0Fp0`-Nn9*kun*$b17TEXmKZP9dAGF7VZr zkJGe+VeGEKry*;(PfYheR-uT-7sis;0d~-O`3qiYdkwz*nmCmY_2`n)oBBJC78dVT z!@j;Ob1W|h7KzF9`QlxmdWQLwHs|1#{X6(es|@*ZjjWb_l#_1I(}H)lZMciw9aWsO z9fZCOs9gOBcA3`lL)IyZHhs6!@?LBXN|E5(yhre9qzRn!NyfvwSMtFT3;5mayVH90 zo>bDX0XiF)pURAa^C2~%m2t40RoRW8_;K)FswP@{@20-{<+){c8u;5J4|LyrC-omv zaA({aKJMi=ehiyWQ#U=5hM*xlTgvvU3Nd8QL~qdBZHA4{rh)yd3UZ=nIyL`39VQhS zz?w8|ah=+K^y^!e**=|thXXeAdvE&-hllFposN9zq!-QP?7MPI7;FHS=APrj24v9z zL1)R$UW{Ka=;0=d(U7OMkMxiGir$usD7MQ8vMeCi`u7r8nhPvf&+ZraSJ2g&$GK&* z^zeDZduhnK%jD6nGTf8IbhGF}J{*+s(1Z%od;VA$a#dD5^u8Z`o>@tbB(~u2sdH%h zUlSqWqB?#`y#|Mc-XQgG5fksr;K!&v{6VIzJMJOeh}GNRr{W*H`7)d9(#n;B+1x!? zr#rvnzlN~^gDOc^hH-b^cf4d{P0feQmF{3S&aB&$Aa%1M^kPiWg^P2!U@sH+yrU9r zVm`0_zybyRSWtiTo~UQ1(@tqvcRwlV)q$t*IzM3HF%H!$ z@oVCBF6hW9!QFvz&w|~E#=Z*T_qqzN>Eyu4Tk(9~pUG6NvyrLdQW)ncEB?)1LrZ5a zfZpY7kJ0BbtQy3@?b$cc>c9%#F!ngVd4e()G(MGf<+z_eYs6))M)0{NB&R^57LU~v zc-lBr(1~QVv6mYhT5rpCO>EDzV=vWxHh{PH)utPC5(vq&fv3+^#21Q>X+py-P=hZR zpC8Y^{;ndlj8wtI(ihUM`!5To)}rqnJ(wByfFrCnHYcfeYd39{+Nd$s1D;G!g-f2T z_%v@W)#??_TdUTV|=N3_T`&M9(HDi(6k^ zpj!ESyFiT!X2XCUtvLJFRo?4w6xhbx#TQxoIO*dX z{A7(b{403^TMpjJauz=0%@r23-p)v9F4jP|h%o4!V*?Y7w8g~dH>vk%PrlLT2Ws9- z;N@A}TbojcT-7b^ij}euc~lXHc{`B(>>lXeXDlOs?Fp>(Zsa^4)uWugDf3v47EZJ5 zVf@KZILWde#&@=el0SMlK3P}zej|mN+3oDkHa6cPxa(CIzdg{1Pg>?lmlxM4| zo4}b#$@nZ_U3Z;4nWBQTx93UUWN(CNU;kkA+uq<+p#gmFO3aPVf=4=P!ue_ylx-Xe z+cL($sR63u4eL-^6e-7j3)8~=WAXu-ev|N~6ihz5fuCOUjZgQ`M$d6?q*uoov8<`J z7ztCM{{9Jm>Zc@XW__f)=QMS(#EKbX^Wu;U(t}TV?^AS zfd%tJ_(|veg_R-dc=JYqv}Iuhd48lEO=Y#=q5V02&PbrQ@17%`m#v_#{0EL>`KG>S zmq6!|7EIHhL+hvi;-552aHjXA?hN?3U5=Ell;OI(?hQ-ZS)KgE)lH3n|2aDEcrL#v zj@x@HilRYiNK?ymA0bV&wX~;FztYg8lC&4mprJ&=2npYN?s=%R2c;={WF(17>UVwr z@8#9^`+c5s&pqe!d4KNPe#VJ;_4J`F=ZzTgtfgl!sr!tvuzzzCUR~Ukr6<3p2Yc7! z$c;1D#WQAN`7~YpnRFRCwDy3b3pCJE@3GMC_i+i+kcz65NQcFC@N88X=51)A7w&6_ z+C0~3!;M#T@DUs6H?$cC?Xh5+GUhss-D-?eUc|%WiK;NgNFRTxzLx9T3;1Wh*K|v8 z((FS1`<2MPFO|uf{g;8OHvj*G%HZs||3Fo&#-`pTY+L`^HduQf){~Our zqm6glwt}9CJB*oSARTvzWljgYgx^F_y7V6-ddFO;O}mceT&*xeZ;&``i2;rcF{2CH zjG+7HGE~JRn4-Rb%-d&;Lv+GGaZm}>QQ0becxZtA6ef#bnp0TdkU+2sG3L)(Bi{a; zLd3Ka!T?%|YsbD9PG+7JU+Z?n6MHRb7oLL?!*vB+auZ?O_E<6@hTp$zOK8zdCy4E3 zg+W~N`9tF<6?q-g3Y4HdH+k>g>v(0sF4E;v1i7QBj<`lqSg_s;&P}bsr*B(npGDhc zi}_Bi_S66f@#iyVelFDi31YX(9EinxL*`L`O}@KnPSV3c10KPYAIY>^)NfpSGJ_o5 zq$i4hw9sp)s?a{GRNKol%6X3B!D2}`>0~2KDOF_KHx6ZHhG#*S*k2OePzcseJ~&yW(P5K&u?((|A1+Q_drvxEU;+J zr)QVxO1I|ZvKIelva3uBO`bjz+PRTUgR8Mq@Ml3~R-7>B$v3Q9qzLl|KNM?+bimDy z6*TuAXD9YcV9K(tFtEx2nz`R<&zSRUnrtqlEYX$PymMJljD;9mRgZNalF0nYhu~vG zGN$yqE`*PbAzgbkVCTRL$Su5{sc2Av5nVg5^OFt5{BF9KW4lxC52~8Szw;rn?8Xrn z5~JLW?anNr|6X^2yuU4YGdf+q2S4k_xj>)33;w=5|0P}x7g-ok+3emR6@SI99vSdz zMYTYVS0kBk!p7fl7q?8;#p5A6!S0+gj99H9`71>+hrt)fl_iPnaYKN7Cm!xW@n_^I z64KL@xWtTR)AMII>D%hT2CpC3yRw81c^3%mOeLyqxDMM7l#-vXIf=k*)sOb9_eMeW(yWF?+ z&%G3@&&9&@EN#){g$CYv(3|^w-QmG%O{q#}J)3Y>QAi(efXxRV!d&$>su!DxSL+Ut zAblao39#@w_2f~6Ih6JSr$DMoJV%@jDS$rY&yPjEEu&mVfQyC z?6S!lYN-2_^WnXimxZ|)c}fS9UqdKJc*o%)XjCYG z0cQ&jnV-W3CMS@~DF(RqTBQ)YvJ0H!^PE(_0zr6bPHLTRvtAER%f7E#33{K*@p)_! zts8rWjtHp6Sxlcj_qa_=R5heK@sTY0<8>Nzh;ul1=CCUxM~fePj8K~LMR?VtiR$wF zpns049W-K)nw-v&dHy$Uapz1 zAE6-~sElO6X|BRjb0uldxEEw>g&U<&n$oCiJ&4CucX67g9wvk~$RfiG;GK3E4xSYQ z{rb-*6Qg?Kjg%u$8T6UrBn|2LpGZdUm6D3&6xO|9t9*wZ8^QAm-SWw}-WP<-wlbVM zRh_i^F7r-y!iNJC>4l{=be&NdHqDEH>yKhd+tXX@k#hl!Ts#U6ty7Siv=^{&m=8gA znz(*BmG6vNu3Sf(rJ-c={RpDaNgZEbw-gQ@^n(6E4K_MFpfB9F%bY7q@wE^GIo%z_ z_YXKjsk}F6`P)F}i@$MW#B3I^t25D9XUH~q#L%Fxwovg{19z9p;IjX9y4*nr4JxZ?Obf@XgiN+(cpSCj5lHl_mxP^$%FVj;5#(ra^7}97ygVT!7-kJaby91@0@d3zDqNC z!Sg%j8x{*g*$9YLtH7GC>ZILgobh3 zSYXNWoIcUeu3g~Qah~to`#yPE%d_kgs&MUYP12M5^;{bHzRaUWRwDI>G4H?QB3S~o zj;s?Brd8oc9etK`bc{Hsw>DnK^|0!IBFyAD0-IPQ8!d|_XGsDZK4t@yms^AJky5<8 zhLUJDn4F7oWu`lKJGEy?SVZ&t)S2t_?AAc2=g;KS+vi|?LlODO=a3I~zN19d94uwZ zQdsi>cGBxUH8Ik{OC9;$>YzDTtxG|Lpwq-{#0v7Ql54p~Itp1n8)0h0AN+Ri7M(C& z7cxJT;_-23;k==ac!S^dD%bUdp1$r7QllY7uU^R>3{(^>8}u=uItSWw5@(ILfhnfP z$=(eOME#^5PFyJppAU6}s`OschfO84y$MU@k67?W6r6oh)Ach<*Q-bMeY-c>;oA)_tAvK)mS)o4BPOciRTz<Qwrs zWIQaN!e{KQdTeA^KCR^(gBH%$9n)+s2CUUWU;hYrxy=&ncy_=#YsL)nCzCgg>KOc~ zN|@Py3ygpJ3*(RXCzg$7(19}{TL&DbeJ*nTOp*p3y_-tYU)aKk{@?Lhg&vcY&vH84 zV2tH8m!LUJ71nUS1`cMdOJD+VUChmz#J|q4rGs4-HcVrkoC~#6z%wMr_7r( zE&r@I4Z4bsVnm`ACjadLSrctQ*0~Y4PoBv759>f0{~EH22N&eMu_M=lo|=>kxyRD! zpG`dPMzf0aH82w=chbh(?Jj~6-!V)}tiaQcj?(fE*}{}THqx81h0v}At#;7G;a{zx zmybH=S=8biS9d1G?;2~0?GmiNY?+^?OZCu6VAPKL6Z8d%r$i@Y};e_BPl<2{0` z8m~cp&y?bb!o#$E*7_I%(!lRqFNaHE6ssL{<_k$35-?l zwGhb_D?Fj3OL}iX`u^o@?0EN&(6r_XIl}kyZ2kq%zHlRRX|FPDjE(J2v=QWwd z^<9$}-jofj?GN+JHMm|Yh3BiPkSLcgh}SgPD7&#@puZOCC9j0sdNw=2C0J~AgO0WT@KWncwqnya zr#sp`5XXIl@jrC|?Bn@<;W(LmwvJeh;aaJ=FFAS@Glh#4jg>y*6@(Zyp`Na+t1E@(biWbL7_R`1s=q zvN3XkIIx!yK3_ITXy0=ge=NfFwufk;cNB@3rH-E)Zc|^cRnTAji4Tel+3kX5U|>^? z6L{vws6$OeT&07-mw0aS3selVJy$mjmVVl8~cncjD6 zEWwoL6x>wLVwN$JiItxQ{`&P(fG*qyy5sVUA`qJdov zugZ5`f5-hq-+C?Pv&zS*h|kuX4Lq66`{m+PPd%=uijZdjVW6(GW?~lWb|8VMOxD2% z8VY33T~k1bCUG!4xh~%%XEU)f^0O;s>n*EQp!o1)2|x81}L%FZOJ6W zNL_kUb&T~5jHmzjUA0&5Eav{yS$sIefOAolNjtNB=z_c0)@nlL&;Vk=SyH#Ud&>rY zSp(-UC`c9O&Oz<>e^jYkIf_FRSod93WGUyg9G|rimUVK2*{vR96LM>g+7PYhZU47ol$J7Jm@s&z;Q zTqwYu3!2gfyH;Y@@dt^iP{&yd<_YcWVyz?fIQ+3dqh9QiZFpXa%83W$b$i=g&Tb;+ z^159=_&au4JcdaH9mxK}MyzD`dAY7Y-@_Q|RC2(3MLJzl^bs2mJS5Gem8`za{V!h^ z3c9(2VCz}_eO`8?8@@_He`h`ij(H62K2rsvhYK7mVXn6Z969v`Q)dy@k`qMYxMx4w zY?NGM@F`eJ5~ioK4cEM&;V{>y9R49h4VVUnmdeuZi0NehV>POCt`r@$hRW;qU+$yn zHzc0kG1h{;R@wM+(R(PeeIq1?=rQe(71ZtH1ej2)jiU_1Vc5?!>f59%c~@ky>A#yv z{x>a*Kh`G1Um6DLZ&W20<=G@^l_cEwS&PacPSmjXJ#l)mIUam0qYJev>7MXhe805_ z^nZAfee)Aom9D;gzOm?n3eUng!m`HB1Va}+>7R#;ot$PV`sp>`Angxihv8wqH{$aR zKSRxV>AmSMyxXlWUMbK)hx<#RL!&jMc2Jl4)*NGl(}ogT zV@tOARvtZe$sGD#Zb8H5Vv?$12WcNtIa|8}DH@tjlsFGu_~RqnIn@Euxqg7s6R>aX z7a>5m4&TM7@NBB_;$yCj`O6lOI=H!5k`z zlq8dMFP2r5Lp`Ikv7!GRo@3S(9=XYIcJ~yrHfaM#`}osvE6Z!#R=i+9Ys)X zDZ+T<Q*F zRs?$=6X{P(4zu++AzWC{mzjOGIX|+i$^Q6N;fvf zf2p{mzaClzo&rNR1?b+UgBK5Jkc-92#Rw$Sre{W0cM;8-ucJuJdf8>;^RG z5)7k8_(AH>DtuVb4DSXf6Z5@l($O7<*wpkmdgq=gj{j>!3dgt6V%c4c((X$xjowQ3 zep176t7ulx<~49`PaFE#9)h0(|InHId|9*YJE-|oaqlI+Uw`$6k(*rMzc-v+nRkel ztsX7x9i%83x&9{Umt1M@d#PA7&z5{CRu&aFPpmK)vo`M01_-J^ucDoBYS%*InWe_Y z4cDiQpSD3I_e3AB_l0fCpU`Wc)TE9d4zbfZ#l%-7mANMR%I6!k_37x)Ze1Px!T;r7fXZ1EM@l!5T9=6hPL^XVi0k z67G9=ozGexk~TwagcpJGUfNDpj#c)TWNz9#>&L@JiujujifaZrhw@%7sGl(y-BN+| z+>24&IE*P21(DbT3GCPmM+ooEGksTTNqZc*cVfO5MBAyO3Exe$`&Hv3m86Re|B;)n zYE=0{8IC@BQP#ej^W^iB+i%X(e!q3Varp!6(UJ%IbKeWuJ#|@^i9WQ;({V5{T~Tt} z7Q((p#zD$6ZOmA%PU>F{hkf7p93W>VnLZ>=m>*`rxgQBMK&6J-6_(@jSxxY1*;;Zv zL|N)HKa{;*J{<^SjJvj%QVp9%L<{?bv~ zc!q-iAyyxCp7?qsuvBpg*vDCeSx6#US0$3mlXQq*m&lU(d!i;j6kUS)LOD zA@S2El&xI`rSIR7Q+3>DG*w0u_jdu2v#s`z9mgz|<)vw1g9 z(Bqu5SG~QG>^9gh-gGg+H@T;U2>Wj|VmoK3jtk68Gmawmd>;Fv$3eR1k}qs%G{qa; z%%O4MVLF)at(M|Id5!H6&9z=n56Nq+^-&W^_L#BT0Vjl=rhVDlH~ocnzm?|N2J9ki zA+A}$@UyTGyEW|`rTZa|w0{pXMu$?>LldC+`FGr5-wbCy=F{rvFSu^|K<22?Ni5}B z>ACX`gV8%nc=kyhhvsRK_IX9|&0knu7D!4<%s`)K6U^wjd(^{W8sb}?;ZC&5)e@*cooDNX52^ zBgyC<=45rJ3^t==+Q_j7FDaLC7X@N$(O{QIv0$0Sri%JW3>+(1p*y?j5L-64*y zcQ(SDbsb6j+&H}{9YdN0V$3~Ga}$)YPfYko`e`|2S!zkwbPvGxC7O^mx*QF5RKoI* zDl&H*&oy2;1&;N1gE{tU(uv^xY|c_=p?HFVWMZl;?wsgC4}0F^K8S(j)1FrHc`?sJ z)QB0`>ANBPx4Z(!k6Q*u<}W0KSfE?ZI>`J~Kpm&3NqX`7*%Iv{(sDkP!M^3-#qYYQ z>(jAeQx?(qMsITYG-wqWb6k zqoz*^lzIOy!v!CgfPRIeIEpiGlTK@a(nf2TdhaVx|ffi*oF2=B$-oDXG%t==zTu<2%6znsq-7ig3F zgJwd6w~F*TWA`?EDT7T~x?PZ+*6; z(`@>-bRukh#raOi))8?Khq5Bfp18KgzkNs1SfZ~nYWY|4z z(vauEdOAFk>%kT~@Uv!k^vKSGPSB6HKHk(H(B?PQj*i>11)h3gUiF11)q83+>u4FPlI3X!x;FH3d2_<6SX6 z$Xo~^_qD{u4eEGov?e?}?gsS5FMOmWFpG^fPU~N&PvF4c3$8p z2aPB)VZJ7MO$w!N?yiBxAr`m~EMb=NNh-#3E#=;U%(M6hnRHeMhw2}d&mTNOOeDo} zVC8F02vc?YFw^=$COnoQaiq~{M&m|dLJr-Uqze;Z9CNi(n*Qm`zKK8M0#n|7D?AQF+aGGmMbKl*B z!M6zf8>@~*&&~)V8oVH;s2+2oTbxFA2$XFKFT)XE#)HCfNAdi1O&mX7S>C&DKhwU? z9n99>Ga-*P4cQd`qjEpj^kZt0W>PFW+wU3-*1w5=_Gb{iMR@>8Nl|2%2vrjXik^+BFgn47kTFL`|-dNal0k+Mj({%8uP+rBNcY?`1F7l|9ne zlxm*Fv*leqU_Q^iotbY)X78E~|Gbr?&9-5LX{yn!QRVnjt=`H1yuIl2Q4^=5Kb>o- z0eNQMa87+WOdqO3!u<4D?^|AUbUr!7*K4Cx7_wnvo0TKRgZG?+xs43Lj8zt2i@sRQ_h@M+C&)A0 zPjPSWNB3YBqBfL_F7Cos1ZLB;k)0uozYDeVRmJvM!SQ~@IN(hnIj~w;?0Ayz;I8UB z)s5*78#`-C6P9lPzX_@&Vq+<))Vu|UKBL7WR(hD~>;+;+71+|OCfRXjthY`Saa@qd z44=%A=ZQoQO2D#_*<_rTHmTBfV|Sl@mCp*+jn~4}H|IM|9DST_&HaQm(qMR$@s1=p zDM_1jNAS6KHtomfnUV8vKzp9M?`ejbHU;ED_btSUGo5SQje!bG=D!$-s81FylLe)7g)oN{{OY}kJUhKf++J&i|9VF| z>HGbqDi?}y*LZu-?s)-?+2>KjHU^eX{HC+Ayxg6*68=5Hs#*;V_L~bhWh& z6g+N0<-_*u&jwQxe9nMbeLX-Y1>10Txw@3CbcMx^je|V{(s9V=7eq7lCHcU0Ts;GB z$+c&>Un(%+gO6}hCr9vJZX6DTDlY1{bWvw{UH!y=m-y+I$^E;kbZXr{eDHUZpnPGpIKrK4 z=6ib64ZAgA_z})CZ)}Fy`6lGJtpPLXG(pZ<*-d+5f!BGM^ZYfn`OWp=)6B^x`=Rh` zovIWN9ZT-iq2Ms+FB(tVD75=zo1b*W$YOsw>tQvWlvRd)lb=GcksmSNsw5pt-O9pN zPX+HaJutvw7+GWp^rqHzwEQrG)T}*EZrjyh!sel%*ZW%Lan5AO(0KxBv-HK|D|FF) zm^=Ji(hC-BGms`eKfua5x{&wHU09q2$m{B_xF4u7UR%t3Z39+VjPU3%>G(idG`!63 z9hJMCqL20AUXOC@Jz^l7neoh#gLJ z0l$OqNxgX%b5*!R$NaT~wpZWLa)J%Zv$;d79&wgt^FlUpyQO$@tu8u+$HC@j7O;On zG7dF*Np@UbN|x>CEYQMqVaxh0FmUG|JT&d1(9Y-IaJB@KI$J>5U~TaM*PVWTUqv4% zyMg)R-}pVf4-4;C>tq>XjTxiv!@6Sz5MVCDK`RQ$7JC(OuZ2GPKLTOuFcWzDq8M*K zJ0VzCdXRkg_sreMl)f4o2oBk1xOtTd^icdr^&Wjev$frrUvehN3B1Fymh}aL{-*Hm znV$6ZRXm&2`#8;dQtnZ94fdH8x^LP16psT-()tqLRM zvx2L)o3P>53wR?g2HaJT{Vw%j^KbqlHhJ1u*Lx2v-|oVHV*^QH?+s=p9ui_U_hHKn zCkpM%z~Rdqu;+g{o_q;r^KY;TG#txBt$HdVJl5%MQguMJr7yEp{ zxLp=(@Lf|;o#!pa4-SSvYb&_Vvy;XYU1x1=O2{vD+IDYkRVrbEmtmip6D-0#4nLm?Z-_dWlY;8A~#~FYNJC)($ z7J%Osw@8<(s#5P!0Zf{4jTUw4jC%$TCE2on^vr_#cD(H$12?V>&W>(OAQ54&5XAW~Z$WU*J}GlWy+ z4CkFFCvzLG6TcRoRlOinczb#(Owsv+TN;vtx7H!D>xpG(Qfdk&QI2Al4H_75qny58 zXay^J@Y-%?$F$#cB3TQ0Ui^;za-Bm@Uv=rO%0;GU7ze2-H*t05Gh+Yp9{FX?=PeCc zLbe4zdrJ5nf5Ig}%RXC>mf1)(bA9Cf?U~Lx+)G9Ueh`f-=!l&}aKsIn!=~CxSu}_n!CP14@_f(28qXn6GM0+I7GG zMypDCo@qo#Mj_kzA1)r8A{Z>r7e`z4#8o%E>4YoaXv3;T_4Vw> z&?#`|^jC~Mp(nQc$ZEP=$9bl!$hLjwiF;fP&e_`qDuS+MZuKg`oecUc7Qy- z=X1Q6#R6Fr{k6Iql+O5$vSU^(i}Rf(AFam~>wH)^*F0N<>S51qaiFB!4O)3L70dV@9ZZP=tc)lP4Q8RIqG z1lW5-0al-o;llI9BBqd3qeBD5?ivt_C1?dWVTNZ#GOwq)Fn&5$$e7xvkkPJDCBVEy+t3|FfaR_k{XvrSa-ik2}w zPpshJmv1;hm%`F@-cD~i@=Urn#;j+(r>M&FQ+!Wt;l8~Vy6{YZ6!O{t`%f_wr=HQn zin{|yd)}xg0dxsIO!O}IB(fe_cx91-@cr{`Sdj7!zHk1EFF8=6vOI9$#-N1x)-_~L37=!rfnYe_6~=QWR$t>CEt_$#Xe6g@#@|V!qNlHwEvu0}Lz9V~(s4NZ6k6>+6Ijeo=07|OW=iyQHpc~|!2buhWCnaD=lS;}X*YYNq+ zgE!B!&;KSsuS`{(cD)y=aF_}MKXUJ+10$UyROyehyI6SdhVW#8uGnvbK6c+>LBr1K z0v-Joomw(sPB&$8NlTwyUNc-?hmZ6As$*Oj*tHbUv+o0>C%+Bw*i~<_d=~$$?fZ~U z_lLqmXRgL{yhj|;Q5Zd{9vAq265>YQ7Xxk^VM2!gv?My2) z4?hKdTETR2`d7?Z*imfPC-ii`j+eLZAm?wNC)W)5S@S^=E*M?QH0AwU?6M??^41eK z@tH%R#bEfjtS59n@e{*k3t09|8*-+h8MhU87AHTpg-AaCQMQRAutimj=K6}d9*RPH z9UhWdj?Z7T(e{2goB!_WJu{%G=XkN>R~;OjJQS7|D8Z2Bb$CB!2AlKx07<=)z?K(G zfL8~sxlidHo@o3-ESwBqIDUJEhS3?RotH8JGqYoXo0 zwrkE`%( z%w+*>{^Fyo4(RwH4wl|igrVQ!aKQHW#3;FrY~5;r@z%w{-Xv4-Y)C`jnEOK6MH@2c z@?GYypD2sboeh(x+hFw5U)1(-9km`*jbo1)vE5TL$XYed(USFmj=M~u@PLkFJMjWr zk$!~wJ}bpZl93p`Ekv9hY=j$ol?&r$)X;pNbj);qB-FkQA_0rlaawMh%xUl{n6=~w z&)G=>%a@BGmirbD9yMWShqRIkzC$VNyjk84PvM!8#cyNS8s9@g-wS=&in$Af_H5JD zs~d25G9~TV1mlyFk*Pcp2A9Q=aZwr=Q}kWdwvuPLCj7^k1XAx}>b`^6Sy*b<%{W@Rbp1*gKlK|j#p!+Sbq z*LraBEJfQLSK+DCEuuM8Rf@Q~lI_11OUr)gVC8T};u%##SHDid^?pZ*{o4)X=~3<_ zsWum~cC3R-r~jdD_cEH<^DpiFtP*?V#=-v5FXX1O2JYYf^Bdp2DIIMsOvumlXJ*1DyMFiG0w}U?(R$ zkk{m0pPI0;Zzt9x`zrMCY{M(VeAvLeSLEdIJ1qHzr+h}yD>n_pkJgbXqvi>7yfg5~ z)04!y$1d^cnGWa^XD2KkTTb<#@La!`TxvG*3aROp$o{AV$!8RsU+d$^`vak8K>!UM zP>T--d$I%l{*ik>wXpZz^U(2#0Fal&xv7;zDKd(z_0h!a>UZ+`eC3+5#Jo&Mdwrh8 zS$v(_p38Mg+3Gq2qQ*IaO&?MqTIB)N3@XO12aUwd zTNK2s^?Xi#;e*i5gPmK)v)G)K$@h`j!j)|{QsVZGAkW4s)8_lQC-hB)Dm?lA9j~7? zWyj<8k#S~;EMSM3ye9vwSC>v0osrk%9)s2J;A(sB)tw4g9w|y^%bt>egQ_%Vei`=j zQ6i6%`iX0U_3?CP1$y_oE_7M*6%FSlz_@|Rq*o-*k8m0wpZ)4=>xBn(PQZk2@93+l z0O{8ST?~%!7L6S=aqXmmk@q|8a@z? zn5cq%4bRai@MM|04v<5w3Cv})yL`WvJp-`A&3|N$M<;U1ehiCUZY2m`3}CuVGoDy# zK|Ch~!R4k8*fc+e&MYnZlh_DzOL3yT zHcsewR?hp{&UY3?w-rS7y3NFdpV2RulnKqfH-SydAKWv*imaci3+1vBd{}*zHn?bu z^G5K0<4WnXk?!!~STlMp>cILcRyl=l|A||Sr?b2F{6)7X#@KiwMy?;5{Ui?S-jmS1qd zaUHfrDU-Nty2F(8yYl!(6L94I8ry&2Z1;;$>g|6A?Gl@b&Y0Qa#SBB7IsWcqBqQY&%0z%^h8R)Xzg z0lq76AC~TEZZF&;Bv0+b?t83|_snAsG+^)1Pe^WcFdW%-8@<(k2nVjllVBeW?7uTj z)~+8*iTa28Yi>Y~xwWG8Vog_YP{~E}9_=7}OX3efx@9lP^K(*%?mS z!%J~;z8d?W;VFK%)yABOt08ONZ|b0;Ar0dh7P)HI$kKi4C}um7qxnXl@>7Oaye^WC zkv+)9B|3N~jtC8})1Ytb4}2RQL$5k-0FVBqI5Z&=0xWJ3k8NDT|6>7LfAcC`l&y=` zhKVFbp^kQYn!*`1k@EVi=grT)d&7jvxqh(e-d{Ypg=>U8+vr`MVW;=^EIhbSO{#P> zaPLOW7UK0;+x`!ZG@rrdP8cHW;(GX#jV+|>Qf;cbF9Q=6M-k1<>f#cSd;RKNg-#!h zU{i80sZ)o~w7ouWuCl#roH z)UObx-@1uq+fEYaH)}+#?MC?ax4Yo3UP2$KbB)1?a5{MD724=e7QzF{WDg*+y=`8}n0OSRCRgRuXW zvgCJf5b5l6Smx?ohMyir(BqztVkc8g%ni6pGmWg_=I}bC**a`Tz5yw{XUyK$Zk6YA zl`k^GW2fWc&?ZJTb8e#!`%WH}JRxrcJ=}8Yn=t3(FxdaC9M}KoLMlgR3r9BENc}n& z(e|D>J6!{9f2Y&Bw@T2Vxf0D|G}&UMK%)MX@3PHJ|a5v8R%mA64uP*qwe#Z&NVj$mLmE5q= zV^%4)G%vf=1}*h`n}b;s@mn+O9WC5gJjX`s`&*snbcbpE&8t6gI%e zU-X?}fOoV6KPl{{1WDQ+7Mele|s94 zCJS-B05ffka1y;o2gg09$!Du@p_&%E`tUBfb2^P}Rx_9H?{GTLI6e@@I?W2DTWB&a zoYzQp-)p2+*>O+SVG>NV8zP&%&q)+z+H1`%s3b=>+cMRp*2CD_mJh(}Ey(a%>7 zP`iEHH~LV6wRHVPv>x#LDY~Ea9dDB*9VkfM|A~u&)-P&<^8I9 z-V(VlV+a5HQIC(amcQ=A*OJdCdA3HoFXJq~gIH=6llsMGP!O5MSpkN`Ed4zx4bnk{ zom*x33;V&Zli$#=Dh#SLy`5Bfe_r!Sfh`L26xB9sn*f1Z&#lChl=kO z%lqeUQ_At{#3K+esfw)SjKNC}J45v`XP8s*9h)4+GHd>F3<$rCPtUb+zq|%D?GcZ= z6wZ)seOk!GsfHL*yi8DSF$O8~7v`Szp&xqtlTWLgv;ki-9A52&&L?GyR8z^SCrCp!(u!bJ(fE9 zULlVz6tJA9!8GIZa(MSi!o{Ft>L%v2v24SU8UFL+$O>_rV%km;{3(%b>SHLc z&uJ&QmoWVZbGtVNHhs~+Nwb~F>*e0idQ(w4lkml|Hy_ZFvlY2mG@E@alwVGtK{ z7bCQ;5jUj}q2EfL-Sbl*>pJF&bIgp`r)FKX?ndB{kXQmcZ0t8twM+I zoh{{zvdbm)IL_FWt!n8;;v>7Vj&X5xP(WvRxcD|kO>ZN|H~gT7T0Y^^np_fgLs496 zu8kWM<_Yf=93Y=-dqy6bNPnn)7B0Lm$IBOwz+h!parK3TLpo%Y;{#0aJ z9YcwdO(HA2=p^r-yZa?^&zgd`W3n!(Jnh2LqaB5IUYT8MBN}>6CNDjA!Pvl0+&`s7 zgBQIcDe3AMG%cDgPg(|J^CVo6_8Q*VoSPo-ednat>yl zZs!#ZZ{zc}dUAVe1<|>tiDy14k$(~cIFOWr7uWY8xm#?BZvndpHTp@!J8r<*9=-6$ zzGVJf`fonsdMV?ubwEt!V>0Gjs&HYvfo$J*r(Q*BdNxYf{QUs`GCBcI{gJ0rFU+9} zJ9@JG2z^p*(89aSNXPq^`Vm(yl-QT4qPdfa=i<|NjvNWn7vEpYgT0ac5X)z3Aqsl!^8==GSq_D z?7c%CF|BVJ-;vooX$tfXuE(wc2jSK%lxE`K~uDtGtD7J{}*x53V^sAWGqi z(t|%|3S_|zK60fF;vf%lEVr5;zqbgZ8-9{kAJ3Dxxgs2YbSu}*Mq6ztC)IGOmJEK_ z$(JY<;FkCMz`M4H>=#7%&cgsCN5?{s;ySeZMFr75d#)ii5kFp2q#lZDeA_a>mUXG5 zzb0cc&)3EDu3)a4^E1)Eg!z%bNzx|ykj|UhsQJ(oHuabCec!a;^0~}+_TW7kx*%1k z*hpm>Hubnf%z3Ct`#qY+DeFGMv=_I?&`%qwNtqFb$VG5b^GkS5rf;9G{#kO>^d@nh zm@QPgZQ<3nck}L>Q8`gr7~|^&*9uDUY?+I&W^NmCzoU-xB96;67_d4C_YGH~Gt{pT z?Sag*vrUmC7|nsAb_HqQNDp4ZcUO7jV5CElGW#1%qzEi-4*`5sR(r0j=1hy6KKEPLmK>*q(kKo31fCogy-)? z*bp|E44Cc>EsNx(2CYr9o_Wl~cvQU6heZ8Sp^0`{xcjrBBz&$0Y_t?f?RTGt&3%oC z_9+weNZJIRJD>6UF7A+CX;;7)kvC0Xx#Zg`rV#DO5gReN}2D-eGAO$({LF`+6U^E9lUpcAB_H-UI^gTR}h)^T*Y?3RnF5 zkh(SIg3p+n{H>uq;fgpBRTeP)n#Vsrr{_a_^7|$++WwkQcHhnXvs2bHH?b_OHJ83h z!WZRmF?Y*QA$mWI5>KKpJ=Jlwsu3J@mjmA$71(0xDlEGYNg~cY63V8!01UB)zN{x4 zKTd^atZhOY4p$4WKC~1T<}^% zx@Q_?{n~Ko$F1a}mnIlA7hvECP029@O?uRp_0^@v_-@Wmwq6ZBa%_R5^gQvFlz;e= z;{>~x{&bm}K0c2<4ToNL@_GMmq1MC>QsPuWrv0aZP1zbmKSv)13Mr^n>`3xLZOMO= z)G* zFqOKyo8sv=reuw8Bmb%{4UhL2L58@8kd6J7&|z;$hR2x|aDlHwk+280j9vyWBZ_ca zOC`uvRFg5U^k( zIj}_q+pfElpU&GLVnq`ww6>C=38o;5V_K9QE69BZRr<7$ad(F#r$7HO7{+b>i+;tM zp~`KJc+R$B{4%csCV!npHNzPL;fe=L9N5I~4O5X$SQIJzs=q;|4^zjCxgJFH+Xz-o zE5IdZi^=qRV~NRW_V>6S=2jj^f{HU%=yB(BdYSYppT@G7TQ9I|psf$cp+*Ji+UUtb z#M$e7Uy%-GCd?y~y{maJc!X+~;)&V#btLsD+gFZ`muG3?Vx`n{<-J<`PL_pn zO>a5udz(v^u&nuo&FZq=*zt5dY9AaWOslr%7X3`b%Q+%C+f|LtP5xl%jy$p|v@ad< zQXRGS9p<)pYJm^Ss{U4bGNYT>8#_V^gPe82Zh*iq{rnfNS~v@lx1W)x%zs^x zi+K60HQ*oL#P%}naJg(Q?9VC1B+p@j{^&MRFiHda4vLb^lcP+MaJ`lqwf+!G4t6lD z(LXg3JJSP{$`qt+;roepz+uV#pElCpC%$F`)P~W~?Cldn4)Nq$KWMsEi*`>NA>Ge_ zSPnH1&TU#ItG%^OHfWi42Ue87_{BBu!L3%or+01Yhan z+s{kEYcTNflU1bleIkX=o~0!8kUEC2e4lPVvd-F4?D(&OoH4n>*>+T;M#E;Z=-GdC zTVfwfTKqQM<3J_f*-?y+Y_@iE;3lFogX!Xgv4U^#H1OTav@u^*ss9QO01sQ~Bp5(< zIQ66pnGWIO@^cxz58chU$NGViF{?p+jW%7mPXlYWYQu}~{h-HP#wL2kz5~e?#9*|! zV0r3_%&%di#(w5*RXReb=O^@IY#E;dQq`$I`=8Ok<1>$N7B?N>RBj1=Fp18PUy#SO zE4QFC9|X%Y+J&ykFuk>5xc%abB8hxtnveWC6_J&yd| z3>P4UcV1P7KQf02ZaF>ah|lUcL3%_suP{taM1`j;qg8ng`Jp00k1jRRHfjqjPi;lV z4||ALFHN}TT!agkoy-{iT$5sdHFTYESXO&~dDY{L;AVLIs!*((UWnQKhX{e1%jh^~ zLp1e10|{F4px^H{rj&M(K|3mlVT~3BcIps$8zUICH3f&IxR8a^mJDPwxBgS((#sXD zz(siz4B2s>|G51t|KTfp^QM%8;pSA5HZ4ua>8B;z_r0)XKCF%dLUUsTfAUQN9@Z1l zC$)2^<3xSDx5ALT>|4Rlj7!70&7+8+c?db?qk?-s+)v-+zXrbR)uZ06Kv;2L8Fc5Hx|Djt3A-y~S+U4?#w=D{B6dp@&@`SCk`LWa8monfqjX%5q1 zpl=^YU7{i_T@@w-+f5|ycB=Sto+oKKza85BnpsU&qCXb*gx5?zY4K_gnMYLV^J)<~ zq?V0VYv~X3$zSvu&~7i{aA=86{yV_Du>e{z16WMZWn)Sqz$}U zU5omirSP3IAU9eJ1pjICW%K0MOZuaz|1CHf_K}}kkcbbOwCJD7Z^_tQYAj>gfLuQ~ z4AP>C@$;Er(#`zY9bqeNXw>HZMmdgIuA+^SHNpJYpQ>fbaU87-jSCky;rB*JHBW8;&8p+L|ILK*HayjCRdDpF+&6!mM~`5 z{y@lFU_{;}_rk>vjQOhahWFg9BApc)CdfsXl4sM^v18hNnTPJd{8St=^(pzhK8%ZC zUU<_7?!@fm8JZcO#xl{$N5`Fd&7Vv!#y74W(EfWPaXrw10gA4|!T0XaxG{mqoHsrasf*;%;qv#8nfwc&p0#;VGpRI91VJ zsCr{gHoWgGjJ$VIHlsL@7LT9DXwvdk^?da{Ddvp&Kq6NcklP2;@Yu!koQ9q~=be3vBRuJe6qcj$Tm&&o6hW+CfooO{7Mcb}61m_{k|97^|2?Z44fdiU7XJu9oB`NskNwj>llgA3xb<3f8z(uK3unl?p%uqFC?$z zU0@AlRx-9gWIl}flfr-XWg4>>mW8p+jE=mlf%@tPpw_+@sCFjeuJd}dEOZSy^h<=3 zi%euQiiTIMsQB_Uxo)osK0O&z+IAp!*F%dc?$p42-fQ^arEc)#hBDiqHo-oZHu26M zjhN&zRL~YS)7hE&=<*~AetLKD6+<86bA4mFP%2L)r?fHSx;Z(YZv;657*kz$A@NeO zB|*m-7KnAEB9tC#gx@&R9mOI27iH>#nbb#;-=WZtOO`OYRW= zb7K*%u>B0#snz7&GUm-Jp8&lpD0CfFk=}_65necla4|b-a7v&m?V%hFw!7o-L%;cC zK*24N!TO@+lk3IZUXLDCZTNTj6u5WlCx6+i0FxiQ1D^tYDrUP~i_??fP5-`dD}&t~ zHNnD?OA|>Y^TjO4T0}H&2EuTIX7ms=s118hsWOh)#chYkvEiyTuSFeeUu_oa2H64R zSEA!0F=WGRG5;tZjg8(x{fz0<;yBZS#*BvvdCh#=Yj#HDLWDZ&o1`d>WopN*Cf(V) zTJ?``p7=RgEHx%aE~%rs=RI!or6jnxM;*V_`itMxAK+tIPTZ;2PEb1f0XZX)mtODT zB6u}i<%e}?W63jL5*bj?W$n0o%R+AC-&X#3Kn^xs9tLG&^2z)@ zsu=R{A5Y9F%rbAqK3j$g$3q;sAg2V}c~_6#(iQOrOCI8|ZBNOO!yRO9tu9*HCUWnu z8Ng>g56?SH;P{k<#Qs$;tYH4dUt_=Uz;b7%ezg|7tfVB?BvmjwPhR|t|jMKFZ zW%ZV~2CQC~P5hNY>BCSxRQ{F7W#7oV z*B!@nGQG!tLl*O~l}fOQ@sZ@GeSkaXcawgv6{LSA?G_@0ad1jY4ZXFOlA)#E@KaY# z>f)wLo2nG~XC@D^$li;*-mOGWT++g2tGA0o{?mYQolKvjya3Ep*u6Zq8DCpE2#gs4 zQCaF})#yX6S&f94jznyG^@@yB4CMk+YH-VwQ)I|GHV3|DiOITA;-v*O{KN{z$9O#g zp2%$^8|Jp-5LHJ(^kOR5x9i~U<$h#C)*ar$1abC}@1#|fK++br;@tT8T(9R zz>j?K5bsnzB@0)+A*oD*QGDV)_cGl9c9a!kZQ>NpVO=hF#5fNNsvKd^Z$cFoYT?Te zIoY0W&6x_kYHceV-xNuPpNkjLC$Wr=Z#Hn|_Y-W0??<0I_aZ$9O%P6cuaxz@KEQgg zp)t&78U%hOIhgPzm8`MYG{ICbL zj@H5@HDTa4!yJZa2zd3G1+^IzNWL)*+n>ljvKl*^)!4fC*NKaxCM3Fb;5PAT?#gj9 z`ngRN#eK)~FWe@8+%shR5V}Ou6%b%*+Xkm{zVGtemk6)Sl1iz25 zqV;ZS)S_AgQ;+l`xB4-joez)UQ+JW(llDaIwl>E4-4}aA-GcVI-WaFh!w;H}%Rd}b zjQwx@2O0NMN$v17#zpAhGpCrqr%h}=aDI ziC0T`gni1^khS->lZ|XocVWRzard5Xh@=Tm7Yu>2w<|%&D?>-CS8#Y{1My&b`(hBw zGK1_{HhoOLFhK+dxJm7H!i$Z^Wqq%&ktH5XCB!Y6<P8 zUon{inpc#hW~-b*7+k`yGcCYLnFy_k`gHGl#yjd1!?VObaPgY1G;w8wVBFV}V1O#t z8?7YD(*nU+u^CT1(3jQTaimyZSgdw^t5q+#Ap|ZiUbmbecG^p4Rc%TJko|7)G`x;ceZoWSp59 zo40D>wr81KT5t+{WZJ@KHNV7U*A2efE*B%Ld&0nkd*pmhJ&qY*BeTf#t+*{_@8yW_UQyXHu^JxLH;C?`FVRBf6N_^*$lzu?O5J)le@dUjki_I z#XV|0;oQ4?@|W=;Pkt`qjdm08k5QG9cP@hD!dPxZTRi?3Y)lW;s`9;4e`9Y8MY?iy zUut|%7q@+ua`nUj)Qa=)d*5j8>7Rw9GXs6nfS~o4^Oqd38sKF2N=k0E~i)CHeC}(n+OSAb? zj9XGs8qHZ0-y{XUC4vy8zze$WP;b-7wCf+?y}u`{T3C&C#{Go5opN*`>%k692$lJr zY5xlJ{yCA(b^1iq*2zY6{!6yf&gs9oCAS^N*hcGM;I;{TcOJSD%Tj!{;t5>Zwwp}e zs36_sxJ8&_ISv-Hndg>&zQkQ|0b~nF_~OkMGHq|y-6f>ruxF%88U zA-WKIi18n?dqd5FHty}WVsj{QfQ%G$9oa zh_(~en6uRBvn5Vy|0?b=sFvTCRE$@znM327jpV>}159z40()0%;0uE*as0|fLQ13} zePok>kvEO0uagJdS4Tw8!vELm!RYZOT_H{{>IHq`b*P%B2A+ESm$y68 z5B`>yp=4nyi#P%c+DE)NZgdqQ3pp|OKB(QiOCKe9+36g(^Ow{l-$dsZYdEsqn% zTx1$#OB+Dl6s-7XN=rxT5x0`@LZ6Z~GEK!O<2w9odyV)72f@MiG}I(pxV2HqWD(5R`5IBio5b}lcy${aIwZl+RyJ7=b$%@PAgHtAK@eU4Qbr8Ot=Db>CQlHBz;H0IOeC*@NB@4 zcZ*nt!fCRE>1U+wn@R8yV_5C|1ZRutNaHqJQc$3d8}JpEu96JyV;k}9+3#G~!2oDZ z&qYl?d3e<8K3T*1|2wa~@q@IMg9qC+oK)*0EO>X8|6*5*CDrqV4+d7WUD68|v>YHQ za};4r31U50LmC=Gh?>8M`33%yX_aGEbz#Q+Jnm0j2k%>)gV$>0VDE!`VsTA`*`K~M zKIK^0rreGrW37a{Po21I{RG^5$xPNu|LMu2-N6b{JXxIzr*zR#_cM29rU7VPPsN$z zuX6j3I+8oGS=8>Tfm?FCBfh)x47j;4v}H(OigI%#lH+Z z0WlXF(dEQb=y>Z1DeSYjH>{`dXMQKqVEJ6_!fsg>(q8R4TpBT()&_hdos3!G5@Sn@ zHq3&Z(F#)T3QwL7IxKm=NlofrP{%!Zu#mc!E8#d}Q~t}}K5%tnHM&1$8A-qNNZJa0 z!F3Fg)$NX;PCO}EE&Q{Nfvk1`n{M={!*~25r&HK$;kO;>W*7HLw3RNfHzXg>am>LP zB3#$ii~qDh0Vc8;V`^fGtd~~%BQI5cf-nN9N0}de|avBQv(B~Zh(ohg$Un>Ws% zbRBkq%fDIv?_NFXq;ZeC7oChD2ltbOqt8$mZEGao^tj;N4SZsZvQ)j;6u##kBymiq zaiO1;koeXOMk!Tb)I3k2{gwhXSy+Qo4G-%4^9bZ0jK||GKS|1qYs8Xi9dlOv;SA~$ zGn$eZo3yVYbS>ARw>ve^cyJD%rfZ;{ z;U9jso;=k3V(;a-y@g#H4wJx&WV}4flKML8k+FIc1fNB_WWDsaee64s^_ci6?1go6 z60m7UDmP8-5vgVR&pp*5-qd0>9C@iAjct7nMIBH0C^c3;_w*JN=UdS+%%2jUxD&2! z?F|F6lQ8^ZUuu-&OXjXq#Sgs)6JbLDd?;%{gW&?n7BpaNb~0v}OSqHEbI2As5!NkI zmG#oPlj?EkvNSjxRwyn!UW(e@2Ey)rE2yHS8af^cfN1Y3-bBn;!4phr?5G-YD_9q2 zS&k%}Y7cOK{1}@S93?Re29iw1ve3Pq^i3};p%* zL@jPF*)&mvC!Xta@w^}8YSdxhkP7}n&{CLuumpQKJcQsEwPfWwHMCnW7~cC52%E1V zbxPhQykI-xlpl6Np4tUjFa7jx4fEQY(Qc+C7jqA{=Y$g*#sw&1=l5K`F=tad1x^`g zNV9s%L#a<4zjjtWetUciq}KZMsJ{j-n`;k!uJi$a{btm4m@o8*btddDn^90b*BmFVC5C!bU2A$Ig(xf_l5 z;h)5|Y4Zp$(SVxo~q2T<7`5c0BXBoS*X;Ni*Zv?+AX$ch>rVdO#hz9yJjxEza`) z)zzR$+lqe zUtLMgyi=lH-a2?>dY;TnV!$*xx#M1O3vLY~g#{YI@L%$h(K|!Hlrht01jNCWFIS-U zMJ4m~7z&Sro|2EvkA>sM`@xkV#xUDRQF=6V9bIj8nH%me;AGlDd=>Un^%?`*9bU?< z4=Uu-i_-8;{2OjSSp*3*6XC{$cFCskCt$+4f0)hY?wtj5z@@bug9`M8U*;WTGn*p~ z6#`^gOAV)Lac}KB8sCfg@gyqvA=I9vU7rcR7Ar{0%H9yY=0lQ2pX8+Om$b>J@6+kw zVa&f^t-yyr><^~%sTns12`f7)xBgw`4j$;-K(n51BMczYB6(aNsu}=98 zjGnfOnC_96hWxi&0H#IkF`h9xes3i^O1xlTS`vEdl@qJk>5^HaAEJKM0pfI9i7u$o zMpw?9+uBnL!uK(zO3N3%eMvi)XQM5cCVrB9+3f}ulLzAFqB&5p@i#wPT^*J6b`T|Z z7nr|`^+MlGWIc9ESTaty9Yx}XpP}WhmU!p9BUd%6h96+kf@ZEI{Q6D7q}o13*s2u4 zFH{);1OK$*rcb?u{IzaiSYM7SZcG<^k1J6AQVs6VpGP%xqu_*k0b?l`P%ii*(dbf? zc39|>XF_JimCyM&^4KR{B}<#`bXLQ*rLXya@_pg>uqu34Y$&|3u^^>C8*yyXVj4Gf z0L*ZHfL7kQWLw%RvS5)0(>eU)y18uyO2v5kMkhz3b2!?OgMa_N=O-6%G%G_BThD&r zXD(I%ubMh`SDFY8=Z}z{vB|h&s4cBg)+2Uf#|teFL%3(}bs#&w7TYDyiLz4=MDCW}= znO2LpmfnGBSMtRjy^GL2O$>1a=>+%di zWCA$fF@{9U7(&3-2nSnm+^i9gpjO`+JFMFzuHNPR+m{7sKISrfznDxmg{KSdUU~cw z9aESTs4TUzSSdu+hx2WR@8GaEz37^SZuIO14V?RX6uGxOmw#26gb&u+lq+hPvO*3@CZg6V?y@?m5Nh%h}cNXEYKS4~0# z_j(emmdiI@j>ka_`@|$1=+r>Qb@e2(zNq06!%{9gIT7})GD3xy6S;<` zC;3h4c{uHI3~%6hpIj_ZL9efAyqeWAP`y=)x)XJU|DwGad&!))4WiP2``uI(}ezC7s^`z?634S?d8L`%61tGU69njJ&{y{QX0w zjTYg(hv|H`Zuyjb6<&4J7S6&zZXlbPT=MXvHmk?*l?PI={b3_n_d|&WUem$kAGO@s z)%sBMJq2~A)^p3>49`$?U;C(d*_viDU0ifm-#mO&rc8M{A`fTsO!$AVZo(;oG3AZEHPBa zS+}GTuVtrT!BQh!9ruRcwk?>C?^A+*+SPFY<^(MHZonDO}{9F^Eg@9STr+Ajz#vSlo5c^86OL*aPWW6VB% zk?gUE;goLLN|SY$5YNYqQ*=lN4HmqTR5Qln;O_<4Xm$~-m3I+C6FF(F;e0`BH35fH zs@Ohtx6D^^`cw)Ed?TUmnUXB`hj>YHg1k>xq8-2WFvMsqS1G3pO53@g zRa(N#JyJ=Fl^g628;AuLr$Y3j-@H!eUmSJLO$c1}mejGmM&8eTWJU|~iYq1I^&KsEu^qagV;mfaQRXz z%EuZB3Ip8WyH+KBsGBV0_En_jVKq4E)e>3V{!^KV1Nzq!e}kKBma8b8zIq559-f(@ z;ZT4Hma%-arVcGOy1A6FU)%J7f&^62?1Gs$kzHs?D>2p9lU-3c=SlZe4lzU z>gy*m@SP@ZHTugndJTg_#=(l4? z9Ccy#p$IZ*A*(+hY-u+iV+TJ$*boyY^8haHV~y7oHAwD*2fX{#Bs3|k=CWGjh!0~n zM){$H)Axn>d*!4<4dbA8zrc^GFU0F{BEjjV2@SMocf{Qd5FgnKbQU1fzd6$DLv|9U zJXQR8Wd!NY`?xD@LB$E5h<_%aX z&KF0<k5I~= zB;E>riMjhgY&`A5jn#euZ-3~ct;&0e$IcJ@?TiAHs9uDRN0UjfK^elspd9}2DK;zc zQIeipu}s*Q9me0ia|e(7>P^3fxX}~6Sf<<72}Esl1%Jw!`5>&0k*ux$Y&b0iR`b1_DwUxFX=YRGKXx74q+l-2E%V_Pv^-BZYZ>d*DvHb|H} z?*>=us|$2XBC5r-6V+*xq4hyE`VP+~)OD~t9em%D*4{5f-}C~;aRE;nEh9a(MQz;mDn@9SFbv(VtGIb z5mxk#Q%{Whc9H}xWZeG033w-`jr1$^Cv!d2ke+Yk{@87XtgJRX@o*f`3uxtCfB#}R zymNS!lR2b(nFt?VzQ>DU3=B?Wx;U{a%Q7CwnO^S1x8_^ur7|z)CLbu?jyqQZDzh-$_=~aV)pKLkBCT$de5_|L`wcQt?)UHj&Z@a&oT- zxecL`z7I}-!m)ZRB?H#-gct~~kJ!q3?6|9K_`z(3aD3=R82iFj`r%hBjVvYf;zmtWi=RO5-e;`Fe#%le zlWMZuFQ40*U@P4-J%mhsYEp65tL`u3=i{NlX0WKPF6qK&AGj1m*jcoN0TmlH} zU|Oc@+52QHqw_}-@!->T;wgSC(Xh$DAm$UcG8{M^y9B0%b1u(93N$7 z45(^C$>Rk6lmX!yJ_$ZgDYo z>M08EoWhA6)82IbH-uWC4vDs!AVe>UlIc1WP8#FnN19~!`WU|C$U`icX-L*DzDMQ{ z72(f;BP0P{tKrJ_YP{Zb1k~px@~f8?;*EoC@XyJFcG;-mF6L8MqH78Tv+iNlO6_pAV7rG#L*XLCVti z2QGot!&b4^ynI}EzZo({ET$=U4RP%E4Kl6W+BI=_EN>7kdC^4VGBt4Lc{kb4vG>GB zc#ywNzWlNv_NxZ6JLLrD<@5qNEA?^c4j0Lh;~)5~^NVn1TsYXgPa(p}OhFv*j=#9S zC(O1{lJ2XSEf|G`@yd@9@vOH4HM=^OYD8P2yTdwir%nNUm)^sqqgP1CbAPh>lp1dE z-M}r<-T+4Ot(dUTgfINQ8a^-%p?q8z92Kg_=#wH`Gsy_P7;!LsS3T?5#tJj_{J591 z4Y1^q7nvJ$o&Qo)g*k-dygD`$N2j=#Pd4o zy#9`inxl!o0(NkrBL{<+) zhI)zxhwUfGNtP=b*C&!ZV!zwnH30{2SD-UndXN{a&KRXAkim}=z~WUs)<5(n)XpEK zt}nx56*ZCsK7qK#s-n%l3w*;uB=zUv-46N1xeZ^G# zamSMQbqyo$Kd1={#oCz(5&K|6y&gWCdyDs<{hZg@U5yhX<%RXp&q)c>b*!~FgqG#T z@PIMWGwuabc2RIa&b=^1$%tI`t>u*$q~q1A*5s>VB>8SG!oWS6vU!MAVI8V)hd^$N z2Ry20tfA}{7<9Io9KElK=N_=k2veqiSaTmuh76?k>&}yqA8I)D;}o*-wkK3Qm6z_1 zZX$hFACe@PCSzfv1v$4tkD4-nhhw6iWWkpKU~#?%4XPr+JzAe!d!;Xodt)wRAAP^9 zkCjHgaQ0s^zwn){RQ>u5x>Si$lCOb7U%3+>MaIGWtRzkG?I6xod7Su_t#q1YG-)ki zTIlcE*s;MtQg&JdPJJ08LO%@d-rY-liaSwq-c1-VgM)!AqhZ6#8hU@!-Rl z%oAn^+jDct?LTTb%H)7-9ul0Ji2Lp-(mI<^uJJ?y&X{+X1bjV37fdn29&!7*sl7NYm53dy(>9cp5zi5eGTWi#zMrhWZb zAt%h}YeDYq?JZ1OvXke99&j(X3H4`gp?&KIz^6e;xTrvp`s#cpS*jYiC02^*5RC}W?t~_^x*OVy3R5Lc)|Jw|%%HgD_EeTcHhtu8h zy5!iL2|}LsDQ;kfF1*`ai|GTZW%`g>!(`MpvnShM$CFeS6|A4KIrC7*a!B9Ui0fzV zhc$=Nc=>OIcyB~C=ekF=ZaCSlJ7_hbN+FixVAXy@tSE6^tA1MsDbChOQSa zm}1yWI$vtQrfK=O`ulu>%)_;LnJUY5T9|3Jcsw+$`insq_CQeXAF+mf0j|1T30m(L zQ!ZZzpJ^_E{i!Ydny@%r(>0V1(rPB}+1$Q~Wq!WQ)Q2OFlJQJK5}EzNh8U#Sp}Nv7 z&i3g`c-EnhUT^1QzP$Z`PuK6nz^-ukx%(A4^(j+G_IS!)$?6IJ*txquajMYxa6ivI zNyM#T!>RSBxinOp<*w#=k=^@?`Kg;&ZqDX#PVwt{NE&R7`4?wp=Gvd*FRmy+k0qO+ zbk<+8$xszd^fV#opDS!WP>;O9Xu)62k9+sQPIwvkQ07T#sAO6)MG=krItgNqvb@Nz zMdSp}{PG`}2B72sclVVWXhgAGhL0CB)E_oV94{AOYM39~D%Gbd(JV{RPDeJ!RMF+{?PQvVnW8~T;4YYrL zgalNXK*{(7Ob=D1Gqg>~VRJRSut%M^6(qo#gY|emE`Xe<+XTnF@-XoFj?C>x?vv4z zL};OKgpXgm9EQ!QN7d*ShzUQ-k1sF9xyObHKkUq@@_45I2{=mnkNC@PyTBNI2ShZr zZ8K3h$M|4v8bl*}3#53qF}~R@qAlOb?~46{8?J84beNw2*EJI|+Y)(C+O$$c=G-r!R@zwsu=+VHTVywLl|2V!gbSV%3=0)z2JFnEEYRJ1&d zo|IhXbbj(^W~4{ujY6r{3}dwWU_unVO8JSI$@u)+aPss@82Q?&!g8{rGZv{I2bxfa z$>zIY@mLS2VBY_TfJ)fM&PJWJ1~$(3lMt5#?SrtU=3OjL~?>M1sGzU>(Dp-5&fQ;Kb-zW)R z7K&(M(PPPo*%|m@n1q;QYE$D7JuE$YoO6lOf#Y|IkY68^nY+G?`!3SL#M`=1Fd~&7 zTv>t9f1Cu-ve#tXU^TRLKSWjrjDUc3Nyz#_T7M>#bGVa$=Qk%2tJ+g^y-O9oT(p7w z+ZzXZ6~$Qgac^cw(?)WQaoAF4MDag+9E1xKo3ZUyC!DgF4Ewg0;wR@}!sRYG>SJDm z53&O2Rrx5$QBT58zeLo^>n1t1Nl`j9ER-x!&dhLgZpWacLz!8x&8e@wIu37*;(Kaa z!p?R9sJ?QtN7UxcAkoj3A`=nq&kTcm~m`Fm;tKeqy=#10X zR)DKs6-Le32K^@_@PBp|qQd-gm^aFV-u%imDs^5mtw<{C&m-tiI?mdM{NxyaJ7$_} z7n!@Z1^vs~$h|WfATD@__d40VQ2CWavL5^9)98%u9$PIyS^CQGAgnyvD%Q^}z|k3H zV03c{&0@1nZS6U*Pp*ddvrfQ(Vki1#VJis<(?ZPwUgVdd5m-wSP#T^@OpUFGe;4z( zncmt-#ER!9tn-VDgRePT%++k?}YD4HNMFa!oq8=r?crH3#3uR*|?FD)ih*bu{dM zo||ZD2ba6raNHzb9N@4_EWVbDt+Qr;$jP0$4AMrGpK4(Fxs&(UUV#PqgN2okj*;W2 ziM#%uARsn{H&^3X-lZn>IM#!_Ocvo`UXL`aNC3X14)>ZxkaX`&upvJW*B!kpZfm+v z;_r*_)x_O=hCKT&W!2-`b(PSq6`8W26xGhy2|<$HlrUCmr}-(;;#0+QUl{A)nHH^D z96*Q}JA(uDNobuv^y}A-THImsDyx<6=<^%bG~E=B`jSItT^6C4{cgTH&)Tf44nH2K zfVnM$x!yHh=zl6qR>NQPyMvKl%Jh9$Bbn%{iyjT8q+2V}U!KR$i)NG9+>vBafk-G$ zd*{l{*$d2BfC`dGna0m3r5q1L7r^gGDdX{`3!NJ35R_mH%WajUd|f16{UVlIcL%kK+n&l2m&^*Xzoe1VX z`V?cq@*Mb@(?lX~X=0#c1}tHG0IMIi(qYbz=>8qX^mV-&-U*pU>gqjV%u6|G^Hepu zbj?9Y*|~>EUB?nHPLqaAWashg=g~u?{lT|IBwdxY8}|LOA+viL2=A_H%lOYr%X;BV zVKrTno-kr+5LuDffj0A9h43k2FmqAGKh{TNx)IwA33%YHCVfuR zBsQuK(KX^Rk-y6J3rw%8s(gvNw@L#(_?6%t$wRU3f)1{2p*}iSXo0^e&s*q}W6`%k z!k46%WR(HyR|g#@75bx~`YO`~4Ar5(!}fD^%&*Z|07Ni8P5m}npxTZE&i~0@zI|36 zF0i~S4zpQHR=KNT^!h#gx$H>Lbuh;zKBmyx7{nXREX5~Lc7k%Q993Yu$fpB#(ZYpM z(86ZOu@2hQH~uEEnxiOH>T!a&=4WJlYAM1gHy?=qzSgBbfH7dl2JxZ;ePNA79S(n9 z4mZzQk{&;L3)%gAW!k^8WlcD{cQDOS90*TX4IiqhO%D$LOtObC-Zj-H=_P}q{!1$A z2fLHPK*@(N63;wP+IMe?SOKjos_>SIJ9zF+ z;KjoW*^J@~sCF4s8mfV1bEm+$LuL@;^$72cA4TWQT~4YPZ)cm&d@|{I0Mw6f#=XBq zlejE;)dpl^@RwNxk4%je>Nz>u6!9-F`mSEdvh)O`=Ll zOKF|FHXbTlNm5%2`N9iQOt_s*o-B$a&sb*1-z!(Sj%j{ST%d&pVmER4=}_MF^dGE$ zG73J8DJ8qcsUp_2@{avR!{QfhI4{OYnDA{gx3DfA&ui(?(%gv)YHYuW4X9jOmcaxp6`8lQ(65^Z7+1p_`kOJ(}HR3p@B%D&{b;t{n4Oo{Q#% zL1d;>6~`<+PWr^}fW;T$G5)zOwO;m{zsgB*>&EXSZa^6+X1SRscHQA3((OQ5ryXC| zx^X6CnV5XfMZIey*c`~6-r1s!$65Z^u*qHg{l;=sbhQ=4p2x_C>&*N4;0)P1u_v7G zh{vbK%sWuggZQ?q;x(5Z#CuOXh;!@kQRhin-B#R_kI!xl=R_MH5G%&h7`J2zU)E~{ zjQLiNnp<ALtd;yh`Itm8+2WpB5$`m|+B0Qql=8rJ+a zCEeQW(z$I|Wpj>r>$URLR~WlS7|LCrmrGO!s^hYU%lJ$O)&m%+NIm&~(4tH^!%1>d z??sVx-^KB~xCdiCfqiea?NTWQGtbm3CTYk^G+e2Yimsd+zsnuKT*a*Vi^#(t1D{KTR=$zHaMA znY%cpPtVgE12Ib#MBC=AaA+LJdMa7Ref1t^itFO(;hJXDgm<*#x)>}f?u!Qhlcw_{ zb*X`^l(=K}2~v`HmD|qx4eLH>kweS&kn^!x7(>jVZDuWhtK<&uoU#~(%ng8z2HF@C zu~{&7*i~9QQy0As?c`sN2;^V0vv&%4O|2Q{qQycHixZq_>1+r3#w-;p_u7-+BQ8Ub zJY$C{tm!{{mwf+%p;x6zP|iUivd*uC@hjopKuz+~MHx#Z)(HCMcI-TPu~DKsRZ|)U z>k~9Y4;j;le`Y~_7I)!OI!d&%^Ac6vF2u7HGf0j4d$@g{Wwfn5pd`(X7VHyaUFLgG z2)@BxrxxOmTb{ziFJm2_vHWI4goog#njBRsW!;EJ9H_O$K{y|rA-Zxgo}c&5n#w=! z!P@4rqJ|R=^iwlqZG}bj`$_JHWZ;Sr4N~cyD-2s!j>{8&g57Tma+LWk?~F;~$a7UX zb6*2?-<-t#^ZCmyRUM8EE&8-5%qTMdw+80cr*kGN%lN1>)mYGE$6fIDhSRDFxbo8~e#wPnbn^0F zSdm;q3uaHF3w7C^*JhF^!&RMVX?J3mRsdO&8BS-!TZr9nhLVy$tVjMN+e@fz*b%RA3{%iU@fvv1NeriWB z*?ZTD2G_7%>UJ&Ss$U8p=PTjwZwAnpG56NFj{}Q5V91{=ZnI<$rW(!QGMMK!$50;U zFLdWad;ajBZ`9$5?XPHA(h+co$i%79Q~I^;No!n0B|+EwXShho8lAIUK+7bHH*#a0 zK07w`pTkcl%Hm9;vw|tqliI5@ebsa{t(%y^FFwO`-J!+(T6e(><}s+}=-^Fk-`AOn zn_hBcSgQwUzm#KKI1fm@vxBa%>PF*b>ZJ3S5@V5l!c}_g`#qvSOd?pe%jBZK;D$5R zV4RaHPe)K`%Syp_v(FgA74_>Uc7qgAawyQTEC=_S&8Snq9f?XyH>|E!Mw{!KATvyx z9-Weg=kGs-mSz)}vz+-=S~58EopH3V!4!Sro`5(t@cUeonA$rt!I0g3tM1MMjfARR)E(+>)`aLFj%%$ z0iWE@>_3MauI#~pIcKvot+u}MfxN`;x4L(ZO<<;QxDKf;(pbTa(J!I_cY_5+}8t2u6y_aLS z9i1QfAxo7|{!u$$K4l1%o6~|5KNyStme@cH`y1-Zorl7md+5eF87Q|#m((q+*TFQ~!lOD8#>TPg6pQV!Rj2Hro`gQhn8z^f6jshV;W|4LAgW}Zf(tZ{|}_9|lH zq)52_zLB>#M#j)KCCdt!Pn$8;rhhet;rF)Dn2UdKHskQcFZ<2Qud7BK{scF|s+RSM zv-^$-@J)LOz4by?yra8;CdfH*FWz0#tRxfB1VHy2mQ7!vs= zS+bll=jX>+LZ8p%WkEh>+3bT&xf5aMO?lCuTS*Q(>)3h5$q0|-uH*}&-|#0dH=vJ8 z5tXf@U>=?)(i$&8M;PeQq%1KGQCLg{=x^p~s(AGJV@z&M4k9z$4X`kNJT$v?@arD4 zvrWBM|2)5I%X0l1NrIY1XXyI$Uc3=DmO5NqLC;buW0jZ83eikujRIN}=huqcHtg3NCC|4?ldAh~x=5WJMx^ z46UJbk#8Lu@Fw)Ueh8n6+lj?fZ6`NAqQ3ql2 z`7F_J_h>%ii7k!s{fi&LR^;>BfjY9?^bz-Spm}&Py~pm+xtuOZ)y)+i)GEh$%Lb4q z&n<{nHR~TK5OF^StI^hXb?9*96qgeJhr4vL9V7Lh)6M|KK~8DL^FGERhl;}YDS^M6lQW61jx{qx+C z{WjC3fZyL6LPfER=ce+8*08(q`fy3{$%A7=7ayn-PmO^%&gvHIFwA1UEDLd^`$;lT z&VUG*t}^~}Dzxk7=ec~T$0wstb0gPl5YJ8}G@j$ab6RFJKcXFn4Sr60N{m4>(@2yQ z^SjcdZEk+sV-0GGLlu57#6Kg0ix@4!&TRoK+KpLS6N zv9fCp44orKY}pL|Wu4GJ!#|`;izRg@)8om7{In&XG3n9+dfh{pJYc)F^ahr@?HNRs z24`U7(l?EpFeo-fux8ApUUp3JiWqpK$->I!l)ValteEU zEPuz%TU^2Ww)UWxf-W62awzd;e4B{sN`Bq^!L)gMGsY(m5{(*a1MBB8@8YG%el2Cy zE#_1DyO{8A2GOAd^4TnHfQQA^(4DP_%XJ@deYu+ima}e?k)`_<&L&^Kg$bQD^!vwRjY)}8@=OXcu*_Aq!)(`c#iD;jCt zfn(EssfO)m)Qb^uRb7nHlqQG!{uuY~D^J_~M0v$RsxmH$zxQ7wj-NSDRB^$G+`6of z?^dM3H5ExZaSp{Uei#{lApokFHWD?>5_V19MoS*{;L$mEVc_XMytngx6t>22>rUrG zR*WoqWe?%KhX5TDDl1mnTt?SM63%B`2S%PT61`b_m{{%jhZ;(!`*)YeLK5-E11<7$ z*)QmMtBNby*}nIs27P5fvEa=yD3zZKZwwSfp@$kBNF?#$l7vEhx5k{b9||Pz4(p*#v^`jRHS<)r z9W#8BA+GKY9JOTGs8Mx-Y%YS%J|ra`C22^-57yF+H-?Ellw?I0M~@{UHmf6tj-!ba z94LS7Hr_hrNLsa{Ksibtr& zGRu-qWVzraY~L6+UKt+UR~HqQHVS{=9!4die`4@;6OlzxByCL3$Bd^7$vdwym{g~P zrl0&kcFA~Z#@^SLuBwxsA4OaS({pARe}!0GJICjjn9j4QO>oXnmew#<)s2%f)ZoKz zh!_9C!!qWg!rPN+U@?2QnqKNZhrck)z+qrO^oQgMlMa?+$YVM3(%O>vPFF_>;}S0Y zq$-Ux|BQG+#QA1)ae^Ohm^@BIU+YEFUk%N;qI;0Y-tjR6k5R(Qzc2Tn!>vZ=U_|l| z^7rWxZdZ8@cJHi#&pww($w_Urb$!eAaOM0QaSkqc7R`O@=Ah;|;|~up;nn7a(zz45 zP%EK`R<%r{#S$$Tr=TwyMkI-75aVBc3n2yX!|AD93-P8=XGpe<0hu>QO1#TJ2qkfO zd28aban`>}TvJ{xaMzS@ZK659H*+Y{BifNg;b?`X2~_e%qKGGR`scQuP8a^G2_tIx zR#b8_{gji+3&BBq3*-;6&!QXk%pKNM6lefqtA)i!Y;d zs8mTXq!(o35A``jTTLD2?Q;>awn=WmAPxHN6Vvd81If#$2k70kx6$f-0O)xpKo5Jy zj@!#}376N=_>D{p)%(FWGtTz?jL#^lNToJsb;*(|>^*pE6dli4^zP~z7`tK?nKE_* z^y$-JmM7>I`$g%^)ScG4hwGM(`J6svPx76t>NF9q(hRIJl6HT;5`nm zqL0|!f4;W9XiLWq{*giwCSIFDl9OkWz51#sGCv5pYwP&Z*AMWW#BVsW=s2t}V|Ufe zx7^*7?bPJ=56nN>!`(9Tq;l`e@mEMCKi{(+j2VA>(A*OKbqq&scQS3wZlLHy&IWF# zrHx2OwTSEMkZoXdJLSX@Qg-zy4N9&-`(GNQ%Bl?hus!?6xo^4b1GDJLs(;v|rT`oN zRPuhWYS7C21K*dIv_HWZs#VYUKE~-}`)1_6YKlm!H8@tuVV!;q1i0*_dEURU^oDys z(`iCgGETfv2?mVe8U0upkG=oEwYJ$(vy?yh^Mx#&Zey;@zg4Ucx{Qz9HH(b$SHdz; z3BU14H=jJb69>-H6IDr`gQZWD@b0y^{yffFEg>eGTM_M8Q*hE^+>B$RV4X@P{qp52 zNiYs zsTd-+HLE`_+5C<1!8%Nc-Df{|%XZu+mXClq^R4uOeJ>8ZSOD);|MJ!y_po?O5qDjX z4+sA+e_(?Y^Qb$~q3k`fJ~5lN?bIY4;G2dH(-zV&-}D&FyK4ib8{|dirkaAj4#YAqW6a#G&kv}0&!1=f zPkY;B`j#Q@;;r*VJN3WtRY7{Rrcg?JW@RL)ijC!bHHG-f%!(-J1(H^75RP8y0;)Ex ze2mmT1W=X)djAz^d7w`0sWq(7fmex-<_GRerrlx4P$H{PiWI<=}5LcAzYl4y*wb6nw}fsrBu&R1TEmKoNdYu2H%*m6r1uD2~ zRXI0)pfa6!wH{+MesLdydN@*`Dhl4KAUt6+lX|K%=6rl9FSCZ_C>R4j!CFt$y72{Y zOp6H7iG%SXdkR{)n0~{Y_#8UQRgg4%(pv)xgU^ziL<_If)^fJXKJbeMu=BZb0VmA? zRL_yaA2THRuxBB3ywWeUsmY~bol~jfu?CcI(hw=mlps%=J87acPWU>$&0|S8O(u z92&2I7fO}*<7;K=3Ges>GNQAIR3YRPTK&#Y1+y3aF!EHPv6_mD!Iw-eP_0}!5!1=t@|na|SrgszjzZY` z7XFbX;@7K`5p8xS^NO46V8ku<*|L#0 za|3$wT`T%ms)>%6uH%X|Y(&B3Px|M%L{ecg!JG;S*o-um%ItZ!u1cCVBfz9?$s+dCO^rH0@<4UTjtuUG*Cc*OFy1 zI{Yg9H`1S$wX+P-*mb1YM4!$N665ZBl4MhU6MRc${H}sV&MA_0zV!S?IA98I7p@kp z8(obfLT>Wi*JhDsM`ipxS1~fDN~4cTBC@% z{ZP<9uE08oCqiFl=f4eK@l{tbh~<2#LPIW&@oMMJ#GC~8AM8x7T`atr=RvOLeFbxVUCaliTLC$cc}oCQgL%sOH%6kcB2J- z`_0`O%`xfPcVYFlDqbO}7C$b$LY*#cc|gK zR|NcYD)}W6$=Egb6f{{KfC4#rOfnh8^^Q41YubL|bH*FiezS-sM6}>z!+1J+(qCA} z_?D~WhtiIbljySG6g+WuHaXrJ4bfq8Sbt?7486R7%CXG;`!_#9ThVqjVp1lquJ3>w>5<%<&lapJS*d@XSF!$UgN62-I97qWjPJ$? zGje&4;m4pXKUdUIdWhG~8clu5e&Y%^T~SYsJjvN%%$e~2{BjKvmq4Wu1y)fy|dCR4~{1N{Kl*~~S{h261 z3Y}RO;g@hSZr~}JnUst&&cB9Z>c>m&6`Z-=7S{50JY|lFM&+~{mT^Or(mON6krlp-sr>c%7*X&)$4dzLH z{$(QEiW@;QSiW_)X*9ealg-T(-$T749bEc?!Q|#14NS9mC)ACVr3+PRacN@=9djcX z;#n3?W7`6_gPo$uK%xu!Je+_(L+RI)z z3>n-W`jK(bUkN+m#?@lp_S!wny&VO)Zna>tPyr=MMst0AUcqnW#r|s^^LiU3IHiYG zSQ-~iKQCQD#H_3Cv8N3kZ`IAuIG%?Equfc6r8HS7tALX32f;N_oqE?YMxsGGsGb@M zyGJYInJZ0PYt?nCXseAOAAtjpSNyUY9e9>OPcElZh|`zD+JSkzV9rW9yQ34^d(=hs zjefl0i$we~!j*7GXOfPbL3kr29KJYq@f(5|Z`rjIYO@YN8SA==s%zkM<+jnujz3VQ zXfRwju$BrRl;Z~y&kJYNLlx^{xSlBFOP6x=_uN(-J3&<>yzI%1vbPaU`&Gh4m#R~l z?H$*3+jkDLH6-S%SDd zDu*vDGpp#-#pwsz&=hNFaaZzmD4Omg*ep|t7cAECE2t|;idVu1qIAAp<~MI&-GHP0 zq(yTC;b1dc6;%?Fp=7lIefEGy)!pNX(s(n*29iga`2gytGH4Rp8J$}77OEd?p%w4$ z;wt9rJFR>I3Uzb9n)LF% zg@{&5CXo#9Ah@c`X4+r@v}J6eE6?=cs*6?d{LmkMyi_kHz9CQ-DM2z^a17~iZ&j!xg=~kR?O$@szV*t37Gj;2$`FC5r)0zUywoc$zg5A zUCDxpcG-eMzf^JdxapARS-}S$xQzo2M#5gkYiiA8pI>1PM?XeTyC_-l!q(%wtDzT- zDzCvIo~N14_YJPEX3UePOzgQbiKZP-#;;4}lkXBYDvjiJePieIB|0R~)y}a# zlI3&5mUEA0DNE_^v&7Q7=Rh2B!*O*8@2mYJ5V-Lny7C`2$}LxlEPzy3iD(20SPwExOS2 z5B_`5fydO&kTaFx^m27F^A(trA46l|ZMLNN{?0~7waLr-#JalLW{!ZsNOdxgc`ZH~ zM+ggFnNj0g9XQtd5*_Vp0?H46;lQ~U$fP1GdO3k&)BFh}#kv}HHYy|M<^pFL$56cv z8S(J3ZD71g5~e=>iE_&(vmT5Egf~*dy1QqEYQEBxvb<-?rPH)`NHCnP%Rn{b739`g zHP{`OiGyEA5a+D|YAU6K1G3j~&+UBZS`B6Px?RkNCB5Y5iL3FOVJKC!*CDRP%6Mso z0X^7dK$pKu!7&z#$s~0TD0{}dDC>e@joD7B@xj-Ba57{l(}4}JUNw*lJ5kODPi(}aDi*wccP<36EbyCK z*LbOJcj{^M0DC9Dqh(i|`Lx^jG5^4N@~mSOx#Fve-<-oBZ(KbeZIX%V;|7r7vk!pM zF4mPSDFMf9xSC|12xb&CX2l_H~Y`q86m&W z!^e+&iq)q+fmxV8L5id+yoaN{?0n)a1;xv4=oEEnabCD5d@%G8IPb4O?xHLo>*z|F znp9CC|0W;$;UB+!N&~*G_(P3LPr}(^6>P4)1JmpDsaY~b&4Ug^M$H`3ST1Si>8brQ z`GAuyUcRgXr0g8;5SfF|DhEU7wG-gZG^;bk=E90SYiX=pI|gkHqfuAS^QC#U7-ZN@ zZP~8>^<`s}b0~rxtL5lNzuTA;ZApgT+z2DS%Hpii&fs)m3ni_;(RTkAh-LjXJGZ9d z<4#?;c`Xfgr?6eB;V@yJhtR%MMx1SWnQq<#-0$>ejE(w7H*eWX_LxhEwSHb9suC`I zQfM01M%j|ty%JKP+8Mu1Q05d!&u3||9-pzo z_2(b)Yi;T<`pyw5eV=)n|FHSYw75fwgQ)ZsX>nP=b@H!1jtd=?fl%yk`rl) z2Rwb?cEun5Hf4K(>u=#w@-6THIozV*%|)+?pdFLU994ii@W_e#> z0J~oY#c9(oS(E6vt`xlW>_773;AJRd9^EYxNBVmWzU|Azc7I8-)yYw4vr&ja0U2<2 z&Oq{3QWbj(c5)$&RLV1$TC07l=2X;Sz$-xBQx>wNlEf!&?QdgpN06n+hB6n-Of=uOan`6_HoPDK5JHQ zH>x%3@kh@egAW2lyfQtG*X|6ah2O*|wV;%qve94}D5gJOPw4MBkUkDw3gs?dRIAN{MTI0~l9K#F4~1_}k+j#E8z2+EGUM z*-RT6Cp7V^ZSG=cyb**kE0*0uIeaT&-aoe!wZG%zHQ{s!^C4XtQP1*yzv-RYURd?8 z1Dh9~C&iuNborfRYM3Gyq`_JCV54CXA>>SW|F_X7s_ZkEJ8)Vl47cxc2`fFll zfg>G5w`R$RJEeQT!&(vqZ&;V&#YLd$wSf4ws$yl9t?-tUG<~7?6Ynxcjilx&NO#D@ zS*>eGRGS*S-ryn%RW9t;RZaw1<2<#);NPCb`&|5t^L#$Rv7%3q{9F+S{to0GRd1p- zwMt?==^H|W4KI1CcQq(gyNmv7(INh9#y%dW)!(IiDJBJ5b(fQ&^=qKIN*;@XkHPWL zyXh}B+hxYfl9{uM`Tcj94#{?3(f;q@?QYhO5E{T4%TJ|utpRzry`x^(!xE?y%(1COMxVeiBq_)w&Tf8tK`cY%$qOh^4WGDJOPC>Vd& zLaM0=`GZoa?on-o=O?*@)>r&f%XWOZa;tFeAs(7n$fHs18D7D46`jAO6SMVu==aHf z{P@^=_@U67oGEc9(->2Cv`;wPji}`(1ZSer6IpV!?EtJF&G_@L_?1hk5YY~bo8GnOWtfqgkGj)Eyz}c{HwF+p|O8))N6m3d9R$m=g@*Z-@ zVLfi=TWR;flW>Z84mbSBgln($>E-!ZxF%yfaa?8q0bPvg=P(!ga`bzHzT)}Pul>8u zh&kD~(q;^3)*pxZ^NgKKbn~MIdQd5u4qWhVU%yU1FRm8tnXmgi>(Q9H(E#UfFMu=Z zQnchy3Z5z+N$!Sjf^GG(_)&jW|C~Q+`3H~e{{tMxKfigw>*7XK7?~9Z;^71X>IxLQRJV1!Ghk%Tm5=df8)vz*VDR_UXy()g4? zd51BDLVNS8Sy$6~bxo0)(=4HK?!T9bS5MCcdj%OSVjT4$5rK@9YkP zMceG?wZu$Z+AK$k#<2{8f~DBo(ULUz**P9z>^O7DaL!DiNCW0nkRO@+ju5_{bSm@rPLmdYV|@|pW04apuxy}>4C&L%13nDLxms3`r`E#@I%RR_ zah?2xO(FEz#Gja86F{4+r_v|#4d^P_M!gFE!O`~}NF*+ijasMZ4)0_5Fm_o{KrtCg^Cq$;s)SH^#~hWTM*%xPdnJ+5=uPG`Q+2g~nX;E^oPS?lmTDili+5@_kgP~e7!d0svYY&&%XApwgyS%8-7e~sosK12WyyaVi+G>wh$HI|j25&pu9*Vvni;}9 zFP=ud_x7M}osv+!{)<47<&`3LZlmo%Ylv&7G9DeHL0h`N@wq+sF)d;o_QHVlyPhE2MO^!W20%+yjA>bn=i z57tlDb>b9HrB+j)QJv`N-$gZlZ|B8HIrx037pdRBg18S=$G-~9uc6(3i%<1yDP3FIaaH0^ zTCjgTw=~sO^kQu_r!Yg4E-&c7CBA#fr{70u=%6gztD!=cNGHR2b|#;AQyoTLpGgx9 zS%*krIGDuL^3FCrxM#v?f%k1wVtGIbtBwct`wwrpv0f6%YHC?-3AYQ`j_gSWyxMk< zmazWfNcjNrdWZqF{F;f^zA6*`a2b5^U^;E78f;9kq(wbaV&nU#pib6DV97d{6HNCD zPR^cAyuH=Ym2q?52nNtSTN=R*{7>+3C$-!f5#Eq9D4x@4TSTPyUnfikE!2 z;!t=gpEp&h!pp91^w_q0u-cxXn;z!(&vWqyDY2X3?f!YLt;8~bE|bajss6-RLlx(T zyF<~qa{ggN7Jm2PVa>l_kYE{^R_<*7x&8SAMf{L+#i4$#FTXLn3THLC(Q}(SLH{S? zdA^dSeytN}fzw^IJnBQ>i}x?aQoY7FkZHpbIMT{tvq^TvQNuwTH468l;x{w-Sj9LG@a#K?zYgc zTVKEvKPBAOl?6eYC({q@Qer)aV`T9-&>*#S0Jv_@8^wUoeO{6IG_{Cp|@KJuj|J;^mz``yjpSg=T%fNZV3E7Xds%}sK5Bb^yt-Y$bx$41knj9ffkB!X~i;C*}mH6HgF&rVrP_vr>h?T!0rk+GAEQr3l~d5o8`;3aqJrUpI2 zy!uNGSvG2?12t4r!29E`a%X;Sq=8yJIB2E@SDTp6i&&qd>87duGrYx(b#Ez1(G9=# zsXgQD9oxE@97y+usU6HaJ?Jz{xx14_jL*QQ25MxK?jyeX60%(0YcOBY24NEw(P(iT z_wveg3M`W{tXY>c3;ZHTV;S&wvt+5}yI;IdaR$yR-$Vw-^}z3yDmYH{0(?55L$A)r zKo=i15^ZA!tDTu9dC3&I!cuAYNlTQvQ^2j++|KvD>0zE~Bkqc4F&KEtW1G8o|2f=% ze#HYFHMD-m4t~v7Rrb!h2nQE8@PS2a|ME$lyk%U!);kK=wMGxTbGFd4XBYz{=oB1K z@Sve9%2EH33itVA9lU4r*4fINA0EQdD@VFf=WHXbGw|gM2HA+_yVUmk!$X%d-s88! zWWcHr`qv{1*R9bc@0TXSD0XLgAv+L)rp%qV%EFXtD&louZjoX)ugk0OiK zDWmd6FaFPTW4dr!J>F9-rM8bP;UeRDWqM{qTGoErz%m_QQ-ev`e+Kj+%MQO7q)8Ie z%OLZqJX&??LBP1-^!qqzrjT8M%pE?0>H!sK{ndm^eKnoDe8@N$OE>d*fy^s@vK~** zEv27lv5dX18umEykonV)#$R9^we>)p%k|l=k$FhGS3qEXI&}{Hid)iT$(N13G{`0o zlW{dTY(53n3+3>O+f+g0?KQM~cN?Zono0*xI?rp2ti?LxSF|udpQOoYVpcl#a|oZj zNyW%l_T*{!X1G0+y<5MofUOtQ^ImMG3y>k`pBbV+cbez zf+JmYq7@r<1yRn>^L5%a!6Lca!Hz&d9)EgHu4+9^WX0xgl? z%MPLE;o&sqnl?WF#OC6M93CF!qT9foWO`01JAbg>UEJCJo#tGYIVD>SNU&c#=QGGs z{5s2?Xh+#OKA6V%W;YT!hmmsh=gMmA9cs?ms{2D$svIhvS;HIq2GU>NUDztFrB5m* zQiT*nJlT;0qWLT7DyaeD>W|0BXt4}G%{v=aCTNifNs6SD<&1iD^x?Ck0^PLuKC>CF zg6U>YxyMWcS9P54(6`fEUfGH|_g$zf7e)Qqt}5|KC0+321^m~cgdQ>XV9zKAni$j%oN(b2ITNRDsd)Q$?3r-*HtQnly`@dFF;` z6AgI*^&4G-pM(R*xp3xJOOwTvqqn)sKRs!@TMr)53*b6FycF3QiI7JWcGYD+;+EzU-a!4|9w8ijh%^lenmm!eqHMPNr>442a`kfBjARn1}X_GK)y7Ix)^BUJSBs(Ck>x8#&fuFiuB2H~QsRo~^>l7i5P#rFDrU0x#Z#*VWQgJj^luY_Or0`4 zC~Cx?#!f`1_&S7)Q^5A{!7%#kX4)wI9d~Vxfpz;lXo~O?sft;Sza_oH2v% zmbr&b*fPcfS2E>p*ENr1x4+z#$uTRAyc#qjDo^!E$7R z9%tg*tPj0swejzfJ@6z*OrIRMg9lfv2f@LkkbhkcZ3n~(3defTXx2xt?(J}zl6jWz zHL1nwSp}>IoAuM2)x@r=g)sf*FTSql4(h8pk}QX+lbF9GQ$gg0S%N<1)%prc zgwaI;N4GkD&#g)<9BoX0kX&$M-_ed&&3w$%Wpqxr82{-9lj9LvIK#4JB$oyKv%U1K z3g+8wff-We{L^TPAJ2S(bz@F~3gaXcR-|+9b0cU%-5(5zILBEUFQfK9E78~6m`Vk< zL;X5=T-(~hZ`nSHK1`QG&yVNe@H#iT@nZ(oj%2^N_e3~zWIh_7`v}Fm^vG0}ZQNUX zmrD{`(8%L8Xc%*Z8_})+rtTV|HMaAGh*#?oq3LWrryI@SN0J>)f>3L z^pn})7yI*@Y84%*={SRV(4KL5s+Quvdd~gxyx@)+(#!eW{s0Afn)T!kU37%o{MH{P zXvw4f^C^7mvq1V|-Y*QGA5Y^|>{N526c;|`^ z>GK@EDo{ni#bHoALxrjytjDv{F2bu5J)C-gny6`NqJy#BEIOjY1oz8$@ml|0@`~P# z_(YcF<*+4=F;zn11+oFAv{0cF-*2*| zMwd+(ciuo$PG$L37j>y>Y!@o-Odxm5tm&q;`FJXE4yk@w0f*fb(R0p5=lv{$5C!cg2F2@w1aV*vztul-P9*+>49*8#U>(?r6w51e6#CY2y8)3IqL@qT}ZZjevIDeIp>)r1r%V;tjoIobVQ z!~(|czdYtVcXE-CkAD6c%j<{Ie}TH>9_#ROv+m?iDjU$c2U%GEeFxbQzX{eVu`{IL zJQS@m%$YS9+L_>5kjojqcq z?YRf_Q~Qj&TaIv{AHG0uwJgf(v48)+$uw?J7oIA3OM4o(a8716?9p%IW`PF1a90ga z@o_M9WgP!B-9r5KLXB+~ri%W|7f*wekFJJO2JVX-W>)qUWnz zI_GZ~gb!mr|9wRuZZ)D$sxr`Ffh(D|P9J7CYvGglLvW{3L|a+5B4Udc`D(b8&TVLC zx%eaqsL6rBXIWl5pj^< zOoP9i1aa&gQFS;HEXTT0U)Ce(F~^+@GCeM|6z1d9*Y#lVO^=+4WzR`tA=k&G)nVBL z`JK6(njt&GM{A0DMvoC{+_I#l``YnH7E*JybF`Z=u8-L7Awdx@z$;q;kMu;r`_Xo6 zj&xw&fceBL{u#&VS&Ea+%qG+C*g3ih)KR$i8E3DmNaG!H&|m62Hz3OuV%c}?Uu?#g z&kLl}rgdXtY%zVkbrMZARm2CDw14LB6-bD8Ej&$PbYytJ;tUKb)+al?I= zB085-IGJQmD}-V!wOLNYkHb0N$6@72M9e{$6LqW!3pE`!otk) z;KuHT_C6JYxVTW-Toa?Ol>{IQf~@-4V5m8Z_0k|gI@2hO{4laSS?7~3cXzn`5# zyf(zaN&Rdr*e|qaTI{<^b|dULhU!U57@fKev{{zkI=%%3dg|nON*!mH zl#d1;M?t;Sm?+Iw!*tCifq#rN%?hZ-k4g&kjd~DVR#O!pha$4K#1pn`cM*-Os_xfb zx+vplIWH!!_8y`#jG-ZnQzi93D?vL+4y{d}a2wLs)7k7^@Zi~3etfkK8T&yAC#aS2 zeLnNp%ULLS?f~gd*#wUnpYv%`biaN+N!W$6N>-3Q=3%E{D$Xzd2xg&gVdFQpGkyJx zGpU$L&u)jvSE9@4;49egNL!@d4e%0Dv8!9#JG+}gSb zSoEIt2rpITyO+4rkAph!zahEQCt(|(Ae(|c%q!wOV;;G-RShp^UI(Y$jl5rI7Va)I zCNZxLK`z^MHa)e4KK`M58atEk&xISD2ixi2Lz`W>+>RcE6gHpz3zYega}M-%nyfhR z)iauKEP$KmVk$zwTycT;?KLJR4l&P+n=P2GcBP>z zQevl-#jGd1mUorOM%~0bF7iwhq-{{ba973tb9urOXo^HD;3lpVpwy;1`fm(o2pnJzat0pU~)C#gSyBj=51+qX2FJZ2V||6(9icxs~4 z*dX}zlv3aOjKA$Rh;)~1rkbJ2=y8JO8=Qloo_RbP#wl}or`OPu!e(q`-v9H}XZTqu z!^GNMzv=$SHAL`I4ef?Mfrrz-@iGU~@!ZQ_XZ6jAZZ8A|a&6jFR16n)mzO^Nox|$ZTlZZAFTHZ~X^R z_uTV7=XpL)Dm}eFoYtqa4iOh$(z2!q>X;^65)=)Oi8Y<4r69=p`HE^A5SA&>ROEfC{pp+czp(avHf?aXp;qcD zsC5D1kMUyqZMBRLF!T&LK1+cg5_Jb%6^zKbr?Mo}R|n@0u!U~+_!Q>w?K|b3 zAJCFop}s@+KCkwCApSXI!fW^!@f9AQ(QtSIP2=<770WQbc#+qWAv)zHFC6C2liuS6 zZjpLA%1#!!!QQibT9C34#Z^CV&>}0xVG*G z9DFy!gAA!Fg;OUOXJ*J=P`Sby&oxt7p0pNh!xK1zf?UQzJPi-D29bJpk1l^^z;&~2 zE2mZB_5&aJ;D!J=aZy#USd~wvtXK*f9+RcPC%^RQGecyX(QtuR&kjG9y{RWn`Oq`Z zKW~*2W{vC%{if&fBTAS*wzrgjSzc-o)~#&52N+Da81c(=S~Z~tT6fz!(j;17OxI9ybTM-y}T zZ==14d@Sp~sDHqBK5XFg!jkcJ!a;KPPzQTUYGD578=!E-fKH3a#Tcy-WJB8s*cmt! z17{HK8dRxQ?kI2GtvLCs?8}}iqa(#x^o~=Ii`$s{sfTiVBRg24xIe$8PqA1@P?sjc;aX^XWaD# zl=3w&@Y{RIouWZ>|HB$wv*{{58fF2}bt?F+C?7uU_wAYOyDGwnQEET>RWBRYDGevi z(<`7lkg+4&Y#~fKoZem5OBfRV4q}WqIGhWt#5KJ&VgAqQG3P zcwS{$v=Fdny=IrLK7%O^{psf1B)r@?i_A_nfllljIew_7Fq2unV)ZxfNN`K5c`>3Fp;X@z2t)sG(>~` ztYr*F`$l%l8V$Yrs7m|as&?4d=0}$(7@*k`J8r_-Cw#-eGVE-+!@ITK1N#^y{HiYD z`~F@?_l=Sl9v-f5+WUP#;W8Fl7pt4j6 z{Y4*p{4EVj%yGi4+1xtAQ2xSz3f#!W@mzW%TzapJeiFV%Z#N$)5+-^#lhiN0$qJ@v zCvA=b`Q*9u?Kl~sR&68cSb0oRrj(1%jXHYtnO#yThe=<>X`Tb2A!=OPOsUEgg*YwWYUmHq?Kh<%_Fb(Wcj@?i*cfck3AO>b2?&pHGBDnIq?>Kc=ku=K}sNs3$mT|USFol2hb zHicgN`N=A1Uhx3tM=qwlugC}+49^p{%L?qXeHVAT_a|Fi<;cb>>bUWd9jutFMl<8H zaGTl%cze8n>#L$Ez1=z1q1(rpec22PPX3b=WxnBGvUlje8&~O+2lpX%w<^xR@UUlB z?|LCG+|pzol6HX`ZxxH9T?UZnD^HPV##I_}gOu$`ZLP4Z50Su=rVcEf< zTz4kagHsaZE1&bx7Z%bFOR70{LSZN@bVF<3jlvJ^IY|{0xj< z-wH$D1m;{4SKy_$nLYEoq^SNaGEO4P4k6A2BRt8Cl$X9Yk+>S37q6;E*7o11S3BV zBtQ3P;jTg}uHuP29r?Kvw|EJ>a(ftZw3OALv7a%|t@s(q`g(t^`VI6)`OEYEL(i*O}k=`uS?I;ei_6 zXcdS4ZM9%GsTkxcRM2cnbFs*i%}_N=3-emo?EMp4a?dRTw8 znHy{Mf{%;NMB}?(xTN0Uu)jnJPrNLWbno!LNCO(@-lVT^Gykt80e6ntPY&ImL&RGe zF-vrkd}|eGT>)bpnOTrjksmx~osv(Fj|bIX8))L}7VJFn2-2IEQ@uUaxOA=-bTiB~ z%9OCJxJWW4)}F2yttcoc=g=Z0e@@}$FzMc?&K`Y6O|J=;wVx)3Lypj@-tk!U!<6hv zy#aQ&RWYrN06%&rRkZ5FLYZ+i0hD8ZJKf2TrA?^0Cty+hp_%PG_kT^}nYqG^m~BUG_S1OMMlEIqTwR$n;aB z)lo)>h{z?b119t10uxc;#5^)VB12yPP{(DHgTQUOHoe$81(o0Zg82NAFu_bk+J9?P zkMAY9axl)hvxRGdGCnt;9Fxv&hClhmMsOWS0oU*5VpxWtM~! zX3r;|BDax?@qN%>V;FSMdcJW|Dqh^(4&S*$P~yupf1PIT=I?OYvY-w1`3Z2;b3To1 z_=pFFZ0E!M*qooBgcIh)^OhObRK-pt%vkt~XlfXd(nb}mQ@;fZ=DAbzP#Hn{-*z(c z%`r(xdk$`VDo46?cn3EH^ho~3WnURc#}!uN(Z3?NmZJ)P`|3-BcSYxBEF4Pj<(gv6 z@K-!sDByj>A|ZXnFS6Wq5@}wkhI5|X?&%2{B(EU&>^(qkY^&z3T8e}nitEYEZ&qRj ze;vH0F9XpF)TkSqZ_1wLQ1EFd*y$?bjiF(Z*!O<)MOPbI&ALMO-Lj^0hzb@yeGGCL zi|LmT8R2gHrJgx&+?0sXF%~35qDT&O>fj5@X)y1aHeKF38w;Psz;czRTo~1qx<8rg z(0x~ZwR#XPZcUVElNT(vQiJ0o!l?54`|S3uh7J!3q2D8WntNP|!iaUGcJ&EPac(BM zM2#YYwp=9K4^3S6X)?I%E9PI{Ou+iw3()%k`waWA9+34@xp6JQH0pjkhL{KQPk*@5 zW#TG4D1Vwh9r_2j)JAk}Ng{@4PtoH=aTw`3o77;$KTBEyn@!yKJj_9z zh<9UAPe%kl6ijaTfDf!pw1+s%(rS?x-IsXzpdf++p`vt7; z+2JR%j*0tQyC5Je34B7+S1ZU+#K|{rK!@#idWUIEm+ovKwKD3oj(HgJST{wKNh9pm zVSl$%JGjB7E;J#e9fQa;XrK7aVe$Hpn3Fh`zwv4jS!bb!mX5diq7#jLY;!W!L>?mV zJv(8hfhHz>Nr3%mNLxdsIL+0LWV1JzcCIoO$2o$seKfsct%EIx6~JQOGd@r@4GSXm zz?OMAu7@gPyvICAH{<0+Og-Mae2P}-Z|2X*cF%zTvRr2_$ulv+yZdwC?vFNJm>q}H z-&+u!z1u;TX(`37lc1ZCJ7!rkt~mM;V$GJ*0h#ykMX4b?xW$78+hH!ua+7p3UVdsR z3d1f%(OngOoLlp7X;h#rbbB3#88_i0r?X^o%n_>aFAk0OTavWc8*uW3Dvq^vg>a*p zbkOonTzKv~^l>TWopb)-#aRM*n)b@g~f$ArJU z^DKYtRVA+E57Fm>5mAiM$8}fAA^1xNfBIQG+FQ93pK@=gxUP)R9}oBR3Y8|O;>x$O z#AHP(zhaa!KKQ+c>(<^s3{e)+oyYUrZ%yL%{#6tbQm#;&XQ#-n%QC`{trx{KKEDlY`oJ|M$~U*j^FkHX)2A<@LG(7*2ym>f^52`?%soe*Eyo75LuEfKO^}glzWj z%IF)_qt7IPXkDob=a}2Ay}RWO!S4s8eBS&gjHfCRO#5|`4f`e$ z5}=0Bxp83jV*(Ax%fgvmI-5AM5Pd{qO@-jwIp|ted1iHUN6;nh-u>a~3dM%1|#yMW?@z4CQNWybx zhZE0MMY81pdzSYMMt^}z&C9|5t=44t%19ECq=_+BGvUNmF;}2X18>ezO%yuxVD?UB?jEQ{> zer@i}TmChInvwma9h>e+zLhhUVES(yPO`~5)_ZPm%kmwomXR5Cui+8vxjR1Q2poGm zitcSoVJs|JViuFY#rKQDx3{BUDeI|8U!sGzLUwX3p^8-Ty}8gPTEf5jir~&}@q>b{ z^4zooRR4sU;CSs7Ik;dseBITI?h0GU*SUUli(x7{CdiZR0ZGs`RvCZxk%w+3z_&|s zLes&`5Pvq0w`WXm{jOZeQ8#lE!hDjyhMwcIU5)6>fo$KH&_z-jOQ0xK0gp|*4IYQL z(y%G*=sa={;pVDSPv+%Vaa@7*X_vuu<|z$zlZS10oavjY-*}Yy862X%I&AeV#|OHR zlEfbiiM+8UDmPu?-$u9c>sE?{!ymfH!Zsgb-o^UvFDCc!ySVdG)P78eq<9Q0-pt;) z4O8J`LlhmcMIS#r(}qFDuXyF;G>lv(f{Uyp>bD!yLtN5w6ZMu-qf7O82mB9_A{Kho%`m618q@K6gtCC(>uj}+|aorq;F=(Lv9-LEa^6( zH2FNKPdY*iqT{epaU_wfz5!pisG?uF8?2R?Np+Gs@TNvPEY2+9V`CFB^O6YONvdEe zQAgd|J8~6u2GTvDpD@6A2OVA{0=KCuxa0f_c>m-eeVy_BK(xFuJv;i+nse|{)3mjf)rlZfp5%Bq(DcPN`g@cRt<(6HRp)&1N zxN_ST`mW^|6oqQw8k2W`XZz6-t5lpSzmhoW_k%f1D{h*26ilwC(2ij#I9^a7o7+ZH zF?;LvKT`pF1|+~Q*86k(OCa~sWi|czybhb4W=S0L&hVbktFX7r7P@F{AF}J9Im(Uv z2X!MfXkA-8E?VYEA}4HwtxS{oJ>qDO4sREmiglHW#A$sh|KcIbT&%8yEpneBk7wNw z5Xk9`o5VU5WQEL~D-xaF1Oc8TQbbAKsFKdA)r|t*k0p zJ4FpouM2^y8cpV>O2PIR1(NV=Bm_38O05p4aGI>^^ZV+0T+MD)>zktKSyT3|DRhxU z&|LV<*phi3p*_0IDo1%C|NCRIaLYCB=B{`gKo^rELpKwvPqde`Q`XGh-iaU7nkI;TD0_f70wJ^2(jUNU`nJs z-f~%+Yh81YWyycx!-IkJ^8@xC`KgL)1{X6P@)DX8AtM;nUL%*EDDbsAc>K`?#JEF; z#EsU#yMO0G{Vz2-p&$!A-)F$(Ck0$wo2GPu_0gU=A6X^B+n>X8$G3do8`7%L&2B4Q z9*_r5cBnD0S1}YUW_{6VwmiBl&1J+ z;fAjDq=S!xhRjs7{-H>c)ckX%Tt)U7q#$wm2{Twm>7CONF2&i5=2lhXhHw|j1E~?* zOYb9<1jh92^IZkMQSO_BXkQ*qcW30_;HMkO)buh~cV7)dYeV41$g%X9SsFGwD3Qqb ziQK}_Sd6}Z2WIWjC4Vh-PU zFiDd4*Moh3v7Xay=lE*fHr{QwNEmcMMm&7LCek@v6Q}h{gC9Q)>5r@F7~9*LtjV;1 z8)6H5J8&Nq&v-yrrPgEqxF7J5zeCr5Ou+cJ7T~*x=?{zpb2!F3x7NsuwzSow<@keC zX6a^r!d<3?QW^2>GX;d)SHRMIxT#3GV)X~>GA@|)SN-*-Ri_xLwQ0km-2b*%W=!CD#I~xsmaL)$SL%>IJzT%7782e5@F!TF<*L;> zGWhZi$ot7M;9o<)bmbQIf0crTm8xW!aSC6NU5yp}>wD(BthE}B8+DcoWj^WrJ)J0H zvc_TMK`ZXgB_&~#kw3NY2_^Zo3vd6(C$68I`A-8A&?#&=;Yz!pgXQthjt+;Rs6#{8 z&;N}5{F#cQ;I@~twDPPb*Ud}+Qly7Z)?DFwzk9?Fd(?^B*Q{|+82kdxF(37)*S`Gj zm+sW*j=WH{PgUq$neD2Fstk6~`JTaOodaIJm@~LjF3=&h}=v#CUIvyh8w)pNZL$oQv68?qx)zAycm#>lsh;%PoFKbyKYYS}^%(VY1^w+5PV2lxf?2Dac>0q`)@nY>=s`&JwHs~hE)3TOqv~_odWi>OP859scZ?)g7=|^L1 z4e?g5Q~b3#OL?OZmfa3|3xzgIsPbAF!N>h3F^gB=PlvF#xq=Ph%#?|=dxtr&2-*zP z=v(zH3^;(WK%syeyGv90_wIRzq~fVGeu5f$40~q;Ky$Ztsx{jI!Z~eES7*DNO@CrJgYQ<4gW!Y#Mrg&4p}pdpLha znfZIeI5X3uG@RuK#2b9=r+P2vedbnU#99xUI;jIJ*AK>;Tb-b1Ch!G;X=wRw9Z?-~ z8@}qKplhls;R}6ptbC>Ta`I#7{jC`;Qw#k(=CqEhMx}vn4()S{U{6LrsiMP~ z9)14hAeNDNh{UUPIOW*?;p~xHd+x33jCEY|FBGnNkEMeSq+^$-2C1@6=8R(E@Krz> zO!C$v-hEkjG-W`JQGx{KS{YZS|vb)YI_DF)cDJJQ;jh*5hKLKEyPvqjl{4J9&6GT!@kK z1Lpt32`_tbKmS>fuU@LSb^bO!Gqn#rIYA_Z9G4e=T38A@nZ7X(QhNN85zIsQ)-sTE zcR-J^PeW|dA}{ur!(eO1rOelZZsx#yJ9&X*(SC`IY*dWV#e9z?ua6H{O9 z?wRwG_lSfwALYe^*KQ)kUo`MWRW?MwG^G5cbjJ51WZfGJSk82heyLtycPxgk2Ynn1 zgP@x^aI!oB*K19MUdxX|z6#5ps2e$SvmD`Y15RpiqYtV!^9v%`-+Vs>aq|5FvMNjs zAIfGzN?jE{WcxjgAz~7I!5_ky<`eRH5%Ughq@Ryzp;@pocx*h(54)d^_toZte3k^> zb+PYOD-(xqw#>;F^?3g84Eob=HFqU+q;#g6D!lxuN5}1N#LNj-d%W?gN(rbvdm@Qp zT$qVD%(L3G6ueK*q#F%7F{V_NoETclcgZka@y84}bG-tJSXWC%qm9E3Z)3Vw@(HJu ziK*!q5n~6jerk^oa9!Dt-rk{$hwBhD4Q+VEg%aEuJ%#+qX8!M16+D`<1iJg_MzEXs z#UZbuWXcGK3H3Ety7LIkw46oWO;E*Qezp$BTz>Ipj7gPtk)uyP9D|kY{hQUV3Otni z(`U(9s8G3sm{bgeYfM*+syPD(Z)Z@-`pB|-X_JfYV`$t40d>c|0c+c{FvmcJ?O@lq zpR8kL#0bWRA2O6vl}7TbPq*T!IWy@#Ept-ksDqD2e`5P`8{dCA^YZ2RkhKGMLfk!N zR6fhP$=+^dT@|S)Nzf+02Qp{d-6YhE5uk&l!qk~eABd0P>~=cQE!Lg5VCYcpn41;1 zY4ta})8Is#uk0Z{*JOk_Zwkni2`>Df@)T5k=S}7w=tUGBXyQ+$^AL1Fm##}{t?%dO%d|gaVjpw|#Kjd8+J5lx4P_ESR1!#{^WF5!L`JaLA)U!%n za0z=!7H*8;CT8BnR`nG`H`<$|9qofVePduxb3N~^T7yyz8=|}IHbf>WV@iY}>+cPx zqYYcpPVqE2dCjA>&r8wzk3Kiwv<^nGJlAoD)qLN{6RFi4kx=HTAifi9L|V72V)49; zo|*rsNJi)!c9gU%JTAFVlY$@EUeC?fCTFyiam6PCn831=r|xCo-t`M1x8x(&$TS>L zsk42zhU3Nhz8?*Cr4fU|=}u3P@NboZ_~AD;^B<_d4<$K0Xi5UI4B8u$x%^?@Imdhv+o@p}fttL+NTMe^SHK?4&7c6UM zoTy*_xOGXI()hC5JzD*W!}VDHV<7h=@*>syRL=PSc66mXh2+EPD2XcvWetwHb;hE% zsWnMk6iPznv@v$)S}_MtgJ-642ew~=xdnlJ$IF-(-ti;xb4%92A9lkzk zLiQ^m5E)9f6SL8C^e)n>k^p3T3JzD+CS^8$Ii|%t_HuX$k!6jr@1h3cnOod)BXfGv zqzX@*GU8r^^@h`b`$*R=_m>=q)u%Un+A%-s0Wq91f=)e>jj7Cg_3A_^C@^3B=&Rw- zw`MeLVY%R#q5VkUlN?TXABO=xJUoffBYxl1@!eiA$=KsN^P0Sl#s{kA0^yq^4X3W|a$QVa{)NE@yPRTbQ8|70W zt56w_ruT#H>}t|NHFhE6lWeR zg{=}5oNb;3E{p-5>)4K`#~va7{M6}Aw$BVm(kDAK%fW`}CkKx7gB{kBX;*tMq4e-g zh%EW#U@ZQKPquq^5!O|HYH{IPiy`w@oC(O;-{-9ot0CJFz*lnZk{!y=jxy zJ+wh*(lTEJG%eVCtf>?7*BoP_a$*SVrcnWCmH~Qw?t!2l(`~H84P77=7`%4t=v#$Z_-e4q=P~urw|ltQWbFb{B1w zFN$`k*O8^qS;zOcx2E)l-!Ztsxw;-tlTYM9rvu zX&({t+g6n(CiW{)xJL+s5MyFldOPt(gge85RlQp%I z`JIDuai#x3a(bC6iJYT}Mi(!^-SN8gIpc2iu^B)TM%%(6^Lo7Na1o+kGe7)T)@xAb z%b67Bf^jcJOtEw1H;s3v!)D402EMP!h~jJ9KlwNm(%1Inp2m1JqV4KHQf!h#Z`}Bd zOZ>z{GCUTfHcY>&902$_obfSQ@tO1rY~3)Amgrgt)k||Yl}+QwLPzF3`|ZNpuCb+) zy+y+LY9;Z>93x_TN(IAuXZPG*Hx)7-%Zm_V^51cZ>{m7P`8NofuM%Z+n>zsZ_3lLtd=pWB?n-c+D~2M*otQo0g2Ugbfpp~K zzj(gXhU#9hr|)gmFe0`BtfH3EE7dYWiDv={oUh1#>_|q_bCZbPC1p}`Sq0aBUJV|h z$~4DM!2VX1;CJvfw>MT(no^kAGsDeR)}urGVeWMBMJjbK$4RY&sLFdD@}_HI!PQ!* zjUe>IECs=TVH$DuxX-;=5QnZC?8(5)P;xa#0|Op=L!8ztp4qW+;8z|w6 zKMCCTxFa;>U6zn8BwD-m zsOPbEbYJk8%-%PG_F_ES`2+Wn6IWSoEl&-HK0DvDw`XfeF=XRF5_>m?`%jhK85fm< zqpm4=!9I^g)!AHk?#Xyl6<%#Vz^Oz8LZ+z#rvDQ25k9-=jMXCHcbSq{;uH+A*IlIJ zRF$Cn-uh{#HWogJglV1U`HU+T!b$lMrVpEun`$aJCw>4ptzJie{$M;knOop)io62z zJL!~6=bJ_v)BEiG_*GC6yId)S6TMmP_<1(-;O(V0E89_SUNHH1PMw}RlZv)-hQ#(! z87%9~dQ#RK!-E}8bWLL~Vd3Yyz&-utkmpf`O5ASlPoW3NEmlI6Drf#@>Nj4vDiQ{3 zD2pc+Zz6k|S+*`mfKz??(6M)TblNtHT%I`^Zk|%ZSkXGDDZEbS4eF0!%vTe9?IS-U z=`OxB@`3`LVEE8q8S8GHcetCkgudPP9W#y$qaUAo^RF`5-}xYA@kyPhB;%eAhL}8n z6Z&=hK+hChCgVsR2OWU_SZ73r>}sf9;X@mATJTebI@5AjQ0wTA*#Au^JlXyg4w*1E z>7DZq-JZ!C6O{xb8E4wo;Li;^J3{Igt_k_`^r-FUCM@f7i;Ue9Odn5;$B0#vdgl3> z@5>*BeUZr_*gG{@{B9BNEv7fv=pDh%|a9_|2<=iEmWVj=pzD-8q0BDO48pvqZFp zxWcU8?00mt3SyW0(eUN%D0Ye?DWiH z6b!uwJ46kx!N-T9V2rOD8Ka<$|5a2vta&R#`#!J43!p~*M<0V)bxoYP=qnV37}Ji# zOnhwNONNXY2tS*2a3;H3DOOSX@n|!C+B%zTvD-q8>?rQC_yU_hgu#9GE?bdAx#T4) z>HcMZ@p^JTCj?yK6OyViY^^$-+1!UzI%u$c^$W}&+sOBM$TEYthkV!F1xKuu(do%~ zC?B?!-UGq9Tgiv)G2BE(?QTT5iXb94J%>J>`UR6OxDwrrSm>Cpj5@o`U~gp@b?s#S z+of?ZV!=FWtYRUAbjrb`HRH&fKZ;no+njfIwWi7IM8c+ds$$vKMx<$?3YMRh!0m+SxiZ30PY){R=9WevQpV|6kALHk9&O^c2hWR8X@Hq0#VVLpmGk1~sC&%V| zvhVg!uH0*e4-KdD-YXe%n|VIJ&ruam=N!ou#`aO%CWWYB)~xeRUhvU6OJrYHa~zxV zYO78Y9pCZdM_DY>J=Ow}b>yjRWHml8XH3NWy-+2ug#QVz94znq(<}Z;LY9dI4O=mV zs>rG0w0l+1|D_kr%3!Rv;$$+(UXkA?pMW)1j>I`ifw(W#!0p4fL%s*Q*|EG*+qxex z?)huZ=%%K0u;fwCoEK8+v36t*7bUq!$J>=-p{fdP&E=tOE91O*eSx2>?tJM-c|j>G zgY18v$5}tUi;m}k_#Qk(cBpA!_{DAD-2Wx>a;2cQ+ItY@*utCHEKldnbHnS8(CUM2 zIB`01AEr;H)luc>H${amlWl{$ef4qF^cE;yo6NsrnWLn+0VL2U333+82s4ts$hU~h zoHoroR4n`f6XvzSF~+o14136Rtum*B**#15Z!)K0VFa&x^_BX!IP~oBzvs2%x`L-9 zcgG02Wk(v0o3)2%M!$yXBUSOL>?L@%e>62yQ4s!nu$mlGlY^HpQ*cl3_i*lo5jns- zBo2$7az*}%bj8IA)}NBZeGCc!%^UJ)e|`v`vu_u@&c3_-8r8%*b_9cdgR8VSUL87G z^=Zw1Bdn^3hXaqJ`Rh>@!l*al9&4v5auyf&?0WQQkqJ7PCJT zb3s#k6HP639JJbq@9v%sVKZO*hno0qRVmzbR7EUAunO8o4gPD#VM|Yv+6;C2Yjh?C zrVSo><)NxYY+SPMN%V<4d_j>KP{yL7)#_$LNCt$ivv9< z&-_aVwCTO;fm{jG-oZ)-OpfW%Gmo3F&G#;$2ZE`$emqtixR5C8o3M|)!MD%f1__I& z(S;Y%u-EEZsQM7eU%63&Rc~%W%{vY9$4&+HTvfSl-tW6-tVe$JCwMi-kB<2B8>>zy z5>9GNRbERO^Tdm&x_pHpL>14S+X+i=4x=?&(ot*oC%AcYu!B!d4*ouW5)$%SV*jIXh3&L$O?5r|ncd7gS8G{E_BEe|iaBFZeLx{(pZ-Rj zN3`IIj~*nhbql>bCJ*!Kf5DH2v#_tf5;jd@*>{$8x~Q)rtQn{Z0f%GxtzK1l>wFD= zT(u85F;5%E%xHqOQLTKSRtD}d^e6Eid*S(VC3MKT1bMGE)2kzxpKan2B6V)(`?^(Q zp{F)^QuGOuOj)+>>%G1Zn4-u8V%w55~z zt!l~GoV16`S}sRYl+{s7FB*!vwCLN}=~$XJh`22s3uzBjrPG~8_uN=Fon&wSap~|^ zbd3(VnT0R3bGVh4FTfGz^Z%xx!v82+NDV&73)_v$$-3MauIgYM22b8bJ{{Ub##A)m zo>s=Ns>`PO)n9RQ#4Pf~lKrsk%73)rg!hRl#%Xv1hisrppL2>SxH;O~)lS_9kKa%Kl{H zaZR#ysVc4)MnV67=JcR_EuJ(3?|K#slDMB_&X!L(F^7G6)miC?QgI{H3$rJt5`(SPq9x^t|xcg^rv zy*a1y>Q)K_SV$A$z$qqeKGphXk-wffY7g_x8QPmu8me$<4`_P*igNyTY1 z^6r8nR#c5*I`e8;dbA5StSNvw2Pi)^Ck?$li@2JCdie2812xyRO6o53r#kaQLd!-? z@uNXyaHWv#mIEJv=Qp=SRR|-xmFl#1P8N!qMPxa<_cgKJAKr5`Z0d5PZ&hAK*dqSO?0~Q|*%35v*r3NF-!tXo^o+ZYI`NTG*&r2>*o| z(RDIO$d8{%^n0}T1$j+q_A8$JJQYkW_a@-r*cqh#`Yo`nW4VmMd%-tlD&4d)4U?Q$|5QdK zzhGYp9+XLimw6iGF=H%$i5|{%`)YRluEj_1)A%{lMKFbF6q*@dd$jk@^?DdoTMUC& z+VWe2axhfgi^#TD!KFEDPdI)MlAbZ`T`m*rbbdnJKU0T@16(PJscQ3 zp6kv)aS;{R6q&>i-FOtF=QPpoWHX#u)}P){6bZ&fO=REq(~ufF24DHS0K4L^)Oc?* zPVKjpyk5M8+TY8=)&g0Qwk!hHCMe_IrgF}}W)=OhUQT#;av;1O6T|Pdu0pL($^6fH zBhsSM2g5Ao$ivxklrt6y!yB5&B(+cA!?K6WxCEoMw$gz4?YMpYYVs+lou>)y*#Ddv z8FlF|RNPR(>xU~i$qh%kWVnJLZW#hKTR5&Iwi?@2Q~BmqTgj?Y8DY=Z5|TUEmH7n| zv3lNqa$=k;@!ZJn_|>G4d~ zKgh!C0q3CJzls~Q#}r?<%kqsT1^hQZmerc2C0>5rk=Q+ForZJsVbZ4YwBeV$FiCQm zculC`iZ+Ubx$PIpn0w>J`&pmPlPX*2=8R1-NW#ENryxLk5~wpTO3X3~?sh@|^_kO- zQ9Ac|GnOuUd{6~9RekN@jD@k;?lUEeJn&KE-LA%?=+1Ofx?O=h%+*2=9|H1BllHY^ z{L-8{=v{N4yYrUmGylHy_-B^?*2nj&t-17}$miIVVd0;6er~A*VmNioI8_gxHXO|? zloxiJP%^9~kK3dbiz?Trknbg@$h9z*ZNGXHTK<;v$}cEdZ~O;N@~*J9NdZIme&E8+ z1<~|8b8MI~gPS@$h^K=-qTHTD{&{d4G!1IT(T#wR@u}sa=4~NLyV{xEp!WKG6nr zhV~y+Pb?;e6Gzg2Y)-x<&7|Ov3pw4OhSHYnJsli-M&zQg*$6VGcP6*>N<6Ag{RGO} z^@%sHiNUYGaNYcNsFtALgRfjrwkPP#?S)Yx&miciQEqB_4S*7@YH6q?@H$ zaCf3UeKE5cRfQp#ttX9iatX=W7RID6Ttk4D{Xt#OIWS+7DlE2a>%_=ieFzSL5{fxQMsmr1sb)I zwsRf)uVj(1bFY^8(6-IwcBCfybA@2k)|Y57zF&n+iqHxv>D$EtTahD zZBiozlJO?+d_>8rK0b!U+_5YD4g1$ zf_V?>x#0&_Qw4u{VaOzazAtX@!T(j`+|vR4z??qhC})5hWMzrZ;(z=mU6G)_zm3co z^a*+c^E>s9>DlLv9=4;~F>m6b^M~(hPr;zpHc)$;4$H@?qK!#o&s~+g|HiuTEWx?K zf?M2Ch1PQec)YoVydg3|S!NkoGv9?@v?m@%tvyKA6?MT_4K3{D9|tX9&~cj$ zxs3qZ^;D#nOdYsxmismZU5v{3%MFUi=OdNb&9`0_zIB{|gb3DG^8T{KWBOuhE>RG! zT74#qbZ&6N_;@rfJV+{zZz1O<4?(Y*`|vdDAHO6t4n-S=kg49jV02Om7pd9xcqT6g z{KRqI#V|s79=);u9_FX^g40U(!Cz3tQ1`2ne=F_j$o(RrZ;Xz((6$d*HB=RcMm>Sg zg&s63Q$`>YFOe{6zdtP``a|9P;K6T|KctP?GAGB?2a5FN8sN!W1o5^wG_g-&Qw#`gRl zpmD{Mny}l)2J2k1%utbkit#8HJiAAq$<${aiHnDO{P6nbskmtDFBn*Ip9|o%r6+tl z99$e{Qd!jo9Cv6qO#6G0PVFqk*t`S$u9$@CeyKN!^S9a-l#l1^C4ZiqkHNMfQ3xjIrE z$En?ca<_3*%4MPN#!-whp3cQKFc19Ida(McN2bTIoRpFrY)@0A_FM%XeKQEAy9dCi zj|zA#`+_7WcMmo75DBOH>xt_UgF!sYReCN@A3o*lQ_pG5*tFmbG0tILixhU>sf{Ko z`DP@KX$4mH;vP*VweLSHk^2P2`*=QRF7vKWa)vK@resyF2KE}YO|oxgf7<2A-jZTH z@ov8|__{Gh9lN=dwp|8#@F-XZDWhe} zVy-*uG}NmOg1PYcS0D+}@=?O>R!NnV<;oUiUOZg2_EJtLHaFVE-mQ%e20 z1InYM+e-St$u51WFJ*pI|8#PC>QTBmEFPm63usjHO>i`0Ed9L0pq?3o(;(vg!TZes>H)PK5*SJkh;mymws+I1aF ze7Kb>n=3~xn3uqQ`v5+0{4sDn%yeV9M&N5%j@UpXz~T<_$2<&1%ML-KiH~6oeM1Yc z7-ID2FlbPV;9Xo&@O3X4rjZ;4-_gupeM1&rS+1v3ZpjI~3KqhPz!-kXnm?FyYZM>v zY)ML*7!QYaADo=u$-gvY?^dr4vU^6?)bY72#|^C( zL`lXMDp)s!`k5rUUgpdZM{d?t-k$Bs2x(F%0~7Uv|N z%@rmcWj-0HF(1-0iuLbm3|NYour42_YcF709|T2Eg4fq1@gr-mz&+DCpWQ`a49a6=nP{UoVg~1 zJGZ1zaJ^HCJDs`u_kBr-m@MiF>Mhh?cHV5xdic;9)t7dOLr@lGYwV((8Y~ zYjwrJxhlkMOR6xAlZp$^Hj}<rz4 zYTt>PdsOQwH{(?nt^Qr*fZCW3l0EeP_OD%RGHt7$|`OPbD<`Vm4|x_JGY}7eJqU z*2`ln%lWj=pEfU%ioGs(;cvY@1Ul=+$!F27oqGG=@wKS)>@Y{@d6 z7#Pnq#v8B4f~B7~m0oYfEzjz}+FlSQj4#F3HSXY7Zb**kYO(IH&)H5Z&1fEbAAQQ~ z!oRrl9v(4o-o2uiP&~n(s$Vj~G>5zJt0gA4^3mXA}N~;YJe1I%Fd+yn*fR zCe$rH886-PA}_AlKysiK<0~EpEwd;(YGX3~yskoAU+kj(5pfv(KFF)Tofb1Nu_SMXKUS#@J~0(I(3A`k1nRKX<*6WuJ}I#ah>_oU0jo zxt4zYK05dT*|Xtv3Ahch{$38W7&gJCWNrN19>mFRSkcww3-hF{%<&f)Z|#o;eh#Y#kD}dlZcr0` z`z?^`78cZm^-!$bxQuA?#SlW6_KSz0X=6Y7{2H5Kv{lJfXKUHnXEFHi;7#ZeXik1V z(LssE0WRxFtFZsiM+~%Ep5q!B4Anz*G0>q6eoyW}UD(;4WUj#PfH0W!uP;uJ=EEnS z_cZPRBVSTB(l>)rSVxj7xqK=F)?H>^k!DpWtz1s`yC{oprrTf@A1NFj+KQ5< z-8pV{cBGhbDH|^+6Ik3V2>sc!IzWNf3a@%K4^FWi>mGkn)1_Is&zS!g zwIsyYH5E>1s^hBl66nz3^VvPU$iN@I*ULB$wPLKa_RRTgzmj;zF#krw7h*JSoY2o* zDvlYYz<@T}$oz7)cW_GX^vndbW@1Ua3z$=p3 zWOwvj7c#$Y;T;n`A>5RNw`ijA`_~Y;cs>pBWEpdx>qOV@NKSdrSe$&{j!fI6NgzN4 zk7l_s-h~z2W_cGQPNu?=qEDR8e}?iW4?{Z7`4h#gv+T<0?Ad41geS~1rhMCkcXk|2 zsu`o+OuvBfKZaA++bUv0_)T)o=rcFOUn=%6izZ{+hVpO1^-=Bd9M)6BbW6`W_)9sC z>4H3bE>y+;eg<+Ck$dQWD|App=S21e^XbCkIOeO5Y=o;bz38Yn3gUlD?i1UGs)BKA zHioCHBgVT7$oojv(bMlJndYB@*$-^e1FR|6HzqTPzlyn%jBir!miM=2ONU zWIfjw!;^7)j)c_exWF&Q8WJ=m(9v^USMnEMc>6#}i5tyVD#z$i-Z|5sHNngJ8tgx^ zhq9}JI#sUzh+VJDgpRCJ+#Ly)4?L9Z z=e3;TGteXhp_Zm5Tg*6JAiYGHQM?uEnL_hdMcv zdlC(C6YD?SdG(Mm`jbRVpQ=o{e%B&@8(F8h>wZqZa1<@cYr*(?>`W{2<$~P$%X>_; zfcK}2X>dR-UYnUsVrK-?9>QJB{<)qke47ORyc*s-a~P&+jHeqslF{+2CdpN~B#@2F zmv#6dta|zn-c@Vk;FeQdQMDDlzP21kKI||1xW)#iGoORukS0jX+)clzH{q3mA}RjS zgSv)hq0Km7@^?=;Og7U(ofF5|+Sh^hvq-^se=TB^%I0~uSUhz$5&Zs`6Wb%Y*mC-!z+nF%ZtwQDs9@b!HetUvnW3*J?%i5R2I#p9?o10! z$x`Ag)3*`wK?m>i=`eYWAvN5Vgue$mlTTFx;OIMSk*_FcO3D9T*)>jwP)1ZSDFE0IqJ}X;cwBAgry*>@2i%6$dqxDf011C)x zsnmTK%|9a*<9nI%J@1&3gnZUj9aRWh$Ihp_-x%WYm>k#=7?Hhpa1!c%A4Uva^hsDh zO`P2_t8@3d>pEi4<3}*o{U;YW##r7j=b}t{&6b9I)x?UxStCmh#R@s+q~gjxru^)A zqX`|VjpdKuc4{@h8Q)v~WGwUDf94h(mWpC+JlWXWiNAG#b!zNf2KzH~s8z-teBzh} zYyRWGhItXcFm`VTXL1+or@m=7XQZ9VR3VmW&eg-(I(M&kRw;;{+a7l6^V=EQ$N%6` zvht1^nVPDNBb`IRP+gn$a!W3k7r%vdKOY)r)LYw zYkAr3&>}eWmvQx9{DZGEMo`1Pj1~F%Ir;F9Y5P-SvCMrDS?qO!%nvd^+W#~hn(|hd zACZJ3W@wU$0c`imywmBowc*Z&Lp1SPJq}vHc#V6;P=_+MCtBEF<`~@sgKyMe)~;e= zw1tW6lp)*N8r$Wt|$1*A^-Bw%U(!1m_TL;QzmwUc^UOcJuLk$HTqb+jz18qxUs01!AZ~^>WYBlUgWWL) zcC~ub70oSJ!1@rs-D6<9Gq>64=?1s*D!}!k4t|YQm$9ury~4a$B-xCY8>IPJTw-M;PL$zF%1m{kP!km4b_Vt|bpLcEg}Q>iA{T2@rp;qmJKM z_iMN=8J}ZAA3sjOOF$v?bq46HX5OB+5u8~%n>kCG(PgzJr~79kx1iiXZoJ2;bIv!9 zG{VA*-{Iu!n}YAY96UW@2MGvIgXsgbaa8mvxEVN&R%a#QAwNAbDd?imd_#`Q**i4B zsuB8>Xrsf;NN!N66*XmES?_p#u4{517|dpP?Ssv5;9DR)>DGkF3J=If2MapBo#h;B zeM$AC50F1z3;(2@gnTat+W%)FK7Oi8F63FtZq>#hyv>C2L~~MqL>n)SkL2PanuRCg zN6fjP#|=FY40@Av@Z%aK(&43?F-$6+?jqqEj)#GEvo_xClL@9;ne^i-=C?7}L&m@K zr6Y%=pm0T>+>Q@{E9V&_cS;xFXDp***K_T+92XFD5ZQ;Zv_ zL)JZ2qDd^juh2un-*2s8{ZAVBF*+424{fGR7n<e#cu7-W>ELr*r~vZNDm(|izjGUEeA)#!4w?bng`m5So_uT|vQJ$Ipi-FcOrCA>o8 zHWJ{Xi?5$%v2GnhdU;Vg*88~1ucOZrL3!W}cH=DajCvY7=+_4go{d5M)yI>@&AIMWIH zrQ(Al=6rmPDVaNwWntRhgOI(Drms>In?A-6@#c}7eBVs`oZ&{cHkptY%x~Fs%tENH z>_e6Jd_xcGHV7!!0S#AUdBeo`&NIKB?MbVW2gnSbMhhA@nU^xwoR@@-Cel{MJm2#k z+P^web!rAr%6r=qK1Ko&iH$esJGE4O#)-g)LH(kgrwd>A&rKTk~`vzcn2H7EWo zf>x#*%$&~l@NY&?ZRVLTt$sx`=H_yImpFXow3H0*9!j*v^u}Vx+wg7OU!j;~=w5x$ zBLU7X;Nzr@WuJ^;pK>r2yy~%}{WxrxF@}oHpBb;%fLqhM1zrTQ4q{Q8@$=J#>N!$z z=>Q48?M)BTZ(4YX+btbps|V5Yt19Bp8%M|q zrqRa-#^8+tbuwAmkT`WQz;7olpo3l0#JbfU=FNvWx97plugdu4m{hh=ZwrlPbNC8_ z9{lNX!BC9u@=J@Y;SiY6^2>%e-{L;=sa+H{PL5}cARcFz&W5wEzCb{kE)G7oM`jmeL8mcY-K2jH-eGMi>^Z54-evEh&?SJn z#~Gq*#eKM7Z6jRzl8vl0oSe0)1XT%p-WnD|M<1&q%jUeAuS&W;{2+5n$-=L?DO~0g~91kF>`AVeq6{#@{Z+{?aj(z`0=jvb5c5%%C?ZG8@5nk&344c z&Ox5$g$vE^e4+~j$>WQA$?P!!c84#)JJoR`g_vZvs>_W-woWBgaE-H zUn&MB_26}nJ|nkO^l<;mFCbB@6lAXwam?j)o&DNmlsXRdIoUbq-)Frx{tpewe?4rd zMp`*4$P~#Diz@K{t$`8GyJOTv|U#^loCi^6Ee$?SXd5!Abv!H+a; zEL)$yc~-K^)iF5c&pjA-*PKk9Zh&v5+~sDPD$&7OpK#2y z^_+WhFpRR+!SgZ|V&~tT{u#lTDy!7^`q(h|WW##joCTQXnMwPdt;3yuL8PClAJxeC zjJ=X&B+DoP1TS@bHoH4yDK4W!^%R+>D-u4Rxhg3CFv2hAG|7D9R$<&osTjOkjW4kH z3QDf5tG6)&)^yoS6>l}+cGhXdxZ=X4mQ;+cHX-Rl?t&%bOT2aL4kv%{^r`$WW+hyN zO@RT!PEvRCn`*GRqS#zng zqeRTO(nwZmM{!3VNX0kr)c7x}e~^Y@CRny1526%)2ywF#aFz%}EpIQ(@Y2TLB|cDk z;|vXotz+*pEpqtK40v&K**Ppzx8VJoP00Y30bHW~ z1-zO)=|)k+SeJdoIB!NyVR{Ni9~ez!-iBldV{t?dSOL=u`qG)E-%wj!LaxQ>z(Q&y zf8?Dl8)INgxx6Yo@H>Fp?0b@4xGEKQDOvEl6WMH^tAlSweukGzTxcAd=PTXQ$=k_J z{Av?jY))Ja-%qPkrSWoHzqSN644Mf=i_}p6avXPd&|bRyXESc8+t0PzxzN{|npihi zkpvC*q>jxB;-IJ(pa%FToINeR_DH9NSk|lDUUob4`;C z$;w5PlZbB3RV`(@{8q#Jvd>koi%$ z+@ZWUoL1sPG9HH#zTr3e?AS|e=OokKA*^G?u?IoP7>NJKvR&W0LkE}4`9eLmxmRwSBRx)k^aCMStpl zL@IWTQ{$tLk0Yb~wJ_peR;S1!6 z$>isI=mgf6@kTn5to4Y6VCE-ZyJs<&T6t4y#=4$&>67cWIYMQ|ZH#>80pSW?A)a+U zw*Cl{S*$jtNynvPdQA_0*xph|+{t_|v)^~>_RcI*ztJ-nQY-ri?<%sfYRx2a#kLX@ zSx@>c=~C#OG?r#srs4btFX8?4SlOC}Ow3rd4sMPfM(93cbo_lu_I|7a?NPwA;vp8i z{k@H3V4F6EHkWmB41QftN8W!c=^bGU-&Sd1`NcC}NuucBa9tc1v8i`uq8KPPx&8hA|GwA)f=>yfPC&hAHdhkSv(P2U6~ zl~gRO@gpXq_CN#kv{)vb?DX55D5%2)vhn2doTc=h*KJ%_@eoceOam)DO;puM=-kQb zvvnoH+k zllOS;mkP0#=n<_lJ$!ibA-8E!Z@T^t^9HPm;h*X&M) z4l_cQ58!6LRHhTUmf^q57%psX2t0YMjehE?q$A(D-&rc2d#Ax~xgQ43ybkVIEyB*r znJfpYk1my0U|QpGA=JGBAMSP|N9HBMMCR4c=4{~aKyP|kT|s<)CK2>!T@fU;Hsa!* zE!>&AUc{-*01fLjNo8xJP$-j%^`#no)%dS)w?FG545gqJyN&AXX~Lx3!z5;Fvyd#X zUUFsDE6NxXA#c@i*MeTq+5N<;h}16~hK-eR*UL)q%F`QMwe4!sg*QNb&?Kd=mgHpY zVm%ken!JPmb`mjEAH#M&fS79LHxrXkVdq%VxMd)WV(fx4mo=UK$?=J{=)q5dJ$~PW zKIt*|@W~pu>~R#XPEo@{3!ch4`auMLwv#n!BQ*!3xPTW@aq4VM-u(Ix68p~py}mz! zwSk`n^$oH3aSD)x^?|^xX7j4T7ARuA5#{JVc+=E~g!s;+-?KhoAG-_C!5QAbJUr&^ z&t)AQe~s*H{~2V(59w}3g3Yy1(pC(Ka%5;lZ3gO$C4YR`i!Be z$(a0Wp`#zsnvhAm54R$Y@fXT3+H=GDn9O(O~(5;@mp@{;FCsQ=rUZL?zowRuK5LU zaIhQ99?7_x|FXHw+WV+g{{}3)naOo873$v@vv66r9Qc@ZCg^#}=F z&hEt%hW8;C=DI_`LzXMw-WzV+2&R8m8>8QcXWTiZ^+I^Fjrek43-=(9b@5KC!AMjs7698RXPS~!#d5G-sf~LIr7%*v51q=o zPNcmfVCWxHnB;CMpS$PlNcB1+dP1cMBmVp%dwLC^m3x>*VWPxba3Rh~IQeZilAGO)Ol3Kpt)ac4PkXB{i?Nz(wKjoU+(Za&W_ip{ z&t>XIc2UJ^?40k>lb>)h7<#3Qm!DOW!Y|vd^lEM$+H1xTrN4XV0n1 zRMheDq;)WOjSrPxOvXvUrJ$UDK+w**gO^6{hCR!^!J5muNPQHzFfR+*;f*P@>B$#A zDTU+Jn&@$)0#>^Q(t|M3X>Q^qxr@|u7e>@#wv>eqiVT| z)_ua54^q)QqbL8n<{9fz?SeJc%uBW8uOKU9Iw6JQH-Vod0p ztF;)oD32)R1=E{3toQJI5Q&zifo8e}!ud;`Y~hv6r!*#W5h+?(EUb;Vhtr1FLzjN7 z5XE-%8FOEAeN3$B=4b3|Zz$o0^L-$ym}R@BD3cEUtvk7Kow3eX_uSUotwO-Qk9a+$ znCr7N7^a2k;{2x?Byx@g4QA)?{b}0#-|{f1zMzd^Cv&0Y<6WA5s1|oU3?Y$YeCfnj z-_fe~6jIoWG2_;&V??GMbok_pCo77(-ym53xhjNe_Z8*adV%vtFA~D~0x~ls_<4mk-|g&Ic+I%_T!9Fa%C^!~F->@L9b?1Gn}w;n)7h?}C(&iBqWnQD+p@;4 zbB6C}S%(Lm(_m1$1NVb+V!wz zRvs*VVN8i(5-xi@fs~dGfOoMP^5~y_o#%Y^yDChWW1G`GZhu0K%#Q{;==hsrv?u9o0B>x9_a=03&DMXVruWb75bu5mI9NnqU zA7}Z*2+3+V?|qzB{i(x@gQn!}=NWWIXdTNVq(MZL5(yd0d`e?9xXP^@y&WMH*EaR! zqlTK1g`c#re&%;r9DO;r@frlyjLydycTTavKIWg=OYu20PJG_m08X1Lbcm-d;- z{(RF%DE#j&H)p${{KJW2SqG!0`brzN+Bb5WWS8i~RH-;!uNObOyBk?ysD;_hUtyWC zGwmJD*gF$5N$!cy+?i9%Z~0SB8uvT#BiP>XfznRc`bM4p{)Xsn@CWp|&4&4J)bPxu zC!PLztxfG1*4)S~eIa8#k(#JITa~z5d(q*&6-9^Dg~TaTO?Z0mHa3QCCjEY^64gVx z=-%Txq;}V(8^)#KJ%4Mm@!=y*b&8%`SnSw&&PT>qVPknx=RB`tnt{1}Q#jxDOQ4a$ z=6Nd>^7+&V+O$C;PCrvh;%jrcV}%K58?cRpF9|0eD%DKC4JN5alj*fHDLA*ql6-kN z65cIj&*wEe$Q>O_Pq9v}jVT$hc+(jAjb)H+w)BEGC!ERt_!_i6{herk2&MlvvOH;k zHXq_@K}@_A#Ws^u#HS)NYrQq%=dN}n?Dikn_n$V-;s(K#us-yWw}45h$3QWpohusE zUEcRcH(7DM2{pW^$G&%(q;`?J@Z_>oEW4)7H&%@!pI+8DrK=m0KFKi!Kjm_rBx3 z`Nua{X5hd?dH8;NIDWkw?WbGEx+&wyg`0b5e&}sHpge&*vy2C`1~s&=*xY%}r=Lo} zCFS2?@Y#dHnYYDg@-PlgEHfaZ8QvOJUP}ZM41f3)X(w zO=lW666dE&kCq7N@8UszeftT46V!40r!Da8&lu{vJRJ+PtH3ZSPG&jh4%WDb zKw6C*Neec@^PBo|&%d?_Lq(}r(bSu-bMz$-*!}1at%B+`U1@_6%Va(KO`O(TgjZ~y zZ$EeqWZR>te1$g7O%H_6rydE|U8(!2T0C9+j5w79Q|*j& z%*)tEl-DG({GbNru{>sW#3a^r+JrODEh7^q6$_@NF}R8`K;j0xho|ecFz?DoZXfG% zov53RQ#4CBza|OHW&6r48LFhidy~Al5ks!LCO&!=^pG9Pk@cw|_fAbD=%j@!-LJ!> z%MMg$INM8(T0;u`d}Np2$Ka!wk6`r3oIEwt!T71=-0b@;La0#=HjOFg+E;nQj#7P` z+E161saexz)-kc|u`a(^`6T>g&*WXtCt!0Six!2};y3;nv0Cp-_did@JkQ>p-kYI1 zs#xqgknx2U(?gpS#H!!VA@=(fVa&7?yhV$+XZdx|<$5=ykGhbAuS(R-ljU*Bba}@Y zU!j`$#!Z_ZzzpYYbkO-G{Lm0axc{1kw6Ez{Wg#VlJ+ffra|!BJ4}jIDI6A|R$is7X3Qnk`>n*7j2DVGNyVr?x_sA1+sWKHdN}&=M@8?2B&6%GWqVW{deXn6YyqVK5Sra(*Xh2AW> z(oiBMhAZ(mCPr~5%cbJ^>3Y0&*Pmp$C`IkI8aTnJ&`a~K}p^5p(*u(E;NhHW^eub@Cx(INR*lu zUTpXQ^A;|k_rEHLZG{;mdfkzn`_JO>TJZ#OO-YBG)6hil+6f)~P&!lOm|D^T{p%~a z@Wlz_;mPw7{Y5)n*@rvS}ia(c?L8wpTh|IcU(u8YyA6q)buol zj19x6DW`?+uB(%2Szh$}Zv}CA!8;=OsR^?lGQP(^)*;KQ5;N92cFy`1#I@J<1_{fk!PX(a$TmqBo$1TY`C486>S7D>>xH7Y z-1RImJ)M=+)FR?-GMJQGH$c9qg{k+4L9u6V`gLbE*1S3cgOpl1Bhg$wc!Z0rqaW%) zMH7y8swcm62GXv~`_#3I9zRRpop9@P8SCsR*sBhsS60b!U4j>BQpn+w4ku#NvH#o)iHFjg9TxZ8?4C5*7>%;30{Q%?Gy?fyBpRlzikgo04j2qQb$m^ZD z^kRB8M$cPB?vASjzwhd}a{7)=zoqk9#O9f8FwrbcmN)J;c3*M?zEs+hz-A-d@M#bi z8Q(74DUym$68i94m-v$35xN*^PzzQS-RSAzQt`v^8nPq&B3zio*e3in2p<|r{i3^| z{(pzS{>>X9l{zxaj&% zShXM<%xr^w|GG9w3+$|AuZDTPnp%RW>e-A}Ln%E_#id#O- zf}&D7W^Po1&3`1&_K4+GXf^9}1sT<%2D{zePS6mNmr z&i=H0fRgCHd^4FpZk0@#eLlTY3F}R}lNsX;@b%0luA#3IbrrJN%&7{mRK3B+SQmF3 z)FHYC7W54}^QUqKyr1Ps7+b21hxMMbStygLIM$)RX&CVv^k+*e-hBQJ0=h>C^BPmoq)h>iXa9lP6cgNHX+pLwRHR*(G9T0e1OBDL zH^^DTIC!;BVBLxB)NoTX^15e8^0O9U-pdTU)Sof=J+fg}7gbzbGz>r;=%cb4jPiO3 zi|ie^NpId__9%0R|LaYnn5OE~tiVrB8!v1}H4m_x6PipRrtQ#;Rjmt`9GY3Cm3dGi$grrHg6`c8%Z zmO;XiQgzY))ejJd7!i}7%nze6hV#EMlIpN|J5@)@R~#`TwX9cS#>gsoR5p)w;wXxz zRC37Hk|Q}q58`pq5DIx;?a!b&*fnI+Jq@S|k{JWDM2Wnxw;5xnzc-XgcNt z8Bx#ntrPE{htqDN5Tr(SuuiDs%kMyXiUIw;CIc&8IuOH2Pq^^4`to6FW4MlNRMQ3{ z4A*Gml-E*W*W6_M9o^0aSD%B-7h0(8rbQxcfSy%S6}K+@N_vUQAf!Vmri{~*S#Kp*yV$x_ZWInI}P1MMcD1|7}6K&;XcN{T(%%y zFlQc^4XX|K9eXW^G)z&v9(RGn&&tX&aLd6ouffE#`8P=RX<}%l3~K9oQV+koxa?j8 zm^A(4oT<6|gT$lrJoo6?0nRLk#iBx-*PR{I<_7a3 zM)czYYJwqP{bc#FevaTa!HlZ)G(o3zrQp8!ig0XdJbv??K^k=9V09g1KJVKPkg=B5 zGC!e;K`Tr*I4JasF2S4D58yas`-d;q!4P8)E}JoC6T{f77~7AJUikr<+5f5b#aggT z52R&FoAI}ICb55^OKT%p26Oca@_I!ju(l=~-F+Wy)gDXt8Kj_PYb)ejjF$PP+(z#O zmtesXJL2@x5TjguxT=I!Vb^o1*s5mBcTe&qty6Td{N+C=xYv!A4U&po;u}e8=0)%f z*JORu(Ve^+&dUTnex88g%7uc>lOzmJY=NH*#~_e#c-k`SxfRbn>5(QCv2V!?xR|+L zu#xl=rJlCD|E=dFUdI^g4k;23>pI~G>q_2K*hq%ItA_O~FSc9tCag+dM;oPGF}gey zY6l+`1|CnvgU1xeY)b)_Bx>ON@J4R?ZlM3|sKgcBMnc+jFK+hgf%3@tgTZTjS8DFr z6ORS!l96vRgskem;-|e$#C};%@`TsKZF(_qe#8{|#-JRWV_%qDQ^fR@XT>4-^i0oup6uN?F^F7?d^Ef$lGJl6uDo|Ls--wV5jPb9xT` zTH75K$$VfbuZQ8U^-0t|OKLfZ`P&5}zRv9=^iF45O~rqmJ66vj>^u((Cxz4e=rZ#- zyl>o>c(OK@sru@8c9<(HeX^8poZf~-bG}21+??(RyaYFK3Li^Nc@c5d0h(+qP0$gJx{^IZuurX%QOP{H8n7k>pIy0c+O%_spBk z*xlS{RSy-hc6}|}94h0wJG@5|4=2zFSxxxe3Zm+FMZS2RyKw%XRNPTx#LpYOgRB{* zi;sKdcjjJobW-s_k_TDebqL(h(3an;J;*s8-$y;wE%BkkQgD4$B*bOKq4LhlVA}gQ z^!8T6T6a%wpoYEgCL8nH_x~hb|Eh7q-Q>=*-E(w2W?0T5 zZwhw9lg%s#=er-&^G;ETZ!%UHD3C4f=JfO>HE~z*KX~!UfT;TGV(H&iT+}X}YBEhe zc(*N|cFl~exX<)w)}@x(V=h%atSCB$G*BY?SwAF8PgZdKvY4Ob@C&l-pA)~}vJT$#4~BMcby}XEgkhuFA@;HxjADMF zix(O?y_7aa|FHD%M38tm(-u7~^f|3fTJpW$cyqfJ4|AJlEoH0=uJID?IxPw_zDf!F~nDJvQ9%wdlLvB_ZZf$?}MMAFBv)fkuZk& zRW{Wd@jcTmNc15^F=}Q6S?ZOQRe3oZ-*g{FM!EimKm`fr7RdmEy3_cE42({VX8!zt zT=%2RIB!ZD8T;QrTE^bjW@g5Gb$~k=|B>-OE#H8cKa7U6p7hbN*GX`J5*+z28r4dA zcb@Z$_v+!~qKTdQ%(k<4aAEhW5W8|BytZXM=@lNF>WH26dMx8^+1T^WT|%IE|77_) z*I_VkhZ!9^?GI`NWf1dIdufSz24;R*PJBP4!D}|3%yc^d2d4T^y@+Hy<*!VBwH*+a zE=j~3r)bzIuY~S?EMGig2giRiW1a^#-@4lKCo(?3QYqtCT&{!Ta>gZF(u|Sn0@1F} zr3DM_V$W1>vTI`nG%^p^)0Pk@WnCC~$nN!TSVqP(T6VPMHm0n)3GIn?WXMm(J@XCZ zJ{+nOvYF0#;J*&LnjSiViUWRPVUcs{z_%? zF(C`$E7+Vsl_78gM}<-q(f^|_v@Y4j4I4F3-tf|~^PFE@Yl7xXSE>ISD|}_2pZlbp z%*pLZ6iPMF_CP#i2u!9vzHHCvvV%;kEEbl(ipDJs&5*3lSknu%@OrEobZ9j}mZ|vl zbU!FLs{&`3R^~BVn{;^Q6(gE3ApQfX8EQ$R9i`&5+;-wBnM7KcA9eKP+o08IPpy9_ ziuC!O&U4;FD+b#qv;f+hlRw5r=r%|XI(DxyY(MV$VIcf+^@jg;=`kL@5jptFl0Ic~ z^;&lmzIMw=$f(xBZF%{Sw)HO6{#1)9Z_g4}Yd<*{1aT*s)+cobd!41! zgY^zvz0d$7mPH7!O-gZj?G%s>HX*ei^)TqH5xKverxbY&!WhI)_e5NJNb&Px5(i5HxR6NBcR4VDkNwRH9^v zL$1w*lhpx&3hR7-I7^vy>0>|~y>(gF?S9UGB~Q(=rJ_MM2cCP&cCQaKad}z;?BBeA zZoi}`4(ggqPVYFHV;h-(M`w5tAJ+X4xQqSXyh1uTHj=1hbas=Fu!Lf6_ZcJk!UR38 z!&ejBVua==Lb%q~X~MF%j7Q|;z)!AsBV!pGVS!sU)Ta!lH!ey!Y18E^ld-j%gj7r)1A9Z%u zs7g-Q}S4DAH!ZqUBB`b@r z%*NA%@r_M?gZ?QM9F;m63Jto`@tJqA^<@f_`ZjVN+sx(Fp`o%B-A(BAGmSVvqQGaI z9YEKnuy<&v39rxiJO1f9_%EOkPHc9fDRb}Q)^RJz@_A{T`ip3Gf9XfkUl|a!DF%4; z>>SY0RHIXd-eIi!7*JB22nE|%Cuu?e_wv7;^kWXw`Ar>o#{nTQ`|o7=u2g5(TVzJB z_WXkbF5M;H_U@%23o`JPh7XDBn+{8S)G>TKW1H<>NnN)mBleaM?}`J$;;9sQ<_6y9 z*b0$M%k{Ac;(9R_qLe+8mh72~D*FHlZH(_dtsa!;1yHw1&8V$U$@WjW)O=tTK0dda zY`||2FjpJ%haZ7MHk0UXc6XSzNJ6SsM9Z3cvRvV@TVVXTA1NQHgWI?uZh*-jVU=P( z(azI>pH2LT#Y8=fdDITR|4eDybauC@YbRpUMOee`s-6+IJ9APO9_nNB%@gpX#|xpW zS_(EDl@Lqi6EHuC@g$8Uu-alVy=bm1-U`|be@gZVG1mP=vfF`2%=U)Z2-|Pt?9UM)`vBn1F=>GQc(>Z z-E|0IolyO|G~)8VpU9~N7PNX4%PcQa;`Ll65!p1>#V{lt9+nQGi;5IQo7MZttA>@b zhWXKW(?^NCIcr9|m`~5k-wUnCf=z4l6y{oF}@n88b1TPl}6Kq3T4sog&Hww9?2chOU5_xE-*He zBWo<#JI+g$H%S;Ts57mm@_RS_e##Eg;;fJBc6{h$AiQRoyWM?#$h!4P`e3*C_g?VM4aa_y~cr4F>iEXNQCEzGGxM(g_dY~dM@6Y(aOt(0hw8E1ED&%G{V+dbA$sL`=kRAEVpP4d%Uuk4cJdUtV@MDdzAz>bU@mo>cGv_gR z{PSqe&esVji&#n~=IW6cc8_bzKL#JpvrZ7U2Z?#BN&beHaCcrA%4POlxeorYN@y=! zxgnP8Zki`_XLsj;w+HZ#OvaE>JC?moXo7X&!|2^T5;5w-bMmI5f}6$8{5JkAF?Jrt zuRpAf=U1M9wE=2W$21uozH5*dnqy!l<3co5YQeGhd#NbY+PY1+qDcj z{Wg@%_75#9$%ZC1;TF?I9QG^m(ty3Bj=kfyOic&3MY_}=L?V823MMC)8-YPrJ$YA; zg`KngSEkRmDb&M)!564mMiM$scY*%C=itg>E&QNkK$`V|Dh^N;EBxw6;Bz+H>-7^u znw9uRZhCxFfB`DHXTfj&ov?K$n+Mi76Gxqqpzp@|eWp+CJo5)=|HahFEv!G$ji%no z!RnV|ARzuf@XoHm@28r{pTlAFb12)t{OHENX|fm8|hW#AxQweLspWnJ^(6)oU#GJwWEXvUZgxn#@~J=!BG3m0i^Cf!25!-;6-@6`zH z%t>h`reLG5E~!`;BU5x1&?YYrVlzgNLmM^lq4s$W!+r^4E2Ls^$RK{ic0Uq1Uk?@b zD-$)D87*SxPks*-{z2bMaHUxjosv?)aYYoRb%yx5@*KdDS3&^mHPI0av9*Cjca4L2Dh{mefDC_E~o)#p@1W%JWe z!}8(5@dM?r7mw&X^VLt+A$Wcy-t{4L1?x?|kfg#-(&|Opw=fQ2QVMkOnoL`-H{n{F zAkxw6{X{nf+qdbFHs9}1Z={2v54wSTu{Bj>J|(C2X>i+70^>AQaoh?Wl8~~Ky8UE5 z=|d|>KV?g5F;glQWvTGR8EkSuZe(P=746453o^Q!^Ba>+!esV)UTKTq zJ?f;;#=P!(h54YVx`JAzwc-O$4I(p)5RMq9;f#UP;VWZtyVe=8Zr|=CwY*Ijet>=7 zUCjB3-@d_i%KWJRy#pP^?R4eKCM+n5B%@PXgog0jm~HAz){`XgW&WIZ{tMyDA~$Lp znT~d)4|&3gFMFzhHTH}HQAgm{=0)zSLbvwIb#+dV``urk__gGeX(^oLQS0NM+WuCDbA0oEw10xg0 zzT3^Xj)5oX{*6hPI6#+}jWwsK>+134Itj79szQu=Yvbw%S2^_JXb|%cUos!e-ydd9 zR{N==;o{~_-KMXoD8^iWO4h$RnqwRpi<%K$WYSeOm$07DFH26svh)3Dq-QFw*so7C z>fUp+_8QCMURiM+UdsPTIuD1O-ZzZ5>uqajYf=$~R8;SM9}<ZbOrm??6RHO={U-)XSOw5Vm z=j1yzq0`|g9590WxXf}|&-R8hJXiiJ4nOTRh9mtA6hWh>%U^sPz|;(^>2R|P9M8Wi zu5i9Yo4W=>(~P}vTHwB;FGj6r`)5B5Y1V+>_*a%MAMu;}CH&L{n;-)r(Z-lGrV`A3 z_(pVcxJvCh^~OI+0(6L1C?Yn}vZA`A>Ze=>w;NI@ii}-#8?1>HG6}>>?Fi>n?nb zkAWGz45_)727U~9!E9qq$g#~2SYvTi)V-TaPHJnh-IMFErBsc29o!CGZ%tz}F`Yix z7@^av|3ujYMoGLsbm5$T;IFMqzn@)@D-x|(B7a}VZ*>v|p{E}hI{KmOReY$B1?>M{jR1Ig+Hs(N( zjXMhoQlaZTwmnkY`9$qeq29Yy+fB43O z;kaI=G zM=Ikp!||+Os_lo>`A`NL~%u4?fh9m1U|+FHcOs^Oqc9 zU@sGe*E5$^eST>F3R=Bx9~^uW&&I#zeGR8Qg~-T2biJWXMX!}{(^(%@7p^YJgP-9J z!&3P|evcTD_W{4J_7*BN3~9=rLs0NXn{64MPE}RL_;X$$ls?y@!zEU5>3K9O{!_=h z01iXgao*+4d+N_wo8YPAQ`jp0?(i%Ai%Oq$MQMwRbab?)V0<+S6L~k#ys-p^Z46o9 zGwu{Aw`n>&LUYM>Of_ z?a8qF@fId&*3yAE9c(z*mknCz#(54t7_#J%_?w^Y%48$t^|Hn4U&>OqtryW~+Vz~| zGdTp_A-H$RPq2y7r6Vt9w)!XcM5NMhi@Tt);-`H3S!>0!iMRZp4Ca3IEK3^jUwgC- z8YkMn;yV|$cEao6U}U_*di}XiupR+UR{QRYO^4S$w%{jd_i{o4Sp{8$6qs_s_7%==l(MjVH6^*|QQ3a*o zbXuSG9?OuIY--1B`MlBhxTm0U>>a#&t4Xzko8Y_lDkkwvdLrIIja&MxFV_u5s(iru z-9zyPKQnJwC&0Q`-XqgKo%Y^0#$gR-{lm)?^!@s4h@0n+W0tp}g05HP>8l&Wa}In@ zTJ0%pGGBsLn)>8WriOvP&Dl%dgRpvprZ8|-BAA34ldL8WRz_c9H^%AFGUEeKwC1ij zJMk0A68$*WBnwja>X1!yJ1|lUV;=jIrK4u2z;0@kcvEnd=9}~o23{+~(ba9JB0&qE zFZ(4HEO3#g251V0YbxOqzi$rgo&(VfmauohH8dq~W9vEp<$flmJ#32>ml<^WAfwNE zHc(Ir?B%W+n)m!5=-P+Nv+s9R+9E1wQwOJW-+<8~}+_b(Pt^uEHM0ZUxOxj&Xm^r(ZOD-8a~`@6S`v|vy)6ztZ4 zE`7O2y4e&rBt&tLUjrGW{=^O%cI@tW&Yez@3CcGIa_^>$>>YAj8I|Vul%-7AiPO5x z@$XS)Mh!cAKz3g(b}#%AT~#cE{!Gq7wJ+5JK?9w9(Y>E^AUO9 zfd1vOivOzVp6(f}9I=EccT1-D$$;Z+H-YP84Kg*J0SC>eG6kO}H{N;yJ>#Z{T0bt5 zrqMzu%K8pBW|)$bu>&ruP+}XoKC`Klov;SKL8ZSoHS2zWiwjq9Ke-WAAHD;t{7uAR z+$V555i!4ADvX_@Md$C$0%Nf^yK(*sx!Ju0T|X81O1F!2PHO@GKlVib8A?)2unrfu zgT)W&F4BOBc0zIVYCI9AM{Adsg1Wvjn-X%BrafDOZ6A6;(Oj8Ama|{pH!PBsKWt0$ zFKvLszY9dSBn8>S7pQ%F6kY^s(T)c>@)n-_=w#j*{lh>|dY&Zr<@Y}O3_C&R=no7y z%xB%M-(Y{-JF!cfEA(~N3QSbn4B_pys3XtIzD|p0jeJgMw|oe0Rg7Togo~uz_aTVq za^NgKV>|mX`LLaSEc*@j)wp{LY_k=fRd9~PJ#};snapl7W$Cf&6I7^d&sBSLf&OHL z_t~w(_lbw#`hTuWWAhEFc-jFS7gosC(~T9*n?2-NV>_}bvnuH1?^E!$Hl8(e z=5}6BZ{cxnAimI&QB7|Z924cmKFm~?Vx3;$$nK@`_WXMtdb|`59q<;c`WTSteH8Ks zXftmL^4fuAj(8*a;qsZL!u>MY4!b!_kkg=j_cEY58yNS6NX7(gdy*w3`cP>Bxr6{z7i4 zG7NlY30YHY6ycv<`1jW`XV1x!&tT4I88=Rx%{8&;Wp=`%nZZ~-U6(3%eTEe1!LnYd zOTH(w(Da`wWU8gpqnbceRpq|fX9l!=*-{wxTAf|*EYT2?udOqDU*7LLfw8X683R%HC6G<`vcCJpgGs*XJRCtOU;JD^PJ1!vcHvM z5cZ{kF7FtRExfX8FN;ZjOpEuP8{w;;`gAO`P=4fHJLZ4YMLJyIBOHG64u*SZ(#TR} z{Lg+RE1T3n{w5D`&lCf8!IAr9^vh7=#850(=PcazhoNKFV7A#=h4aRzVYjqe|0$d= z4X(v}Kj@B6ewk3jj~8;C+e&PvhO3m`r>9^!dI@H6U1I5ZP2A#Y&U!B9n#>Lz!SHY* z4A*Q+o`#RW`%M}v`eZ;>O()>ufCu8HBN=2}X@du|cY=JCE^U0+89MEm!93O}OIL^U zKDD7yVjnA4NpE#e9``Fmm3CI--QN_cs#!cXk?$@Ob%fO}Rp7<*N^2|?F!=sLR=cT& z9-fQA6A@bPz>{4 z=^{Pusw<3&cf=TN9ZFH~?rEE$EL^35R_gCSq5O?_lV=GJuCc+C52fJ4eJoX`9?+73 z(m27j!G7DIxl9|9Kgo#Bnqh}=QLL8}_gK!a!rNW!Sl)COsnAYWD61KW>yx?feZehg zUfGqIg{epp$M@iiuyFt18_Gz`8icDSkHS?Q4asLF&sL0AW`|07#!W98zO5Y%OULs0 zc84{N4dvwwi+JY!kb@9mwFe%*G@zxG8VW*2;CRis^w=My#XS={z zB|j?XxAJPbw&xzIdGA59%~bKh9ew(zZG$b{+@0b%D>8>?e71dq@BB>js^WSz_eNeB z*GRu}F5{5QCb8S%6#ARd7cV9p0+WKpMSNBtP~sqHvelTvyRQBge+Tv7#!OJ>{>IVe*f;MqFguyTanRw` z+*95~3$k3f8Jz1Li65VTpou^Auu*;;V)%>~U~;$BC;2%*O_Hx{BN(nrk}ubGl@@ey z6uj^Kz&X=Rsr2|CI2KkecH5mrO*=MV;qNWr{Zxx|_^j){aSuBfR6~bHkH)JHMle&i z_muWQ7jZ`w2p&4b!V2ZfJNdKSbv)Dkq^Gbg&kCROnXuucCO$XkOaM0($v5c*rp9m2 zO>VkCn%@@Sm5#bN@6?&F!i|3O1gZ~i?o?CGN*PD?nlJ_eeJCOwghIzA_w{++)&wg6_Pv@L! zRVm!$A8v@(7A^LFZimZ471e!(86h2LVU10`^oQLi&PzjnMuLu+ewGoA1Q^$ z_qwxnChAhBnb%s`1;jf$Zv7b8sO{RH{cfGZ(1g-s{u(Su~|J2@< zFP*TC#qpoHbh587QY99=y-esdXAyM0U&8*(sG)NvVfzomUjwl-l8Ji9}te& zk#+uye`b=C^>?_U=#H5@Yq_{XiM;Qh8qrb7Rr+$vR~Q(x1XcI6FjBO!;fXnWFqvyI z)q29vGl>v7#h9)qK7wO~mzb%`FY;Iri%QS{>aL%O-XU^TT05*O*v^DVbv z>c1td-44Ew?z9~jbm6{kPM+{}=zvBa6_9AHN$MTkp`@oD+s}Q)Cmue6Wl`(pnBG;f z$vP0;OtxVCu!?f#|3J-iG3>-r{_Z}hFT`Htn#?U-a`3wY?_UjPX+{n7;lge-X+sB3 zJI<4Lk+iqy3#+sSp*8O@cMrSUdbV$Upe)&(+lPIZ%<)&_f6t}1JzlDrX}+vEmx++2t@lVmhn$$spG=<)G1Ps`yv+G6nvN1BbppVFSPGImm2V&-Q_P zU8HS(?S&gRzd^^bI&`kS9A4jB#ol=SqYm{MSaz*h49L4mig%+?P|JmP{9U&5>niY7 z?#mY1XVHNr6`(v`RlfUWGC3}Zfn{)} z@|^ebjBzH4lm?+yZ=dB@L5ABH#66E^&U~glz1UCC2^yfuZ7<~_hh%^8q&B? zA8~NgSNWn+{`@Se#EQ?}f?XkJ)xJpq@B0SKZ*2zs@N~k6%6`xR)v46C3zV$hz@Fc& zqdgb-j*q`1?rqeeQL$E-C!5Z!!wt>`+XKxFvTuJ)d@HzJiShE-2J*o086pKG3;H5;tzpkYMF=sIx1DO5#k^@7DO_ zwZMiQ;+)}XzN3_G%b(b}N-I3M2J_TF@UZAg*)IQD*#%l$$6HYtjJ*bW!J)U>bm#IK zi0Ko@8egSTAGdOlyS8Ed9@LPJ*-e->LlZr|R?@W>8bZp*cy^o5!|pTM3rh-Y(R=~t z+G%EEbaPJ5g>yMnAdE++M?YZ}pGj7(T?4Dq9oc7>4070A4n0Ox$w$AiRQMVG@o(vb zve5rS#(~;G;Tm`LnSZ_sTY1*(WiZ~c)1{07KR~@x5BAMlU8;%@F?o|J_$zYAZNhk* zd&wT(@a$pxf@ru=uEC^IMh||}L)NXypuJ6#<~qNWzjs^9%=p~vyTDI);2sMN(@g10 zINwK{c*pK})sS2M1Ds_M&ARjR>dlB~OmokIG*3EDBU-hr zOn%JqpZJ!4c4piCg!lPN@ahah&Z5`DGvBOO>2ls{oTM)d&r5_6kN91F{w)}CG>OT% z_HMK+4$GD&vuKrHbZGoIG@GS>VVAUMRdzR65E05OJe4HJsRb}WH&QH~=PG^w=qD6! zd5Bw5Y{@#(8p}&m+52c0DgKhaP@hl*T0FxQU2_XA#Vuj8$JdhK$Q}5;I*k2%<}68R z`_a0)2Py_@QIuadXz6wRJxxvOZ}tS5Qr5|rHgr>HS_VVqQA_4lXG;lMwwMu+C0g;{ z|6RSIaI(M=UApQ~eOdwZIy{0oaSv^u348HUVzH>-`zG~x!uhd3o1o5*_uX&shexYz zncekl`f%n56j^D(or&5M=x>dly3tIvxq+^3smI19J9c)Ei)8e|P$+6Y2sdy};79)l z;Jm#ni;OU#_X|_umGysq%7+v*d6p--^zguD&VLBM2~g71C>q#Yp@CNpLVndmSd?Nw zJN+E6b0>R7+#5V2-dQMLw1;yHwQ0XzMXP_tVoMDL*rjp)=Tes3!1bAXgV65hCTMu2 zL3n%(*v*;Bv_@vosEAtVGjFO`dnlEfGWWsX<-fqFgFYRPvcm|yI`JaUhV(k+EKE}_ zgS7cN^u4J9KG?5j3F!?qaBLP{pU@=koyuq9UgNQv`&6Ir(4;msYoUcXIgT@+npf0A znzovJpKUUQYVthR25;=1rX-aOZ6gfs5F*ayIz!THXQ5=w8m#3V7GuxUfnRr1cCs_) zI;z&N3Do7$_#mJG!|_pFCWI{-Hl{+BOq9aj6+P%`Ow4hjJG8pj!O7s{#J;6Ppy0G*u=FQxmt5bB5qSMx4Sdu=btmZxM+mc|%Vi)#(|8)vH)=PcUS;b=o2VJ82(Sr54YBV)Ch?Ts5WWTH3zs~iLS`lwNciYJH;>)Dg6 zI$FyfL;D@xY!7FXCUmt$|D+kr*G*ZPJXc9b&DRpIo^p{K9NGw9J4fT{v-*_(v=D0B z8L*4xjJnSc!!-+^$j^B3dER8R-09FDmcn}g@3LT6_k={J`!cEHoN~~6`W^Q0{&$-- zwzxQ>H?ujZE**KJCfNPCEnnTT{$?G+vNGIim)nm!B8J zdT5iwf=HNgES5FI@jjhNH4sx{$Zqx4lx~}pg4JnLjvh3pGZ#8x(8O%fnRveSma{OZ z!WK`)DNEO{U&p(Bujfn_a%j=($v9{Z&*wMkl8@m=XzA}ROHL!3&ehOv#xME7C+3P} zaVqlIE5>X^{cjqetlR3DG_2*G)p}>)mRSg@ztE=FfB77AqC2~ElWR2}B>d>4261yQ z)A6svaGbI^25{by@u>gc))93Uk)1})@@inqhQR23nj|EZ%H<)P{m9?Zo{=a74T*&& zV-xO7H^IP$5~exSk;eGwb+J&`ppC)rQ^exwd_M@;h^*u!D@-shQ8&B)6XEkOGwDtFWcxwZ~~=+BjSdY?d~Q^?Y8U zX8t?7FU9G(hU9*v4c10mvk`orUsqxzjQW@eN-;cZrd80&E(jEUQRukcn7uZcWyPkG zmD~+a$#%jD-rZm}Kn^XunjFr^s_F3s=9F&`hxzgMV1OX3JO2=M{LN`jpao{WXb?|u zeP(N;k#IMy3VP@9F1GjrXtY|w-j>!-_=E(^7Q@)Nw;6OluQN*OBJ3C{BiE$@6wU_r zLPJfmvHuAN4cEz2jJhedd=7yx%@!;&yox5>t-+|~75X6!WF!mnL zOWv}<(Wj!=L#`8^ov$kFS&1G z`5A9cr4c(jVZ&+%Tz=MoVz|e4psF&<-I76Fo}Ox*?XUIWeM#=^v8u_Q3^+OsDx4 z%@A^Iig>z!k%#RiNGMT8yYKp>b=nd8pZ+aop5Xhw{v8EXc^U7p(V@}-HQ+aXHG};P zbkZ~jHRd&mLp-u*>Do}V+n)oQGI$S2l)#`TU%D>;Ub-~ugCGi8F*2ztq2`* zUOvYznsM(wE$^@k{1z36UmvB@>+#KyJT3tq+}EVF^}pqJd6$RZVl`>fSu^3I=V|#_ zXIIIlu%qy2*H5g^aiAx>Tf5hKC05k(%m>wDZDIq&f{g6Co`vjg32f8L8hUVaF1l?W z$)fmuHtwS`-s_bIe*AeJ-Owm+>HZt_&qeyXP7quKYy88x+@m(>qSb#B*NXW|rgFo!{h6Dy~w^m`3N3kP03X~3;b3X zvVM=!XknonzQaIR#JOGyzur(?7tNM%Ht)0QcQ9p)H#4^7-o+4GocnAV+bAeYX50@s zr&&uJ!0&E>$;QGg|7aXy%kzvAir`O*J{$NXhk`oKz~h<^CezL@iEurM->nk#=$efKic|Wqa=tJ4a79CC@kVa5bd_xFOoR|kLm?)> zmC|z>pi6U;_1EPcrrh)q>XUwO$^&MGM$7AO>nTtkahp_hQ=%IfXjb1 z;MHtKD%xEzGdf%BbA_|`#&;A>$m~#Sn6gwgOo66tuIKb4?k%4+mCqjKusDV9SgSX~ z6!Q)&?o}%3>}rGqlPcsLH`ypu9~;Q?`kJ#RFKp<+bx%yXJz4Dhp6i60I|>KgL(o4( zi~20AfE#~2SQiZqNgR3`m#k5PP1i1w>DbY@e61N;E#W#w`WDD|p~}>3(y5;NovIp! zfZ+yB8Xxhyb)NV7%YRRmK7vYQEbMbLrMNmXG<^JywP~!Tu5X^>1K((N(4A`t+W(MM zJ7d2WTC`o~JmmO>vofxW_Ug0(?*xmYCub{7DEtfX<0Hh*(<7@7>M(Ms4ZHA^dp7EO z3rAkRhXI8$YP(h!L!PW-)(abG=&2Ii{K9~HW?ZCiasM!F{xHlRq)jmf$tVYc3;3}P3(MOQ4T#7+Q3~BXNL zOV)K!N)z4QSOqKP8^j@9xc}iqAEDj-hxk=hpDs5V;vM^P(S_?aYsZ@k;oqx3ew2G7 zT_3@N=Edy0OD#=#u^(Sq%wQvUH}1i+NjR^+2e#Y7&v~05SaB2BVO=$;xEJr7a#<(u z@}#>WZtW1bc;1SgS;jkpd;h_5$5>{wma~I?nhFPaui_@2PyC=(1Q!g3G5f6z)Fmbn z^Plk@t5PnRh`wBxu7%(nHTtu+4`|w%v&DIzNJGCE)@M3HBIk|YSY?AfN;j~ol6tC( zP!a-m*s-1boHzPtDp(vFgw2&)2Wx%?yZUrvHv&|oMV(LLwKL)VQn&Loz|a+opIM=; zl>u#eHw=8YD>0YTB9(bx1@&vQ!ItX=HeDSs$lrz;B)Uksr`&`&H}=2;&e;5uQ42*K zuCl&7BfsP3J17{NAhv&=O^Q3S@I8OGdJf}z$=RD**#%dZ@Z5@z8V*`MMNCm}jS;WG zsjVt_m~-dWUv|Rolk3D%u75UOaTA<3l);BXGFn_()0%;5-=>j{e-`nJL9_ThG>e91 zaIV^i92ojehYnW8z$cUbEbMDKUEijL1un|+5UwNj&PjqHKfLf$ueP+?tqUe3&dVKN z>>};@;wIQVU4y~x4e3#U61om*%ldKORQ#(ZoHp+am`>ADEPZ~y)ej#xM31ISj)Txp z5?#D9Nb@$=uCo(h=5$ROP^1EMV=S8y!LturErgY$Ps=CrXLVTD&cfLnKe2abN9yR= zhVPV=SYLjh-6U(~e*Ojs;yi~f3ogK_*Lzs(q#BCMU4*7RN3!4m?(rU@icNf{RrhVXs*3Z-V0#cjoZ z(J~q(8AK~F`0~&3a0a?yEY;b8BHC^f2 z>ZK`)Qm5wY0dV2v29}&!OSZFqz~vGzmUmH`LhjgMn^Dtv?owIWG)qm$>MRqN@jd4L zwrz#0VbQqwkRc^%zJ{DWZP=!yY}y|?3k$Leo6)eLt#Ho8Pn7Zp6@oh?8TEIo zg?^FU*kHbEI575Z>pXA8`^2a9or!63TQnMCNO#6^77J&{f9G8`Woy-Nz`LQa<*p{r z{i(u*n`>DU*FbKY1_-M!#=@j^rex5@0tZfh&)jcR)1z-MaBzocc2D5m>6cCT)W8MH zhV#yjz9~>%G>@(R*hpWxuSUmgQPl5$p4xt|hd9oQobyAE-aE?RzYjKS1ossTP!13V z_WA%_YGo8G=;7l|>zPGb1Ihlr#Xt>1HigfzowS;fts92^v$ZKYGzFr2gs_~+Dw1Dh zB+l7d=U>`4omAWM{0Gm^)LIx5bJPd*_$G09cUMW)DL|NVXekS6zXl{V8*WnQ^<-VgI8{1+_S5)Xp7b)0~cSsGYhCOB4^n2Fh zRt+a&lnGrZ%m(HkD;~Wok;gg#Pl)$nloMwxx8=Que!$kBzDjy?(?I1)SGhE^yCNfN z7>rzM#fWF1vdkLsAD7mF;c8Xd;v58La@(>V=^v@*ov)Bp*8$iyE&9684i|rnWEbbv(?BB?;cB=Y zi`&gL##QD5R1ZSWzdTcO=p{^a?aJC%sz_5(Ph;WgaQ{ZLRC-h4iQzpRaHg#RdHx;; z#fO#H++P<-e38a|N~547XHgDc;*18f?O4%qp6_;Z7ruSl1Kp2nQ^Xyfm(kB=TRC6o z@7z!DR4YNWvQ4F@6;pBK_^n{Li*u`@VqnLYX{?lIQLX05F!;_CaopxyGQUCabcz!8 zi!!B%gYLNgjxwXuJa^XBU4Y~=I6Fi}iL?H+vM49C<$seM5=z)CCUe$J@!OfW>c4E* zc9-{L<;THJ_rC0P#|+YaEW?S@l;y5rS7}@Hb(otGfM2bYq%X_c3Ui(Yiw0c7$(-sg zEaP6`Bl!m8s;`3kblS4Z{P~x^Q5I%y<@Z=gk8Gdq1TP~=^l;Ch2~TC%U6BBzKk__9 zl@5INp1{J7s7YlvtOS2{TJGJ=Razvu3-fgu^drMot$s7ty$9KG4@1!Q+&$c*GF)FpICEnwrt$Z3KY2RrU(}Ixd#NrxQfxv0 z!A?+EWu!=a6e@q3@5Qr+$q*bdwJ++p1 z>DGhlMK7j1K$~#B1BO;iWxG2mOGCS82m{*7#1S_+OW};U;JYUplcw_d?QIDxc5K52 zbjzmj{`0Wo$O3s{fT6;6M!a09dJsD|E}inb$+Z9-c{C56#AcF*caH!H~9{jE8jv8thXe_pV=* z;TMNt5V%{D)*R4=mVA>3p8mYtxH2>G0epgx%Sv zBAr*?f=-UV{Z-nf(y#_?Y#h`D%laA7mS8LR2>(PQPghAe*I#haTZW-V`lRP(iu+}j z><7;j>kqdS>?4lAG!4$+TKlZE%X?+BKGg+X1MTw#;@w^;G%LjuCv=GA_iHVRF&+(t z)uD_AG}D_BP3)4mK@1IcmCk+YFZfP)gcZAt$wS`?r{&d%=Kpc-*=$Q;{hDfscFcO+=Ovtmzz%&2L$Encfm5h;#$o&2;Eyu+NZnsbudc)o*L9L)meHd4^=B))Gc z5vS+#{;c4BIIgM=!ukF8=;aBpe7h~v=zW=rO+{L*VKMYD?aJ&Ys7N!V^SIS?uK(PC^Q3ma8@4dygI8M7 z*<;IKyrjeWE>e&~Od;sX=EC77Lpr#@4dsIznbkqQLqFS9_^O@&1Kt=?PZyrk*-UJ9 zIQNdaD^P#%XrKTs@Q$u{0-qz3U84%1g+`i-1Pm^!~z zlaJ?~lWlSF@S$T6>*jKWJTDpGQ7097$L`7WUq&|Ez3z=~=POB93d{x5ogt#lW8M}1 zv8#~Tb1j;b8_@b-wbmK_7|()D9E16t%p8#hj(plkbnd8bO~4 zJ=soOSLt!PAR+m-HM-5>ew9x~_%L!3%jNg_HDPtQc6oem?}a=wvQSM}QLq(%bIomD zm+P?0-kp^vr_!eQUbv^nEBV+nMv6}-X0^`nmMdK;>xLKfk{*fw@%cR4DM*MK+MlyY zb?LNd+^XAbTdpB}@cfM~eaqzYxo#u-q$cz`>?8bGsYedOvO(QM#yrE)NPDDjYo_(e zKXpot8v&DMM6%u8YiX#r8m1(8u}uX!G;w$b+;l38wc|ZdG7Bx?MsJyTEzd==aI_Mf zE=Qxr0Ry`A=skR0Xvl8=QkU!&U&1AOO+XtA6jpQh%6G;OWJkj)X#YEZoLG5?W00n3jwzg*crO@ek*OzpR{#!&k|{ z{*e}m7j{7Isu=b|CykQ4^-$}F0b9rQRh*)aeYzUq@A++MP<^-7tkV;|CvEe)tMKe3 zpP5FfNSl7&$A#s&IVPQRDY0NV4w_a8VA+K4Bri#Y!wao@Ln&uw5Mf(8w+N3j>=NLTMXu|tMOmLv;QH%MtG@HSKK(fE%~Xtz+e{@ z7S)%}6+=RVF0+>5wy-wz;Hf2M-LYY|oA~|ihP7~V;}Q6HozH9sU$^oKGV2Zm$m5n;YncsGL$KqHBrqteXP{tI{bLwT?k6Z3MQ@ z2}K`0+SKI(#7`W_Y$i#hZx)3nnHR*`iPy=_B?Lcv*Mi)c??ZiOK+HWm#^NtgNcY>& zP@n{%eK;G(!wD-gBU#^-f2n?ey0FaBj{W0j`zXB4^N@gJpp_q|GH9BMVN15cQ~rI|kKPG8 zmQG=XMQL>Oy%E26go<-6UL-5`TkuBu4v(k1(k`n3cyF9Bv*R9^#S=V*-GSvGj^;fn zTt877xq>~p(m+PL@8A)iX3=C$7Mirh6aE zJ)How}M zV=dmGM<$8;LGhWyq3b@A{(3*uFBZY~ng&U)%%O!*aGLjq-&V5|Ru4ZTZy(?)wfpEP zEKR6DpAH@9U?;2A^PJ7&zOQ#&A70Z4&bwt))!{1ic%Q%`qie|ebu=zKIg(xaDx>?$ ztl?6cFRS3(jK6n7gca&G_|{B^ww^M2+xUh7W%yXM2nldh-{_Tl!o3Jh!KdiQX`5LcZv3<|?U)Awto% z{@5^+>-O~~sPeZLGkeGLQ2O;4Kku77jC(1+j@J|xN0G<)}<8A8VPwhljU+9=14bf;lJ%NF_wR( z8;;rty7!|op7W0W6@6|!!+nz_8XXdahHYQS?>HDLzAffics`$NZ>^xMVgN?AJQ1G9EQ-Z4W#;%v{8=7im> zGuhGZnPl*JG4|k+^46VNv^ppr?gz!NpYzhFa+?wM4l?9^uoUW3d=o6(72tcMl9YF~ z5j=GFuw^e?B;5s`LPyaK&&H}qT}>Zh);KZ8HjMYA%zlrrnns~2(twFSKht&wstCq5O-VFiL+T>&u^QL;h@cT;qZd+REs8WER+2%w@~EHPVCT z&6vJa6w|NVpoPp1)2o$HpJz)C>GK?=2It4>yGpg`Awq{AA7B~NCjCGYG`X;W9rA7@ zoo(er>JwPBLoM+b<8c zpdp-Tyi}pa)MvX&N9_g(i<6h3k7Pg}j#*%pjx}?;%>DK;Hp0v+M_~1ML+a{T3O3)8 zS^q(0Hftr!Cb*Kj^$kI+`;*wKn68gRrAZC7j%PjBQMPr?8p zw)7E>-DOHP&up>tgg>GdXQ?Sg+X(-@RYR93ZL)k;3?q4d$Mb6qMU|bzIsIlZjrwGI zvAq{QGspz{qgv!05ejQFFw`&MTJv zPU3p|KU-nF#64$|b?M!gPq58*1WVm-MB>7Hpaf+x=-@Rf*f9uq$g1HJ?`ZpRHyqyd zv1MT^zEDgL8Jf0pg>S352X9LUtTTvW_c?#23;(_wDciAu2|PdY!&Vr$d@v3?qD#{U ze*XWg-c?1~ubPHl`g8qNDza$7p%C1b?Sh%#4QTVWB`|S?GUr_J9-l`~;K=atV7ADR zvUn>0w5B5)#WM~wo_GmgW+uSm+4>Z3p@~krM5ZvQrM$v^UVEIOWCX~4K&xZp!GagOUR_kq?I^eeGW+6D{?910DM{;$mXi6O3BA2 z;p3@(@-`V4sD9ynm^Hu~^;4TEy2+~5GkL0kXX|Xd1;@&@cp}A+{(=k_jWJ{KoC{&! zLnf^Fb_Uw|$P{Ca=E(J*M6zv`mgK(oJnZdLB)W_(rH^p|_;aNKdL7rGF$3*DQyjxQ zcB@HIlD+Vx#~Hc8%T<~>k!OIeSK!bvGn#PJfag+wiHo>bYRq_{EN3Zp?RJc{?}4*9Yjo2QCphQr$IKjErG=q`1dFaV*zJ-o z=`S`%v)`dik*_K_%Ia~Q->%#;{{4!bAQMd0c^AtQ&b3&29S->LzK_&&8d4UB?DHFW zrp#DzlXKEqm}5G(f6{SheQfbeD%@SAkMjo!W8U}2TT68)+|~@&`S`L(UkxefViR_k zm&xbwcR^mUOc+t?BV<{dP{_u+@GIGX8Sc{{%hc&G!YGQpvZ$jw(MH&^S1n$xOYUuB6v<*tF5lE`=m_#dy$`q>UP4|r~G}Er%!edzru!x25fO=2JJIjj!{?g~k; z)EF1YjCC(km|r0reWZYn->b;e(?oDmPGIKc{F&GB7WUNHq0GLS8*U_ab8i(M>)%NUS*Bm;;J;3WHHp+X4{2}|*X2O9|54NbCtEAhQEmebDY#AlG)8{q=ChiNPi5O?;;oJ$4_lxTJPcbjeGmgd{V&Xw*%O; z$r7!V#^HIltNtDG@@VOqPB`d!Z|paf_kEOj!s{{3q9fNWzY0Tyy$_aQ&ujV=?rMz& zovqlMeSH6(VlTKpKLYpBfJSWm4qNYCV7;!J(1QsNT6vNSzFnYO*#h3~9|IRnwMaQ} zE-=+lX7nI~f~J>%=^!t$av|Rnr4A8hdOk+Sqz-gpi5E`VtIei!e~7HmUTE)L!+GMo zi{bcZFpXHsw)0Gcp*inCj-A13{Zr`7iavO0T_!BLqs4cH5zyWM*bbXA+B?_~&+nQd z*Z%9JFfNcGq-5SY_kC}t9=qc9&Kb687Zx8nS822#T$-sV{!u=P7i4^c{G}h#F!DCYl z$;o6bMEp=@))5N2KD`2LyUqpumxdJcyc@1M?Z`gx_bGMnDSVDj0EcOYw6|Fs)h813 z9ac+Dv+v;?ww!&d<2~k6)}ZIPIC#PN82ai5U}K+Ytl@Mc`9(}b@!t{go$7fqh$@1l zZC}9XTwA)O)(bO7sIsXA+;=^^r|^W8gEwbU7DuaKOCR@$1inj+c!buzO6*}x7TpZo z(CUYmmC0yY*x}Y$eRsZ!6ef`i zr?A~}9UcxfB$t2MxUqv7o67TXUdcMbf85Km@|%`oW~JE5B{&@Xi%ek)&b@PrEj#yx zXZ?b4#9s!!8~Gi?vICeak7gCz2m5EKqoCq^M!tL^_rq8A6gGGKh38J0lW&y~CUmb7 z9k`|^<>(0a>KnnsLYwOME5PyiUgo7!OQpYJ@YujnET=-EmoGYEw}X#iWvCXZoO6Zm z89kW;KNA!Wh6qbW+TgYVT{@9qiMPg2VYMYHlI7n9G#|4wcky}`$tP1s*z6F43H(gB ze)$$$ukXzI`nI^@LaY@OkKWfk=Dk_onG?Blo=y}xpZFwh|gb5wMx zF4F=9dp{Opry<>Gr!2Ib?ftpu^S{2j!ViVA8`-ISwN!k=9J{G{vn#x>O6uMj_qU(PzH2E<4(IiRFOf3Q?V*bV(GG&4 z_C`EE(1ZdjYN7pFQ#PFY@Xz_=;Fm6@P$3y8K5Cq7_0QxP{Gw4|!_Y7GFl#u-`{-+Q zQCH^%+)mY_f~qb!>Usd{6r?VF9$_Rb$;_7rjOP13bw|Oi%uvv@F`>jGwQxY|ojAeH zMS8Td443k*$u0|JG>Ugz77dDJ%M4PY0hzOp zjUugLVt02UBB+>%-Po;^A|Us$uN{c3p9PAI3X&@IZRZcnGY{N3cb~P_dRJdlQF$>F z3)X*Ni?-fnng9Jlvmk4}V8u4kr-sgil|Folt0TDEX~<`!=b)&`&Ed4muDtsVdV3Cr zktW6%TXm56G`I+Z{+H14S_|0xqDnb*)^8jTWycjAJ;ZhL_Nblo;Vdx_;(r=p-5FiD zPwzzg5FNQV=PgVQ)@BPmGRc>+0w&CNfZ7%2nACWbdDrQR&|4YUX|@9t4G(8oOc!r+ zH@4bjxsdE=cf2r+H(yFK70vJ!^PIs+{hheFpaP>ZzeCd%i!or`&`=d>F4-SIiRP z4RB_H9RKVZcjGD=YxFM1B#G&m183MN{#w1FO5I zGoP+Txhc~0E`IpNX5Bm?>QbDr_2bWM!QT>T=G`-Bx4buTo7b_qwt6@{e4dISX%Lfv zI*Ko>lTl}B37zv#`i67k8IR!hMH75B&H*0m{2`s889slQGdEvS$sW8iz$LL?Rp-3_ z!%EamI0r+wP7vu~S=eICAXpQ6mEGN>kA{O6vb)|O+Vg98;ZGf#?(DCupVKw(@a73j z=S)lS>)J0&T&u%lR;?EoX`Y$;&Y5>JYYp)m=zrbjhw7Yv)TAEIw9J4Zb%oM{d%37} zY&cw>Rl_27=%Yr(B6f%FO_M%k;76|#)j6L^OyhnDZB!ok_s)N?`4Iy?ad1mfLU)AM zFP!<8_rWl@sWH|y`^ienJ;cHV8uHwXEO`5Pn!o!R;)0$S2@_v;fEO87cxCNs*0NAr z#7Cv0((fzN@*U2sADE$zmN#6#?Icp^I}geB;~$Q1XH9Yxck}f}uccb30zh$48r>Px& z31eWpMO#=ExXI(*`tf;nCCqIJam5ExR{Fs*v8i`G#-u%k7U$H2+3!r$DUF5Ut#g^3 z!T_uGC9`qudkc>u4Y}+6X#koM0hhTxh$x)>YN`mMj`i(?MD8VGU9kP$5RD%fFJ%yXKB}& z)Xs!|bgpMj(+zRh%NvX>+9kgCtilP2o8aKyL85P)%UHAD1$2#Wve*6ev2m3ri&Cdv z>~;#daZxxwu(>(B8bx`i=1o*Lxi_wV*!V<9Av4 zqxRy#C+eej3WXUX-YC1Ywai=HI$q_IG;%D(`UOp4gwr-LiRP%1=y0A95&$E~uRiQk zGiZIlUp%F~WQ#2teA&{k%GEUIPZB2lK$s72H^Ks+4tl`qTAPR#{ueMIvp?MW(w+Ty zV}xzqN3$OOYlU*%zYec&?0J%on100w=aqDT5SK}!%uih&`Ph{Af2l7yzM{S!qt?7v zhdB6*rf9IEoVC?77dK|>$Rnc!>|SBb?oTw!TU>ZTnRz%^L>HD~3(X-Ax^$nIZ=Qxl zYl-0&ObkgnC%xP|LS}IfabU2vd}q8Be_Ve{=`)_R+^wzo25WOZ(ZdSeEdH{v&?3p- zlXxamN`bFUWtMrwm1>o&n&)k=R^qIgBOttWZ_&2PI}E0*(1;^{*sam!Xtdmh53buL zKL2);%Z$45|3Vz0lJ=?_QeVMLe<|ltAoU?8mO?sptWG;)gs0aWVe<~S2<-`(7*o<3 z3dp}`;YV7Hb5kDf=ONTO(hiZbY%5*|f@!D`E_BsbX*K7L=*o7*AK+k?4!cm4f_2xI zf`*M9XlGjC?{{Ze4^u;N#GI?~f9{%!hskr4e4st-eqe~n zcfDC-Xt^|LnnIp(Gn{u{yb!LPGr|1Z4iFjKRP>|SZ*ZeCFZVjg{v0(z82E$LJv=Gm z#(H3vm^yasYNOOC`aEu@+*r<>4Xkhsv7l?_v44HsyPjoWX{!=;XF_Lb#tzCv)Q0o4 z6OZ8NOcOjE=Kuxme@JGxX~wH{=IQB`tl2;#TzdaI3$R!u`lOO?+2uSWEt?>m4`t$^ zMFU~)Mr7wn|DV`(F}uAO#4UXT@L6Zf0_m>&vxygcD>U5aq|6-uP;l*R2^NkMBX}%d+-(1Zi>@*TJK&LF?IGrJiO8B?iD{1?!W;jEVt|~94`;-~W#S2T zbR@QI_z_h%_eJ+QEbciKk_%{_ueykaPpVnehidj{w>9SX_lLHr8lvDc?N#HI+;!-8 zrnZTE1xxkep9kJ|LLGKL`U2L6tBLXS`S0oT*Ba%rN9lSv>)~N`rDIP~c1T06r8LqX zgKo-#jsnk~RfnRUf#BLjO${KBk ziI!WnN7{-$l$s4Fz?8xtgsM~)Ugb^*p7n!dHY1@4|+b$D_M`qJ#1GGW9%b5 zRhqnEg0`G^unEsua$Bi3Rw4gq>BhHpGUpI)g^Q~im|AU-6zS?FmvpLxUb|D-gN^!V z`Sb|0PFyeUMO2~k!#HBHk?u$PoeBBBS>TAf%zbz{t{P~^ueRDQ>L{0_wOz^QFK`6s z*XnY?_qVX~V{VSd7&qA=p%Nyn7!3Ot8R3SY6Dm!Caf z^PSH5=;umaVm1JlOfbO15&AG=xR;Jftx>bWnd96bKD$WhJ*vRa zfJ)e_9w!=TA5`mZ!OuG@=ucvR103$Mn#D83;=Xm5vuzj5sg|S_?rFGbr2;(Yz8*7YhBHoc7GCp@O&$Rr&j`~tZJe`v#Q&)=JP=`NC>Y$RFi`B%c8Z*#>KfD$W zj(-htWV8G1-RvNtPb?t$CwX-mjc6(%rqi)5AU9LOy@#ggk9}Frm_L$3xI#Yd70Gwq zUkLdH=6Kh^1;QH~L;?8~M|D>4x&05a4wUs9GPr`B^*Je4eQ?8-KYz0mw<@H%>F3dW zc{uc4y@5@w)<)&26|CsiaA8B<(F3b$S@lA1>DUZ~+C>}prROb09!duy%nWA8VVx!fpSr0jWO@kmf!M)pcgA8micGN+wP z=w^|(^L;H#32vtx-pwb^q1$wJ^`fK58$w-9YVF{m)&*(k8S?PIRdA0%t>G|vo^SWA zU~dA##h49sXseq8WA7A7qk^ws#;Nh}UtSfHI~byIemoo1&_e9*LtdkKf7xa~4fep@ z5Wo0&LMM-S;W_UQKH6f!XTEAFhNZd5-99RKY)}Xk(z7)C@Go}aUVE`{k%sK6L>T8h z-M^H2V~3fKg0*kmpdi!~-ESnY#Fpw}@T@e9x2a=^-osecYIC$7?F%=moW)z3x6P`7 zzcbyzhSAKxrdmUJr<-D7P$jzedf$;q z%9x|#2KPL73U^*AWi$JKVkOUQ@u}zmL(ggpPx1rLZo+xLec##7B7GFE48U#35;3E7 z9Xd684deT(2^LCujle(fyH`7SbX6adwNA3^hrLAia83EevSr}o;IAAogc$7i)nNC# z?y$3fdZG)Qc(6{O)Q|Q@Q~f#j(_I1TwBL!lX$IxRO~j;$l+jSPg~=)3^}RvnWB(m zj??%5RR(e2?J!=eDRg~PDH$b^UgT=Y+wUh9D{&Y1oV&xS6Sj*c_p31M!*=)(I9NEp zbd{rr9fDq)y&=Cf?bML7&LzIWn&z~d7|D(PG>3>)G&ApS2@ab^i}S?&a9W_r|LHcr z=shycnR&a>>#*qQ%B^e0i## z?b$g}Jfb_u#?nYWrY->XQ#Z;adj2!Zlwx!YWh&3EN&w5Rd$c zfthW||8q2u`jFPW*}%kYz6uu|m0ed@;x<7n0m-;D6{m)|U6`6+R1r~)^4Z(!GUS4sx#JPvFeteWTV#_D6;x7CbijS;UXU)f=% z251lVmS${G$gf%s<37C~Lp*hsy;$l5h6}$-jTz+CzukskrtHBt+N}e*y5+79bw~%6e;K#orhD~@}EaqL&yE3pC7JKF={ULs>f*t0(_H-r1-+iXb?RC z+Kv0gZag-``R&)Kyfhu(q*C9d224%YU`HiGtRY>67srdsE&gCk8#CVNUQ4m)I_+ME zw&k@+Auu;zALXf)Y(ks%;^j;Yx#x{*Fw}Rte_2Kb_6!^isqI~0NUkyVw%EXOVjHDT z#_3qmlX|{%hqKvFEO42p5`y--h+N7FU7OQ`7r_p;vU?LOo?{0$zTFm=UsU26=l{S% zZINipC@=7!9%kATuRqEF)#A>wTdOCFDgEoQbI1~Se*B=c`7C9u;4eFr`I)8rIpfjX z2)KCLR1E**CQHkD@Q?Z5*%%E2^e!`kf4rLTpgJ^{3!&p8HIdxgO9U9b*37;HS`6(WQ zGmi{mA~D_z6Z){Y3ByE>Y%N*qXB)mW_@pvuF7XUo^yH@0AKZ%m*Ws_4!lwFiDPae_ zb5~jOkjM2b0rl`~(0$c8?{%XJ%e;4k`i>#%>Brhu`H7=` zbYJc=j2k#QfawCtolS9sjaH*X+9(a#q_sBx-Y+rNlV+ZUo2>b%lk1@TEOB_cJ!gl{ zv={14(@?`?BxFRtQoihFnb&#c7L`8V=43h=UD5=XJ0rzZ@{-*iHH_bO?+1n(jWOh@ zlj@wW&eoRKZPDY}L%%6M^rpOFizeLinGa8xYl@>LyY$Yj@E=$546SaY(w-`^H%L)d#-4L#vR+k7d6M+3FYM9TiceW?}~$v zXbV&?Ay0?Bm3Z!^BmWqC2M#Z=X0Z!R^P=9Ssr31|eadj*-05Icwog2@$UxB2f~jry zGTmk-=w{s&cDC&;Hc~I%d3Ad}-}Scg=}?7SUEY=lPBZ8I7dc|PPNs0Ns#03*LF}oV zdKmO3mCahKhXFpP*@ZLfgx0Dm?0IkwTyE$sxNaIwh|_?jvDaDO%3nD3Vl)27d%IZW zs*qi7_22`m9UoO*=|Akj8|Dpwk#mi3{tQ#qIX_23SKhR+6!a$O zFl%~`5A4$bOBG2l?1Tj-Jio*uBK5_`(lpF{(h<(A3uUb+v;SdEZ&tZxxv(zMlGR(Z z<;L4bu*qJ;2N>lJEei_8tVNZ0{^TFn8yhEn(CncfW6i(MQ@~Z~*-5Z?$S!S~DW=b? z$JKTFp{zzo-NH!2>Dp1H;RKUzeEmuQbC_x;9tA7ptD(cV;gt`pevuAp9&HM4&zFdV zQFZwCjT)c1++0+irB0}w*4(pe1e`H8#vtm3OY9UP)}?C5t9~7ZmtB7Q%M#_914C8k z{En5h+e#Y7J&C~@I?))9pK^lGD0}fQ|C_a-Ex(d-kjRb*vcwVJj}T7iWiP z$g`*1Ql0bXuToBP{RB8me&xC-(!{PLvVmjN#5y@0FZ`zmLw*luE}gBh+m0TvJXRst zL*gNn_u@svchFpFg)O_-!`_a!#LJzP_&4S?G?p$Dx&4SUGfJIb_0fd33}u-?4k_zD%f;9P_?j9Ol{T^-E43WkXf=e6VyCGEKR zoRiAS^A+-q^xiyV=`ZNp#EMuec3@v$BFVJt8E0h6S2#AXuXg%)(h+>=7za4_g|u9s*3fu(jEJgL zmw%kq;jd~p=XS`V|8-MazVO*PK+-YBd;Z6YOxlU1|E1#K$7A4WAf5A5Ec0yMY*#UA zK7CBXOCEZFB_l+SNea1}=}4|KzaJ#7F~%DetwFCT6M7lsU0GwmrB&aQ7szMc>!2-P zqUOt=QO3~b=PTCG+fcmkmyU~0kE0IWJ}fdp4~OTkV-CIIgq;;-b0YL${V{D3NE+;s zo?W2w*hF#Wx|$r+(1e$K(wD0K{_{~&RxURVYGN$V(^3lt`C17#>gK!O=RU06V$Irb zGt1jF?y^d^`7*&6cZ$u->F#BzobKaoKk2~$jlHbZHDi4I*a!BN^b(zdNoxve#@(*m zR>smjB`Br?AGpn&FYoM(J_c5BHRO-vPJWxRVd{LGSsHuot&g`F&a-(l*9+G~x?3Gt z3@2Ok5r-Tz(6W_2%=>babq_7aa}ON&vpw5IE7C5O`}O9|`mJDqKlp1Dzj>&La?Yg0VLVA|Jv?Ci~V zzo-5+>TdX}ZVoSBcNX&-b>yuRE1+b#4x38*wbEnie9s`_uy`BeZrcoYH&jcgA4$Wv zyS>4zZzwYyp^KyKgILJ%<-(NS7ta?)@m%U^+IWjtUY>1KeE2RUw%GD}3$WHcE`6o5 zebzQRZhKAvV1W*TrJe*iSnw7u~b!kzdo|hnHK3)+eX~?uH$oyf^|@5F7bt`b*}! zAXxYw*N}mof`E~~{cD$}5I4B9D))5#vn`H!F@uGtX^Efo9L~}m#k*cz1R>2#F<_=b z#V&}yMf&#Dj=b@|gUoK3336=>n0M@q7@1{(LvMayzdWBv#d}lmfc|*cAG?WdtJlF4 z`wi^$)sZ5}Bn|tA8iL2`PEz@5%1VTc;ukX>L-%+~+;XiwOnOwU>NxxRwIkmwSFxox z^ih-UaR2!51zW1n@sNOdx|2l8`V4$LVG0!8me>@^Kc+-%WtuB`i!PIi%Qx8=6wd9H zbN&4Cj)g5^JLvsBdX@ur>Cg>YU(1x1(K)X_&VxI=Zw)1u!~h?p200%h#H@vM&ab`! ziH7f_dGV>JjGhP&jlQrcs|-=&&K99wrSiV<#hwkU99mBU~+{E59)( z(~`#(wG?r5&hH!Q!L>_5z`58E_1x9qU+!t{W)1mZJY_eoPxnvTdI|qp&wyu5+#u7$ z1ozI_#_qYQiGGx!n@!!vF<~RvQSvX1?b!>syFxgS7x6$wU;g&g4tC6%`n$(8f%t=Y zBKA`SekU&0oEdb^521U|YfbJmTod}&=;QRS>8f*nmv#eA$%=z5kSz65KZ6t1b-^j@ z3)_%qgI?^0U^OuTVU+Qq)rO&YJubR*gaFd%9 zX!4!g+QFb&$_|t6_s>h&N79gs4z7i&_-;y%-Dfazu`X=c(gmIytI2gw6GN8aFw3l084Ge~MMyvA`zN1T+70Tgn=L4p(`4!{1KLN|z2|ul5WRU%pc(c>j)kUHM669X&r{XaGO{_!m^1w?@mb=1?nsN~5yfeZCf#N z*%jPyXFfb$|3#^^w#ti__NX-Z&coBNs=x?ZMvM@fXOaGpHHs%^_k#xFa?eV11;13K zh`OaM7wk3Su5Z67^GGi>q+C+V4!-=@Y!mcyDrCjC4aBvh8MrlZDtw<8zz%-b$8RkY z*}1dvV!M=ztHO;yLBH8wt&A|_wGTwhog@ywRg=Ta?6|3mfmGc7F^T&1f^dKrik6B1S6%zdM+~eBZrn z!ct>&JLU%gdA-C$I@@ChIq(a=ZY%8;E96TKp8WD{bDmRfj=M6o;j#QiYE53*vG+Ck zbWh@XlP{=)MY@VV);YflKTeN<7L)o2yKw55qpZ+{j<=YPV>wnQw&coF+r~i=Oke`T1aTF?AQ6 zGo708=%fgEO&;2rC2yHuZm^KOG-b`4b0BT`u+&i7!|J)!= zSfr3oTp7blofgBue9D&2b^+UJ8_|zE)ouei@$Q<*%s<-{m-WFk0+wzT- z=026gnoBsVVzz3AAEl;;qqMfDeDY68b6$Sj43-CbNrp)Z`J~!do}~T+>PFb%Nu90` zJ5x#TQFXRo-&BQb+Fylf?Iww?QJFYCVlEVtgqPuJfU&V# z+4Tf28Y(i-2 z@u7nT{Nqd(FR91s&Uau;=XX-OpetBixdiS7R5M4?`qoe0&T9L%6rG)9Tp&5XfB7cF z;5EWiq1|BM&()$=>TfjMZq3cK97Qqhrbm`_;?W&KVFH~GKT|c}Ur+1QWg4=k#{-b> zP4|DHk%EhorhuPQEAZ@QfrT~uRJkXO_&mHmmGWN?r?H~7me`(po1wu~jQv4TuUNn(*}z?c>g6vTqHO#F`QH zXjZ!h=6^jXojWOTUuH8H*G&T|{S|nk$yiu%!AhK@8Gc+)e_nXu2m5JgNNgM{7#p=* zWc8@Wtg9t(tB1On8%6A>pE((J!x+1oCiqpIc#3=Y+3q{s8!e9$M|0T_My7wv8Zm>a~ zXVz<_*XC7XrY14Tdt@>D(Lyo`xqw#fyMfi*SYi88U4Agd zfbX$S%sok;-ked%e+T62UIisxIdBXi0}v6@~_!L&|v1Yx?O!Hbl z5h{<37*K`_e#gLM_x&P%>SxUM^@o86$&VC6-u@1LDlX0aE!y&wb1ixJhC9kBtH^Vb z>cwrU%(=do6FUB|fueT5rR0&MCDQYgJvoi_Jg<+A%QM+-iw)v=5%H#~SHbbkeZ=9H zh|O0yfPDb@L&_=a(B2HRi$)V@*AttU3kSFPjNp~A?Kg(&%g2@D3U0bt=j~Q zyLA=qi*%?Hvli}c*I@%Mk%w@n4&SgV2~uvDqj?{h{mIi4q9g?yKl{V0`N3?St{%>t zKa#%x3K62vk>_f8afg^uZ1Zy?)R?Y-?)RRFtrMEpl`vJl?-m8qtUR9y$S#ckmB;PPvTv)Z=qSuek^st&p4a9?N|X zd}I#|^zpx!&M>NTjF`IqFWM$(bJr(kVmJ9!zO`u1bKgY3FuI#e4=iNw8-s*%mW+LH zC8YRd`LD=LMd#Z}n0>4Rm|Qg@F4HtNJE~TCe@G$c?iW*LMyQKVR43cJ}+Tdi|Neq5Sd8qg&FePb*|HkYz+#Nm_-d}NsHPvQ#C+i^d z{6v}JN(tMnb%bqyr?7))fz3Mgftv$d#e;8j&fgfoM||JGwgp+CUvNu^(YYlwDBn6H z{4=p1sGDg7-7#f7K6H~N>}p59BRQKz8cY&HS2bW*mklueQnFMy{3@R9-Wm+^wcxm+ zEBfS)f$Kjk#9JNOgMS&o<7ij$kMBxOZ_o zVmce(-nO|a{+P~O8K=M?xDaNfyqcemfp)g=U@3s`YQ)q|?RY{)pyWaOBVFAfZrwEo zMyH#jUUYLPKVTBt*lv^#{ zv!W;N!d>$suAI35O12j&6FXbxE%Q38I_EW~lw$kU{ov;DZQ|dKa_O(}yk5~CqCZnd z=dm`h@s&~>Or&1CC^K&Q{hM+-?FD@FT5`=XzWiN#6O5>%LiB6{(Q?sc40T=#6RHQW zkcGNf+kHFZQ&x#hcdJnQdocX#^6PA?kB_Z=!M1FyXfRQi?{{g=2OTw#Y{-M{nc0~S zc8!O5OHFX%6&?8JvB}x2BPZ^83E^Q)ShS5<-sLvelw1D>3%em@xM6Y}{OY-1^qcS* zcS}8B)VZ6iIqhZiC;O>52ED_yWsk|NcgH~u)o+1?apAD? zgF1UTf*3XLTsdfYil1Q$`B_iOxGfEWQ5%hLIK6|$yLJ_swK}qSzeb49*I}Qp(*Da@ zpJz!)pb=z-zvf?Kb#rw^@w-%vYU}||FN84bY+Z~^9?#nBCOwn58F8B?@{bi8*?|?5 zBe>BHhO~PjVh6Xt{xlQyUUE*V-9~I)Jx4yn&KZ*>r!Hno1!z^qh+9klqFbsS zU#ep+?&Z6JQ0J_?y z`1!y>b~NUb*aZ0ArE1-|2ye}(G}A6V`&zuX1`|{;yUWK zD!$xOG+lEMM_h1#P08BKuEYpGEuv@g-WoBo{x^==Y{%PfbQEvi)4i{W4?lT66dIlx z^xmi;#}q%OeB2EGu=3Nm;n;L|e6l%&jCRI?ds$4m(n?qm?Sz#b^g08l=MStf?+`8x+m<22n9jB6C3k>;# z6is-xoBHX_=dt)5Q^etF;)Ydkf~N%srJ)nD@SS-pxa(5K0-sr6yWIisJV;$MP!8zz zo)Dfr^e4O1*$`v5*g|u+XfcDl0Y?6YJj<*-q>MJkTkEf}_38bEW`>N0mcyaxRwJcP zQ7X2GZVK0yE8zm=q0qh~-=GyF^&)+yZAu8AIxz-ftj(~1I2G}xwqibcsODEV@~az9 zv2)crc`h9am1%2Y#9C2?(SuLGgm1@0Ynko^PTk>k>}K|BqAvc-nZ|-I3>8IbTJp~h zo%wElO8MVjnj5`Bx#p#EFm!Xl@wT1e)O#)Ql4k50y;j`RsFAfTGR6V>zp;q3d&Tyo zDy&I84F?_%7Ui$6pxfes5cB*V`!Z7>)dOa!mNarhf(cw{>N|k}dNNy*aM( z)vP^RilRH9ZX#@|x~Gd~QHIq}((oz0L@3{IL{%Cv@Z+XWoM2+9qt6 zx>;VF$1T;_zVB=q?$BBbKAZQ8E#E%l-W=*U^}NM)4bVsb*lw!sCox=Gp1OjvEvN4& zSD#YIHKjg0ez*lU{QC?0j{5>x0hh(4(Ztd6G35E@(pZ;kdKl^`sq#?wmR8~TE9>CW zj6R}{W=>NdchH;if>BEc4nF2Wdf*O`LC;SHJwIwMT7hW?O?eyT(XM~U%b7|3)rygZ z+*68#&_okl-th+8xlbX^1pf0c^#cvLT)8CKE-#_~YURH^Zuf;Xc(_Qx9|U>|BwwGh zK7=2A8U(d8r#<(vhty47g=v9~th@}pTu!OoK zEpaRF0xi!vieu!(veNbAo3|&kzBF@2Z!uAw^IBz=XkA#tj5a@$))rsHx#MEM%V8@k z%-2QBiThN#jgxOZ>gSAs{?;+lK1m@bx0%XE);nmi?E6z=Y%=^P>zC*x1{hw%sL@VvEKHmIAU$?^Sr7Qxdad|Y z{Tn^zHs$%`+gwKsr7MU0`1}u{u-c*Yq9J4dSD>ag!{5Q}EPm)a4;BE1d*l*PZmikFgIE~G~{kL1eTj!Ci`9@2e@jehN_q&N&nzwgZhV%a-ce2iUO)&Kw z`C4=D2;XOw2XgH^$6}Yv+4DHvpgaOBF#pM**jm9|hyLgJZsp;jVzy6@wy#|eS#wXps zQoq@Ii2^CuDX|~?Y?;IceAmUyu=y%|zSk8k`C)KZ{%qwbWi0LS^9#fI5R(eHwa*#{ zcXok_gi@)wAivWlXWk{Kk-fZVjB^(KWJP=Sis4C>s1tt<+^q(S$c{PK?^`77X?d58 zrmR6?%tEF+)K6TUsgNyuPvtQ)TfiXF=r;D~0I@&E2#5FTa{vBjJby!C?ukc~_c`Ru zLzl0I^HqBIX7MNXCCW|gxu+v<>n&hkh6}UYWSN&&cUpDk+kPrV*XT$nG21T2lfE%< z^i-aAvp?~6jB#QQ>WbOT#5Q7N-3YVd3woC*8=T3{`OBF*?e^s@N^H>dcq7Z4WhG`b zCC-1sPiQE~VSd+iP@~O0w&_i**h8Gj!?Q=g{RLfwBFhB*+V_TiZ>Ec_XVv6h7h3Yd z)dtc;`pgSo{J48`JhV$S!Y9O#O!#RclBVd&e~XGCJKBa-zA?+o+nle|92zPrdY0kj z&g)@O)P4~-<`?#OIt0$neZa>jk9g&-uMW7jGdw4JIM?oshim((Jv* zndhx^hk?W@^sfHS%%{y0=ML6m%U|g*`c|Igxcmz3jEGUNhtB+&1{nHkF)K*57alRh z#27x6XYTpLn&}zhj05ddzRC$b{^B=HL+)i|F08N9oVm@Jw;44M8vf|u8mD4bVAfYS z573ZPKU{{rgMRyK-#d%%y7h(I8f~B*&DbWb)~Fa|eJ|4-a(XK19^}c(A&yqJF3`-& zQC!d>j_Y+l9-5iVp0zN?;CN%0IqQOOQCJ~_|6z3{&m`lrOzadB3j^8(PZRydV+>G%|$|FK5506*wzTqlLsxygzvemuUhnk5l4 zYCLsoZaYMI&){n8!wO*Jw8`R5btcxv#lrdbGE++?-{z8oY&LZV$9C70t-efyo41!M zZ`o4ER)#;EvHmIc{{DrF%51rw)kbl$nlk=e$=|$mftgW;nE6K^#$`kZqsV#;c>MzE zbKgk;+NoIP90NmazOdLiv}^lyg6VZ~5_=b9pntV1$mLpW1ZBq>hx7%XCkf)X{~yG) z&AGREE3uf~DQTUR+|W4;s_UpzZ@U5f%ftE-e^Rt9RL%C{#|3P2F`7E%sdr(6H6|yf zvT&uYxc(>uwF2G1<@!h#`^FrNp9I3kViyr=ppf@m7|4gL-pOV?Ak8+)1gusjNk7P! znCD@}y}oKf>^b7aMcibwLMDrVKlQl$#tz8emnJXVHdu%%VAXxUUdCbk6smR|~T(HAM4;bf$Tk@nvJ%!(}aF?B;%t z8O`V~!YKP6GG;H7D*TmOo}}W3*w&D?Qwgn}G$1eWRO#~#lgKuk`l9OTu8(rV=<5}%&xkKltnWE2KQ{m#zE5NolXY;u z*Ai9?Lqyp*E%{HdFQ0z&l=Ag<%Bw~V;*DMvU~O%JgX>zr{ETAhU$;Vpvn!u@vXM<8 z{?EGm73|{jeL@~ojd#P+Amdu3DDIwxBWs4iQm5N2;Fv!0W-%;=m;>i&KV|%PIzM}= z1x%rxX1~@RF!<>hVgFTK&gx^qvo9y+wxQ2|=H$wC53DC0Odro4_{IwNxQVaFb>#i! zGMr9!Ve3{})ix?YOi6;bfkko-*h%d_13P<75f+EIp~Pc{Lb+AlK9e&N0mqadOC1Gf9PDb{8N zz}VUVVbDrjUen)=zrs68^_>cNXO)sGw_EUwOKfpSMH7{7vuX}8e>$4+_ZsQ!)=BDJ z61SMgQJJqcdl?JEWrxXQyj>?4nmFBmkfz}6}5e5qomXiFZ#qdJ55un;G3 zf21Lgk5%VpDS0{S8{Fg(z0G)p;Se~lVS**Q^Vu1NLTn)~)6+>2;4;5lDKBlBH}+DZ za=O+C^*2Fv-#)xG zl&^_47*qlN4xPChumS~CF+!p?cvwROfsJ%}d{!&*G*fOQ21>1rERK3*CD;3ezIuu9q@y^^JXzcXx5 zq?70wk%5LOZQ=SSE%udur+SG25I-V8sL%L~Kb|_MW_$HY;&_|_er04B6q^{~=42z7 z)WK7vPt%e!#(bi8J-TbXYOQo_t5=fi6eZ=6e7u|HBSB58ivn1DOt>SlgB4m@SYl4(D9@`F0i=E_D!8E zSTen{H1cvs$ z=UE*3snq@&D{gl3z{wdJ@F=xXirsY{8}uW<-9Cvqbko5f>ton@qah-P_Hi4q8(-i3 zw9@Dzbw{cX;nR*(K&P%&=%lTH)mMK=x%4{?UasH?j~dy)d6pPVT+Pzfhs8rtMS93Z zm^nI9v>$RAZQn-$XSbLgF-1$3#WM2{UooHVv+Z`w;)_4GfR)tSI7HhUZjT)=if*gR zr_`)e=X_``^}kP}?|))FaBhgAXE|#=r;T7~I&x&j4cK(cgQ?sXAVZ+Y(2p zU^6Scku9xSuaHak&f>vAfxx#KW1*h6Y7d)nP+RUZ%9fA#QKC$+&LE4cK+m-~*T z%yPLp*tfS3A6#h1WbzxDcwJ!=DMzz*;4vm5;=~HlrefWv!Xwc|Xc?MfZeu@ateGJa zcBv89(V6ecHIP0yDdg!z!25`JP;)oO+B|dUoMkDTKvxbNPy(rI=$u!W=XGfPOqrt} zCLX1bp5~eaAMfuMpZ2@T+g2rm)*Ca}mPl+Rw*e5mvcIT5L`<6^cYZSGt}-f_GDkBw z-=Al}bKX$j!5mXaQ@oTeEF}$Rvjv~tE}cd8Aa-2MU3SoBqxfl1gWoiEz-F}ok#@&b zUUEJenxy-}xaH+I*Q_l+Ub%zjE@IKFkK`KhPB4}@Efa$@`SP22IclfqnY=_SoyZ{& zPWyeWosZd&DtGaCQ95c>4}t7q70MPiHP|Ym15Z2SDGb-q-~3J_-+VY2O6^S0!mt(G z`{*l1d+Es4LWh?w)?v*lQ&aH9f}io*3Pxj1arElPs$SQ}%P--*Wa>AGAH<9c4e|1? zc=m1VDgg_L!|6MRug=@VT2(edkJ!se6A;H)H zSLc_jyp#=>h{xMgf|EZ{8sAT#)!V7?GNqBtEH%Vt+t;$xgk~a|-f{NMbLd_3nRPn& zKS|dePj&al?Y*}&?Nt;)a?j@^ql6*}kx09qqLd~H?X6U_H<6?i?s2~D^t2Q0rJ{wb z2*1yBfB!#^SFd}|{hZHvPc_uax`5x*b*X?ScH=sBu)5gM-LFF-El71-okV#l+VGcv;4_-i1Q_{TGUMn2#6cp|jFu!T=c)On`&Mq=U6CO(As@}hGIbX5Np zpyHy-AN}%#u`Z_Ue!I2cn>~uw8XY0YNh&;OhZ_8sX|w*D0hel&gVoV5#fyia-(TDX zj$@QyCibUC7vR1Y9>=^dck@A!%fNGGig**p+)mX*I_SnT*xqEpXM0Y9wQp2e8}9IJ z;!$)?emfcbL4_L|tHaOQrR;2OE5Ddo1NTL<*(g_h@2mWUt7*d^{+$ZH^(>E64Dw>_ zs3TH7lma~+t3*dOD00gcqhP_pU+f`k;-lvGrJLv$R*l)j*;+P9gFWbor-gAuztxnoT_{FTDF91%uD?trrKwZtQIhk}~8o^CrU;?5Xs|{FYt6BIv~AU*xZx8dttE2v!EAupWGK zC9aUB4`O7PSsLEyYWlR#g(0wRhANlMe?;8E$1sJ#vO=!LF{uC7Q`Cl82cJ?$LWEub zoUQ5MORI-dms0`aexZ0znMG0=-Bft!tI3aT!5+hVhO7&5MW1Fn`hlKBJVmL};B?df zdtJZV@N2t!$%U#0ao~5SwycmofQdqmdXnw zsnGQsY)~7JIo<|h$9)rzK(6PtoIRbaA_e!g(F0r3NP@&!EFoBrdl|kZOA6MC=OL&0 zEg&9>SKcPK>y^2EXQredWEJ8ndpr_pxxqkqjygAk-rJs(o?Dg9#jDBLL z$v}Jh_}3=rTCB#?mvu-q^Qz?v!pu{5A+gbtZ0f61IrC77B$sj~dXZZH*-n=FToTVY ziXNhwiL`ItIC$Ev#_N_0hks>(T{cw^4*l&z7i#|y)nay;LySG$+t-6`G}Pg)Zql$- zOOtu|qW9LM8}gTylg@t>`K5@{WNs<;L!A;>s39F9?6mmqIvo%_*I|dl6@@$h{DMwyNS@EqtSl~mF45cMu4&|3 zle56@dM+Dq+DbSaa02$UYC)M;iw744fsgDsma;}(2)kxab9j}=_Ym^e-ClG;oeo{K z6g`RICa^%UUVJ(Uv)rZisf&Lx*^sZyN9aBveX};R;}3K>DZfmHpI#`wcF#(vTyz4? z+!+CLtegMKC!saJFq>i$`b^Cusl^5CVosG2T>i+>pPMVo?&0pLL9pBRKsXeqYjDlz zY7+U^hUxZR;N5GYq5XNYsH?P%&z2cVHyj>@JP77V{u4=k>Vn`*hz8$~Xbxr!@YDZZC6N9fHRF80Pe`CHFtK(0>*8G_iwB(n{qGS`HeZO5}6kVxlcej%5!=Xz&< zXSk-B#;&h6;1^I6@w8`%cy9;Z`?mJ<`QS-#S{ZY69b3p7jR1D}xs34i-gWq1{l|0e z?lXK*RWR6~etYC1b>6&qlVr}P-oi7Mn@GnduYi_TeIBJf3fjh4FbCX$eWrQQexr_% zqMge8kG&dvEiIjV>MJiiEUf|3d!ac_MXGuLh+;J8n268vd!!VheEJ@LJ$ScQ&{NRdBO91Z32zgV_> zGrzs8KTY1Xh0Vl!#QUK)m7Qt@H@2fT%ufp%wuG|e+-}ZPK0)#74`QbY*1}pjX}YgZ z6o5P4eS3-}Sk0S~O1^2C7pPil5XH9|+-y`3_-1Tmn|5^Iq%o!YY)#p3^q%az?@jwZ z4TfD2>b!W64otFgX3JV+g`{ym;LPPko_rZdVx{Q4K_UnjHatF49B z6hm6&DF^-btMV+_YLc!vpXoXD@`rE~%#R)si(9OO<5SLJuGe%3D$(QBSHhrz%d+dX zHiGtsD7vid7iq_wpN{(j;MtPp%-Oe_&-f-o15{;L1nwjbd4}|glmobGs_{OTt0nln z)+Jq@R$WHE)`WV>)G=Okd=xDI9suqgz5K=*clzN`p!oYV%q@HrMJJC!4Vj?^7lm4a z`~?H{8L>pa*RGjxYD+e0Jfy&L zwyY=LUx%}Gx8#K2gFsE=&x)EaApY+WO%n#Uz?R<{JaLj09J*O2R>b$Ff7TGXaHtfR zqF>u%b~kYxc7W|dPCuij9BhV%vkkk7vEN}jB>G$<`}QgGAv-sbrvW2bJnnu|nwQWo z;|GFBOPxoRxq-J)JoBrQ7UVUIsJZEmiVvuRT6cH|9j(3@-bX5Pf4O!tZz|3iA4TD3 z%mes-*@{$4=~ikqUX|?g`7(|CUP2;NP0M1_PM{9KIEj`tj)R$NRQbY!;ovDa`QR}BaMALB2yMG!&dwo3Ucl4yh{*(pRdz$RQ2-Lv;mZBFnl#|RiO1w+0faEx& zv$GCueBq^JkdJm_yGymWanl5N9+SZCV$T1b71nfSe^qfO_C&;6`p{VeGGH10H&=7? z;qH1}c2=Y)$hrQO%=xl4T9tFsUrTTsqohV2_bD5kp60TbC04?VzGvaAwl=&v^PeYo zJcNtKGMjnwg80f18veFQREKk8x!8x64$-AyaXMUak|9Jiz7;E{TMIuk4C$!V#bnn- z6@KB^Q*!<47S`3%#x>M(A%Dmi7GG^8yz)E?UiBkjVgKR$w$VDcH2$M_I_gW;UW=kC zAI+d+Eow-vE>#`CabYlj1Yz-xsv9soT<_02aSMr%jje2m9XWl9)D6e8g%EHvpRX4Ik$Xi?D8X|1AiBBcQrv>`4s!AXv*It>%xeS z-^7_XC$HDYP}AK?@aYnEsKpeMfi3aOR}HmxTI)c@CsnLli~G{XWpwoXY9Kppc)d*w zRDmW7#P@>exi9_4qJxAFROKI6YQw~`Wy}<@$Mw~3A+U5d>m$OPy{|H~>DDmtiBQEZ z_=_Y?ZZyj}AuDW8Uk`KD)`(8FD)2Q8-jX^02z}E=0Rw4h@fOw~gPG*B{OHCVR?r7E zz*+t}pno!y^`NJ$=JglQx%oltJRP+SX|nV|cofv=p;jv4GKn2%#>`Qlzx&)s*t1@q zoL;NJ-Mh!bweXE>_SO!*GT)pAOg3c`@$(^b{b;sP2&`0B^n@&(q>%%AW~uWFZ!b%{QMT_(_>B{uP?s1(2DfYR#yu0EwZM|CYsLPW zl%aHp$0A~l__NG%YwQB9WZILBc=5FX5LanpnoIjyIh(7k~M?w zsXU5FiDe_tL>s{arV*FDc;e@};@S-Z&6U`4LjXNx4eY-qilFui^hZM}6? zRCEd7hVNo%#qt)o(AdNWFVdusjtk5TakKYBhSJT^Qm|e|mG{x^Ar5Z)80%`~Z~In4 zhFm!7zwi=Y;yxd;*4!lQwF=j~x1D$m5V62)8zHD<84cSx5boSk<0ChYfFE_!nb~G( z;dPENJ^5*S#Vh1@%7+f6Rj6CN5v{`S)%_)I+?KiBRS=GEd<@`WMIIP7@-LH@L;sX4 zHaG{lzpKk=9O4~I-(&wsuLsEFQ5IDqFZ|impVn1<7u`dz!JWlJ>44Q9G+~MkpI9jm zXSZmwKlqz+Um{Drua}cP$ORlhzmdg)batnqmEUqnfo$T&T2n9&xpTY(t5LfyB~%`? zrET%5;*F@yODgiCvqc$@G+mp|N;ZOn5qiwSOA+;!?ND21NN#3nR|d`eC<@dLVM&EX zJY~a8vTxIE@!LyQ!oGI}Fx*TV^jB!|4YPwKvwiV?d7(&gD0PaxCo04(CwuG|sy|+r z_W5PR4PpmEkZptbG3p-8l>1QibH(J*4<+9H{u%L=+05oAwDEuuhe4^v z!aoB%VD=an9`a)yWN-fyXl!4jsBrPW`4I8PDl5lUZ)VN=|rq);#*1IU*f+Pxu)@4==d;^@GF>OvwbUB zw?BnlM671Z=;d_SxNRgGGXQ^=`ND!ppV_x!177Fg428o_h?DMG3)@c)qq8IIAmXSx z|9M*mvc4vD%EiB^4mF7r%ua&aueDLusa;^n6^GWD&n7*7chp(gn z_spC#BjHtiI;+?2uL)`LN-m$T_g zZM^X6M|d!F4!eSXfBgb^dPLRoMe}nF=xArd|wwpxtu()=}_kz5`v*zY9q5lZ`8yhOFH9_DQnk3997+) zwjj>JP>ZrXLLYL*II->uIpJ)OW71lUnez^!+1`HZL);tjjNgT?k>KfN}kT2CCvhIu;XcaUz#@D0g};Ia{c>T ziLSEbslaoSQenhUb&;d*S)LL%9P&O5hdtQe8uHnbZrL0p*2F!h*(8n*$x4NOsLPs; z-6#faCamre=CW>gqMdink}hAR%0Po|3089(bomG024eD|O6;nAnalVmg5LUls2x;9 z-^31y#%5xToS^u9G~L{AR^<80MvyIuqgVd40GVybO`f~JwRgYqoroH?^G-A;SqkP>Y8H zVYI9oe_MolfQC3`bx~SyzF|W9xb3LegFAf1StoiSa5F48j2WaSrQzrzduAV|DEtU{ z4ke1#WZQP#%80(#MNw+@?DE7$PA{dv<;z*@-bM8LY+pg2ZU}(lI`q-IiC}dDWo6gp zg|8*DpQ1-Fp&=Tt5THA`8dE_2<(!(`>32KDdK*GnOe72rL*_X zT6y#7G$`b(B}C&`hYM;kIgkx z6nfe^A?m#$u~?~HS+?|xWX_L3Z^fqG*SJr<6pt;o67mig0}R!M(Jh+1G%gg51 zJ8fof=HdAnnhLcW`?HLg0>1Rt2&jt|i1&449`h>>oaR=F^>LQY92`d*V$I>(VHtrm zsnBJkcv%%ZJyC)K(-Dn^0HwwlD3t zvkSJq*W@c2K9Ms_5pkP~eCoo5u+t)x?6St0|9l5A7?i>)@HcQP2Z|uYEQ5`{(8-NA8qj~7byz22 z(Gwmx(K)Xt!KV^sUR}{E!EMfrloht!LvN;WmuKtlJf5UD9X3YVg6|wvetKdS*?|FY zcJEQc^JoPv&sqt-=K7dv=?fk$=Io@Cjqt$PpEkTaLK07?@{8;BAmP#(HnQE2uf?9( zPm5oRD{&uoXqBg&D*;0+{GF zOemG$HnxXkg_B*ILD77TD5*w)8!3&I;Pd;7ns~;0Gg|v@3)?#gb=MaHsG^EBykDux zKPMVU@Oe469zOZrFHp<+D4sJ5^PT1>QT>7_=th5cp40d*pH-LVfX^|v2bCqq#4TH_h0#6z>8%5DFegTpN8Ec)icROU0_1vP z>hnP^_lVd7y&lqgy`ZkLne07=*=WU)pfq2G>Eq1*y)&Msi5p2OzHy$Mv4O`?DQwHl zE}nZ^kuEqQ%|79KAxmihJs9Qyt3uJYzUmFR`o)Lk4MknkfD54FB@(4-qMxg(6dq<@ zggZLD{H7kEn?41K_ph`OmOPKA|J+T5%W672;qXuhh%sR;HJIJke>j!tJWKi=QmV9g zD@Fd}VT%;?dHX+2q-*7Uan|@!PDRUMK;C{b1NZr)s@-JrxJb4g_1pFLed+Um^F$XA zEAaQ6LF+79A=|`=AM0@gmruwEC= z&eRq2`=Z4l({_#I&qc1^DVrpo_hf6)-;ptRH4Rc31YrkM`RHIz*pME_CTx%v)Hd~_ z6C8F_%*2^6*nK!{S+W_P1Zr^KkqXfNvjdy+L{Ye+`U+6jOwvnrE5~fRExJF^o~`@W zkRNY2Ne;VLi1#8sf68h#^(e)RMAYBLuJMFnj)a|lATRV*pf)D?hp0FPJ+no_>0|kk zbgPUO_kXSk?aAsa)Cawafl4&2vz)XG%KW-=8Ic~7!D5cJ@h91tVA|%!PT$qw4}YPa zT4y2i)sPZ~oE}Wax2T9;pk^bjBY-YEkO8lrXmVFm6F94=%LeHx3Zf@H@bIT0F?y+8 zxz7K)NRfvy>FP#)YSl5QoqUk3F3;nI&ql&SzMFhos>x^ko&>?*&+bi=7wCIu`XT+E zXwhBF!b%CG&ra&n^{u*Gaqj?7?f4+hNAK!WsR8uppJI|WUx`nZe=W(JFA>lelXeQ6 zCXHcl6AQTiV*;w1v42k8kUt8Fg@Dl&;yJkA>O6?24|bVDq>qfynWjdMG*p&(Bkq?l zYyjOH9sxflsPWv8kL2q^E2g&^Ii1-_(C==WNZG$%rEyEX=#qyqn^w`zqxZPeQa@+b z7y05`#TnG1aXg$_jroBF_Rv?;gVm)g2-3#dRG6hm((!Gs{?7oqt#cQ6T*ll9moFqz ztiZNLT;Wqrt$@>OB1qU}MZS1M7E#)~hAl)+Q~A;wI`#TCl45DVzsmgMB%V$2`Eqk$=g+ zdn$bQ-~AG-{ujP+3X9j!2ams!v|x2UT#v$^s&w|rw3BZNH>QJ3b(l-HwJ_zID?Qpj z492%B@g-|z;HCRGwoO`Acz&rGLVkC8N}+#8YRp{F!~Vzzi|}(($R*w#E#j3oY=pRh zDb)P$N~lfLb}|%m7>26Q3B(DUsRmDR zzD`ao@?&ns0yoq`rIbJ$i^I1ukFi}Ccfvo&;F zQsbq!j3K$tWcI{Ni(l_jhHYljV%MdZ(S28iDt?WE71e5dm*zDIhU16#yZjS>*lh-KBv4bZE*ix_Orp(#UMzH8Jo`yXSfi82r7f2r%u-Tcl8)AR)m%lKK zC3rgTM2zU23Y{L81Fs)z^QrB3$k|vq7C)9$#fKT+e828QDQYszxbBY9hD z7Jc|7n^+iX@H%O)O+nv;a(eU;kC~i z_Uc*}AGlLlg5exEiT6~(AnLQh0W%%s`0pPti0)2cd$!36VZ$$h+!vAPw9i?-=ox`J zO;>nyqnBUWNU2F_kXQkKv#-X_qMZ$?a6w;(*WPggkDVqgydJTvY&WVlERXC=Q>v^h zkde&%)*p@BWz|i1EPsmK98khDUM`2ny4j>AL6O&FXG`|{1#?l0*f55+8Rm=DJ;ym# zJ&W?RR+uuanXj_cr|tW%v5;Q$7o2yaceoVr`6}FEog7SW&Soha+jw!`D#&RKXS`nt zzgn{#&d<0(0#H+NZg(!3dY!O~=mS!VO`$a~2xPx0@jJyH5IKD+yD(E)C>}LHGV?>! z(cjImul3w!I3J?U0$iD!v(x^K;&Ky160)zF`LAC(Ol~tzp2v{l@*)QJRJ}7?Lwg4z6U z*e6we61rC%WcAzfc&r}p&w zE%<8AGu)gZcUZT00iK_!cz%YuTqKv4C~@7IcVyC|O>8K%^DAz7&{8{wx%QUft`Y)U z*dy}kl>z@}{B+68w?Q3L_^es9@`*Wi`N;_Dc56^Rm6yFkoeVoXh{oqcz>N(Wyz6BH z$;z^24c8QeH7Bpa=LlDFfcL444KI-763fW8^F8$==RQqRj;8KBdlg zPr`hyBo8JwQxKf9b*Q0*A{iuWBlN8rM1u`>!@2?uo@w+=g6(W^LL8~}D+Eu!NhZ4~ z@$jYl$f3X#mWVU|luIf#YTZWC#RmMD!+6+O|CPN9G36Vkj{)y>7sM{e`5Jkm*SXma z>W(S%;rjCMUmilq^&Tz?K>z3sL0qz^h)>r`hW4Hx(q=V!wpR&iF}GZFi<9{J z>1papf#>k9k3FY`3!qp>hZXcg?8PaV+RXYx?x3dh@)l#5 zHa(fC_iy9d)6gqaGlym1-`C4mqb;+Ypt}!#7Y4UUXM`V%b{F^&RyW~Asqz5?Ia z9sr4zzt|whX1?pQ6}3#+${gHKb5a|O7_T)fmO&4-TVFVJZ8EFR@8N0N+Tr7rPvVb= zs~d)>(;GvhVOgabH|e=4nfaNe#e8aZ5ZrnvM-KI<@*RC9!I7Nx?Dvoko~vO`C%rOd zmgq&AQ4&ml7)*q%&8Ua5>UCI{IH5V zZINMyCkr|KG!{UsZUZ-e52@NMUtbx;UAvN~Hy9)=*+Cg!GzGErxwq z@$x*R@GYrGrmQzfR(SjB3fR0CiITRI@zKX8Lt6P5hc2o?pd?4{pwZu2_l;;~^-k&UX_XXD{gqa2w^v&UKqA63bcNM*Oha*NJKc~irepiA&`&F1Bp8qf#b=o$$g1jG}4;)<|ye9{O% zXc)VPEJ9C*TyrFNjULCw4VD-FIps#z72XrAeS>$|=@7bCQIDQmXTXPIE?l3GFXHB0 z?6vu7M*jp~Boj<9a}WLf|LJgQE8F;n`310Q#~ADcFXJ_9CPQDhMx6b5vBZ<6UBf;9n2n(2GM7GFH~}7`j{4MiN6F0BL+{(t zN&3{FQIW*Mx3AOQ#@$z<}e8A!9FH41=!RTz$Tz}w_;~Hs%I93(rIU`Vbmx!es4`bXnz#OPT5HdtD1X2rS^-s2WS3~+sLO! zMnls+HU9YNT~elQ#-d*q@fT^qV7o(>1gWa=HS;Dz*Yox4I-aEw7Y9>?+osIZ65qCw zp>#~lM5xD1yk+PQO>%c-R++NGqkGcSqJM(tdE9xrUushIq8vE7PMha^$20CN$68kx z@}$xrIAjz~Hl=8BoAFb@bfgtC$M<+u(tH{ayN_(0ti?5ThQnH|8%%Gj5#JPO2jkA? zh(8or3tN_3((P*U5QQF@R~vtlJF^zBjdOc>uSY55L>v_#x4OVh-vmS2%HQN{xHd07 z6a#DSNHcTfQf1f9r)uR*#Eh%(O>z#Bng7_Ti!YZ|rzg)zv;1<*=1sSxS>GL?Do=su zvpOmq9^UUHIJOtP^vWYRv<@;*0RUATPCLd3oWBgF_XN@{N?g> zuyE#n@*zNh8@C@MeLBLKO{qS2i{ju;e$#9>mG|<_*>0z^`t8dLLQ_s>^SC;i`XcJ zGv6kSUb!|1(wea2$e;7i~wsA->6%8Zq74NVVymjGQ5#@TW^I4zi{RYHo`{xG-_242*rBZe98iU z5S)EkF6I@xowTM^sy{`#`8I-Wrig}o7)gWwK`-HcW!M?4%qGsjo#ccjmCvXkdlOao z$E&wUic==L=-$p(2kpfCPj|K`QH{@64+jse`AjDl@%%7n8mgftUOo#ylY&qht(OVD zty=v2O;Z?hK#$EVQV`~$hv+{%e?USKuW=2Q%=`_0O*~h*0A~NdJ>T&h*XaCH>4JojftH{=DoogVZ{&A+0QPd37E|4B3efd>`Dgte2cz<)uVxbPzOS*)_8 zw|8D7$BrrTH8Z}DVM8{te%LEiIi-f2bXX#uGwdpFjGY47zaNk{S}y$V*G=&E+DGvc z^rHT{IG>Kg%xK;&Ei7%)rs^`h>@M!i<>xKwX`M*0u0wzNnV)3;St~XL`vE`XU4xM~ z+{iyQ?L2iYp(nLnSal)pHb3Xnr+fkoLQT;fXBSwQDPr%Cx2^iufNtNeNS-1d9`MwX zI#1mVQv0-cM?o7gd8oubq7F)Qz8MPgZju=6_8L)glx)pOWp5B8`rDF5{bIJ0Kw~3* z;_)OHvilqJ3UB5+)%#HAE$M6v-c2pz2{rSz$DU>teyBznK3gU*|CK%b{i>I6=(!*+ zmnz~vXf4ZRBO*~_?>T@L zR_HKKY4j*90A5I&vKHie!lJ`y*SVwQOn@%8*R_JuC&kQh5qhOt8sY1~^GuY1 z`iE?78iyTS&z_?<|Jfa4I1#-kQoX$R_&&%!oGLyeV=L@fvW_MO*TABF19^UWEM$*R zVui>H983wL>iV5zD)L`O$^AiEbp_f-}Cb7B?I zdhW$MGW58=V=?I%yWP{hT7k=N3Wjy(8=10RGcP}ACz=UsQ#7Q0MBh`;19E(o8JiVb#69H0fQ*qPdod43 zx-1;}FI>;;H9NTbD+iiA*o-Z~_d>hsWcp9>L^xoh&XbN01UF+BR@^BgOmLE=_7fI) zwxjQ+eufTx@+k-E^0au$yQicoOO{0{pXVL1p%SjPbqC(#8c{Gs%bd;q4`WeTNXMn` zBYh8HAHBhF35Ijx0j)pQRIrwZmNZR%L-7xp@nJDLsol%X&y>L% zkE7!B7}TM;Plk65zsZaF#$0~aKk(2&nLWhWe%fv!by0368aq|F-OypMu`7iQs_5c2 zo|<%zi43c|YArmIwV{u-9U%#|tmZ2k$QR$ytZkXBuwyZY-GhjzT>1*%H7W+ooqb{N z_a1Jb=qs7+DckWqGH)UMyKF5e)@ySzW&|v%GhxGjSPOL{ftp>)Bi3V;D^t>yNq2V| zOIL5=g=UyRwEPr%?1Ox3PCN8&QHSm~ioD~(agud-3X4I0&^Kp1HJ3jpVmRAZ{$5Ch z&25l?xj+X8i(sH@llU(3=BH)?RU0Y|e|IbMB@dM)v%O<0?vM@7fGmk%Vt>qfJ=PA1 zH(X&3YR1aVPm_kFBGz^rar>?7sExcS$kb@?mc{&3tM_7^M@$pDr$i&Dg8OfldgBt=Hn8yVc0-T z);SHc<_vY{wi6XZ$5Vy-&8{LN^)lJP+3j4dB@5QoyEBb*YTW8fB>cLD7!LNoG=FoU zo}W-}iM)BzIP}Vm%!Kacm~Uoo3e_$;th!l2up6vM+s7G^b^1x%CN&i1SQb}~X8L^T z;@uhrp`?dr9Rb4K6&7mf-ek-{pnQ51#aX=zUQQYA_c5oJ?io^=M( z&WqTKp$fvbOGY$3Taj!t#W&Yn8#;Q|Zg|>PhbM37Cda~6*aZ*dh&Q!E*S(wMh`BPq z=y{SnpPI^E6=6^A)O0F3vYqJG8}ja^$&xugExDPW#(mr5Mmk%K+AY;aN<-4@VGU|8 zYpYdZ_oxK+$ieXL$Vp-^LO$&?UJ=%)}t z;qy@v{YQtFeY1uG`-_Hga$T^;*I zx{Dh70e|43`CN8n6`mg}Jvyz~3Ched$0PBPWS>u~k`?CNI0{!yQbgGf3OwX|2n=}n zi*=z-wtvuI$;|fz8(~yY1P#%#0lzJ({7=I`$;{u8(8K?Ppl_)16P_`|h|2Y7>D6d> zyG4T!L(SN`ObgaK`U3ZHi~?m@ITDCG?=iJ0urzNyyBOTT$4L#NdRxuduHmTbI37U< z{+tNccB=CN%q2T=--Z3@kP$YR$N=7eSZ8U?za}R^8i<}p1wKT)@qiuu6yyl^yp_0XVj~%0 z=);`m$_j4wH^6@|5y=!?;id62V6>VaT-+cfOt>|c_WwFTeE$IAepZRpCvPo0YuDrI zD*@8N2Czp;sL5;?MIC$c$mu4f$`lt>l6^Cc1qU|qOCO)Y#M`HsMI>VHd;h|LOX{E? zR^l(uV9v2kG#isGFC5~*bRnD*<;mL$>sTUn=xT#0f;}&Hp9-ByYHS_;W{VZQsCBe7 z=yfP@rID)O`f@L;#(dPO-Wt$0j$nV$4{~7VUzpV73T8`Gd9czsqMA+Erkl9;Hl))c z4^tR8AG-q_#zE`4+3cQ!v~cOWB@NrXqvDAb=7+0$QL71Cpkkvc-&3m&4#Nktjpd4h zQtB^wOKph0f^KD9)+>oV$5PbD(^Rq~xc%g>I2+|N==6C(KufU?$lf0+biCM>XYzvV zPkXxd{!fwVb;KD2FFG#Dlez|L^YvGBfkkUF%_#IpZovMy8#wbbRJhr*2Shm`lO;H` zqc3A0cs+M#w}-0pDsi+#huM}aCDb{%AqSx*jzHf0XHNv3z9Ar_B#vkb)== z6{bHCIfBi9;fcyEvMorF+kQMH=@YcVJ5Em_gSudLhudaDKFTXxg4-nTZRT69_NC6) zL-&sX&V)as=(1vaNX3p+O?mWhzF5q{>U;Q(Pw!w&^fhte9L)YI_zMovvB;CE^X}9_ za=p1fQ^DP%^;{Dy^?GhRj`_**-7rk!G`zm1!xtD|BCma=n6{R!aKk)gPQ^T&+6X#Y_ZaECqs!Ch*n-80i)=Y+Yn7Lpz_Q-A;yyd@w|QBQ zvenAaREF7ECm)fcXJ#?=nZ4XJ;UHXYNEM?fNq7>PLGP*8!oVN{es*OT9MP3x*P}7Z zt|o$hJljbEFjsK3o+(%F-;g#MP)j*)`md4s3`9f7Hlz^wbd9cjoMw3HFHT$AVhBEOA|mxbC?r zlAbC1W$io+{Tg}0%rG0=Mwk{5MOV9qLW8>o-)&_H`A>&4w-K_!v2aEDUmk)D>V#!{ z4XLwsE;wOEliB1NGUK@vGm0(dAB*GQ`>1HL@~$TDYa0*MMpo=aJoXxAETMNW4C}=j z8%~cz!9a(v?BYTLZc*s~nqB+F$8Tc(q}~v!w^SbTe02Dpp=iMDOlFhJdiauH0oJ}a zA|4%C%BAJzKu6SHV(?m%U-OLzoo*?%3$q+o?p;E6Uuh;wOjNjAmNSs*HB2YzFTb%= zmo5>@urZHt9~gkXp=3wcJr=VjmbZ}Y-ahR1ds(5d;0}0o64ABeXL#eJFi?0k95gee zgn`e-(e3uZ68*{gH%n;li?yIR%z*ES8x7;C2eKeJJfDf))YUSdOqi-v+3&O(`7gUz z2uAN4j?oCInmj)A8WnPe>4qv^pSu1K3>sP)4Vim#iFc)sebt!sqkQ;Prsq#Y^ z=g9~g!W0l^-ZdqY=5I2E!?@4yQ3-u$r!KzxZIEY*^8g#Wugjo+JGGmre(P zg_IWmc4<6}Px4`Rrzr^Jk^`Nk(I_geK`-rG9~yVUla9>Nw5VZdv|JlLRFlfj5!bc zqUioTnc$DU`1jNTtQKpt9aj{Deyu8!*}k?ytFrx}H2F_s|JJC93*n_;+wTxdy@8!* zOXJ~|RxVkrpuvm7V?pNWSeCI9JHhu+`ZDOg$hFf(02)pE+|i@)4*LA2-w<$f{46d; zerK1=5NfSaLZpI~_?*lZ$(%Rl?flKc3Q+qxmc0-abIZ&)XimLNd}U2|mfBJ%uev6# zJ&jpUUzX7Re=NWjJC~QvHNuQ*q0FKidkw}7p(}YLtck^3%12$2ZYk^Sio(;N2hdN^ zo!sATQt7wqhR9FJh}EBO=SeZ%G_BZ$Dc{E&;C@Ne$viwB zL_uE_1r=sSX>A_+kGDU;1qGWSE+TSzhz7r@(arTYg7QaR1f_XVQ8-3pQB` ziCHq#!16SNAO$ zU)^;1!n1?nxA#T%uN2N$FJpLf;<;D@F&3{sMl|#g?(;I3+hAEs!cjkS_)agMWOxF! zJ=cm$RcwV3``6RsqiSI*X4`JUEP+#f+QiPdZ+py`N<*c)NJ5Az|Gn58BD_|xfwM7J zTwaPwInQN768_Wq7*p*b&alx%o!@YMNrKCLS=|d+p=A15_z;*P(t0b;T{FTYdVBjd z=&$+iNL9MFGJDh+9{e+vTCTBy!W=dJW`-rCj0|U&-T(55EwZ%7=A(GuLF5WcjOoAq zr^0O1E&mOEL(J+d*dfz0F8Y!HYGo><7~fwCInk0i|JA>PFaF{}k0XC^Kg33eQi!3M z+d^SqCceK`T7lPq;Y{zZj1a7@OgH~oqzzb~xq-fwO=N{gPEvx2>T zfw@fQ9I4JpdF-yzFxJhF zPR^HxyH7CpV7L~H(ci~B@3ry^n(v@^Yy>NeKz*hyVrx!r5I0zr`<=Q-O6L-`vkv!O zVLk2luPN+~(%|Q^$HOC;IZWJNT8MaRE5UHGEo_9{c7Al=zAccCnyYCAy6`;Bfzen+ zq404V^yt};k561>j*a5Rh_$r$3b!4KkVokDdFb2k+kK3nt0@LsT2?aiR~k0)oz-Pf878bv!o!fn`l+66?p~YPF)+`uMdYkmC9mwhORG6GtCBA+Mzl*cW(D!Ny zw=89Z`|^Egf~HUwkGS-jXO5Vc90{V0N<8pq2Z^^dXP0Iv3VV7VgLRV|IbrC`TiUl{ zhSfT8FmjqP50}xb_F&jHOM|P=9tkf>J((qH?BkpI(-#Aj$T>VS?FvKbzw%jNIzyYU z-Y5r;dz9I)SoAmym8FYgZV?}Q*bi6S1U(d zU&KODtR^qJQ;waVgV=f0@Nd|;0ezj{NEhmR(+q>5^b7W4Bw<%|jHLv(2}2%s($6te z>CR+uIFDU~`Fb!4?`wMn?86$>3b6)KA}jQ@eNvLA&EBUW;JiA2z^{^hnjKLiPmW%$)xa89yW3*PhX}GQ6K42rYyi*I*SerL4oCNt+ z9pXBilXe4RsrKwHvI22(yG7POC$DD3W=6bIY7n$H?GVSKfAj4*6RNw$8TI#Sd~);~ zBCUwsWTA4x=YIF#~215mEasQ+ED(>4I9(}1y^i=SesKH-+eNQs?V=jcs6&|;039O{b zr1Yvfk6b_7V3J^lQxeWX7^1u@9~&me$pT{*R>VaK!5W{`TH0B#|v7QW~Cn zPTG+&S|UYL5-m}(T9VSx)ZSBj__%NHThT7G55^Tw&UoUhE|0UD{e{qh?g1-}bvS?}S_7_=Ezm?QKBX-cN$d3T1ZC=sfSxXAU%M zj}k(oboqp@Q{YL7y?n-5{vsI%M{W~lzj5a2nv>z{%dhN2ycy3P*#p!Awu?3N9`z?} z%eFJBu=SBHUmd9oKcz%A&%ceIzj+fTI_(vIk#F0!?=$6mOM}bCJh}HA2z;o*YKYtL zqf-jDFC{H4^+=<>^@aT*8SG9-3-7th4AqE-Kk_y0p?thC;khSRQBI#=+A8noLrhd8 z^Zn)UU^%rJ0mry!|7b9J=?jcFehK|Xp^ZWa#R^jo?4N=W-kDI9X~w4}4TVVZ^Y5qX zA}MYjhC?!r3!lGhmaK^|66%bWv4peL-244o*f#GlizmItwtcGjSX~cV9&2)|iVMQs z5m9U?Q;gJ6 z@`^te46Pk!GDihPN$t2BD!t7sHldw<$-`l|=NTNqfs8^osgkd|}5 zH?{>-$(){&#xRfcENU{`YGud`6fEVsDn@59o~XlGYD8L!l@fY{DPyurR3tXylxVyej> zz(*hdJ~J15=Ngt=y{txg(4j15iwW0!^+Sl8dQG&Nd73hJV&Q)9HX)91k0;qv7JZeZ-R4#} zXOdKee@Xv1!W%WMC%_8I?RxM`8S1es8+C$oZR4K7toYu7-z9JU!)864^~n+~sh^Kc zO~JrEA@GfIEu}{Q1!RMxdw_WL(Y7ett|1I}bCL8{(K8)3!G}y!es+l#=&9(jm_X{y z@>H>LMw#&YsRlP(eO`{wcWrf%_Vvuh@Z3Bh{<;A_KXWuZTkxJ)Xw>rlhq~ZB;=yWr z(ECLgW_^e|gl{1KD9SWkFmygMd)m%5ntsB!>}%pps%b0lt75ikG<-Xz&u45Gh0Pai znUbQbw7yR^j(q(?cn^Bqgl3Wd)%nzlCO);d6E5y*%+v@2nXNb+!`;Wh*fBa>vC4#M zPcXadqbgl3tq0El1(_cCFiT%l@dDM~*Chu0xmJlVE$N>)rn{^3W>Pk`8K%MI(CQPAP zy5q-N!G2;ao3KRUbClB|%4?9=KEqY2TAPjcEnk9hnF-B_6F`>PCMM0JyXoO%TyVHW zu%o@wwE}0jqMXVm7u4}Q;;Vc;Gm{OxU~)H0A(qEpf1j-N%X6ILHgN`)>u?f0AX}T zZ&&;x+&1NUze{(N)hmoLW1ahs_0 zTK@Ycd5!E#VH)?yTlkm{hP_gS|K4eE#k&eHE@dV&6xw;%pnK5pX|LEX?KEGtX$~Yz ztrZ4(>GO$Rv5@#jfql&*f2wCo(BpZnuV>y^;Q0s5%X{X!*kaSqf5@Kf&1dYp}S7 z`mu3(skk9F69#`b<-^Ep@r}7H3$k>P3jG5yr1ZF85TafZu+LD=w^4j(&t1$r!t39k z#hIj=JJ(4AkGtr>4I3@~zE_d(^hXqBoRKg3qi|fh`lM{Pg{zdkHx*Y-Xap^57rwha z2F_j7WZE=?hld8@(jSWOm~tZaPqu{7yLYjZQ|fuftFN%#J)Akj)Bk0yfpyuwFsVCb z$ktvKn!fd8w_mwPd8w<>y^kHN->A!tszYE`@C^2TDCuVnyW!->^~GPP=TT1y#B#-4 zm`MDVolYG9n?0D-cy;O3l{R=X(nVNu+oWV^YL#sC77zAdYBjIfvJaU1W;T%e-bn{n zBfmNlJhcsYhdpE9$I!vdnz$bwpZj3{|Egryzma#4Yy>I>$#B_p+NUhB0^1gSHk)Sf z(5==Ou~8Jh|JCHXTiys={8x~tWdmPYb_njS>B9ow>GA>OHF{@J0!tzcO=l{|>-^k} z)UWQEf-;AdaO;B+|2f{HS?hy!)&l?D5 zFZX9}7OP2v1v~WLtRd*pJ)U9J6P<%Mfo6_AUu&#RxR(Z76ieTKM-2=)T_z+*wD*a) zEU)=<%Sp2^JO@oE>+!am0r&1P4(t@)v#rl-c;__^m@Y17I|*aiSv~^0;)OVzo_Qz6248DwQ8tn`-~0EY9IM}Jsvs43 z6oSp+3=!#0*?&I=4I*E{+H9H~c1OaZrdIMCBWy~Th7L_F!Xi6u?y=Yv^veu2M?S`7bI6BjFt?$8s{Va~#AcDbN|ckkI3$J*Mnh=t^>)I1FX zl1GC@KhQ`-_yM+qru9KYz;`x5?Mh+ZKHb3n1RifVaQ?Dd*u>lQ(kzF^k|> z^+e(QUVU!iI2-=HbYjQM%y>*K&35*yWZ@H>dCaad1k^Lea>+Qqk@|u4_;Vl22z7U3O{VNR6*XQBgiU! z?wy8_JJ%zvzWSj3;*G7i60A;n8AC}dOP{z=x*J?D~2*FtySTFe)SGA z70F}D3plKfGPdX#Uu_Ww_pmqI%T$mmjKi?sm=JLcCyaV*8on*agsfAh{Ogwh=%ZoF z0tf^7bu9=Z+KvkoNJlnt^%oet>@XWcJN^4}wNM{`kq>1JQg zj~URs+&P@7PbF?AWx{^m?F$Y&HTk07ZX9G5ke8cpsZ1C$@QPBCL!6$TlFYFt;oE`epzQ_7N>6j5V@pDNAi z9yKg^HeOo@P6}f`lB#)eaw+Aa?qY%Vq}y8Z4ea8Kz)jNTUYDl9{0l?aPct>iRT_pT zx;~I?AinhQU!;}WV~XG3JMpuw2ixDr+(`>B8pG2sDj^bLD^r?X# z<+mYp!*HgScaASQwg|ElZwZ)d!6$D?m2+LaxEuqye|`b^fR&784MZrm|+E##Ul z74z!I?>aRNUFt%BQ-2%gI0znOA`3gLCVihqT81wgLNM*xhUWU>y_8L0Z)m|Exf@Y_ zt|3caPM!eENWWHFCioMFzhbW_^h?WN_kR&)`+N-!F<37=ePzmH2FE}L@9#`KrG|eP z>V#j!Okf^h53VYx$dYjpfYy_`(oY9{SUig!EIxf=S{nkvQc<0 ze;g?P(c=e_Izf}x7}n{PvSe_r4bH4-^Q)uY-fM*phTT03872mNNa!tL!|aGYvi9=c?nZueAve8*T?a7B5BP z!_+V7+hHFcEvQ)kjDBUWdKGyGho86$JCR(c5*7s#{y-*nKj zRA!DbE>czJnYe#ys}OaNG%w@bp}BG~E3>iSMZcY4XwU|+mGq%|JKN#UU*s`F^?alA z8)5nLek`0kBx6rrhHmH6WRB%3{97t%LdnPYj86@3bLx$AoYt|PROfeGo{7ryTp@j{ zF8RiI!l%M;X8WO)d%o31+k#KxrmN1V9whBy_g}&;R|mG`gN772okMN> zaKZUJ@#`+cLb>*8c6WIr_h|LQJ@xi1m$1+^r8Du!)zP3;s?B5mxWnMxJ(%WuC8@m3 z0CNiy{bGwLqv5I@&L}N_`eq|;Ze1^Q4^?A7^~eKo?k}i)`anpWNqnjeROiX}taTsp zjc>%j*`F(Aqi#9zoAJ|OzSmdwIjNTSUD5$R*)L`tYn-K~k9}}dZ#CGLtIdrQ)M0s2 zJnMh6jqe%t1hzccEAAL}hL5gHfvshA!pA5hexv7nxay(8{%j(y`@VG4%B&Mw$eaCl z#{tmcb0+&Xw1p2CZ-wO#mDqpe4W;>}4-S~o9eTXf;QHmH)A}-)Me3+X-8#L7tWO|2 zvhf_B(0Y!f;(ouy~K^yxsM5>~S{}J{&aRXa47Z+1Z9I=s;Zb*kFw5 zazf}-qFGWr$y^veY#AG{wVF>@^qulO53?O}s1H%o#d6ADDVUE{=WU3klOG&&6I6{>J&S9#n6Q$L3;vnH?-Q)8#?u$G~8l z8LY-sQK~HWLYpP)i{JXXNYch&1pi!!UZu+$@~q(4QBStDN=^FwR|)@z)o+P1E*X5I zUS{jz&iZVx;%l0Zz}t#^7HmXV$J|_WnmP*h)7?5^!FYJma}e7}*{q96=i4XmkF4Jp z+QrWb!LoBQY#C|D!%A#G+tq++(Y)`m*AAC7h{BO4>fC?cMH zQW_J81MWPKopp4TRL{p^;R90)y3v)#Tnhu+KB{a8?Rt8>?1QtdF9<2!H2Fh2RhWBp z4GVEK;l`w8)6AYLo_2GV+6sQbh2#C8TfG?{{%JATX_tsMZ@5T{Zl&XLcPE&kt|aN- zx5c=#Qjxa_&4!wNG4IO+Sbm3ko1L1FrqPvE?$eNV-~9wT9s3Hlg{(sVS%NlaGH9Crh$EN%JEI0 zKAHSddTN5%ZZ*czDZAN37yFpr5NeaOc-FzIg11v9OQCt~=j>dR{MHNoiwF;4;jrw= zJNB@a_OpYXal85o7C^gz4%xvt?UOt7jnL-Bu9oteAE>Gz9bM80@t)VkorEE`_0mQA zL)6<-Z7<$YCS(S7X0f!BIv<~lmUTacoVz-_Xdvn1bXKtYH=B5(vO6jrGG?Zvx!YJ0 zj8zrmVE$_zUizpbRR0TMJ4=ic$(AMXkG07>oD9sV8Z{ZJrtgjSNXLd zS82$hTx=%)rXA$X)zUfvW)JGZ#-K$Y{my9IYPv~ z*J2T2$med@VQ#P%ye}hvt>|yU7R~7_$F!Y)?{N;E^vDnur?^Unmvhlu?G?NaGU3-t zCX;b@o49&2^~S$v;tQ!&m`)xqKjyf@5b|A|SyjhFlGQQoL@b*@c+M%&4%eFdfYLuT zo}&3dSd=EPJS!Ec_{bGl_%2OmbWeq^$%&F{W|eZxxYL5^uqp1W7)mw&n=B5q54u9L znl4|P(_N0|jF{HS6=&$8ddw%$`mwXrxwj(*j*Noxe_DLm=AXiM_byEPxw>@x&{deI zG)$-=-PYDgabW*Do9({W$luT??=``J?IfO3C&xHcdOsR!2=5Ix^#%=P@*%vdB#p>3 z!eyn2evCLRH+wo_x8?%a^T3eT^=K60!d1z}n0Ts&HK5e|K$z5`%kLS?k^7;IT1RKQ zG6Qk^cH!O=Cw{SQCY)UUm91B-<^LMYvFFbewym1YE%bCv}NF+>N=q`$%2pgFdF_k zu4M{2EqvryYt%AVX3CAERSES&yk@NB6FZ^h@^xaGULp{A72l*iqhhB_oT-`x2E^HJI64ZhEVgA*58AJ(g<-<%6GG{8&6243 zmV%hRj7@*w!ZW)&!JWmw#6-fV%ctq1_A)(q9i_?VzP>KZw~S(If2m6Q6DQ-#8K-0s z-lW%)%-D)fBC&mHPART zoEegyB65*FPVLYeUeV05=h_V+d?;Co>bXkKuB}C%&i2qm=fwQ#I60nkvQ|Nwxuyp$ zOJ85CM$ZqV=f6(Qh3$Lw`0t0Eq14-pg)68_3O`iv`EVD(dysL-v%+S1&DVD(?&8rC zU=*;KJvMZe29>SFDTSjTBAc*+{Sk7_?CgPRl956`{E$;E`=L*Lk>zL%G9&%Z4?`Z3 zZYS^aFP$O}TT@3|-;)VBEgIa`ty1ojAo@0NN6j;!ySonyuh8a)l4rp&!+5sTUO{^M zdLWK-))g1*pwFBVhslRlLi}+PUhUQwo;|f-ucoOBkk?yg1725gfn4Oe~L+0`(hJJJZ{Ke&eDg=54G4f!q8Oa>f_x3H-ukyq*1Cb z6&8QbV3hqVrKGRJzOm~C@2&d0OW%od3};YA4S%H66~Ah)UE(OWHq#YV3mx@!iP@mbs5QjXZIv=dd`+D6I{$`SX>LY1jx39w$fxm?7 zIXe8&w(+o};|g{uw~3E4@kGxD#_UB9?Qok%V^6Q~5crHZHeId3|5h-2vy(hb>XcAv zd7Ix5>SJ5O4N=+j2*s)x^1X_Wg?nGy#0E=ONwZ=d9(bPyO>Vke=X5w|R#>yK#LK-G z5RZ<>_X}G`8uMu`eW760d3M3mlz)2Z3=_>O#9+$wyr|-g@tImM-$jQnK2$Bt-anHa zyxh(!e_jFMc!n4{jOJOhJS?2|3d-s4W+_jG>d#H$^?9_PjfuzM7XO58l%=aXxjUrG zmM||DD_&gT39~cv#ZGk2x0pDi5b6WpyQ%ZgL6yQnvRkX{MKvdd)7~jv)~im1Yqw2? zrBPMvm0b-t{L~MBELq1A=$@L>7LRE^T_G}$uy^uNtH>SCeipQHg?N25yZ=cHC7+ES zMb6lq6$QRV3vk-ulHc>)Lkye#2`x`Cy-TjrOxY4Kw7p{liN}eEZU5 z`1MwWZKoN(d2|-W%l-=U^7MJXfy1Fc`D~QwxAH&RZ17vUGCNOoKKs3Z8}4+6(}9|l zm!S!hKM!GrcI0`u>n}S{afT~I6W3-dLh#-$+~G+!92mL0cx;7>bRs$JH z?DJ3zvxfyh`RP#;{rW3cL2F7UrPJj}=jVupCK}>CDQV!QDNmvC8+o>jC2zOj2GFF z%SYMuf#%HrK?A?FIs}jJ?8Wx9x=63LW#PBy#4k+O=UqL9L*;5<4?C$#wH|JGzFbpi ziExothXU?Z%ZI%trhMc-+N*ZgV*yKvulvRj^C#R8l7DIPU3+hlS6K#2Zg-K)G}hxU zX}vJ~q%rSPH%;z=rgEc(&$n{NZ4oQTBZV|F;p6bh91rqN(c+^WJHvyt`OM$EoqL>B zz}H`{iJOSu61v40x9P?}{%~DxOMG&x{LX9?aU*Yq3&vqW(s_@JoGZzT2MkI1j+O^+k+ zg}hHc%ziGs8rv><(tGr3@_J14NC(qE$}=4?Nsi~RB+`#mCtzj8e&G>$myP(=59axu zXY~$d{9+F`%B+7a3WO1zUh0Zz1zK=4fbbC3Abhzzi>beB=U1+X5cecQoI1u;y0B_J z=DnbrA8EjsSVqI_w~gW>dcKKCBK{ZuPbj>u#Z}gL0Vlj-LSrqDY}dwhlVVvtX_3Zl zaK)X;K45xYop-bUEp++;tgKpD5dbNEB2a)Zt_HHwg10 z?Af<<8q$=Fcc5j=aN#QXko3D5Pdlb;cF41ltM2f}@lzd`?o#5*9Y{p8yfI*~l{kBq zq|1Bf%X&{&lCJ2P;hwBSzYlf9C793^uT0tr`7V0gF|b+K+Ea7|C)cHnfEzC9#geSEZl&wk?j8X-N*}+?`rbCSG7Us?od`lzBE0~ zeTQMr{zPdg4_+q4|JSLWi;HCECRuZ-blRH{~P8PaF+%!~cp)rqX9l8IRfzlwh#6E^nID z1^V7BVBNjy`Mk4Dp#LkJm29QG*enyAI<+_4BD^Tz(OqFjsUI7s=_>8bU5_4{?P1nO zUG8#tBKSndvP$xYe>%n&b&sqswjkZ{)cNC4`E@Q-KGWk)k@lcm?!`9bs!IinHPLOD ztMC*|O8hdFJq{dNk8R`&@0&xpHpKHSu^Y&oI;cti{t7tz zVYN(?H0CG#!*SbO0dLys@l82)@V}hd7u56YG3$yRIZW7AO1if4DtT`|Rk4xJmM(+x z{JzAcq?$i?j+}3QsY*fWCk)30v-HGlnzOofnu`})R>6>yrrb{l;ZN_5Y|#ld=~AO5 zevh>fB0n0I=rh1p|LSz1LwxySv zw0&I&o=Gj24VJk|u@~p!(>Z2XSZB|-vrypU6j5{%@z-vQE)c#CltyvN!#4v`apy z&e7*Lk_}@o2MwCI>tHWjAQ`h$ z)YIDS9FM23j)%)%wfW9g8~E)U!bTIP;##aKCLC`gFAg31NV2SbB|lU zg?W#G6*;I#um6&k({W z%j-w_!aBnVY|K>h0vg>7ZY+~RM2jz)VZ{KC)Z+K(iFVi`Dichd#4#~4*aHhK=afYMt zhvsPUYaQKv!7H%Cu`KYQ-k{U&PzWF&r)9l}JNo7U+A9bn)qE@rYnaTmhNww%&&@!MV}&wj!W)-uTY*E4HA76a z0slam9i!g;6jz1*&nq$lExsv1lDi>y0vB*!vX{-kdY(M%AG~v$z+^N#mwhzD%vHT% zSEMFC$jgQ66@Kh>Cs%2V=0?2p-5#t7|Li)7@I2z!JHJqn+86i1kU#5-9b?Il%Q^zh z^wvV%N?oq3=m2@)-PtM)b?H{U7G~XW5$4*Nl>FMLBCqq&tEzeL>6ak;@n(jEJJogE zi1CyOx0LjBTZc@N`y|{3HEBx_>D*&$WJT25&#sTa!Xg1zb<^Up7PcVm)?}6BM-+O{ z9i>txbQ-V8?Oy$rb8^&|HgM&?|ADDjUv`!JPHpxi!l}r3w(_2WRNpBO%@*m2i$v0@ zpO}w32d)A;sRKW5I0$Ulc49$0)ugLcRv4CHA#{)oO9m*I$?JSvUNv{|CbjK?-RvyY zVcT>CG}ShSJwddSnx67L=pKLaOxC~cTsH`FN zTu=+ri#|e$d#4gb#VVOyyd~-By7StSZLrFfc$mcFN{Odut`DPpcLUyI@kqGEk-ckH zla6-v#3lbUg(tK_Oi3AtzsBW5{44{0bhn9|Z(pC|ES-E|hDAj;gkkNPy!paId7bY? zxZjU28*w{s5Z>jQaN91kA*Q&J4gOutM+bXikG?C|AiA4UwnU=S3lFd~B5dJ=J%s#Q z$W(R7PoP#ACna7Jhwmouj^*a~F**h`?&|T||5XU~X}0Vn?ShwAY{VzCe+v#TNZWpr zd@9tIvwP6QMec(GJWW_5oykXakyvLO4tJ*L@OD=Rs2UK;I$cwiN}DvWIi=li9$^cR=~z&6RsFJ8~TSSur={6l1kJ<+@RVfq%R@9go6*%O-g2mbLx1q zh5?R?okbdU+OM7Mh6^hxui}py?|!yUpg3%Hbf}7SN&hbBB&N$Q-B;mt<7dDJpK6*( zJ93MFWN2D=MO>Xv=cG##8XW2hmq~A^=+g(LG=;OnD*yP=X_R02=Ce5VHDM#eJ<;EJ z65N}p&EK#4C-=J4>Y^d#-G2mTjl+cGms@b|hd*RWh9&lZ1nitz1}l~@$KLzwr^fggF32*oyEn6^?acU(XkJ^dwY zmInD+>>7;2{;E;FA$baw8p`YZP*jkdM_0n&-2LKdnwLj4C?UR?1~NrMzP&6Jc70c7 zuc;1fTCo!Kr`HSL$zwCQ+bH;{x}14_B@eyh4(K^fnWdP~Y+E=O`z-K+Qu3Jku4@Dn z{Q_BB4^=5;ObrYj+4NlUNm%QLCcifnAEUEsd37Rw?7J4aJLvNLg^p0I)16Ho zqAsoKr;Fa;Ds;PHToO53P52z-!4^8$@}euv!pkeS#3-7bf3Dkv@7+QGVs!b5#At{~ z8pzB&)ueT!2cYGS8re$Xt#!T{h0W%GxwKoK_Qnm?{4r#+$P?qVhbIO%GJ&ljk4I=0 z0`gX{vK(01M`DBf?% zH|!b+d$T*TkXSXzky*>}9E%FWk{N@|h0jYzv-3h19<z`@PlGMHVufYYd1DAUJTh^O)!TOW)aZAH*fd%UDZ^NRYZ08CVo@2>N zpGCt#1z$0S&V19_N$4~(9BfI`s{Pav27U=)2dtH)HT|{lf4kaq&zz;nAsumK;SmTZ z)#o#Jeh_xs{Szlp&ELE`AAPQ;gSyOskGVAi7WA}Zzp@A;(n-doRR;t=^5$|@l7Vt= zAqxmJ zw5xrYjPSWD47AhbCL8;KU*ZI&KDU*hX*I*&`Jct-gtusX_rmPOlc2Mc23I-XB9y0e zW{ZL~BrW~t&=5Ubc-V{{kQ&V^NM`2Z9C=KCBtn>a`;C9cbq@?;d##)4%JZJyND zTkePEv06zQ;ADj_v*!Bkr9QmlA1|Evcqc41G~ipisuJH=g&i3{z0g=yob|n2c>A9Y z58kr~W_dfZ4%CO&yjg{Pa(4)}{hi38exba#$1Alw_E8u7YMIIsNUxXTHw+zZ)nVap zZC>PV0!Jn#F#Qe+lIz`{P_}5l=pF7X`OQ?tsan(Fy^$d|JCY{n=cqm*Px$6lIO=`9 z5Ur%gmuLjT%Hhjc>5gXpWtNk?=3gf~C%Nx1+`h{THreUWtY-ofZv?W|C{@XQV?CU^ z;xF5iN518oRB>65W=##;E|ufu(BIDx6HCwmvKE``RDUTLeVux6HV z$+3YN!d!I^rai)x@7ViOu&*x?M-bM1uqGdq6GOn4d~7bnPLbFAC8#FdUpELNwQFUY z>|G`QuxOm@54dTlK0i67EBsKi z#^dmH4`s*x_gg3~Mn#7Xm|WJ8ceNi0ldx9YX-aG7R2%%HB18yjGvAvv#aferoo3Ky$9dHs(au=Z=FsN0pactGdG ze>6zr4Y_g4Xz)`Rz#jEim#QxJz$;s{gnNW1|GGE~I~L_b@jyeq`H2Pi>uWP#!jNB9 zcEqDzH-%Be!&Jhbtl?*$7* zTlS6S!2miZSBL)*N(r-S8#zVpjgva6iTh9VCC_0KRgaMmepHryXHS zQ!qO|R#}>Eri~+-+Wbt2M}5K43VUBW0tvJA`3lN>8I|8E<}al^klE*SnAf(^`g>yx?Q_*0QhDkWb^ixf2f z*(U6<(c@db_(9X=bT)QP9nbMM!eJL@F-_`?^WS)3d;gyBv{IAzuWu73jIQkM6ig_ ztvs4$oSj!b%ku?-qkVA3o=Kn`t;^qCSAi$Yfwc_RlHz*21>KYp!orV~`FK1@zN>v# z=EalGt%uHg;>C3$yQm`si+rQBUUjh3nAy%=W=& z+PmOlqdBiQs1Lqtb=Y1HXQ|UAbxf=)7d~X^@V3n<@;cv2{g_w4YV7rRhwyw=2d=nk zGVI;^kh!0#<>w3S@nm=^`_jQha(fnl?}n;_g^ms%I>ije-%DWUUMWcLm21dv;DG3` zi1e^^>gX0R9mf9DUku6M7QZLb4V<+@jo5{L| znDP(dHsDlWE^eW{|8c^pZcft&WAcMtjBkZ)xs#crt(r8*X%0FLJuRz@b(Q8lUyZGw zTj1saBOcg09A0Nsi&pf`)*DR0#3W_#C;h_lc6YG!-^1oNcIL}(b%lPj){5;^=ZDX; zMjN|6aI&5}zW)0nI4KNb#=oxf1)klp;cAKC|3jC*sGJVlug+re;fm7eD8wD68;gq< zP_~8s6inT`7S>JG<<`Ty!n5M;EPR@}bbh)aez@o=JW@3&aaPn8%HDaf88yayQyF

    (;)veuZ>JVq?+Z}ZrJjxi1SL*O{1u1eLdr$HlxH4-3UMhbmb06y})gMSj zt-uc0iL$mGOYQLLtYTK`O1r1u0T_DnqOiV6izmxW;qSC{?CyvLUO@br`mq75j{ISU z)T-kd+V29@lY47dK<+U~TtFE6u@$Sao3;yB{ZW)I?e2z0%&!&g2_U{ohd?BEHqbKH zfxw^K4gIQnU*bb`_ezjGO+t+{X#%mW9K*H!u@tlLJ^nB-P%p*<3 z`FjT3Y|&U4y3(JGH&d6sZ0?ETMlE5^O!8Uk8;Eb8=7VgtF_$G;!`cX4rm=@O&*QDp zC+Mbd>o1+jLGOf_zF7?EUXGA$#Z;AzLIC-0*(=O|qK|Lb)s;Q@xJj$v@XI@50quXQ z_D#j2P2HfQgElX#a)Do+7qZl-e>`o7CT1pG6HBi+OR9!8_`-Aww3B}J@ZfL4>Rz_& zIpIa&ep|8kl|O>rR~$p zygHhBq$*3x^7YXCXuIF^3d)HaX@iX|N8m;R@rPZ$3PqEfMEwD-Qo+)#7|=ZfhAYtC z@a9Zt=wi!eRJSemc>&V|;41rmvOW4WP);!}KLiv~<;v~{atGH1P*GO%+ z(^Z$}*{Z>gd2x(Yw)6B6jA#=d6wr)zX(GBx&4R5P_*l!SVemW1J5)Z8s`SP>HADb?GM8*M6#CL zR^Ix>67Rcx5!aI+>9giu==5U}^n0w!vj(ffnQ4x!zcXpO?6vTzUy5-0m=-VGku0zI z8AHAJR=xq=1jUQ{*AnN-EDcX51R5WGq7V~|O?$>uiL+%(tkF!kZHEPSz- z?=CR8q|1-Esl)3KCDx7JDGxyl^ZGm#&JU&UZOl^nt~QVE!P{qZu%~f>pfkjt-}Fub zcHk3R7*WfQM>^uhkW@C$neO7WAXHdP{K%K2Sr}pt9%mES1=9EVXKBKV*_Vq`Gsw>~ zUJJ)>oDR$P=<{1QX%9bGnO%M7BBk9VJ>8)O;qgzxtG|ar%C0Q7^G!2XN$ZN?v!I# zz3H>~koJ=KpKb7b63zcDq`N==LB6ZCU8E+RQk#oERL;oM=ebHb{%i2Vh*k)$HRdrZ zCW3Nvt=LR+){58DaLYwyI7U0K>P!#l@`e0f*8SyMPOD;OI8a}(d z7L+pdc~4DGFx}LHef3h8>U$bv%}!S#`-^djwvn#9=5vo~{-jGOn5u7Kdx)!0@pCKw z7#s?}mT2<~pJ`BW(4R$7{oMCs7}}QA%KCe_65c)?w@QEu2N-a%!4raq8n9W!sdKp6 z3)?eGgfENLxkFz?_#Z##lR+b2aO*ZKbm+%?lePIT!^IHaG>4rzt|;CAGa3s81JV2g zWoLw?k?uPig4{arTZJQF=BZAs^@^JGW`G0k7;Gs#Z8azByAq`IR%bY4rB2pYLfljD+Z<@mzLRBYHgeBRKVh?VARD`c`e)LrA`&e>td2zVkje^tnsladJFo z@gQ|+T%9ituhJ5hr;<*mG6>%qZiZFw4EUXrPS94R#rjaqKlaQ9)sk-tX9_g=#f~53 z7`}E@DIf8YW`r^B!UxLVnR0u9d{?`z7kTnOSp|9rZi~|iBf1tf1M6OQgAkfk$Aq~- z)AfZcan(PbF;E+QZd?$(c^BDJ)t#jEPIpks)rA|jdYBb<>j@6Xg-Y(vl=qjyI-;VuLGGJqZ9a!i6SigbyTE_gy!TF%Dzg^t6$3^opl?ZWm1 zXq;ceGWK=gXC5s9|LYgTcgIOfz9JpZ>?5zAXSzJZVE`0_MY1*6%KIO%!eb6!#EA;T zSIO;zd%8^qwR~N^)J_v(`a3dj7iVeb79G49mm=A<9Hu}4Xg`E|j#1@rvU2phS%yAOIr?1E`0wRpb} zHSikJE?R~WhF`3MM-m}=5Hy0aB8->ay@*S0pk@xv)3!8aXm^&_hrOX~tpXO~5j8g)= zA@l`d7bzVfVnz@fJB~bax+`GUv;AcaRP%3;HY#ZDMbInk!82~}ho{f-i#wB#itngg zj6byueh}w#WRGyjpJ~Ou(~ik~=uEuY|CG>vL8HX)wu_v5f3e7f59?+RiYv-RAZ*Ye z*$$JA=|hiETKwnGuY&dK$xL!A+bU~@#K?C)Gx>F?oO6pyz;>mviMV-o?5_J73g zv`_gzlCC=ttM`lBdy^Fj$<8cgy!RZmv?rlNDk+poo9vMWskBtudr!HK=N9d~cWLiM zN$7XJ@9+Qb_YLp8=Q+=3K3$lI2c9a!mN;X6OWO}R-`>i4Ha75PA9b9f8O^rPo_{mh z9&J;p1Dp2kq@Ew;82-~IXSwQPAAC!@bbzSG&wot@uiMEiGfPq0f4V0w*;ZElnD&#P zC5gDmU>R&!N*Q{(w1={WqI}O+PE(V<^c#R3$2Q1T5FWl_Jb9P25PR=5;3s$bfWch@ z=0zM+=LCOTeZ59-_^!rvjwpdcaxQZUXyTL=fjz38de0CQ%(6Cox#w#gEf0Wb9+;iBYv4}DLf`k<`Bn@@;$%f;_saQ zdJp-Qn;4(qB(?ibFHva>C%@?N!O>Z8WYS>PgE|2f%3`s)(`{K}ii`BhDht!ko8j0z zBffA$7~#yX#n&FhL)i?){pKeG&DUDIVWgPz4XF-gTmTGww07G^s`>wHCNxPcEgygXBNdJ19t+@ZSUxjv4>=;k4<3XBTQPaCvD7vQ0 z1IH#o-l;-%`tKip;;szMXSQRvwoz`+nndihAR630>hLSd9Uz@-4j;~(0}y5 zpuWWM>7OJ&RQN8KKFx$L@7^TzYEfc;%Uq<^$EF9u%%T^fvN>rfclu-732m^UPIG-tb@`ls()N$f z(6|fAY1!hfD|B9;TZmrpj~SN*3r0GzElJd+h1qxazt(Ountn*Uq$p=QgR#NJCKyuWN;4f!oAX@`<#?(9i!n0n~<2Pl`zv z{4G^vx%4-`xOgdAMl=a=uEVXCDan>RqxHOSC zCQEB5Y#hk!=c`DI`Y7Rl`kdPHgfo=sW2Ym>q1W)PeC+#e@Uvo7brR;oJ;a$ zj(O@5ZZX5uXjj4Ft5J$y~9c5Wi zkIB;uYSO`mL0HXQFMXPl_fUKr|TSmQO-PR`Y?fA*d4d-xen&Dg}WQ%LjQTc7$kj9~+v z^}DuZLf(-9tUq;j`^AmJ*G9Kx-V=zgOwGn8Kh3atq#a+PF^=*U+C=8)ENSc=j{YGh zgpQ-Q#Qp@C$^bTj=KSm7`nYVc4C4H)c*51Cu>bM}k=waQcP}o* zk{8ZE>I!KS7L}<>7lx^#m0N(YX~QqR zUwItXEB9b_esu46ycBmY3x^w8`h5L?Xt4T-%;dJ3q_{K?r(f3+fad%@uMwD+whBVD zO?c5Z2Pg+UcJ#QD^!L33dVjhg#64E$k2}2;#xBleONig}+`1lZZj=dQR~YeI;dA6! z$BNzB^Q3muVD8I(;@g>|y*!bOgNJ%T4&|)Ajq#Lga!hx&@)wT!cq_P8Jo$`v$b*g; z`(!+E<*X$yzdPcxKPIegHD%=L zrr@j>(Xho;hi6rLLEpY3SnNDyX>_Iu_VrSbHN7G|^IbsSUg8wfRD8ZODE#nSC$($1U9-!=mxoVnz{pxa=#i<>^!SI@pNo!W^jS z_)qM=nYv4UW@DMF0(6Pg=bd|p!Oyg8RvFsBx9hdXe!G&`CgKI^+fi>qCqEc4M~f#= z4^d>NUd-8ARa#y48iKB8$!3t=enU|jMECp2?kQ9MUH3WADf@t^Uh6F74$C2}g*)Uu z*W(lP!XP7aEL;DW_}ModvEKKs7^_6s=5_(IHphXdE@gvU(SrZ9m+^g_B<1ynxS@5P zka0(of7MzDz4MCL?{qu9druJIkWU9WZvQ$= zQ5vtWh=-1E6Lpt5NnsBRG2D3)tTHv^R_F6zn4rqClwBlavl2}D(Ikwm)8SvHN5OsN zToyj-FF$4>&KZ*g0qt)q~HT_zp$^r zX3fs3E|hJbNB$`jn&D3H@!1V=DV-hlbDi+)M}2s4k@`VCd>77b7|#k@)ugdk=Az%S z!?J>frvwY#QZn%C!jj-w?^+DW7hAx*A+09x- z$$vl?ZjM}0olMW_*EcCRIb|6<38&7fDcxZ7Z(rtXp)M8sSm2>n7oohvcWz&K9o`Hr zXGO6tl11+d+&5|jyda!^YQ!{o|KP*fYSM;{L$F1+QFgQ!&9p01F|HKxm%9lcO8SA& z{U$7i^vqF(0#*fb;d?BdJGMFyr?ZH?RcYe0*W860d4VjzTZbPD%z`Dc(^<<-MQQh- z(YWQAfw+VA;SRYusCuRdq83xP@23@H=%l`HmiYcH%PPIhH$C!xY4oV8N+ z@|_HQxN2G>@>IfjYYg$=D`TjooL=kJOjv%PKkGPNO?ntN9xFX>%Wf=pk&ZOvVBaC; zc)4>&%7KZ4{FQ&jar8`{jR?p7`6q58|-GwAjgS% z)h`MwWm^1V;8!8{Q#M=Z;Uaa_+<^BLR|t2~jQPG^3&1t*1Jk?mg9qlyaAI=-%S$Fb zQus8Sk>v^IHJZG~eot^ZF_WF%-pVx$4e|N(TCt4w`RBeaIM8?kcxY(yS>jhgn>MSL z#LwQf*?=SGkWZCPIWxs+P$(5JUF|>oW=;s^Ol`+BD=7P`dKw;g8x5_5{VI;=3IqMa zSxm69q#tOCJuDSuX_T*`IKc&dw(o*>olJPzVMX|FpZ``s+OW(GxIZu(hV-C&Yt{@{ z9&X3}(!S~#mWyT@+l8AGEx0|8gaf@93tj5Y@4XlU-m!}8YAbaX6eE6D)`95{H2GCK zZTPRd#7BejZ)2VVoXr+DFQaE;?FM`j@(g-RH{w?a_X`&PiBGC1Zz?_)|0F7aC+UJZ z*$seO$~nw1@F%b7Nx7Gwrm$Bu=e0LeZ^AG?SlXn;m1A_^zpUdCvs9%>vkwp+oGrV2 zMui{zG#jd}|72fD!{2pK4h(&BQp~BNuDV0HcxakCObMdz`euJnjf!O>%365%E<5?0 zH!&rxPQPHh@H-CHbfx|g0|U4|#gVNXPC7s<>fsUQ3nMw<)h~0P{Lm7%FwloPOKnYodhnj&Bu}w^6=Oya}#Kn*_h! z8E}&a`Owf`l?@{Q&gliE*m3Y5!C(UA@-2>%=i~&3H}fxlz44)w3du4!KfP#$7ba%>`_Ci@nBOd_S5p7%(o|HQpaQGE z7;@X+0r2Pa78Xv)@!Q_%;N+jtEShk?VS27;YY+f+)VFo;+E;lt&U58je&=9!^qI^B zo$cDZW!F?tKAgzL1+?Q{T9ZM&W%ucUG~17rq+<8=%b=C~h8N4a!`=>E*)=b9Njt7;VXBkr$@WCKw0J;=;B48hqqz@+@Xjw)t@C z#LRpMZj{@pv`?Eq{GJ6qFH%_{-8&-N#$fqH192|ps}z37#k{R~)>&MA#8% z#3Qww;Oc>L_K)&>9O|24Qsw}rOFF|_i6+=|RR$NBHIJ%a4i-t5#fg-$wxpsIeAmYpamDBec+*jz_eqMC<2H%Y)g&7P%sQ(jJf?jIfN%W?*WKbQU0F_E&a0l#b%ZA0`O*`tjb<{{N>iR`<_?wRAF8kZ zb&`BNT`{2V1Zek!G~2eMgC#ccYAu2sUZFDSvc>`ciHh1$lNLTz8l&{(QO%Jgum|b*Pej z&JV06-IV@DtV+#>*Dm_})X6l^o@dXDe-I~oI~Sjh+%8PmZOP+YMnlnu8s@I+z_V5j z2dUF9vEGYx9g~C6q`MBxrkUgOR2QC4n!@fZ`o}jvd=B&Tvc+~!DfhC=Mr^El27l9x z_?U$Gkaho`*sg_oiyr6V+ARw3b}nInr~5(6BkIvu(7+33SYwNKGMh%4lQ{!|k!ShA zw6EIyhNKHyr}bgxMXJ(7g^$oMDqA*xfeKIBJs0$k{bZT1t+& z_OLrxDCqOwRRiH+a4c)oY2j}|JK@E@Z^Z5nafWan;mWmUF~%F*Q{Ki zTw8YUJLz!lFUNfoDujrPc6`9IBzQdU2HTYSgD(LOIxo`M589oUFN?;_y*1z^Wli`` zw}b8@Q`zaaZM;rN8S5&yh{=SXKdPt9tG$!pwxrDqy5+#qIt8|s@bj%-mSdFoM`$}u zI9tRRu$_>@MvQCb^{u{mY?KO1=tI53+oKVC_(Cz=4Oe^GgJ!@W=B2J8T{)(X&)x>h z0xwX;HECA6c02)J$fG?=We)c77%l$iD;%s>hMiaE!EHtz9786+<)s~%FL9bSx-;=h zw*$hpVvU-IEnY(Yw_HjyZO7HlxPzV9EisDpz=liQacvI+_}!+*J@5PzdJB`;@xN-) z&$tYn-sy-eXoZUuF`*3Kk8Oj*4es20*0N703TRC@s$}=##PjQhHyKlnKm5yM&TZjAA%#iDF zo+v3vZ=MXq;aV%Jv*=9e88j2sE-iy^PxblH`~WD_>c-ZLQkN9VtWmbzRp{1iTywp> zxnOz9gKdfV&XYghgVy8aY{^X8(_jrPh3={B=XOQOYE>+@8(=6_(wUxu`RHK3h9bR_9Nee6m zyDWp6(jX@}KEJrog1@|JO&z&c#L4qXhjZK%V;xPvgYrh$pB!-NKaj;-R+CB#iD#L0 zN7kEWe%X$EJi5;uZ%{XPn9dORbMmG5iulu>JEQTl+DYMSyb<4-;sRrpRw$m(qYKkRaWUxSiG80@2VWi(_(S~>mU(+%?TIB-KYZRpoqXV!`qqa&Vi?ZB* zMB|_IvG9}nWkxdxaKGZta?&*pyutedV-Xl=z_88`EBrBg7S?mq6s zj~w8G?Wx?3NL|cg6Mg0_xqcKpw9NbC!;qk#1PHCty zCDOZgo9B+nITr;jCoNv-_FH(amBX?~TlLMP5*0SB5c*ILNY=1sG#S{L2^H?vO zID$Hu3B&m`$`F?1Okv#>6(sN5Z(-5*Y_ZD`7s+{hC4$Fu_-$y&&y7r{jG{L2TMhYh zI~SnAMFp5tY`{-l9t!jIbJ_U91|D1A5%*LjGi~~r)1LLhjB9>SP^-#OGRE9SC+F zF|5B+3%}ZzGNvNliswC?rG&!XShQ>$EPbKJ_x&@0l{roiT~!*?20Ks=u=&bUR|D)Kko zIr*?fjIN;Feh@WEU6=&U^qmfvkq1f&N~}f0Md~?n1?pNg3-t}!yhr0$dA|Lz3C;Xx zb2rS)Q(>kdn#(Fvw>#`$F&6A4^Z{ zKP3PvDl~Ze6w0RSDq~60==ncXiRz4vbYX`9T>j^^}Xo1@`1vov@ke{e3 zf*HS0i{+GSdV_pzFMqqhq>qYH&hsF2KU-V1KhIezUll_>xUuk*x|yDSc7X6Nu1xEb zx>R4Si^hWjg%Q22YQ~xA2^;rVvaADoe28xW98C`wPZD3e@W2YJb{GYxN$-(9D_-uO z9igr+X-D+LLC3X)e>CUkpNqlBz;fuSqRX8IcZLXU4K|HD^%@4AsBw;V`xp&=vE{d* zH;wYp2$!o|xfzdrBxjJlF^^Ttf{9;0u&=j%@Q{>He7lVJ({$3CrOl!CBQMxZo@lde ze$YF77BlbO%14!&(!X0PPNKWp;;UX5S~~$|r|9w7Pn6(%Z##CFbWOVDn=$M54`CPS zH%4}!3APXNnZ;}BSgA~fMO%EuvwLaJd@=_Yn2&+aE%aW`3xGkH;Vi6+vb3tb6@E=r zkS$Xt{h^9CuI#cKV%t&I&uTp=nWo8Rl+)SwZ8N_7nhkri^!U#9^WpU*d$#*B?PD2* zIO*WgPGbinh5HXk^~82mR(ArGda z6tdzoEO5yczZ`dwPTFok+cMhqiw*ghD|8MLC)@X)vlP3!5NB#C!sBkF`Pn)IMw(=^ zw|yFT#5z0dc_x{yQKj8xd|!Op=tpOv4i6z;&w9-;c6Y8S-3uDwPg%Ci^ppxW+noWO zel@UdQ_cBF$9$-ta8m4a(^-1;s1QH+bpe&$dVG-AP`G<=EVC>4%e&liL<6n2Vvrqm zBWj1?zEk61JJR2LwkgDXb!2pz7J&t-iUs#&1&fjKa!Eob3R#)%Mz1LKL^43(* zi|!6^w-61JqF~SoeO^CwIGE@Lu|q4Bq(i}7P+K!C=q}+c%Y4Hq%W)(0i__#i>UtgQ_Dk4<9ZGSwu5;!G^HJR-Zf)U5l~vEBoG2C8@K%p&9FocBe3z#U{5~3CR-e&qGreE84|t=vGXQ2+YH*LaEdq~~ zvHUqM(izV!SnllvNiVhee%;wn<~D`h>#8JqBn-oVgS6Yz&U5C>T)Ye=F#eDhUt-b& zI=t~IH_J3WI46v0$@bt4q(ryJEMyR>F(XhBbe-xeFtng|k)L%y`d)j^I7|lDKCT z>6Fg2$BKC-(6maI^OypN$r#KcNVmhjC*usAyE4yJF4Dt!MVRhxft%JD^7sznu<-3` zv0Fc9>EXLrESz~#2q5qI-KP%FGNpudYp~$o?%6@P#X_-`Fvi*&?Quwe09tPixpQ7I zOjZ%a>cO-#E3Cpjqg-LrSw$)An1GrWYpbS}Qg>?aIP|xOgJc(6vvCmR3czBZX ziZ28}pVoQo_^Vd_cB>gKA6zG%B27!!V{bfTFcGHb)4lSpA`Ecs$UO30qz^$`uqpVb zuqRH7Cy$#c_s@2l>%$KnDuGRL5#r^ml;QkjE*>65Iq#$;yUnP3&Mus-j#HKbe_CPE z4h7j!7y56=%NZ578`g9%=agFwQy!?XF}jpOkh=~B*uLd zrGDZUC?1q64th&>lQmoL^6TeNw$Xs6_%DR{ms-Uw>auorJExI=XzY&IDpe!fpw zQ^+E$zZwPmG7b5JUZWsno4^8kC`nH)dEnB@nL#Clz5F}YA2(HQgjKr@_zREr5Z|K8 zoMzD;+pz-*{Fb2EsLA8?^I&zE1Jk2Bcz?%o-08JJ@a|*6_c~99K|8OrEPV^Ew|X<+E{Eu!xc>Z2Uh0sHhxgqE)4r-lNs zxu?i1?8(0qT8_G!e}&sib$Mo|1ZX~($4sfeUPhVZCoie6(r9OC$)Lq);ALu3&aAC8TD{gc{S^nNB;MtTk*=kaL8Cp`A)Q_ ztw{nldne_B-ipSI4!>o6=-eq>l8%eiL$Kd)I?MX@hq&YBtblZ4ISc#ax>!l5)Y0S? z%Epi%UBJf0HSs~6-ouRIAohszMwYM5mHVnT`uXy4VVgkjO;~ju`HALbEyA|Diy(fl zHa9383_l!=nLT-aSKRJ~h4Zb1U(*b0t~YuJ-hL4*tZzF$&%Pscjy*5VpiH6rLI?C+ zYXZYw>+s|c1z>b@5G%}3lYWU)ac%P*ndKqs5o;vB(gNyQ{$k3%j*W$N>%WM469^CA z7mph*o)la^Y4ZuaouTL9Qg&SH7wI{P-+$kq#W3=Z$9F)D3<2(28*%T}#n7Qb6i@Xb z?e~Ooe6+$9?mSeKgtv$*-Rr7$lKw=kA)aywW8sqxY2Ko{z@c*0C?krU~kEi>4 zIUJpB#1Hs*LHjkjtb%y_1Fl`sx5p*nVGniw^I@x8hjWy;81;4A&?a-G(D}U)pV}t} zmJRsG-kF&5&x-S)*VR3uV;ONhf6{T*B`Tq!% zaghTPGO*p1F|Z&}hyQFR$mjg*pGwrBX@hBL3bKLp%$zd!L+`xZ5b)NVYgrgVPL(=) zK-~I(C)@DWm>f9YO`Au5Bj1p1M^;37t(IZM*bu)%xRbBPmluo#zsHA|F!cu?tLK38 zYLBvDTY3(Qsax%l4p?5$;lEa!!@(oTOm@vh8s@Sc-_LvjW2hHft8F37690-DY4$3N zFUCR1ictAehf{tJs9_e1NNC`V3p(SMX({Yud(vxdABb7gxb#|gOjplK>K{Bj#*H6sgcbwap3hGSAgHd3*v|-+NEoXQTtgJ&>yD9V=j)AbF!{x z#L0GW!`>F}MAbm*9~n9b4@Jbo`anHyebf?~dpNPs5hl|8L|wFTixKk9sd9U#YoK|U#_{6w5E$x zS$qs>IQvXQaPA6jZS41sXjgLrI#00XJqE9V zCWqYWk+hHXdbAoZ6y!s*mL4Ailfi$U6`PV^%Ez|G!AjTlGKWLzHNX1xkk59j7dCwJ z;}Ga)_)?rr&%F6XKTLjR02dbM@WyYdQ1)yhE7?qbpMTlt{Q8J2VFPtK*sVcSQXu`S z3BR6@28M}Eq9~GonY?T(N2PHiJIjgg*bEULYKF z*5LWq6~R(d#)i=Dw9sQaF1hJMnL*n8-^Kaxy>SW~K-_weSp-@nuc~&V-7MZOZ z0!rS7oQ3uRr{&#Q8{zF;{T$G}##IP;WKt9U&Q_?I;>DabC=2V-Yp7`}XML6t_u73s z=AI0P0}9$aqSHJ$R@sw{B5qglT?__KZ<6hyxv_QALUimMg2xY<@s*thfo-S-J4f2B z_BaRwY9!%Mwie&E!xUP66f*12P26zkXWAiUtfzt&Kh!TD9Gj=HU!#2ZNYzR>5ENED zgU<0@uZnT4MltmDGvJ-KjshKfb9RV4UtiXD#|{&$goxV)HMLW`)Dn|dxT zkA}2u@5Jw3$c7fOmKX+cm$HtL0l^{o*=t=RfKeN$Y{iSrb9Ug!)O(X@Xm#J?l@n)6tGQ zFimI>dWw`WzF;nREz4)?VtlxB$qJ~n7$pYNK7Y_86Qk{7Kyxzr3pB`!lorX%jFhD_ zO}2RXxPokuKWXpp^}zElcEd~ROb>Ndg%!Dt;_cm(laR6lH&RyN;#3_zH!lMwU$teS z#Gh(jBe#*bLl}BSpFi9e2@YG2unYw!er)VSnBSvCEG3=E1h*l$Q9~CN^wHtNoh@Oz zNixe>uO;anP(_7NOT`t}U8G&xcHqT_FCbzzXp!*Ad zHbU;7y4|jUySO{yh{P1;)QPx&UPI7(Z+G%0Y4f@@7VxWcUp8l)ij=(cAGqDllI>cj z!dE+I!wZF9Z07~a%>SGN&m9hld+O=`HClp~H9cUAiXQJ(9s&DZsPm5U+p7(_VD_kY z;#b1GkNzHlN4LkrqTSR}<7Wkvk2|u>KQyHyi&b&|i9y2SAF5n;eh!@VEntpOHhf+G z5?JasN^JL%yw%3kbCezpovZb@>7h~ZHzSZG3{{dW+I-|Qe`qA-&*%-sT~?dm&NJ$- zf7ns3t8XI==Vm8+Om?{~cs`G5NClOZXjfW3)q=8NCUFwaX>?#0{DE)g9T zc7?``x_rQH4^Ue`{Rpp=CDo~hIC*`DtUci&3l`gBh2}|!@6m<79I^-IS1zx9FvLYV z)o(5StH}rdMS46dF&VxGlMbhna&n?F(J|wopf2mo?|2V{n^B*{%|D%_@BRIea@C=2 zGj&o>2bZWco}FK-CUvyW#gQ&YWgU+Fr#D`UJ$ozQq(6lDWXytfNx#M8H%RNAk%?8M zst~G0{sIjEHT?=^Sl_@eKQ+Ur3S(GzZORv#;E#EO1L2pW79YV?VP`Y2J=+N1xUd6T z0-RxlZLelKzJN(o|-}&JO??G|;YUZ_r{Qehr;MHys;H|F3mmZl%zN=97rjxp4 zrWJ>mPc+Hg=^n9HJqu5+3c>xV7QA-^WkFxEWE1Vk4{~7$o_{9^b>3Qh`#5tjJzK~k z{x$JC2Hy$)l(GE-HTm4D`EcHC8jA|^J$ zx>~STN$S!E?EpOZ&`P+nSGOjx%0n1vIE;BxM)aZ%4sa*tg6Ot|zKc+MeE-S>c2F0v zV?_b1O6kvD4X-0?!54pqRLGo8x=3DiOK^Xq1qNL);2HO#p&;+I_&(KH>aCH85Ozw~ za+PvrUwXibwlbD*vyuB1sN;V=*-uxUq!Hv_i>w#G1x@&{%2IizvDY{kX;IW#3=eRF zV)DseaPEc6Zq!u;(KEB9Zz9hA8w9BCFUw4> zx11hf%$-h`K!w&=kCWx1Wzq2*@XERm!PjA_^!bQ4NvjZ2mtQ0m~GUS84 z=E(h1`QGNdVQD(->$O+hexAGxvoo=Nm^WKN*d$CqoIvQk;_xdWzl8~|pD*f?b<8E+!p-r7`>hN}5 zlX&-`izKz|z}ruAAn}wg|K1}Lc!WLkG$I|8{}Rl2wL=)RN{^2vpL;^UVOAGt&rN2; zg1bYb_^=Ooh?<7rEH_;!t=8eayvQr@A(_=LRieJ~76{SF7rh-_rM`W3V!zmWXx*g4 zk#HOLpTET&Fuh+m?p_6>KUo?QcsBJ^A;uUqt-6Vdn zPkUH>Cye!=zNFw%1^iEMIjl~FI(kSCS@ny3Icvpv2zeQwF|m^NWb5*!Se@ztrrUIR zmjRLBUO$#~xbT-p-uJ+*W8aDY<@TDl>2TSKDPY}H%U15R8@8vTSeM2uk<18^*v=NY_u`{mwR@BFw92n z&Y0_Y60TRe^M}G-2#H@_?cI+$5st3Ien0a;_W=2S2c^KXMOJLaPSU=f&O)Cv2Zg9F zYBhng1LeJhe$y!TyPG+VrM}AtD$dfn4}rMd(-0<+cBmyr6TI~%GG+2Mw%ePBPyZa1 z{i|`2g6-B*R)7L#`kU}yQFEcpuSwi{n>1rjvhcp73bll{4<8=_+x#}L@KKGtLDLd- zcaLGwR;15V3Bu^oKnOlT+NwwmnE3@+A>poreRpB!G-nv|nC_1osgG}H3e%xG+Q_ld z*#G&eYA^cymGt>1%}e2;8fiOA!^kt&on8K;F72&$!NwwYp@ewYi!q;}SMh3AvDHP2 z4&8-omQz*|)8v793t-mVQ0DnVO}g@FoP5rQ6uU@Cle1CxRR|{7nDPn#by#Vevp~|z zg+~p?QI=oFg`Wb9Tj>DRA1 zOGdtiT6*U5i{acZ1FqCC29#ATSR-}jX15DM<7O-2_cXnlUQfIQaq4iEVPnn>G+dyq z_OjR_I!O&r9MI6Z9dxGI_^hZHRPGLD#;eq&>f$*VFW#5ECEm@}Z5dANVu@LA%=w5d zli~aRAEMDhdXM-NEG<1HXta=)U|DwvShI%t`TXJwS82-k`A?*2seR>u4T=C$_Zjhf zk)`rXV;N~$EZI7grn|v&H6`i$xIXyT|6G;&VY+uy-ko|x9Bd*kY$j<09+Y^p2wM&5 zi=(-G&U@>2sCgdQUaq&C{n&`t7L>w}gE3+xWpH&@S&tnosV|VQkuj+$@_qh8KXpkt zdoW&puOqyELFaf_63!j58opJK{=C8;zIQTU;(vK54+Amn)g|HJL@nM$TLYGU$zjLo z4rr^r8)5h=!FL07xbMz~h#wzWw3j*0=$#4A_wE%nNe}k8G#lHm^M;FaX!je{2d;)J zWWPVO@Z}9QSd(8T=93QO&?Xr+`6Pfc@k(t~x-fLUJ+n=w>~59a_|&jbIK{R2^XUua zc?e3w+<8;~<&YRVR8+a=dS# z81ULDW8stSG1fS`BR7&_Vep9WVhw%fvVJ3R%~)OFq>YI^Yz>V&lUURdMalK90{TYf zi6id2NJCca#;Be35KMUs*pdy$?*A3{w$a(NZW*SuQ-VRy2=lp2x%&sRSnoGKd2X#M z>Rm};-lXTeG@d%zI`)92_qBQ1OKUkkfAhVH6lJ4=S|!=CS1(m~{GnXf9QB)7MVfQX zq{VQl=9Kt>&Z&is%W&ms57_=wk0&h{1LI}mSVlPY?j?9(W8gb6e>i=`Iv#vZ z>+?;=?7(fl3u{d@mPR%k;poUQ!V#GY_o2MT5nuAyPTfDeyVpca4RT@Sbl;g|20~v{bDEZ6|FMd|C~-tJ5rK@x8(vbAIp#Cj)W(u7ymM z-l=oFQ*hj7O)%+Cy4>%cFz@(uR&}k7hx;2~`yE@wI>|}8j!u+4I2nFDB)Qm(yPVBH|zV%8lYUHajdz$lId{c17%dT*i{52=nc7uKG zN3wR;DNo6-9o~HsB0ENz{A;H=p%`@%rh0eaAx;}$N>*NVIB6HteJap3qyR$C>vD;5 z5&!c~)$SuKOD6|q%7=t5ZE7{%B{I48X2#*~ygthUXL{~o3ka_(OcC(%1i}-k>+^`7 z7JRfC&-Rh_Ln%KWwLcz}{krHP4PR7&P1Oo`qS%- zp(xp;=A^ol9K#9jqtDMi)PsGI$3&&m^!(TEMw!kim>)*Feau2wytpT8pgYU#wDEEb zCz{TMkC$>V0z-}b9ZmG9?azkmm_XY{*7 z=at~hL^?ZXJ4*$DDHy{~39+jTxWR5eSSu@M2j*DwC86GMXj`^udyz7H`clW12S9c| z%8KzU1DDxc^dgL+Q@0AdKw9uS=araWAvG2DX6?L4kE@I@`IEUo_gJz zDTo@9{$)!n%8>~lk6G2Y2v&0L^;8cx9@%p*tc}eUYe-viBDw-cPly8VC&Wp0oCfUHi7|}SF zFtBx6$c7uV^3XP0T=}F<96;Rb5);I)0~6pBVc<1$srS%_e46A3Y$)4MPr6^6aI}ME2m7<@36yEMQWf`f$(B92sltOU<-yL~znM09PaGST zLe!qqVw&22S(>G&@Y4fA`{;4q>KM>j5XXAIXyzw$edPFj&KUARvr+gpXFS|f*5zSm zY~|eRxDsP2a!5Or)r}EG^it-xy63_)_dNC~sF~YNNklf>m2IZa-$I{1g?dAWk+16U zyD?DzBY>^#rX>A((gWX_%?kP%O?Qy$QJB7U6C56B&96`Qh3n&tm`j!zW{ zF-`C)r01c%H;CI)nUd;1-m|9>{%P1M4!upcj| z2J{bT750_WdD=QnKHHZ;Gv6(R;@;h=tfh=_Mg3IVL^+}rq+2-F*AE_+3}@z=lrNNK zh6VAVvMz+N=ry=tQ{G8XpQ6vV6_>z|p);z>2)A6ZbpyuED}c<8lxf*IQ?9q^OxmQs z8M!zp=8(`UM7^eiG0L^{4~?k{wE+=x4PkS$CQo0l4fPrEZ2JT?Np*Yyj=XtPw&IP8 zbj^GtW@;$njZ`C^Z!jM||7aAyzHydrugFCUH#O))*rsbhf3OPL%sLHd;Lo(I<(T{m zGs1J45bZw%LIG(5uGZ+n@h+k4DD8NaPJ7YH)CHy;A^+($;$N<%kQYx$3STl7+Yc?nn~#NSPw7Y4(!=qS5Z#FjgF1u# z=o_NZjyj&QrY|P6wg@S7PNg5uggv&s7-*?WN0Jh-Z^a+kPr5s#*yN%Aj8Gg>ZNg6u z8V)&%W-Nu?DaRF~Fn`w>LH)QEzi(p$EA|z!Cs}`Z|Jf}N(@kLhhU&b75orKsB{NOB zr;jU5!^IKp#Cx0b7y6!Q*PqRv$dzWmWN z=uz7szRITE=Jzx_pjjo%B5z%>dsm1nE@Q*OfAN+uU9{{xkR5#HB#nITg4a_4n!GId z;aO`zXZZzjP%7z2cW*!?Yj-d&pniwo0eHFKeAR8@&{vO0#bxBRb8FP+)}(6+ka@8n zYYoY~lNCO`9YpzMHZ{3xZH3YQImdy|y=oTH3H zX{S<@qM^MbWUmMjEg5a?EzjHgiPGMC?@xR0;&;A&|G+iwz2`aSHCys?;i2&n(eV|1 z#>z7=-^mk9ziIJ%T48Ya73t!B{^MWK248MDC90C{Zk1yIULg)x_@l)`>viBwGwtp4 zzpag^$H_L|h4>iqkHloaoqPH0keU|{_*4nAzl{+et2s!<`!aBDLNvsuY4PG213_uo zSY|F$kOHVX)hCi>J7ocFiVVQFRXgF6g*KmZNeA>4+rf}$8LE~!H|BpM#?qxUHDhjpe`+#U5s^eqB|P z)*rKA*PkD($WEV+cFF^bwgY024&hGMOK@X<${Ebl{+kuVO|(cc#Qp16-#^4#ejC?JNn!73Z;#>gQP$QOjveUCrv`e$^~5>s)?g#P?UD=3y?LTB@v5D4ZlN>I z*)|=PNZK5HOCT;&nPm(kKaSxhVz~baTFM%H#+-RDU|J?CZu-q91_z_mRhd06pp1fR z^C^?i2d?^P@%uKtVNBR?mPlDin^u~T=e?gyoo?7cmCl%c=qL!aq#@TYhR<{7H3rch za#q-cVXfJ)jeOavwF_X*1#`BX+e?T4%f!g?eZtpR)uzRt`wP$dX0aTj&wLU2jE>*i z$vh~}d|X|Bd{D0oYlf@yC3f1N{B;VubfkqFEDOcI|1xA*k0>jtaua^-D~GAOsp~{J z8J-^hF0QBV>;;u9^qrs#5l{8_+%Chx?!p$fM*kaMkZFax944@D2GmzVuRq9Rx%LZSlLGE>e&n*y=*c9S51Iv=wy4aoh=?rxEnKKGo2`me;5twYx0A)7(%rrYx_X zDy2BUqX4qH>F_X<$sJnC1yL$e+k$?my3#^0Yc}NFU0gud>x>xIOuavG&KQ+x2zPsH z@Ou@7FiLI+o0X#?ZE;CK_anDu?}=0En^cPB-%U~JrWx1WzX-;S|0(t?vX{o+oR5Jc z8w6if4Zbj7pd81U&O<#5gNgs4WIg^BK) zuur@*XjI8dz8eRl?$6eSL8Kum>ahU#4VVO_`=}#nLSM*=@?g8hs7i{fEzx|uOgKB# zswrr{jqr$DvM!IE`Fx#yU}c>l8g6rtVyA3E4c~F_v_g|-xGsdjq5W8yvWj$m{YaeQ zttsRZE-^HI0apC1fD~OLK0B%(gml(pmk1xr+tVMF_ns3v#i(*iYYjL)JdHW}a-RAu z2p>c{2|?sccUR~k``a7GZ>VlvFvg$1*x*T6W%M9lU)JY%~k~A zsivK9coTK6$Qi*tO*v+Ciads&c4M#CG=Cp!a2tb67_r`lwUNGh`T0`3sj*%7_``@F z+dc=f|A_3Sx-Jh;9|osQ?uySy%eUBXJRW&V_{Sq(n5DM zs+`R_g_7qhay-7g+Z$qtf7IF89s0cuW#!8hC8x^H7?qSJyIZBm`TJ~8b^poEFVp2E zExGW+XTRuVPWf!TR^ymrH;{j#!H*kH?7-oR7Z4V4zz6*Y{wF?)CH=Yl1hl2BiHw7E zBiy!yzU6kTu*^>SUFnMA_vOL^!i5?q7D3XyLN>QSlV`eTLEGT~(U!Qau7RsDJ!L$6 z=&Hr-yTroVpMBX7Yk4W*fOZw#$}H@+JM@c=GAEZ4#Q_Q09Q&A~-Upm92Z`%vp9Gd<;G+-d{>N zpZyl$bsII9Q{S0qp?60{@rSx!5`&Bg4 zmgzxz_*9l$*vwac48=V&Gi0-WJ4j~6HFzvt4nsfd^7Be5P=EWIc=-+avPaX-U#JXc zo%DEBzY$>RzJ)bwe&d4&cg3lbCa@*m)EVj*jF%GpA)mC|R@FLSaxQ?KI_Dr=8np*? z9ymbBcIvY4ozan3`8dm+#~xb?HIFVHk9bWy!l-O?|4|HuuQj=%=3sc;;LR3L*2=UZ zPt?2ZBJ}e$XmU(<>6r6)?Grbp?EKMTm2CBi6I{tM6mNR`7LLu-;C5d#U|Qt>X7F5D zGTu4^7n%K*^_QskN-+mDJp=K9sXqU?VI)`{HDu9!>F1swk4|RILiPaq9JbrQ+?+ht zlJk>m&5^^87i4VI17&_&met(U9Odfhm153C5du&j|&ORJmS>RtIjg%B_h{%MQlx&5pulFI{ds zBoCB*-mnXlKk&LS9Ukx4DMr%nF}DwSYOZ_21i}peSW^bYlvHLk_8&j3VTT1LPl-=` z>2`P>f(hd($$8IsyxZ(2M@xl7YhYwRpH}Ctbk)5GTFyv9$b0tdg%Kt zQgnYy+V6-QRJMqL<{y-ezdr)TOd89yKFdo+mz>dJzMSlL0OjEr55S_2JKqtcQ$ z22X{Rk3Wce=^pugF&c|>v|uuJ=1UxHVCwK`%#!@DCr>EjY26HQq>`gFs&y}6BhNrD zOoMMZoe6XH{u1BQ%C8hqg!TX-8Zka>#=(wcK>`1|1sSvq0zucLFpxa%*bOng&RpFH?4WuMs8(?J?k zUxvRaZz6a%>GZT>J7#`Sk}3a>y1I-OYm2s%sb{$+1~-kG0*|Mw^PnJGn5AaRQs?SR zUs}!3(qn=UJW+#xb}5El{fgM)aMF!@BhSdSexke~{eRX`S69P$SbB+cxlhS+bg3`< zFobw#55S{+7yDnCW-p1`WAGAGgU)2asH^P2@2>*8NHc#xe-G4Hd0k*S8eHSfD#%~r zz^p>3yX|QWu1()0{Jmhqv$a;iEqKMwq?z-fN0Q)0`(|-qK5>ZD1vYkq8Z0LcZp#7R z4ov>C)W*$T8>3O!X0e`flj3KRKf-PXEK1houSSvP_MswEBVDe`pBil6+$N}ZSLeTH zEQGQj87$twl()7lfu*56#M)ZoDcqK#nNlzKutuHt``jB;?nST*lywmG!yI>w?=Krp zc!=>956p8t27^Xua|c`v8)d*_)|@(kb`3zIc3rTaP0x!M1Gwrrl{qIhbC0!Q zXj+vaTk*z0nwL_G&-ch-S%D6pAxB+WkG_ci^BR0Pn}f?QE5nXwq~~lL3g_x-Sf^cI z`SNew&}PsCrfNrA-thtWw#XlTII3}*zq(MR7{F?2-WFZji#9gYFJi97?Mb86k2(>3GUR< z?7@oH8S^k#Yq(s;#gJ@?uUi$0cKW}BvqkE>`>;&dvNwbc2v?C7RL!D1r9U!@BMws9 zgj}3HGZ2H4^|*@GXxKc^kgcKb*Of&vD2;Cxx}Q?x7gBpbonu}{ukpi?3fQVn9*t?b z+-ycUY|~Ci9?dHbD**KhjP74AC}?ty#??(SeK8bZ1ampOxe`wD$?%5!MIl5 zQW#RD(_~Nw!mAgf*`yr?yd~Tn?5$6W66s;4jq$+JtA?=P7WK`sQs7%hFb6*s$=8-R z=y$he1z#u!IHnvM^38Bse`CJMX946kei9FtlNQ}#DL%j6Abg?uTpUNb@qgt^XX$sI z{7VnJKOe+;zp|5J7J6Wa0zy7zkouUF!}}jhY$k1tg?%k{>f!>MKgdgya5z@BpKkbY z%U*huv=pPiOoDRCqO8r9QC656GrX=UU2(NR%jtp;_QSeqwyuL9)myU%l!?-*a>cjL_)E986WDK>4wFeW#|dl4hOBsinAfW+i9_8*qme zfuKy>nTLbD)Qt_mZ#~Zoj?|T~x>XlU%rn^B>rMR9xey#T-$^(~dAy;63&8v5JN8sd zhtKbp49k|)iM!S5PQRLig02^=*CMZd>JYeAmclm1{o|%BcIfr|l-NIlc&N7naBSRE z=;5iuOUIbN`E@;*L17D@b|f7AyA=wPkdoY-SAg=eOxEeLJJ(pap0KP)@hNp8uXsZJ zaf@Q$GT0;S_R2sj4RG^lb5}oMSV|tp*YZ~9zs+N`OXCvFu_KNH4Zt> z$93tCdU6I3Q%pSm_>7JW1m7^qGCE&|&#Jcz;ly{Z{2kxH!K_)b#j4iz-a$Po7qbd-W7?8DwapV3`Oy`K*=;bY=2 zv6ObsXV=S+GL@mzH0mh7HwAh>PiN1DnDW%}NpLA^jo7%F`aYh+KHSbRT(G zPJz+Cqgn0zU)=nCZ!G`zQnXr3Gk<(6&OS5+!q;o_P79r3w~r%xyFicfVazf4zbHX< zBlRh7Du$hng{#)lOn)!oFcvX*V(CT%Y`CfD7JwF%H|GYs|SWlnBn~C_OlJXM${2YR2H&y=qG zw6A6$jQnPsA$P8J0as#Kql?3tGYC-B$7M!0>;oe&-Wb8{me;;Sw>l+ZRG(N- zdEJ>8-RcdiS35B8p0wxB?T$aU%Y@KwR!zTGICNn6{uQR&a9lMUZA%a{c2Rb#Sckty zM8V`fow?np1z>9}W1mN=NLSZHVLxjvVV?@=Y!@b>`^HLmY}B2HSVqCU-q!4UPudd( zhv9&6=Y_wNdvmI@0sM{2U`IkJ+wFP~K7C;)>?qRZOC48&W%*lnbcQQ;XkHHis%JzU z+H*$y$irFTUXb*gJWcB;FQO%xx!C>VEw>#JjatP&p2StD4??}IQ(-Cf9dzn$3giEf zmi|f$Z~hyB;Vp$iZId$pOxVcns7!Xz*^M`+ZvekbqeOXa2Wg>uJ|6xM1HRGZZ@n_2 zW9ElzC`jX#Jn+d~IoVIrnUoD5ggVjn@FkSG)UC|nnwcES*KOcRhXS$pa(!qrB`-#& zEHL-#${egI|FApt=DeesKi`1cJe?1rmB-nH*=AgE)l}dI-iYag>F??~1$Aa=!Nq2E zZZ^#UCeruCNxzd+y+aLcVrkFUb(DrbI)LfZpF<>Rw{&?9e9QSGE~m^=<$e`7Vuk{w zm{CT3_B0s$C7s2(Qt!qEAFO&en{^vOKCjRz_+zCX?EXl32wxoGMP(RU)KyV(wAaS) z)HGSYGm5-tZ9ZJQ`-^?k)#Lw63*o@+1L7y*2s-6dVCy`0*gAzUE9ZDf(~Ds(_kZ)^ z-+eK^V)}CbH>RmNntXl#$zJ+Y> zF%7=tVGbk=4G;%(qupRd1>Rmh0jx>KSZ_WZHsA1P`eWrKm&yIH;mczG6M6PhfAcsL zq-wa)U!VWB^a3}jGn1q2-!r3nVc);kh3E7vo03rqL&6=IL^HYIzs*?QqgvQjY{akJ z&4La3H(4hGOCETDa_nuliJi;rCApMjTz5hZR)3{j{S<_EhD+IIv5otkHbc*v&Ef>& zPb&(0;oyBUz<~C&9--y1b(1o?O1zlczs;z)k@{cS)wsd6r4S@!GMU;RK4;ZnyxUoY z6>g^7n>EQOOYH?bK$Cwi0LZvCjAcwwkQN-WM$?7;WjdYhC5J7&P3_EOEWnDkK)m@~o8Nmr8tP5-S#Cdj z>GIJj`08r2Q2&YaLiTivROhpH>S@(NW&9T)V+O00xk>Iyn9xFg!&~P3%eD$IN%U+? zob4cOX|2Elx0Ueit`n6=STkl(7?bS^JQ(D^=w-7M_Ra{~v! zB$J0?*?)G@R3pnTwIq;!LV(t zHybvNys@Wjv9G-#2wjbMx!gwBlp81ZyW$}29kT^LKZ}B9@&`?yn*@qa16XyIiuB7e znzW8uLIustQnM8FxKjytXBqSM8H3=3x&fO>&)J*GgR%b5dBLow8qext1fw%E*ngFJ zytnl_nA(&kyLniP8&>5*__+VrvJbZWZFV{66gG*!2qTJ_Sb*CryukCmCQtDi1&a4l z7<~TA|EqV#I=fc!9L-FJ6A_rDH4V(xQE$`;bGYo@oyD9v!S9tv;MbKa1$%jA{3NXoKe#ce0~$@5<1Obrnx zXlZc2VN>CO+dj7Zwl06QEDD~@zb}p%OKuXw)cH%v+Dz8Q7^X~9GUxP0@I<14NT}yoH!X_E+seC2w&ZfMJ#;JHTG7c68 z=yDl#Ol0Lbvs?B0QX1tOUv-Was$XdEVav-Pam^~$lXjTo19@PT)=xZ-G+Q*+;!F8x z_<37{yZcS=(9#<}l$SmR1mn{FOZ`L0yKQ}KDq6_ZKzxY-&;Hj7CUsS3ZwO=W^RqWb zhusjy#%l4-Mr)u)e-|bf?I8V#-HJxDss)&4$bhZfA5iBiy$El4t-!V> z5dS`RD?U)@1WPC*bnc_&pgcZ{gtiVPAU)&@di}Cfz2H&~d51Il!wSWb ztS{Y(DoQq(rWz=VBR)$n#1CD?W3bB0khhQ92qDW-8qKQ6=UclKFRA3hWgX&qqfb%E-E*+X2m4*iXd_@Reb8Qr)wS@7u zXT$AHGa0Y(;MKdUp6(}Cf;F8jpe+Z1u=mP&SR!3iGI9D(Ya{|K>%)On>*E@*uiz@p(Kf1KxqVIPmk zOpei>Tu8o>&>*zP(dWU{(eU__5o7U$)2^C|xqVuMMV~3RJkJI0pDkc}oPY4`T~+aa z8q0x0mH4yCDGM`FKy<{N7GltnY`5#uDs+9 z*rsu|VF%6mUSm>m_y^+2O7!?$qfkg74#j7uDlvfe_~E=D>@K%#da~Q4gSXx9XU_BP zZ-#`)bHr}f93=7PR#X}=9!AjqaLp*WLs!2nQ$?~EF%g$HXbG|O9Dh156;G?Jg`mM* z_`~tTAWh4Ny(8Z9(wZSC_vXBi;HAdD`I*4u{TWPgz8+sXV;xN2pC*ePrOWSZE(DL0 zZ`q1A3m*HV5O$6}BsLn*9j&wypFZ}2ape1c_i{vsPj=SCf4tXD7i=$U75fs$_wLdV z^dCG8N@+h|an-zIx4*RJ2-kH8#6!z61&u>W+|n)`ysI);nl)uysMW$8(>g{?l240Q7BaSMj zEWtBV@$P*s2>Yzg?}a-<0-MDOrgV}f%+$owPcy`;QyrzjhKF&;I0*xn_zqS z|Id7lR7Gj&7hN<^Nta#fro`Px7Q&n9e^}a$u6)qIP2i?+T8s)MfAQRPxVxJNG+AnJ z755n(ImRW8e|SbAVnO?B@e<+Tt--{d)x-f%ugwS>%2#Z2V5xTc(gFAG*lEoKp^&oU z-kvUpv`?$p19~=%`C333(Sc&96M6AQt;03`(GYA+9f(g8I(XZaXXT~vZUb=g?4|y> zghzcEHUpEKYv8V%5&!Pg7n)9Mu>I71aBEy&T(IPZF#M7h&*l~I+Srx-H;;VukGEmT z$!cNzI78CaZS-sTZ+6nSRe+>dZ(?m8UuZ@3N zV1-3@H;bk;^Jgq0jgVOaWa;3=|HkVP@sjWtQN85kb)` zE`)MrO@`x;6*Aa8R)ddSYYtbh2C~;JBEL8(97nBb5_o zk$KmS8xY?VFrHrDxfFKmX>pyUW8jcQFIN3YMcOdeADaid3bq>zn&Q0tgeg{@OmWjE z{^y)B@kf>HmH7$&PJ3v_%panu#k-aiK=77uChvNZztZ!;4?T~{Zqr=4_PY@G?FqsJ zL5KTXiGqF2`fL&DY$vGCK(mAvp{IfxmtH#o`Sra~p$Bxl%nX&?1e;gO|!;JZ#n?vD1YZX(;{mxD2nqoNR=cEvx z(^kVYb`fW1oJLwtU|TRHhEr zn0K_BjT;D_-Mra>cdAnNLPy*=4unJptET*N_YU5+w9%Y@W?SL!`nh808_IDVy&c~* zj|ZQ3ow?4;BnbZ_u>3R?X-GmW2E5S{ZW7dlLRZU77OQcLAB`P=`4@W%x`dUzXN4VFokiz$`SGSqFg&yZW=sGEwW?gn_U0Pdo6IsEZlG3g%l3^6`a-h5{Bf(x$=|a9Fm0j>)o;Hsy?h3DtbYiXp5A(w%LAWo1G|!zn^HH;N zz~s0!%W&|a^=fL(;$}DcFy=3Av69q$USWEYN zp1oTKp3~2*lk{ncPRGpG86onU0|w!U5h?I=26a7uT-nhrd*6$4J2Tf~sg5G3_0!}( zf6apL$I{u^i(h!Wia&Ky&t*rG$wxV2CQga(16lG~e83Lc!!HkFb)JgSgf4~{_a#kc z+e?YFjYaTX{V%H-X2t7Ws=zMjq}XLB@&0eted%V2zPpDDmr^vj*~SX+=f!Nn99{D7 z7lYls0b*Pq($(Bpk4C$q;b;+gesNYuHi8Z5qb@xeh(4>A`M*CvUKl&-U|L=SLl&Cw z(s2le`r2&c4eHl>C&QwHH-w)+dYH%xP+8&39xro{aLNwUHLejpE;r)ya`M3M&rKFN z(wysQWV;b(yEEHe#QGl%?DgBXa^}jC3z@kpe#RXn@Yw4EVd^O|YRVrSS^Q{FDtl z@MU2xJZo3y`WI-=*R^0`8~GY`7U6-72Lz`K<)(P0A;O`uO!nx2E{Bofu=n(3@gd#0 z0~$tR(`P+s{YJb=pe2l6F_kf9%y)>jus{5g|BY^rl7-eztobgFR^zohaxl_QeGwD7 z65oBM2yLILKwE?sU)3$DBfEY=_E&x?+zHi_quCVFm90NG5~CZ4^E*WOOO{s9EhC6k zPCLoB#E-&Nds+pRy(-ihnhnWu)7VY}Md|a~`RHn~u5krngZh_?aPM5g-L7kK=Z{g~ zKH8TJCeN(GMghz7T?MZu{iatF`w03$9?Vb9gv*{eLWAxJQGq<;BQ74rEPKi+7^BV= zP4gk9ODK~+ts<>ByA1bOx5@szq**s_75eD~V_(z zsT*Q^+FU5VX2NntsYt|-kFIm<$o5&8T=V5ayirWaraWCA;pBhas@Cryg72M|XPFNZdZ`f>1nDjd#j3hr#5#$+~=$OaFzU z>c^hKxF_2DQx5fzCca_u`lh_Lr4W{^-X})TZ7A(uh0|7gL(xJF9(ZFc3^Yw)Hm!g7 z#j_q*@#BBt1u5rUQS}|NB{7_`vUPm%^R_>(q8IvX$~rf#Y3MeZN6@a zFZ8r`Viz0jB<1Bqt;|mmG=>xByQ>1OUtPtHtLX9RcBODzW1uLb?3doNHX=I5z-YqZ z`&!KDz;+H020r!i9L(BM1BT>DS(6_KuTyl`*K>AKEZrA1Pi_b<`!#u^%UYNd=fYMJ z)*AA5Cl*H52tB77@e}9rVY1&XmfzWgA3wMPHrCaM|Ldbk49>vTwd(NOie{a57z~L{ zVt4kn@q?>uFn{D0v5oMSh3^nU?pFKXKnx!q}rTaL{gFxV~PC{}?e4oZgOP8C*fC^Rvg1cLQZU0_j!s z0x)h?10)Zk-oR$mX>?k<==dW5lO6ndT1%Df3S;}}Mo1w+WT4q5x`Rh+2UcO@lCpC4*bGM$fy^(D8TotKqdJbMLxFO7F!h3(OG* zv-`F*E50MXiwl77>BjuPhdS`ve@2u@E45pw$3Sy8xbst9Qu2&J^J`}tJ`-17lbC@C zA16b7UmZTPE*!2Uda}ZkouxnD-0;7DD3p^9zw2HfA^e*aJF(7y?`x`t$oEskS?gPP z=JF8yC6facFLnN7(25Sf)uPAbajTh%zM{4;tvhM7HfCUhv=*MMG~^Y1M!?XwdaNjl zau;*RTXg(_U}USx=UbXnKU6x~V|#>$>>NP*xvkI=t;d^Il){3;A6Tf80dJ=r=h3zu zVlnZ0xBC}kk?0MD^=jPVY9uJ@B{7FVfBC6h>R;n=UtN^hctL@ zIKIP6d*hzG^rXZO4~~(S-6gGv+x1Aiuy7Zc9q&dNVtz2rSC5%&I7D5d!RTtE3)dn# zb9vH~?pfTGeN3WG-inQQcF|7Z0cDxm^`8rmtPZf1C64?B%Y?7jN8~Lv%gYoFV6v)ZZ=5MN2L3dL*rdLcEP2{I* zS+5AHl*#Egi#+u%>8vjKE4NSrG^m)z%xJ!4e4T?uZ~FlCZ}SBod%@K^5iEJQqO`ct z7#(EkvOljB`Sa%Djyb<7!;Eo z5`wX4-5XJZ=KR8C^Ran#Jh(OL@NeDv!nHllY%XPY1R3;4wY4e2o>Wc#64$|o5hW}t z)q+oT-2_7>j}`sG93-a)RX8vs1_s?!=Nip(J8}}nj!}?eXGfs<%0&O|_4ZO@`Fz~> zqy`Ko8uRNd{ULFZ7JK)@PI^12KVFNtDO71tuEqED;2r12E}c5TPmc+~#XtK9Gu;h& zK6xS+T)V+^eNA|_bvpbpsud$zDL3h0CKlgUhntk)v*%|x^axC1KA~+qu73~I2-qUZ ztB?jbx<5YtkpSjOI(&-iMtG;(nJp@#eWQ36?x4PauUoWu1J8tk&vV)F@!h!l$9!PF zT}9RN_R{X7ndtw@m-=+6GxS0jxWtTPPiVJ4;_8S?+X7`1N#C15-ld?L2C!aD8aBP! z4m{@&=}d;6+l8&Rc@PppU8rg4FyWO2yF+`(lA02{5`0il-J;T@*l(1u&@`Lfn*W)P zZ*svg|8}u4#4%Y~kHgd<`tV~IX(0|;Lta1}>vyMxTPz)e4~J#TWL}O^Z?E0>GD(4Y zi?w;)%PiPC|C^{o*-91LOK?hWy_(7bdyrpy>k@o(XkDX$3wdu3 zm!SBj6m(u_@`X+@5VoZkvwxx@Wj*SL;~%>UZ%PfC>bjy3vd5FvKQiXxJU5s$=!B@7 zbc&aRj6<`@a-hFMh5E2^A$D;fn{h)$x*L&#Mh5M&Ip2w+pInMYO~F|6mAp~PQ{cF{ zAzQtIW?kfbd@=N-U}{bobklo*N%=|^cl$eco2-r5zhrFk0Y!c^r?|s!HK5LbkG5O` z+sYjqFR!EAT8B+IDzOl{L51kLi3DuiqUFf#*+`0+f7g=C2?L1>wB*Em9Z^T!$ zCv<0-`1)R>U=*Xx>vs(TozK*_OTOC9rlgY}7s1lHQAT14=>S&;z`LR5ykNslNXfb^ zI+32gP}+rxv)rIl7X@i(*(Cft{9MCl74ij>N3S30rIT`W_@~GS&@}R5)s;%pp>58% zYIt8^-5Tqri=}>o@0700bB{5%O4$NW?PrK{s5|(9#Q@Yh(Fv}+R^yeu(;$9m0PB87 zMH+Z>I{ta5Eo2DvoHZbio8CHbTC2yGjTi>{UOFsu6zQlf#^IKa7pNCao!g)43R$u& zHd5y>pVDU_UNE#3c2mbw!SK}(HS#@kBadg&)jYyu$dV)q@|PRGx9YxTIRp)SH9$1y6F_$l2_}y;( zu;12stb{Zz-*OjXI^o^vqX_F*)Elx32C;>y3eve~Q>@#XCJQC5_NI0z>^J(y0?z32 zwadz&&$L5gAn98MPNLVJ>~xEb!6d`IZ$>W2>+d;ecnom=lGOD_`_UgamJqa#@(>&{S0x~bO&kA>}r&0 zO@y?b8a%gVL5KE!g1Lg^={yv#&QA27#>j6qVG(|_tA+d1$%}C-5TH(zwG%En{eBR> z%epE2uGHd3S~ftSha0=Fo%5Y9f^kKVpU@Oy%olqW!4c0p?AjB3%I8dl_-z}-jWp*U z8fN1@Z4EH<)8ZBV2Sd~JM0S+_<2xVQqE?qJVtN;Pua$$*F=8hCRiK<7zl|V`P-QpP zI!ODvkoRqX9E85p;5~+CLdNVI_I0W!x9+_j(pZ4F=pJcndt_sKpWe{?T8pa(MS%R9 zQLJl&g0#M$GxGjHvO{5%n@xQ5nTHKv66V6!YDu7-S>CwloP+dy;2wMxn+Lw+clc{U zK8q?#W@SP?FRj)1pzxruNL8ij;=<7#xc$W;-h8HII$TpxV4f4{y*ND{1Jm{49p&^k z&FI$Qs~wTl%H@40VCK|ZSubBl$-H3?PH9xY$%>SRKRydC@BJ(``%o5y{c0>ORfUU+ z`aGqcd}eOj*=)_PJmQ)=#=nYYO9%tM&^jKI5(QYrGl;7%(@bz(jfXu~gZn`8mzl=G?diU(@`sAluSXE} z@NpB=59v3J3JK`g?I$H!@Lywl!<}PiL_JeS=~l9c8k5I^K7D^@FD`_X`cURtp(6b! zq+&PCcG+SrM=9XNYV6_=f*&T6zI16E{3jZ)(o~xBN{jH%s*{4rK@D!A*Sll4H(d3d zr*+ZAxnE?AbyDP~$OpFWegfNFuFKijgZKVCLmDjJbU0 z885nG`@#sO>rEL8w!s*FKLEPlGv}*ocfqbLSHvBcDUWN&9#lW?2EsrE$;^BT>U}xa z;6uLk`@^%*RGb1`*XVG5cqnY2=*4D#wQAZI&{q)NShG#nEP4MMd%)wwB60tgX72Vk zl%AV%V633QU(L^eLg)T0m8nPtuM_ZAXB{EQiE@V~XXA0-b>MYgpGU-w0*@kHRy~?- z&&Kh%+~uNR_*RXlr`o_joh*i?c|NeRMV)V*9s_;+B;43kSLF>VddP(1qhPTQm$x;Z2Gidr9+9 znp%Um%}40e@by7RHoq(0o8cf`xK6JxdV;G&+L(8Xp{acmt19`;y-tRrZPptxqK-5G zrTu-}7^%~fz8ZI7* zC0ycs4Ni)g2-}va^QIjODF>)8+dW%B(rp-yN2VtEKcHMYty}c_hu4B`4(bo<9; z0v}Z?YCj=;+L9dHFkA!v%_m&zfAeJbBQn4KU$jfOz2>^~B}mph|gf z(n@La*GfY=F!`i<1?g~CS9}&1B->7(|Lc4JhMOOU<6#EeIc_touupCDvle;$tw4lX zX3&K+>WRNIz%SN*`!NArlsi`XCOGIY=+F z%kbcNRj7GPd4@+4AUt3@Yn%9$_kHDw5zAxP3)*KkWXGV-YXKaUG8&a)$_v5P<8H#N!v;+jX9EQX^kVnQjkxzTPk5;&i7yhhq$7_v;?um|u$wgbSN@bh z=#jx}f{lt)^(qx#m9@zt3C{@%EXN&7Lx@+?;Tgos6)iPncb3~r(^f9Qf^#Q@hl4eE z_If{1HC@R*(>x#hSP!kc3+ygx@E_6ZVTyMW`(UiYw|rU+ec#$PiZsth=+t6KTOkhNdll40W?Gj=tZx|YJmqK~q*a8da)-}l+NW1j2lP=Dg|0q7oW47H~5z2 zET1~N`>_{uC9XI+6s`8R3(uAkAE%K83ws2zC*-$PzBU`%59kOcq|H0rl!LpLu7i=J zpWJ_Y6g*q0!vblqUNa~L*Dt*&G~1H@qO}L;%*bL5J5KVjx8t#Tzn7r4R+leHFYmx- zuAI{2S4|5*UwenBHjuI@O3QF$gAd%lqQPIjo&;G+sVtQJ zZr)vjwVidK%0r#^?A9CRYR_gHlsZX-Bb8tjeXrFYEPyWy)0k`B7amCZA~iOTeG_Tddb6_><;*YIq&SYk0w@77adR z&@z}29m{5Zap#NXt%7kWJ;mDpBk4T+di>r$j`rTmNFr1cDnh;Q>qtAKNr*%=l}%|6 zr4&tRZ=qyG<361`4SVnLvB}<>e%H6(Kk$CM<$j<0IXdcIII-?TM~C~XgfOgr?B zZnlBvZzs}gcg73H+MUTur8utH1@msd%Aijym(GeA&c0b!f#3K={3$%=(`~VzsB<}l zzLaD4g)IZ!g1s-q1c!2Oa(REW^(ziR0)p!>&x@-tAh|+k<@OQ-@?XTwIP*Pw1J+MW$neu z1Adz`M(BZml23k_9_M`bNp`g8FCLiNFO_I9jcPx*(s-B84mT8*{P8D2&()v>|G(zk zHH13l5Lz1B!ye&t`;VlFe#|o#mYz96LhQxKYB5EYgZIat$j^M6s}at(1>`?f8SvLq zVhPx(_)({Zmd^Xag3nqInPxxaQlj^1%nI^I7hriG_IFDfLEdG1s)cj)mrO>|`H7(I zh@2~_O!$!=O0Bnv3rFK($?s>y?PCLs1g2d;rk=?KXHz*=n&J<~o|q%cR7!Zd%!yn* zIEgD$Q}1ZEwja=EM%I61f6l6q>braC>!pgqYUOgWt8@B5wyVN67qs5pr;$D|45 zpWz^G6J`XCmlcq+O%CK)jv||^5eRvh(--Z<-D_YJX)x{K&dtX2s?7>qrthRzlE1N6 zE$XCsE=PNR$us|`Qiu_Yp;I>?E0Pt$`BBF0&%4q4R8>t@dS-!>4tiw|Yy4e+ zm4z{KKWd1Qt1fZG%<>+|IFMfVinn`&9<4iR2m=APIW%OFGCDrF)tNTtqXL=`l|Ja30EEohKsP{gd zj9wjoTlyDdgijJ1$ZR!LZu&eUVY~Sb?1wFaL*mNpvWFLJoUDjGIzvI_mp}QzE^=nb zLpV6j04^>_q7tLKS+1uaDLHS>)x{{YhNuGgQ}m9$zJ|PF>r6OUu%Ew-9unm{1*Brw zH2Cj@0*i`Gk9r5zQ>&AS8OvBY)-8t2|*!n>hu3HAd|q|YCLrjjxg6m z{F^*aRk!2Pf|J-huFdsH%))E271I!k05YUhByGxAt) z_qQOphSYQ&@jRqH7d5jKlX`XdyJ@iPNE&-8-3FLpByjfUr)E`Ci@% z6RZ-c+{NK6W^x?duq)=jV@}h)E}DFnu!g26^g2cpi2CSClirF6=Gdb&a$BM(@{Ks# zwFlp)5&x*y^l41~ErYe&p7a0EL!x!9h8zkshtD_BPk444*xX)0=g$Ab0-Rk*+ReB8 zi2bNho5v8Zdx4O(RFw^zVGp?*CQ;dY(6vB$Zf3RTv>b1_7=U*k3K4w!l(fOw2nhxS$2 zSMF&9<`O})XkRy*nZ2C6|CA~U3o;gRLXQ#aLUFQi80N2sr9y4#2R>wW5Bs;>j5wB+ zakYyTnB&SoaPX+2!#bz3aqCjSU3DKnIUaXI%>ks#2|z%O!DVR^cqrva2X`G|s#0^v z&#%p#!5b;I>s}_5`GnGl8@kMY&0erCZEstKci6J%J!I#7=7dNK zvSxFL!`8_h>{si^{OiEoSY<|Su8(1_0vzGQjcdGVEqa*8=8=jK6X41^Wp?IC0gUT% zrv@*iga>~U$&ht}xJl~hw;5eXE)H`f`|wOS=M)4{XH;nm`g^G)=G6RpIB_|7wz5bB z^@cm?kMeKq=mAaAn$J;$SFwkM<#2X&EVak(?*rfV!aNV-_MJTD)G%i>Eh7u+agQ(O z9Rqh)>QGxHX~DE=88I{%#l6z{%(B)Ppy#TFR^ncsR?a0~c`fKTAkQko%Rus$7mXBe zV-Nf7NYeU3k+h4kP+L|@4C-~ssky4`{^bNP-~X1^c!55sS?OfM5Xv2vL4SCK8(5FY zqjS!DWvgt*4V>rOCLx>m`VuH*kl#)!EYD$uQ_4r9F$(StNEbOKUvk ztIJXQ&5I?UqLrZ~LW#Y9H5-1KZl1lc4e&2^x6Q;Zy?4rtOST`F+bi&FKlZ|vT=9)Wj8woPI}lf@#E zwlmuL!8v?)D8>mj_nj)ROPfM3-cn(& z_V0xPmkd$IH+{DMaTyFRdqcesPQqMg8MwTmd^+ZgxPuvF-!FOWgHT}U72a@GaT^_3 z^_S)5Pb90()$;s!L*aq#e4@5u4WwcJ=7auPi1m}FxAc2hU%ChB>d)sw`z6>L$3#%c zOrTrZC$YwpWx%8eKjDL+(1o90y<`T2Z^j&-yf+NF?nSlo#e|*XEr`o6)Z2Xwg+mGR zNndjt6yn^ju6hVujg#BsRy*RLp{Qa6D znzqnb(0Y2DygMsSejqby2r?Rt<-hUydOa*g!-6b5RmQDZk6E@ULGU8JlJ08$!Y21m zC(|02Q?)G2n6C*W%X0y_sS0e@v5D9n<3QJUNwUn_neenHn7%O7WibXt;54Sa?H=aH zHvcIk=N9!&>pA-hKO=r+p^s4PvqicxpV)+E4Kh8fh(_;_6eb-mB$?bK zm~c;-%_=Db^-d3(bq>4gRFcWu-Gews)T>_>?Iqe<9LarS>@HUd9hlEs@Vm7?j3r+C zdboWDvFk_925SFhQrjorSW2@tG3w{2(qVa)bE+KfB*aiB%vsMKy@M>irNzr#L{CL| z9cjIj1*>F~*^EE&AU9z+&DM}ccIa{vw0ab08T*MvzZpyXL^U*hDt2sn%_pO=3)y_V z9MknKgHx+K>5;BGbD^)Z<_*Y}eUG9=_2f(f5^@^R;+TRei-P_8ST&Eg59) z3d;Q|m1pZaJ;D7)9xW=t?sdQMq-&@vjmJFEZ2$QrvBd_4uTWslyDGrSm+~dG?QCM0 z6S;Mwiz}2iW5pLMVC)|GR#n_tFME_hOpI4UVzmO3nC}h$iYL>vxzfU0X)B^yLpbrl zdL4^C*>XoKN6{;EEOR_bVUt<{|GbZ}mp|u{VdjG%1H;5=4A4z ztD*(SSJ54^lf*+YyhpvF?x-*Plv1IS(fb!NH;}w@zQo-vmSLm72yXc#)6N_F*|Ka~ zQaWPt=*-t$+Ml0SdZS$A$!T#Q`6vR8FFSWhr(T}1bWW* zH)~PgNZqW{{4vxVVjBa=tZ|{BIa7u0LBDs>`SJAA;sdPC#Ev+m#BeuvDKJyy{9HMe zN!Ou%jiB%3p~sk>3M)YmMj( zz{^nN>TnBTXhjs2^8Cl#6(^I}4R!oDbL>8Q?M`kUUjs^*dHJAH1AE`eP#={OY|uzM za#Bd=cuPs=uk_^ZRY`a78Ub9u>@?bZSBbs(wHW5lzRV{@qTc&6n7rSlj(kPDGbWhAXd#%+ zT)LlGSJ;uoU&2H)QjCSur6KGB!F792L-88y5=GM_AI44>g$n^Z<~Iu@Q-< zt95jS%^A>Pjz@fA!>?+Q;QK|?Vd@z+-7kpDJT4Az@ZZ~Tvk?9@y3-NplaY2zA->lJ zaU~kYLbhZvF~uFmCe*qQ@?ir^gKc=f_Og#BpZ@i5j~&(7$W3!$(z85zGw&NK2_8x` zesZ+GT%H+YmOAxS4AnyZ*lqDLco$>R9)1opAj9fOhxRU5i@bgRoY;X**qi#&!lfB2 zN#)T|+=b)1Y{c)y=nc5dkJ7?kfNpm(L0%g+qK3Bde%S!K#(HrJYszyVF7XE7G8>`77`A#ZZ{3nMv-KQf^7Q98+2B1w~?c)HvcR`*z=mBq+|O z%pK=pRSz;tYBtb91-5Ne6^xea;4^%Aw&aBiIdr3&yKROH-WAmYI?T`6MuMSFCJ8TJ z4MThsSwy`LxU^59Z-2@N>xKc@e%FQ@Jy)+|X14=(Kv$n;CTTH~vPST13gdU_wXsa( zRGhH<$xRr79NIPMkT0^QXFH{ZH42eLfm7v9u0d@)I+L8wE{4y7G8^gZ3u~j5Xnh=J zy$6R7`GQLv-!99hqQ`a5o)kLsPCd(2u_qI659f4$;7;NEUd+I~rz)Cy%y2;&)GM~} zhw)DOZ%i?n_hTA_;ttyVXgI`4B+%&*f0@!R8)D>pmS2W?V8!`RGHFRDL?G+T{GJ6k zw2z}B(LC`=%buueMRUi{D^f1G2Tb}iY2hC9*gwsLh)^?rIBLIQ0hk*~3xJ+ma;!-+ z6r@}i(<^$Mozb>fU2J| z_OlnkbJGcQB5EcFp4F3?ObyV`?^#YWnX=X~?}QDo=AWWH9ZnY~K)Bt|xo@avlbdvtXV7$gj)g_yN89lW1B za+QQz;&RM6H5QWBCsOIikt~0H3Z&JQ@dq($Ss$K2?%lA4;sn$OraHiu_W4xRUR+3a z9!JjDCW%_{oDWLa3ung<>iC|B=i&EykhSgM!*`)KW66HX2~_yNQQPf_s+&X`WO)J6vx^3bH~)3QKY4IH-lJag`vyE0o!rdAq>o z@K0XlK{rdWuq2tP<=o~>1(w+qK5({Q@&CeJV2`=w-{o{E`du%d3nL0T1eQ(1{k62& zfbYFaR!n#>95tdoNl-@Kou_6N`q=_$@@`W+yAHw6Ls#15kS{UjaxsxPnFnVvlWzSm zY`_EA^iWz*T<<|v_DCNZ14Yi<=xT9Pftb?;$5tZ|7Wu}jPNcf6x+y-~# zS+y3!cg~A$vXvHAzub-<6bs`?9KfDXx0Q|7-;5qWu~}%A8a#Dq+NqG*vyu47(IPrd+|+V09NiN z#{Rp&Xf5hj+VQadlr}wqjF%U8R*|}?`rO9T$OV0EMBr8pz5!8_$?+mD7HflSgdB5u zTLJ#yMZa`+Bhel6UsJ0@X3H>NW`f;AStCi~DkXOKdg8zgZz*OZNTg;Fi=UJedm_tx zc6)*ZFv>DZ}#Jd1?%t%faEmDo?KrI2^soND3On9>?X7W@k5VhZ&-UKTlX z)qC`5<8%$yyQl$*GJ^S-`JGJlpF8%p3qQo^zfue^M2(f2tN^jsDzp`~yY2hKNcEjdT;nF>)ufw(bz}++U9gYYKDQ%Yy~DWc zxbtc)D+1+n?`Zq^QS9;7N~mAW^Sg1EdbFX0lrOV{PTW(JYD6GEDV`o}|HDi+*^&bF zv;1M)=}+1gPShJh!4~xa#mUp*%E$5a@wR=e61_wBYNEIvWN}YQ-UD0GGU+>SE#~^G z05-0%=Evc47x}8OV$>VAA0XmJja-p(vmw|qZPT61+qxZQ5l!>S zN3sEORgfhvy9eSV2hm-4HqJ{sKxFbHp|3=i%~%izvz!uX+;M%jXw?oV9bd&Su1CGP zGm%Khis18Me2*V@f(^EAGyr)u;)@K4YDALgteFHG^rQ&JCJ*Xpd!ohcXV$=$gbqHY z06i^_50K?&Ens&C_8sg_fC}RPIz&vL>8b7jsS+LD^%mZnuy5>R$Y^-Q7&u+L2`2OF)sQEK_ui zgR8;VE#jun{(0_z%eRWH8b4xBD@h`r_p9OCh;i)mn^5?EP?tU)jr}+>3kmOgo7*}@ zo)sun!`f_9>Yd!oa_%^gLl>uT)6#XAR?%MMB0i*LvxhPTi!3l&QOBzzgRA?;E)si0 z0Yum@W}mne);q>f&1-*|{ULMGpIXO1aY4R^Xd!vw7Y^#TWmw0e3UKEnsN7TZR!O!J z)rn#-(Nu!T|4fDzYZGYwPaXE_T_za(9?!S@G882Gb`dS>nP7be-^Gi3A%4;VI%uw# zu<^qT5@u&F>crj9yD0qr(e0pndooMkd>J&mi`s{6JQ9C zh4-l$rDXQCW-dibrsKz=VD87L9aOw{7>kry4=TSO^L_b-LfpCt;`dG+nk})Xrg{nl zwgu7Bt~&Or$Bt}q3K5N7Vk`vhXeDnmC5ZPH1$Jy{CbZUn;T`dgyu}OiaSpO@0q>iQ z-^1bK$SUfi|Cy;)i^!@`%ju;&+@(fDkl}6wPQO%O!P-;7)5D3X4eMw5GxLaNo)|=Y zkzgANcf*N>V7la~GK;*i8>}ZbwC&n}bB=c@xhk6vCPwlssv;cz#7v_{=1U8SJ)We+ zc?x&?#Tb@X=nfh8uk&*M4zZ+-u0+|kk9&b#SMTh~;J51nsv#{cwBJn~INR;fxBp3| z4EeoIM73Fo{nxT_Ak%cC#Zd6qOd>}0z1*n+ z@iap^#x$cA5COzpq|;&Z=J^ur4o1yu)$aB(F0 zhxc5Yi^&82_PzKV&iJ{DIL+4d{$R0+Za2C9C>hxn{iKE7`0+E@oK!>y2{N+us7dLuCE9LB?DxB zzVZe3Z3;by+HX!=1gTvf!3iOH9sBOg893Wl`Kq%Yv;lk?g7`g`d)U!N9};y}9ERPN zV)_SCVRsqOgC;UU@XT29)KHBxNHh|D`|c*?x+T#1N0qIJ4}f58RcePbz=Mqu*~#6S6?cXE2(31_Sli&>BG1doTZQd6z zW(hA(;a=}R1lSIZrxi2*ux&lIftKzCmQn?C+6VJ zF_I41(9ecHA5HGuN#tSn(0?U0`2+vjzrfbh*AC~q(5_(+{)KleI zk8c84879;I&{1sK?ld^qSHZ7*hkp}M63OrvK>~U;(BA{Dc)laq8Y~WXZ^*GJeF+1*)B=5d)|ZI+qZh?imH7Q16(^Gm>NRjIZa919 z;0J+c)amU}*oRoLh}OW~H z+pu;Q(40EnNXbZ$_Rl6yUn_uz3}(+|{2+%#)B3c(%q(&$8JStfYodPA{$UY0PQzhE zi45Dlyb`{+NYF1IkOyATMz(GigZ)YpEJ1wxfZndJsl&`yXTcx)@w^=Rithzxlhmr2 zFvnVfjp$wq@zvh+c^CG*HdvFDRt_RSEu~l!`?e0ZgOQ6FlYejxgk>e|dyXGx%gT_& z?X3mg*)r^Yc{+TYHG*E7gZ$5$GBQv51UF-uY{&CEYq*x`bed*8o}IQ!g57Ojc?Z-Y zei^PODPuH1V=!ur@#bJ%5kxKb)Urjt?8qSfVA1S2V?laWJ30MUf=tEz%RZ-FP%rw% zSED{zbEk})&XNTiJ2_S!7%{*ZUOD;;J03vDwq^eGD$c_z&DN9Qiv__EcO2zm$Z)D#exe}!%FS#0R zCAQ~f@xWent-rJ|EqDjHCNqTFa20n$W6FvA8vMUEP-3I>Hp9{h8nmbrnW&M;#P)YD zcUe$i+L%**d^(H9PWjI4E~+KBn(ZwJ8Q zTsOZ4JLa11wUHgYW)SgLTv+jZD|s^WN~@S7^5Ju{$=9YpIB%-R-0b|o*T#&t9F`Ws zx@ME~&RLukYEzeD55c?2VE#f~536#==X0el6WG(EVC3k`_#oV#(bARn7zT znPtbbiM>M!Y>QE28HWNv{(>s~vj_Qy`s>NcsLR}$az#chr^ChvJLro^wJa^kp2&s| z@?Sf@!PQ78DJ&-=2Tz9!s707>UJDa1#8OewA66ai zNYqo$@)9SoA5Cr}>Bs!P#Y#1%_XOaO`2;FHq?TRw!_WV{g?qkLku4fs0{q`yRD1%y zi=A_UE}F`Z2r{XaR@8;wCF20dm?rh|&+VSpoJP{5x z9;0*5DKkgxhL~Xckbj5S#;hGFWfx6rU{riIO}MYgTJP2l%$wMIBBH{qJvcwy5n) z!{3p|UsEdi`xsll)rlPYJDD>YrOd($bKtw)RjNZrFgi95(%AvtW;8zY4|2$7GesDu zioW#Ieglkx<>UUbrni>lr^!Cva*?6%KFycB8yo@K0;E~xj7qRyDNf0Jfd!i{Ad2m| zTt~1h+t<7kqKBqZvqEh~kQZ@Xay)+-eQ4wE<`C!aGeJvEffe)Edx+=!?a%1vmjt5K z=^*-!=lu6$zU2I?c1ZRf!NxeX!C<=`?RQ2a*XR^xDE?}JB<595RAhl~l^%`vH4=6k zRgh(yPjI%f(jEUPhjC{k)2O4GA)7ci1rED>=YQily!z2ba==FeejCU!)!S2Hm_aa| z6<@>FV`gfCR*-1Ic4NWy4o@;IB*{}dywf%9hUM?S@k5ZWxWTD{yy}*P2PVjq%v?9n z1AA@o7v^DWL-cn0Q+>=n5B|214F5nNX%q5?pG}8BMyIo8teDK^9x7X`lF15eESOWEh`_iq!gIl*^RJj(sVk>1JBGUK4kg%DO`=7 zMn}B(Lhf+lRH}`B$m|~7fpcEu(a5rpE0`wplH<_#b!~eIOty2U{>zXV9_vhICAW!& zp)aLXzLH3LIFmX%WfrwH3KViQ=>z=EQ5RE)*W}Y&9(rK@Sj>fSeOa{R@i%tNLZAFl zCbTF;n%Uudd{*pMy54;vGy2Bh=Ab$4s_%F<{qAgXXyIr$8>PT*A4rD%bwg>vFFYHM zts(Y}qq$+#iXHdnuHei|eCU_ipV%k+No3}TTAFW%y}E0B$?0d>V1dto(djxcRq~;h zvrnwFp(Y$#Zj`4Tm8TbPlc&Ssx%0tdCTd_*NGQQKL=Lf_J_h$vrrWn{{<$#}RQi&Tz3l zwLOFx>i10p+0{gE+#OW$`U(be0Nk|J@H^&W}`5C$Ro0^qNHts8d zBqLR}=VKsjZcw3*ijdiOZ6oREyv#ZF$g{A&maxGhjSd-F!-k!+CsiFfoLZ9-b8Rhy z?sXq%qPYpXntcTBzCOpFUyPmInE6_@WI8+Hmw;sg3b9^0S+y; zd>_sp?@1+jrMDWSB4ycz&+7&{VMk<&30D<8h>50zXxR;Xeq^?gM&l;9JVJv>XW4@P zK`9zNuZt~94kd?E_24|t&#~2|Fn+l)edxp3g-Xm`WZQGz*mrZQJqb<<$LNWls_bQA z9Gv_6gcrjz`2=c=*DtHU8ws2BSGJi!d z^0xwW4RVFegWaguEO8+<%#_T#nwpkdQo}+n7g9VFh)?aD0dnzZuVb53f`b6&QlMPbK!a#tqu_CemTz62i{g zlgL_wIo!NP1!nNP9-dsxqY>F!EKjB$e#d$9D(eJx-`t5ToF)d!$7Gn=EMy48SkY7H zIXSxpiL4p1)(d|c3g)X)iB(<=oKjF@FWncw>GAUP^9=MG_b(%QGw*Oq<)m4pb`{Ku zH>NS$yVxU;7)gIP{$;o3%ph%->v&Ip%;H)2ks}@vu&G&^DZQ)$)8FEBY9C`uQWlaO&AD9G zN?G>yRVLhYPo=@v6j_={Dukqr;1}v)Hry_cbQ3H1uCBmrwO7FZJn)m=iwVCqW|7*z z4x(}BaT3=1k+)VndKY4mp#_0A71)=UZ1`|OpYF$8o5z7l z5`OIjmsTRxaW-$w!0z<|7&6H#+rj1KcfK5dUsDpc5XS@!h(=J;^MaTri1MWpfr3z`2wEct7Or-0!US(VCQUbe zVb@A*$?o|pXbWn9@AJ2io-wmv_7cp0eVPfzA}6|eX%AZ#8BW%Izrej*fLyZhV(413 znd+OXvl{fQP91rqZ6#`qC(l)qt^Z+H$3r=mK713r{yL3reJ&;JZ(c<5w@u*+MCu*h z>OS1k{T5W{`N(`*^vHqv#Z*`05Ucd}Ad<;_oHU-j$;~A&%*>7UFFD2h%v{L4=dGd> zxOZsGuOg0uGfBLp%vN5HfrU%8=+ujt{kKgeKMGEB*;^D@a{hd9c(RMad-T|h8$({8 zJz%+y1Pi-e2DPRe=&?N$8N1&J@-1`PCoZIHE^-U?2af?OWjPj?nFJm-+Eo0nwD4u{ zT9Wcu8xr1C=%}tkBLSLQx#2)2MK_7lC^~1Yi!9+i@WxNh#Q}j!m+Bb0K-;wQQ zrmL3`@6;O6dVK#{E;~#P+|eTr$JE%Ldl~St@e@C2f{}2-HIJO1&$t9-1*WF50xldX zppCIZ*%<71^$1DiZ{nH14g5%_$QHVWphhv`5L{I4>Wbl18ZfhFujH>cT;{6g> zq^`w~*m-SGe|KdA9J&jDa)XeP}gvFt8_`AGEnOn#xS8vK-3o zKVtv5BCFY#0}Y~md;sb#KOa<*V{AH9oj`BN^^FjCGLDMR{L7k-x{z1F=lBTJTa+Jd zA^uuxK%Pgi}^ z;q$eUxR^?hTrXRNgQaO zc)~Bjo!yu9sl-N86{g@WtWD$!)2?r%stfvAEpJH9k`(?}%^?PAo~S9Uhqc3%*^PbW zkdZ1*&;RRT)<5Twn=K{W2s;J#uOS73Q&VW~6EimLIp+759_MEbF~ZKfRFY`R!DjRs z?t9|~p`$#gjGwqb2TdB#b9~$-SiWWjJU=nGgGaBI$?*y>IMvKAKi|vF7PyfLWCF;0 z$+N=0DKJ)I6?->%R<4cK2WW+y03EaxqUqi)=gPd1e(f~A=pQ=jh-KTm9> zS1tds!9%Rc*SdZDijCNN`yN}yPDDUFGI_+R_rYH=X{z<>2-}o_8M>J}xSUUNOs9J{ zRO{}bA$XohDyPAnfDyc!sgbaa=97y>RdX3@RQuu zy75fucq+VI{++*ov;E*%QOLvBfO}#xY=W~Tyj5FGjg_ic2XeWNl&li1sKfl}7=i4+ zE{R?`W#)7=A6|X?&6j24%-~#2tmn!B!5Pd&F%mA6R@0qhuoEp~9e8cq!H+>bq%1Uw ze2Sd~4SQrU4?AOkGbtb4#NvCs$=0e9TvHonpC^>Ul^t8?*@YUcwW0{ZZyas=QD`J& zyH%5ZlLAN%Ku-RrZE$?oOzJyAMsV(1N<6*Ixidf2JEW7A3}`s7uYF{dmHNaswV3{@ zZDdjzo@C>?KJI3uB70>}4(D_{sC>mKwsQJhGAE`@G#~raHvO$8&jz~?n|67&_0LwA z>8(Zs?;8s94yO^#&!@R7;}uxbv-tomS=4mRH>T8PKwJ$8y|GS$X^JXf(UT4IPlqK1ayxo4dhWNsc{4=Izr2ZK{kKi&{ONrH`Dsv_py=PsIWUG@PUv zT5RuwWpKmjGOw{5XU=Q>q-dcIT*IAOieo)wY+6Wl8hTmV_vK{u%39H~0%Jk_`w=3T zk0QJGDKTN{4$ugH!|RVX5?oH^laYmt`@2q_y;`;!ad zoC_U&Sz5@;NhAj7q`HqDya?q2@^4rvY{fm)l=M}w^n?PfN599;#Zg3T%@yuB@&-+r z73gTC(Rn_VOuNXQgxuERWKUpc=)Y2sS^b7i{xg-W`_Tc_4!8Len31s@Q$v31%z#UK zWtqw0&5(kb)}%A2C+u=1;)~Anp{ERmtCOP1#?5PB;YU^WVw62*eWCg-zWGOe@Xx5gtrm`NkfOd`l>H~|MEVvLa1F?I9$l0? zz!PqLY|3s9DS^S44)Y@X{EwG+5cyILwALxI|H?d}N90aFXNU{&AI-?&&B>zG=&|wF zs08co!5ud^E#|S|0A%GbUgAg(OSg0*?$(wN?rK?(T`~u_UFO)0dv-r$#Z9J%u6MI#&C7{HnGN^kGwxW;@*yYV3cWcT zwIg9SY?)Ebdyej5+E!*{`?Ok)H&J9Nu|Z%uBbJu8|7EaWg#Fk1cq81CS`-D4bFyn; zB=Rnv(|vH&O^Qxge}oy8xDd~wJGk-qoGcuc1N+zSpp6$WQ&xifLm6E@6Z;6_r|cnF z@2z0LIpk_iUp=sg6?YI9B+lCrc{wN1-vZ143IXKHF&>NpG}%nY6R`bfQhT4wF?K3s zE;*{N1%{=lrQgnj6Vt}fd#HifHPn!-?I*eFDN-Gmeb)`l^TwGP%=f^?flTWu)EITt zVo1y&O^Dqj#cJnU!q<~4>CD#^ETYVw42umADepsOOKT@-7%D|($tkl_J_QiI^f$jC z6Ek`pHDpJ6&tq`EJxML@>F*p)O1y~MpHF(mWsEFj2Gy_-4{qHArb z-m8{}&CH z9?qbzPD%@p$&f*bXp zJoXBe!N(D9bl3yNVio3)$&*?{Dr<}dwY{}uL6QpzLBI6M8`01lu1@pOtE?}TPR1La z;oeK5hx3d3fL1SqovNf^9I*}|G&BpnxQz|qT#`WND-UHi>Kg&LsqJqS+gQ>|)Hk|E z!K*&(ZacGmfJL(&nE*k0dx$CL!cDMI#PKj_fG50niv|;`S_aZ$7kU3B=#2>vAT0?x z;EcTw-5d8q>WPJPORGhPa*c%_k;jN(^eAHRLz%5<&46A1-tl(haBpI; zha7p%xIABZW|X)JW-cwDsmSh*JRCr}?%Bd8%>G0!Y=YSndibbKl0u>z`kiow&wDb0 zNiHb_Q@h_S+%_XYYTX`U7!nM+xRa{42^wIIbsfSPULuA(5nIPeYU_6_NngzUu{NMn zO;uR*vnI$h}4abDp#4`9yy zf9L$*2orW={RvR;yuiPWK>z0+%$)_yfK{ckjLApBLn}PzpZsPcmFJUb!_V>6c+P)a z8%q|RUIQFHWAGlckjfKiic$rOs<$TrmFuyK92w4H)zE`|D_gf~v-^$}uz3jK(~%`5 zdA*isrv<_)S$XE#whdPN^Q9Nd#e^e8K4eX+glO**WTx$nC0AcHK~?;4)>Y>Pi7ypt z7k`AUPFq52X&L1HUR7wEgS|Of-mpkw3tb!4&sye~lFY6YKG(m2J(ln$bx+sAy!$F_ zRsibK&m`%*EnTeF-i-vL7IW)|NU^c+65;k3%!NHxWfGHOzEbog->ipKyFGZDtPWPPat?{#Hv|sekY(RLY=XGBi-QU0hpFOnf4@g zF(n0mGWX;xF4_n0Q#bR0Q@TP!to7I}`4ZT5@DLw;wwrw^FekGo*K$5?s%%QjIw%>J zNK20XW%>0$vW0#8A)J>2rw0f~Qx(&#h zOAI6$(iBt-4OsBEvv4dtyWKD37)#sXN;V2w(CLVC!jD4Cxs0Q)Gmz&zy^d78ImtPr zZnI(aMlR=78vRzI!<0V6K)U2({xP2O@HCd#m}$bZUi2+=5U7`0Lz_>Qvn?m=NynU( zqFsA&ff}%cTzi@iDf6&T=WIU6U;M#W7vY>^Ux(cdaGqATcnu` zBgFFgH#pBfd>uCDd?dZjWCz<7(m8A3!;}&BE({)t^h!P^{{ccU> zbhQk8tee|v>XBXPSw}2c0c^+I&~U$P13clGmt=$yJ6DoLy%yZ#T9=$ZM6ca8zj@d3D`| z{K9iv8+B3LlNxl$2keL1okuLooMs z0`)(l!}1Ouf}n|0+s}u#vYoGyp}Kt(yfnmaVyhi6&1V=T2fA5KlsTz+@=la?Qn6!I zTPRoccM;tb|A`GTvLs1k>!{v3Lt&IzAPMT$0XMuSE_|^ctmPKcec!v8)$tWXzr04| zS!OJ3QEnzLuZ<#I=;?L8nFfD0yyVp)yV>)3=0qiJIhQzGjuqhkFlTx`9gIGlbtN;1 z(K>f(orpaGPJtv$(GJX1lvpo*=bz49{HRlsLQ`KMvHq?Iu9J1yb1A$}VOPlWbw)zU z?Lrd92Se611vZEa894Jpvou-%!4**Q(pz*;d`!pglYX4fs&Vw)2Aub>$L4=sA(rRP zF#i#OWMh~##BaiGXv4j*DA|=lfwZuqC7E0lSLb5(8woPtfh(5`uFA4PiN}~(8a<&*f$u;hp+=IvH<@;0)VeW6~3=y*CPSk?3 zDRwlYu5!k&j-+C@orazqa;Tz!>xrW|)Px;7ngw6)$zz@f?`tY?B-kh%lt!sB&qybD z)HQ*&PA+F@%J$@X)H==?y&`&i6-4Xg&|kx}*=Vi;4&(s;=`!v*qv}Y+XWUbtlVjTk zM}vQ}FLgO3CY+31L{`3)5RF$d5{4MWkyN9@FsfLGeOl!XzOM2#deJFnux%}o{!b6a zVUAKkxf1eojp=`qos3AjlHNEcZd95!+qOOrh6z3NJn9K!7so^A$^ZC2W3iX#SOyt% zNfj<Aie;3P?HzHun>3ZDK0MP zHd+uf-DHuyp#+O*tp@vmAsq`WRoFZGI#^!R!iUuH?4;Tpvb6U+Coe9~ZXzeyvtbq8 zEH#NG29!fU%XnTv!U)-VJ4x!7P@wo*qZfS!a#B~!kfRO`K69s~xivTRscDp;0@sOGqCwh_PEl{2%fjWmn|Z~08} zthN@E7NDoAXc+`glc$nS*r`_*OiCBr<#stsGpUMwpgG5cE?d5z?L|-5YiC2w9``bW zR3Z2ry-H7fAH{YXmV?jJ!~8j&Zf0L;K`#AQ!x;}!WD57fASE1U`})6ZdHpPM`RhKu zEfiUimxD=jDzf;|6Zm9p1LVfZP>0YXZ1d}RM6YTGSNA{G;%3YXAI_k1xMLdsYbTUs zjpWnN4_QC4i1Zz_hSwf)Oz;hY_)IT4;~4J58=Oh@OlQ$lygP555<*@(P|$WOV?Var z6Ui_oersAcJE9UmdIQITQxWbOHe>elrvW{`!$@d9ypJ5RYT>m0kEHXCtGR#wxY6D_ zTUJ!EH=WP*78Ok-D>AYo?L?xqMM_F(YHDcNsn7ddhZ5O^jO^{U_x@eq^ZWb$K0NNP z`<&}s@7MKuJzoQqr2J=)Fd-+N|98v~Tds#fuf)6JY?}G5!gi*-$_Ui`v~gmwEi_*b z;0bAYXm-z*nGN@p{CXkcpNWgv)jMhMqDU9dmS(}(KL13&YRWO)EM@h*HQ?zwb&M?E z2Huwnd1J4>=yoj{RDx5*#B1a&nZ2ELnQsjX!nJVRJR8uz>AzWGzi;mPwk5LA;gZ_N&3@9H%nc0vC`EEas{P3G6tYo{pj1kmx z45WG8J>|Q-Mp1A4=d}pNn_Lp_c^${jcAm^--WTEWYjylNARn&9&*Di#>JX>cv0VX& zC6=KUvj6hR*jhVBHlKEY<~iZ;X}mr!qnTg$CXqdRbzV>xG%yVn(f&XaM)n=YM(eE*+_Tj2%?&SD z_-7v%yuRR^xl`mb-!;`t_E=>-tMRabi}|`ZcZexG+i>ZuEVkBsJ>UgR+!MV4BAv%@ZMtQ2b=l4$+5!X%t%1@}^E`zcg@gHL z+G(9zWH1pzMV01Lcq?N8>tgXoP$lNu;rp4O)7ORHI;SF&_Kaf_wipOq=<`z>p2f5~ z=fSICdgKKSf|sHme@LI15A>PwT-7RE^D;&~>1;@iOXW>d@=)E+jvae#DDP*C z@b2n+etJW1d^EKTHvTy!KBxSSLvKWNk0Qc4RW zABe~9d8UjtI1&qkbbxoSBBA#pPd;J)035qx2bdlCIbxh06R_5IlmrM~cs*iB<>3&BUjg3r!7fs1e0GG8|k)Q3$#rH~U~^yUNij4{H9 z@6_`-@3r{g9pw#w>}C%;>4We?1Ko5MLh8be{P?E7IB(x5rkoTjUL96VTCqD@5flu| zFVpXlR)L&#urmKR*0UI;;XW-=SCBo-eJ zuvAYQ_pV%FqC|8 zj}vbQvHz){0qyyZzbxn0+sB}mY6(1ZuoSQ8lfTrDdWBYOfb$16aYM}_n7GQ4&$Tm? zy`Hv#S0A^&ype%{RioxmB?1`8@Iah_g6Hb3Xf2rVItBhM#N_pywWe z-(N5W4?QlXzRH>@_N)ZnzShH{+bf{tiw3u_H%g+bvO9Ubq473b1y6zUnu(Zqwf@Tg?F+j5mE?B{DM*x#m(+1tJ4TK%tj1=*fEjx1@H zy~Oz-Y3!6m+8DyYdw4E#dWWW*)DlN2H{rB7t687frf`gqF<+X;$6hnR zPN{LAG;^OA@PKZeb&+gkxiyU4M|}i6XTtV_PJF&YBR&t=$o?o^7OuG}p~34c@apNy zo16`C+NT2`3_Mn!a)oYTf#u9?T?X{Nq=6~++u?T6B<>nYjFfAu*@(n3!fh`DX~fV~ z@|mA*`Vq6e%-Q?!93Hw)hVA-+EX}(M+)>oPp2-DrJ;yW1Le{rO1)G@d$U25;VvnNj za-Q(D|A=|wlEnUwY7w4lP`7f?JgAwyn`hFTuc9o{t^17I6>4H=X^mXNIeDNILkHV1 zqlf1j7F;@pMYfdj8Q2G2JW$4f6>+eZ`b@h?wWKy7{_@$b`Kl+rxZnq?TH3{t8^}Mf zc>}BH*8?J#sp0xPhhX24`8@ncDSBDiu?V#_KSz`$`7RT*dK<|-&cxDu2y5fPAAsw{#&8qsxF3_<-pS`vv|0z zs?4(`o=vbd6#Absm!1Bd&DJ{RL2L!h|N0t-k6RPE11dd$&i|*itgRR z;m*r&{)F;DU$hh8{RRb5h4MS+(xTY1yS}iHIv))q9DuTqd}w73mh`qG-lm_hlR7x8 z_Y}aS$|OGEKLb1vk`JdNti&GldnEO!U=!|p!Bz4-KA#o^J%km!qVoXku`B^zxtUt^ zqun*UC5qi>tcC8$-Ei2t`7rXTI^Pt8_(wO8z4h-4HCD9uUMhrjd(HWoLMc9GvzfWx z3}MgDk(hJkFldf^#Yc|P!AlEb!2HTXv4#H3TmH$c)m|UoyO3Yv9&RBaOj0qub=eGiAI@6iIia(BHSKG1ULW)ppr-&uTW58x`1Xt3R|EQE77IyKNHV`Fh{AY zR4rQ_|E(;9q5(%l<}5?wDDpf+UlY3AQ^$MRyI{VshP#*%$LV!4v!^}y{54ICn6yOh zrB5Obs#dEn8|xh@IDb+@ox&<8Y)$1ZOAYbMlPYNWtAnT*S28}k`&4g77 z0er`l9Q;E(oVjhwB*aN&=xH=@1A zeCED^OLqK^;ZSji9oKeZUH@s~?EO*T*>1=Okhfvum1I^>&>{q@P!@0Ie7L?bkxzH~ ziensxv(aoSxBN(V^O_^z(KnhauRe$i94L3w+T1Yg%rWf$#Fizl=>v~cRd7o~JgnSi z#Q!T&m38b0XP2E#g)zUhq?aZH$$Ox7^fJfylxqmR^PhM>!c2Bh@MG?tJs>cPH0p*L zI9ln>olYLaDTi#>Q1e8|=flLeIe&_UUhB`et3E~yCBOIH&!VO)^_yttva9n?3%734 zyR|(Ow!7u=b<)r1fr5O8-%q!Dv&DX_+dUfyBaeqy)=601+9E#ilHu03o~%CNvS3U; z$x%Dgpvm@aT>#Db))~3%poTY`&QZs1K|b(GXB2lKt@~={XkrHi3U2=fNpHY1((hS7<~T#JX}1NyU}f>pU)0f{LVlyJ4fDtExBw; zb{+(v7UK0l_*CIBDg;eCB5S9ok3Pc30i^y?=VJ{K zN7J1DUp97bn+7Jf70Er8kEr)VX@VV_XD$dDgA6gd%RZRnc7{)h)I%-u#hs6PDt?<{ zF4Ov*%o^hL;q+W$(kgqvY4go|dfs1TqsFp9w`0Y|$Cda|cQM;(9|Tb{Rh%-OGWe4_ z@nWk+Y&kKH&3DWZBJV2V!1!30B8%Xu-+STAv^{d}ft#(l?32PCb{80&{7C%L^-JWw z`b;%N+42Qeth^*v($`55tHe^MT+vnf-BuS}Ju2YQ)l=f))x?x`aAPYww+f9hT3E3y z8NO(H^J<@N_$GBX?7E^S&Lh9#t|=+Z$-)QB&uC%c6Y`Kx7|wT+_uzJB0PAxiQn=Jv z52w6730`Ni`SxsMlsrBRBla&8jhB$-S+)-EcQ7LVG`o0J}tp#V{F;Uph&@JzaoB_o&s5pF+5pG z4^8z_p?{|VVlw$0`ftf&>iH6wMqZu6k$%wLI**%ORFFBC%w{`AI!HENA;03pKz5>+ z6#j$`#p(HXfV*TigjqKdAIXcU&Nqdt_q4HUUk=P1JD8uSpx*h(mF&^{Q-WoYiqzy- zxX`C#C*ND5i~n`o0#~C5P)IZX@sb$U)XNyc8?>-}h9g+V2Jlb5Cb-ez0@wvTwJLaV z5`$9QS!+uQL|oQHui04;+44g)Y$9EBZY7)eN&`m!Rm4HwTjVoeVb^C=$tR9b-75b0 z4Q0N3VpuLrgYhS|@$O+KxVFHV{|c1h5r63dL&rLUiYbDoxPn{ zEO{FyCPd3;ejgQc*`I+a?9}TP!D9}+{W})I)6a?gq03h^G#SahZk)<4PH)hZP@za7P$TeQ?_gPnlBa9pm+gVDf75}C^1;c`2-V`gx>3Z+k0fO{4t#n`{{N(uwDHX~Z>sX0U7ya zMV_T{x^E^k@Qh(wo!f*-q)V?;a0KbhU3_tC7TVO>F|}%aA(d|E9ybokvs7WKJ+aHR za?rJ`6UQGS9^<$wR&6^4-aDw{qTi8l{pEJP=9`)9=%QFwQ|Sk9-s$3i<#XWA{Gt56 zpe$VNWXJx=HVD?yY8XSAtl;fQ{IH)f&ZFJW#+Qi-Qghk(#Z~No`da_z>UcUkiuU29 zeC)#h*wb$pTo__%WlQ(LgwR-KJ^e8B-erhE_4A3htjd?|ufnO%mNI>JUC?aOzy`&G zFzdAi|Cw z43~l1(Gb45`43L{H(svKpDjLw_FI;)^AUkCVYv#vXwQd#SO1C^-cZf8!+hrYBTHBw zu86vmh!cAyf-iCHjfTYBwg@{QYSDYa(RweN8N$HyDe)h0DfG>o%}uE9&-S;#woQzc z>@lZ~%Lipplh9SFy-*JyC{=+~M`&G40_{0oeA?-5*gPs3 z>^=0wCnnTaUa*(lj`D%0D%2IOvI2^dhVccn&16p~Yi4vKQrMEEgVU2vLTP3eKX$+z zm+D-A1#!V*+CCLo^_6{WWuM7lNAKeKFA`wj-YHyV3;Akz81vJOvg$H|av3#y*+=O? z&~DMiDQauslb;6P>}e)r_QA}2_gx|Eml}?qR}0nFqj>)v#kkYLmUX&4NU&@%!i^av zpqlf59}@cFv>yfVrcaGnFwb1(^x^>f=SBSgMU>Co9suQOVf?M}KWw{i&$iwy7f0or z$^H}uvtXq_=u)SP#eeJI)Hoe}v$hx~y4$jj^V@|snx)H$Gh9wPgTW|Wd=s7uQy2Fa z_l1z3O*x+(&=lbKb~T)$;xE_duN+X2HFP4b%XkOL|F}RV#3V^`k&^dL2Olgw33*Gm zHx$ik#1}v5?oe+ED=F_8);$+Yt4;aT(K2-XNjY+zKEGyh3bEcOck{Rq z_{%Q*{xx&ivL{t+^;k{Vbxs|3bwt5Tr((XWa0K3P-4BwN#bO8Dzm8mwWx2bj!QlO* z`?a{pcl-anXX7LxOqg>)=r>de)r0dOWQHG4Gql889#Y72Ypb7bO85Qq)@(zi1@ur+ z$I3xb^8D0q()y~>_cEJK%LVl!L+P|pw2Lj6$Ri( |G=zjNBT$Uz7sM*BIZM%Y( zn>wy3CW`GT_TJY3JOtm(61r zgsJ`2Q0;=de9rF}{uMKSjA9{KQ+b^^u>!o0LC5zfZXG)k?>M)Cak6WJ{^UCJ`t8Ir z6#B!lPpX)po(K+uy7NIzlsW3OojIKwB(yCy$MZwTGj{upXp}(gg~(u5ahWk zc?1eSE#{*q7vn(kT;(3vDJgzuAsgJCv#tjRu*PIv40@ajLEAoxNWR(DPX}1I`WfMl z7wNr=gJ4io27k8X3+=kom~Wyh@2EACO>78eJ+|0_3vqH1x}JdL|D6?2emjdd2l=qY z_BVvWctZ^NkpaIqy|2rr-9Ue0K2xRJ*+ja(r>mX@N zPd{PU40FDY`UN^B9h2|#&uW{oR?(Ne^;ChkA9V5I*nH?VVh*=_--rd5?U~1tcF8=_ z-&7XmGu2Q$dITSY|FLeo=J&vV!4*(`DEra2E;o{7DJ?bxScZ^6guX7j`Md|l z7}Hb=mP@9Jd1W%JE}Fr#3YB0OX##h969=ya$K{n{k8kSn8ESW;PtMZ39b}R2N zEOOVwIo@vYJWq+c90b1gg>9&6a6w*5b?9P!Nac#4I-Dz zJ(eSL)G(*5SgzZ6>&tMV$pW@$UzV_YHt`-eC&Sd5IBvRK4-Kd8go_8##C_f9dnBf^ z1-BWrrjkZy>IvOG&*9zu>Hil@Wh^RIqHs?EJua2Y=ls=BJzSeo4TsD{@xjTn=zhh6 z{mZ>2s0k_=_ClJu7Q!JiIDCr;eGTK zWm{nzyZbQGYVTZgnVwY|+cu;WE;;Don+fY-S3gazyxB}Pv->9I_UW!reMJN386JZa z#j)IHMiD--qMPQYfx_}KBOE|`!kCT+{KZavyfrxkKCLbk@6&hc-r54Dc~}S5Hml>* z)L=Oe!G76ays_Akb>3etekmutYxyQN-7^r*nJ8hs&mp*?qR9KX72zmHTlVg6gun{B zVo6jATyKx!*OYssl|canzZxzU62DH|TELbs72s!^Dq0N;fMGZ0@`siRvR>=wvR@bN zCF^PTRxRAbj^|6E=2>qXZ+QWNuO&8Uo^HZ#`+V3Bry(%PMH@e*=gIf^Be8n8cW62> z1P)04KBIh1z;nt3w}`uG8!AL6Zc;6y&XG{2VRT8DQ>Tc=qYuF6KfZiyr_p#Rtr^^v z?$$qb~%PXp!ajcP3|_?ExiX>@Y!#HRVJ-S(* zliH(ViD@+n(EHT~(W8)9Ve>XIcjKP$n{x5}YDpJ5|gK29--#4LE#0g*XA=qTfI774-bZX>kQsNJN*5k>1@tYS6)?5 zEb-7y>~^y)^r;{}$=Q?g9p24BigPZmX1^jX2~sq`)GhnLtmIu?`e}1nd1C>q+q41P z)HHGM#SpNo8pD^gQFgv(JR2JmB&d;ZMCyGU8YZt2*G8Vj_HDjw+kIu|G+hVn$`3%U z#VkJ3va9a-w1c1hRgv|~RnV2<1ApK%?mC-#1KPd)zY5A7IM@vK?%x)66v6SHQz z$Y*=j{r&iBsvVQg)Dz}WM|_|~nS5{m-I;Xnd1X+ca9n)e`y8ruxUj%g_ke~%fLdxK0%T)2|CK-l&o58xID#5^L>c2h{1MAh7^RV3tvZ|YF*^2kd zk^|GtWp{$(Sw{O|DCuET zlz+eBuE_?dvxTxbPhN_x3(aMRSsDXJ12DRzj+5(`!H&9MzSsR9R+mj?4bnKV*0l!T zIjm%O1IaEFsNq?5BW#$6vdt3I3!JEvxx^dDUB_(mME_L&eqrcYG6uvgE-`?k}Pv`It!ey z4+oYiqg~4`c;LC5&(YGt9>MW&B3xDMBanYPbsx)K?+d;un$(}WO5X7o=w>E+zBiQp z8XhJ5e4>SWM%2Lz|4h!54AE8lC|sN{U!3_zS@yIbgS}Ur3_mT%A9W@fN^di6p4t~% z*X@T%>vE=irrXo&oPF$@2mRLi>7sNrF~i9x|Bw7>7o?#qU`&UQ`&HUYxk`YAU(|4Dz(#pz>$VI9*C(eI@YKD94~L|%rPrAZCXssB{txG&4^I|Q!BYGUHETzD5Sh=2U4i|koC*!DUg zxo4s*?IPPQB>YR@t=h)8B0L64c0LeI$%}g|a|f&FFb0{279NeBBlpsL{?;3t+AhM% zfX7ycl8)fkWs8_jU=kFC(dS1}0RK95;z?ULswUa7F&#NV+hh%_t&N3^D@%CimqW13 zGYy`1%M%~`qh6J~9ZX_29a`wFYCo4U5ucs;z+xG_*~8?lgBP2XFm*)%jJoU3zl<4; zDI3p&=CQl=WgpCC57ZB{o6q(`zkRCsXh1YrKN`>H(JuXI%|6yzx?C9Z!ch8OXrSOT zY7$pUC;rG?#iPQ&!SV%GNzF#lPo-DA$xr5 zFq24~nag_mJO3CBs;c^YBK9)%O$?%c<_00->0 zVMRB0Nc=i1WIcz<*wsk`neRyInN{8gxAi}WeFEt>=zSrpZXy;L`Hmj?hl1EElaF0s zfTKV7!NmLF;vdQ&hwE)&|GwD5h~>I?YeNH^$!HOCd(K#bf!M6Pf5*Bne!fk=4VN};Zu@66k-fBLq zbh;9_Y|z0qmId+~>xrKR=%tngj(!6qx9*tB2FxvDP7Mb@zgi71eG7(|%^LiACv(}5 z13TEkCD(V}^@mp8ANAE~rz0dl?Dm!fqUg$LTisXC_}WTxS98Jq)w213E(#Ek!Y%S7X7!4VrkSB z^>-EJcYd#haqmO9S?9lKG+M$c=hAHVI)Rf<`>}P$w}a+D`t3-nfVb5O{F~Qd+^X!r z?#@jXI^JnuuiU-Rr6r#0FE++;kts0UG)v4gCx&WqIx~%*3h&}Hu#d`WdgspONreis z0;vsqp&KX38%*rn)=F5nK|!kWntYpGs$ln=IkCQN_v31 z@0r0Ak5WGT9rg1Xdqastod<{0E*-s!H1K3H&v_%OBKe;^vA}I2n{9rcq90zke}vu+fF80(IQqDOAp--1Oxy&iXxzZ3?Xr zZ#UCS`?!_)j|hU-rRwP9aU3*b!uDSg9Zb!-d2Lc97h?MgAi7ZEVFrghSbyxbfXd z&^{F2@TsW|Gmd*Q)$4tr#ZUuR@6H8Zqk(+&G3r2hl_8(=3-2gOv2wfIC*K~Vi)p8} z!=BykBKvJ7lXTk2MjLm7tzEP*-fFH~d-o~rjb|udJS6t9mC0t}V|QB2TB?(XVWfw7 z8;jvWU1z?brV*#Ny08S7LIKGmdi!P^T*)Zm%U6xWX}-BIXbtrq{v~!_=bdb$&veLt zqlLLSZct+F%!l?u+?o)^IxV;;Kd?<`R+}{JCJKea?iS@TyiTmn*gcTWN z!gAW5r>%?w6P3w)r4IRa+S6Hz$_ioMYeT8ir(og1=1F{5t|69}F9i+vMse>8j``n0 znew78V7*rZZ3k6ARoYyBeMB?vQ}kpD(@slt-7W zVgFqgFYh*!oy^+GGS>BkN%Y&4Ir{`yUs%FV?aoIJ@^2Tc+9BEW+Crvx?KDft9LT2L z*GAz7u^(t}HzTj$vFKuU$*NIUcv%Bk&oH?3dOz>nJPKPRDPRNq{lzJ&l^EK4F7wiSEBqHq_v^t2VEP9~P8cT~ z`O=5fG8A$A3`1zDaQ>i>taW^qQoJMLMo>FU^p3 z>1f((1`BT25!5$mpe|)w{^yfCv7fwcL&{+K-NWJpUlALo&1CSMh4adT`HBJQ`0a`vv$OLOrr*-U{Uwzk zSf%op{YK)m=jS0&)l)oejF>yrk;!H#fiis#)2)a}a%LINBhN{3kq?Vqts-fq+_707 z%I2&)0?nNa(DsRkoGmYneTxIOWHUvuh0Qu@ct)E-HFTRE{Xa?V>OyujZ-(%s!hrGx zIiM|Vh8A!c?km>W9Y^2b*{p}&A0d9O zHvX(ihuRf(eD#z*n0h-CSWfnoEuNHz+OwZkbt!{OB;0|sI zGSSqXefZBo@|pH|)0g3Fq(4H2uMXZa;^2@F+2DMm7M~q+XZ_c7gDT>K{qoC)6RM^> zh_vx;-;c6!6B~pdYmM-=e;j<9@j&cGUa7ZBcCl|Wx`F3uO)Ts;4~)D6xME#zyjFGv zYzIBD+BfP5p7LD69yTRGoRJnT8$uip>2L9vZzFb{Gn-|sDHKMfDd5C?+u_Tl9Dc+~ z53iR-!6Wqq(N&K!p254A;+5&}i+)cR>(7G+=Nfxlv2bhM1pcD22?J)0VOftAgp-Pf(zq8J z<#*Lq@(3+y_XI7=vtri#YP{#Lmi_JXUbw$d9S{C4hcCli`NRiJcy+NS>!_AViY{8n zD!LwLf9U>a=tjao{*oZfEG-3DEV_3;TUt!68;u2J?f!?Xfyk*o^Y`-*#^~ks8 zPD6Dtyk3MFgE-z#=>R^ivtbebvW6R^$<$nQVG{%Tf>mE#+_`T*l+WnT6R)VqW?~FG z{KZtre5xt^eIi`G!%y9Ai~;IfAmCJ+c!73orG{{JAj4 zHq`n3__v$kOuN_)YUrLdd=`iK0WG4IDX~qOgP7iwo5IcqM%anE$?VpC zt_!(fE}JsxAa!~BKqY++)#-EiyvrDVigY%|MY~vk9xMb|>*8fgDfln<7H_|*!nM5? zuq^{W2s;L8Vu^k}WZ!k<{W>?|;JdR}*_(FB71CtPDc7dpmJiQK_q(wr68hWf^DpY; zfAibLUaQ^^d_@h+Pn`?8t9SCO@7mZiM5KK_PI3@vU%FdPjPAF*QAZ0;_bUJc-3n3D zjH7?PJv)`yCWKWf;f8}zV4<*$XYCk{b0oPCZLK4A9#6iky}KBT51`&^`c2ea@c%n} zMLJIVHG?%yTPGYLkDQBPC1h^f%X7&;|2ww{imomZ!v-Uck~y+FtChh16J;~ocEH&u zEBN45qj8v+4`;4Vuo}CVy!}UZvGn6d;Dn1VrbfHNZ!0Ap^y?U|Fz{z;@4G?cf6Dky zS^|9AU@o;iik@aJ%p*z=zV#f5`DOLccIY*K<*kE`EK%MYa_&hZPLBTn*?uLFbgHm* z5c+g8&(i#dH)0s`?;9^V*HvSmOVr~wF%)o*76yN*0=?x*JndR7zICHc%+bk$!)7h? zY1#)*GZXm!Km9Q%J`Y^O4vOt7&1F|o_A@gJYhdry@q5b}IPX83Z||fi`+0o^^Dc># zgiTVw9P4UW)ki^^yjBaZ_pgB;8|%cUT{y~mEoQ;zuL}LA8(^DFEvz7Jn_gqnH8Tqiy*?^S zgDV8;6Q>3N6lwBHbi>M^+t$<3_k?@}P3-&Ylw7OHJ)DPOq`&o$_7jrNcgKfHwXnzi zIUh975Qll^!HokYV%K=muL4ThpewpCd4(FTT^j~nFNX0MZ~x)cpKk0>;URHB4c*9k zZ)XpV1c7pm0_H!g2FGg(T&&H*l@D!MuX|gCM@f2kw6qjNqg4KCPA_bDTO!wL7N-!S zEUc78T>zLLOtXF2HgKz3!0%Nk$l4w+VU65Ta)fl1{JGoN*9!=nx*K5ix<)7-5!;~b zDZ_?yer%MYDL^GLh&mU_J@D@9Phij9HtfH02jQrXlJwx-Xt`FSPQC5rbEDu?$4#+- z?*8U&iEQ28Zg8%WvRV!E9 ziq^zwF+6gd*_Ua7JuyQ9PR7gcs@?5J;RMois?HOuvk&DRo+h%3gKeNMX+ck17lL_b zXI}8M9@Q>|vi=v&38QRu@KC^E@aY}NLnz}DVP?Yyba!p|v#tT_LaEC>V<>pTB*;R@|l_cpfv9sz-(jvrbRqOYU{U``%vQYI$Ca8+;P)UI}JqhkpwS z%hd6M`yu%6kSqTM<#?8S=J$V>NM@mhY<9#6cJYe~Ya@T%?Thj7NY8-t`ArzTe=OV6 z(^s%4SI5u-FZrBzy!i!>gim3LS=QWg0d>@_tA|x5qxrXfc{t0`mJK+M4Lv%}qOtpG zb~1A~bjsGo(Kh>G?=usAdy1;eYH=L}%buw`HsFR4=)DqCW5mKiS|#ER7P@b5$FcZmHW zel8%-?XFT5(YZzd%OCBaYlIPw&ufN$ zliS2s4YVtM4q`TzH-ro$BkI{a0D)TX=5e(mF>tk{e^h-4LEtXyD(vdEgzrlc#J-M+Zv>wkT0o zcr#F)zDM-mG4~y>SYv>D^XRVXdPFRJLpjYICs^D83H(b}!gjwH*pax6^M{SNb=Wx8 zRjojr)yrH~RJWV;{1O0FH?=Ux+a0vJm~&Z9I^OhmV3x+~1%J91gfBV*W*gFZ)^uYW zuUrj3w_A&?!#E~wbz++Sil8uF1^4%f1J!%(yl7Mt`X-KJ4;wC6y^@&AF1_5%rYIi; z&xN|!ZQW96+@r*O)*Zvfpg?A+*BxSKs$jf-8R+gA!e4bM$M5=dE8pR7p3=l=^m`kBJ(OR#`xkR=O=CY@<3*n?HCW={ z&5Db+Kp1&ccGT9$=X}!LKe*{y3hQ(Mq$;IDY@yys7sJBp%CSB9QwO?zY*z=Sa z6({0FVF_DYepQ%rk@U2qnIK{Qe9|~=+_hylJV;U(d#*5-?eNHE7yJ1`ilrv5SmpzX zortj?OK(ZrNLH^LEkw=NMe{+YVMS6d|GsnpdY`xe@AQ1c*@@?HR?l_pW34*r&-D93 zK8;s@ZF$yq1z9Eao@Dt(S?%{VmvvsB%`(%SU9x@-hX!(=10EZXSemj+kvIv^Q%fcwvqaqTFTgf zf4ZO;qlRA|ZIf&AAr1X-b>DbUY`)Xbxyej6JtUG@4G0F!yV^L<6yeV-9e!e4F1FvX zWlO@s1PNsm;;QoD!N5d5t8;Jc-MI{kB1VdD_fg-?Ysy*^PSGplnV`hLBXLjzc~r zK<51tZl+*@OUYBYJSSaD9ZI_2^dy$L%?4hQ7Uc9{k^IJ*c%TxW1beX>^6ihIcf^YP z8t~~J!S}2ifSYnf=zi~f{p^<~a6fs5HCu*2_#-tuVwxb&x0+heJ5kadl?%@$XzF^X32{EFr z`K0N3_;dLg7*f51YrMtZREf`RFm_Y*d*qJX)%S-@_x}MC*92LtMd5{gT+!9UFyRj>E90(kqbY?iMRQ zAofuVV3A>ppmvXT2A4v3Y3;tE4)$TlRn37Buw2Ae*p(gPeN8HpI$?O|thC3S>VnNCpSUp~i>%Dq~&gnU9 zUg~t{yh<63i_0M7`e5GgM=5p>wq?PT*E{;s7^g)S!DGu7zL3}sTC*GXhaRTFh&0L>Tg`O zYA?&)a7h?rNSra9WN*DAqD)Gf<=2hzlJ-4a ziTPXuI=Twdc{w`7v^ggC%yje?u_nQTr59Wk45<65*XV56*Cl{&SfPU_-y}o*7Y*^| za>{I8rCzOQf0($O{0RjccH)N6l5RTquKrRD65S$hxb0oVbh+J!2s%S&2ilX zj}B{cDR~$5>!R4$7x#oEv9u3J>%r~TSYpEDph!FRz)mKD`8Yi+e_ak+uixc|Jd82h zrU+y^%EYClbDFKFV0YZ~pq=_1-uOg9&anvY6h-f*Qwy1T$06}Dc^CC=MzPq?V6e8< z!K;H$L$i)9Pjt&cuaCCu(5Nj!aV}~2Lkl5gUm|aCF-E6xMWD0FLcDZ{X5h98HXwyT z4~aIeilQvc+@<{Jo&NY~Z32v)5oUFPe1@98qS&mNGMHnNjsbtEQ@%i5yzxhdnM6oWt1>s0t z56m<1hYZV$;?ZYy*y+X==4jFhF4St`)OWRzHgEywol4Q-gbfSzEtc%KXCYfqa*8S6 zpT(AtCK>%I5puU0^P6-Jntd#Xl{Q`yR*%-eX{x>;*}aE%E&PHHMuL2X_bS!FjGEKX zZA(1=a3LEDrrENrX5P^EVH0}ZTFab$heJ2|K0cb04ZT$R^TL<(*j%2#4w#z>&8Q`f z(uo#6_gu;yjL1{%76J2hu8Y>B<6XTJ#hljkf^OE7zw@jILDPe)Pcp&JuIC{nO;s}A zfR3te=UIkvBJ7-(PUq)vzJZB@zw7)Jmg)30+UJ|Rhar2ZS>3Cs< z6)clF5nguIK%emKprJjMPa+R$NsrB}^r4z0J%O@3f0Nn9+N0n+i8%1rJb~pZ^Qmsf@nF{wrf1&+qHic+ z(DX8}m^_%rU8dfvtv2l5+R;M)K1R6Xc>z@4Z{~YL4Ny}z4c-m;Pt5w=gbJG{veu4D zLFKqQx{mRY``-H}{lnQ`Y+1mEc=22RT0HjCm(BjU6}r%Ex|zD3tJf&<;8W+&bc{DM zJXa{Zh*LzL3(3$oC6XU_IU3)z9fkV$b)wTw+Izp}u$|MU!J~_6XkO$Emx^ccPbrEr z59L{G-}!h+?&7ZKt8rMqx3e9(*f^H5NEf-dZE`hgK6GKX>SRJ+4;}3EAqR2?2J)li zX*oN6FK9@##2++!!{_I*-Kqg_MyiRO)q>=`A>U$XZ|M@l@;svj-=q5Yc=kE?`CmTY z<3~KSe~012V`ovfXEkQmkq@fx7on{ewSykafrr0ma@BqcvTL<5EIB61DlN`jX0j%a zDOi<*r9JJaLqZ`pO_LiHn#o3Xk6{ZY+!v-&pK1Dp2DrR6!=;T@G^hklwhp&t6cfOcPfTOVg@% z3j5K|791~XqQ&r~a((7XTpg-Pwle$DX5m&3eM}sE3f3pa@cxrWqPosCkiEKF-$uEr zTjdUH_(F5|5T$~tLut;>pTI|UXvvl=i(yt05Il-3@LgprIR5uo4EH{P-J$KbEK)eE{fys7GbROVex^zXSBz;SEhV0Rd4yd_*-*{;6p&_zICA4gv&;3SQNGM7~WY4BZ(cV(p zd#91J`axE`Nlsw$r#s?)x=h}hm&uU!6nRRI6C||H5oP~1<9b&P(1k0CQ zTNX|d@7qGkiJ`cz;4FOA?c>{6{^g*GKRFzHjXQkNjP1!?PB`rJt=oDEn)CwjJ{t=AG#_wTac>X^x*9-nHGT~!DQFBMTfDikhgs!~5SL(!DK zNo4Y}n_R?jb~kzF3Z6$|s9HiAj{35cm{h8ByI;uSC9N7Ue{AkcHSF!Hf=3=F`PFrZ zf7h=h+vnfrUd6E9u2+!|^eTw%*{Op?vlHRPmj60Rry7c2a54$f_kq6K$|!Q)0P)R+ z^!?E^9H!t%{OfjbQ+KH25|=g*v}e-Vr;Ojow4jO>3qIsZCl)h)ujFKTILU5y2gV$Q zixr!wUYV3=v)n(*T7@%lYF-$+p*pANnFZ8)~&*BtgH4yZ__d=T`DP> zvdf9}PeloSd>)KBSL?+){AHHC+R)ts+Dmx8Nx1|6-1lH!ohzK)f2@c7V;(Fk^`UDQ zv0R2%3Z$=A=3lbT$33_6NfXNmm3&shMQwgyEHtLI8H}a5JA%X)hH)=GsN=YvUakPPZUiZx=La}n8BJVIgGRdwwbIDK@`;QCP#?hU7%Y#AnC4~}5l1!055pUO%3<5s zsl0E8p(rh}hUBc64{gkc^DH404()ZNMj2x<=V=_gE;(pXEXA^}-4W#Na}l^tOGBCe zmXgX@iu?*k9v7&3lhkjllcA{;U(v`IPx-xK+!M1YdC%)IX|2+Yz25B_I(x zhb!Xz4W+Q7^EW?7`!p8EyAbF93OVCzny9GCywfs`^w3K^oXfn&<}RuHifM+TkdS0z zy4e~6&#>o(z3atZ8tWtN=)Eh1%(gnmnX#OHjAH|6zYL}$&YR$bt=C|u=7V;H!c(~1 zXbEv&H5tCC$zjB&Sa9Dqn_AkjPSyN;@;H1W_orDG1;hPdRNDpK$hR4%dY<7<3mM0H56SEPF9N4e%EAkk5nRML4|@Kc7An>s0iXTX z`2gl`d3-#AOnN#3!ZhSCeO@~#rn^xuWZd9_R+!cF(<0fxNJOhIkbSo&68@1gdZp*U zeCf~p=82u?T4zhB=|*l^FUysGKL{ro7gt->3_E9MLHOuwek=1L4qyavpJxYz<>t)I zd5E3R#cv*T8Z9(fpM}bGZg!O^+N|t`N-g!a&ylBbuZk`Cyh9#d>{LJ{7na$4WloK? z4Mn@QCzI+k{+tKXH_oYh0NtxD9BeQN17n}VU^a7pWih?F)rXXwmV{oWC+M1#0yk|j zP4VrlQg*QU$ST#Pz%$4FyFY220A6xf|Y3l-z9Mdw+vrP9E6X!sS~A8 zGbalCQiABY-P(ACJ%j2_{@t;d`KVj=q>#7eKJZ|x61L6T09)r6&@~6r@ch`{ zF3d_D6T;eI@T*LE^1L<%*)_3TktLsYs}tW>x)N@WJS_bti~DopK(%NsjkJ&!MHvK> zeMt&}U2M+x9!nv2W;ellWex1yx*ZlglcneWyvMr>iimrPEzDv1XS;VJEXtTh2SEuA zZDp*p8WS$YMiT`UB~Wty3~f+V#}b`Xc(Us?Z?c!&yDt=wPy4jMLQ4Uut2b0+_|q*G z5+X;-#pM3iX#VWzI?T%OCg05tL5sIEKG{|U^H)gFrmmCt?e}{$sn~-l@gZP+3ZJcGOBz)*U4%sUM7= zMGfM6YZK#0tetQQmbdeKSbGinM>!GspCYdJpc0zdq=(li;e)IuP_J3a zACNwS6S{YkBi#yM_fiEV|K!0{AA9QC!}_)?Ghr1TpZ6!)P?RvgkO(fEfQVc*+%`K{ ztiwBJ8Hn74ktCz{A*ZUYgi^YvVYB{h`sPmtj+$vhOdIq#QJW5`-EIao-B)zocWpFe zew+)_DtSMqi9JzwApSWO+}3#tXkixyehtCY^UObdG|Phw>Z|4zSr%{7w@C6Q*AH$o z<}-h>69R^-(v=FC=wo9;+LHabzSqhqAyWw!x0C4YF*;afQUNuKr|@riru`18BS$Ld zg9r0P`z;KEYnraqZm1N?S#Ko^UMvyhvD@VqgD4_tc^aO@PQ-D}FPM)dy+d021ODBf zLB4NW4BzS$(c85gO2$v30W2%`WT8Dd6=TmbLCP5LFcQYhzsa|<9Xs`53aPy}3?BVr z`~Qj!Fk0T5)+|oLEk(;n`^L3`tf#fOC)ksu|4M*x=IMR8v`jqP4N@C%`9yn?^fry# z!MYlYza_vIjWYVPPY+|XQbBk)mCt0ir!6m2$eK=TD0fxD^Pe_=#M{MGc2qsyZS^D9 zjw83yP8rW#YzAyOOg&{svOF~pe|x*ygLHeb?bkZ;=*KL$d{+@qNF}i@9s#Xo9L|HP zh2;3xjhxE8(WrYe1h!4R!LNPMhClj4NM6ezc$CRLM+J?b``m?6n_^7+YDK`%p})Jq*0yDj&v}fjfspk>_*tVErpaT=z%>t86w<|COU~ z5z8a!pOO=}Pc{-Q5?mst#*@g$c*c4S%mvAQmWNu4DCcWKB%RlDa*2xQmJklI8?tEW zU{ieGkp%*uEZ&6q!0k0y?k3a@OiUE;XRr{CC3W)&PehnO1Id*2*SWv!&u^H}0~;@^ zwWa8t#th~;40D%?p~Y+|HCfbyF$3;o#fSTXEQ`sal+Zdd!Ig0pQy6G zw1+AUJQnp}uFG1Y8~liKm?49cC&xmZO9&m5qk{c`Q6RITzoTjgyVs~5CuS19u#tJp z!bW;Rv%3MkdoB&b9G%3Bf@;?N^m1`4$VsHr#BwdXx4ID??_S97o_Q8SX0Im)9h4!& zSRR*>1hG%@i_<6^9i9fp9TO}*Gw#`bmLb}c(ga_xYT)3tJ3*&Hj=mb(k3%bq$d^7_ zP-m~N$6o)2rWu{Kv>0RmSdo%$V@`d7Ha^uVhe2NFXd26w9(o9xx6n3YMQ0-pma41DUzW3-WH*K zs1^AZ9l`k;DB}Y8TzK^`miF1O%;vdFc=0QXm&<0IeNKhs(IVCh)+vwq>%74`Y8jmv zBqjPd-G_8|ZttXtH#OKhzE=AwAzEp6yYe($Rc_4bfcZ$NgabAMd_O#;;4FFMOwB zK~E>F9B0k1qG!P)$;<@keW?yTyleq(D6we zSAHp;PV~}1$#tw#%Yo}Ib$>AZwu-SDP9B9b-^ysQxeg``Vb6oENqj1s?NgjmiMxgk zgy}0`?VF9_+5S~fhx5Ptl6TTVZueU?-1w;jG~B}Jw6}U_lty8pYIpmYJDqq!)}5@| zHXUxUpW(sn$&lRyRDBbBemP!5EVpmsp1sr+-m8t`^nT2zbH1o!!>U~{=HqGJFXuHj zVFCGFIR-jsDd5)Gjqu#UnI4cWLdzl6WdGv=fufF)$Y8jL>=8K;{{7fQiHu8qBhV!GNUkk@Fm7CkrTL0HxljZzfA0sClU7z zESnRM3zN5g81DhB3E4tc?II(=2-9t}$}v*^pI}$?s!%gzKQiAQuDb;r$(VZP@pSZ5mP8?hA22?0%H71tv;NrasMS`0x1& z@-BB5XC=e>yU%q%jCCfRsHTOj>dlbizL1yIYG%3AB_!5z5NKbM#)^w^P(R>CCH164 z*6TvZ<@@piJC-|3Je)=}pEp7FX4di1vj@Iq%F!v3pK#OdGLk!vG0w7;ab?3P&=Z={ zS@DIqBGa10#!TaqOf>Q0;&S-s*Gn(4zVCbQkAvyZ7rgg2wj(tblgjPz`n~ zEQRp*Nwl>~8OPckhpgNbUiARuYuzd)f2bwceNw~)dk;X%&XrWSR!SuIYc)wd6fL-B zIT%|Wun!>f!=KSo#j}6g;lgpsYkz6Q_Z}O_mnoMx$$n)FiztB1WBaK8ijnx?O9{je z4Ck*TGS>af5@OTK=KLuIoWt)IdnP>?H^VX|hPYdXa}!$CapkuQjA>R#6}(k&xj{R~ zwk_w6#Zz2pv6aZ~kcJlQ%-(+cpUNd{m(8r-Pq%odTb#SG2!g z8@Gg1!uP~Veu@djsB~M>A6(4c^^`+jrqu}V1<^A<)v)#FVX!hh)3M-xJm;PmqQBiA zlpe8}px*=8YgOr(TkO5M--hg(?8|L8Q^u|*Rgl=8L}Qsh&G|$H%qX4AFR$rF-C##z z>-vOL3vRS*rIbj`Y8NT{vQ(hY`~co>W5|k2r$KKE%Y%GgLC)?{;vZ_( zp}*B;@tlttCy&N&%i!>Z@$|Z62ikmGNtUK8=T1M974C6K4j=7wzDZQnAgB1`zoPP%Vua!@}X~TjYlu9moV9BJcf&+D z`kU$bO)2nHhp@Z}^Vf|iAzz+u;_hn?6DGMuaWa2^=F77TPV_!_TiM0`yUWUS#}$#Q z^Tt9RyAPHz28){KDq8rg03D32$wln~L93#XD4^&xX&<$mxNcU%+GXkR(@2kw_AwMm z>amPl<7KYoAL}<9b{M9dN~7x=Oi}f35?qQ;;773M(}mgHVsHG{Vd@xKK%qa@tivVZ z6wcK4Bu~jim>0|Rz^l2Ce{2-hHy2`7g&oOw_@1>{s0e3i$BJkErC(}T^y@H8*l~%s zeQhAxC5j>SrFvj|KoPT<{$J6sfyQNz#3;qf;@w_#5qln~y-H3=>606?)bWjF30RN* z$v?lUz+3Mr3H`{l*_+SV7c!HF(hlOJ!svK!}bFR zSJJxprPYYv<%7s;nd{uJlN1BS*pU~zWx?sEJm&6<0N3f$>21a#+;%37NSf{E#vGX; zyguqU_ti&0ZxyNIjoTOC_B3x^`!7ZLYk_3sTPawr%sNjOoDk3XG>{XWQ_muw_YC7= ztlM#EgcZ5xJ{`>1E%o|nmSsDuLbdG;MNa3^h~3*;+#OH$J{i~qMaSdlpF7Mmmg!7( zuN}%2usQ#0cLUtq{eh|(7~t_&m!Kr}GN1TXT6An~1}QwE1NM)V@yvl#@NEVs##>u@ ztOP0tbmszKm%R$uE0;VV!D~#vtkk`RPJ!*AN*-VYPXI={rtyCWGmrA z=K|>1VoL{fwQ+BC9@M{2o41pBRQ_BjCBrXQGHxpCHeGNSt_qZ>-YEmoxxcYw*vm(p zu9XVD&OQr~J1wZeE|$%I#>37Z#{^C$I;eZJO}x*4W1h6@lgc2_xRifCtE+fU( zC%DD|8N7cY40H<)P;$N-N6DL$c}F7ocdWP9Z+aXFz2grriy5!xU>8XEDAQ858~X*= zlJ%Otock9gZ2eRXFU}^>%9&Hqy`={Vi>>+fC%VwlbQ$@S^@OW?B!|c2BS1oXH7zxh z66r47Lq4iH3f3@R){sqcM15u_XeH@ld+HrA`e|em%}#??4`OrgDjA zoX0)oeQ+WTuAE<&URfqUaVpj=bOg>RSWu_Fh63?4ASyNfitkn#Ov3=F?9s*VY!8bA_9-NC{>74}qy_3LPsj z!n2wQpma2vpTIKXed#^oIlsSB9lh@$7@jcixYbgJCuCg7Iyw?`)0rR1set_+$512V zE?iXONHzq06+E$15$<^$%hi}}paX{5=>9Si-jBV>zxc_z5zXSr=1+RCR-lFoUKb$d z-!{sfn}`Z~@4*fOH9?1mk?7LiYh<#YK8a@Ci_v3>VZ^He{!L^n{<5oEQBE&jv08Z18RMdV$O^Jd;`)|YcM z&|eeXJo=z1B!D;UuEpMhEhNTiLD>A|Q^br0I%b{!z z%ph&T&_r@^!#+vq5!;iR+Pgw4qlEiN?~iqtYQ$nw}`co)qycK>})sw_u) z3twY{c`)HQ{K9&}pPih-^@Xe9D#i`_-^_osm-RqJr$J`! z3*L=+Gd`RzB~JsjL8e6k|Ee8?NfLonWwwNfmt8@;Qy2qE>l2O)s37w4H8B0W8Y-S- zj)5tPw4^Q{yR59qyN)ofOIj5*MieuzS^|C7It}mMI|Z|jw(tjqhN4p}*XihI1)6^u zkC8dDcinfQy zuHYiuZ=V#3XTE8%E-t#xSe?&w_#4U0&tpx(&fY=+Z|X)vd9EA%&!!s(1k=fwyTb*2ri{OF zCZ5bW&CAotjT=De@Qftdls^)1i!vKwo8R1@4a45FrC2KXla zD%kvYy?w>G2F(Asl&I!R0#(*!rtXmr^SA{xmhC)0)XK@0S}!j3)G#3pjpgQf&8JUg zwD5atAl!O=hW~u%6^e3-NrU!S_{8psi8ZaTLuD0}&B?>T!OWi=nkOhUHxd;M=^;-H zSCGxGRj_4Q28x-l(ax_IWt#ajsLq;k2R>#gX9uiKr#Jp-2H_Cldxr2~&w)D{sViCJ*IP96gjqu?b` zp;BqxXcjS@yy`s2QMMcKMf zByW6luxNEnDiIhDg}Z(#c(En}rtgTRJG9EB6@u_Sr@;D6ZkN;3DeX5=dnC@j(8d%nI!AiEC^d7edn+-(Mf5;c6T=nH`fvh;la8{}-t$h>{F z;I&y1UnsOg&vX-7u|5w^tg|7m^QUmgx;v-5D}(#%x@hheb+r4NE%sRU#j|{YO$8Z! zQyUt`DdLp>g5j9Y0eVGmEV@cWL05lm$K=NYIK#M>I6BtDl0%aCAhZq+-}=WlYUN?M zrVa7#59MrFK1ktAp;))~E}Djr-2tx|d%uZ!EKOEbkaf4M;EKE=?)(}IDnnP&9ju$f z#d1B-Oo$PD+B^uQ+grsPn^T~PV=T`=?TsG(Sa28S&haC&0`GI5Zph-gZMkqXb1Tgl zHUf{FFM}UBy8L|RWBJrxK}-#Op|Mg9KMV;H`{z5_4Mg5&6UfwO;oQVJWgK_@JiKS# z;GUSVxM}zuSl+sqzjwX~ZTmdQO1(kw?4Tm1R~EwLJR3?%SqJy40{BlpeV$E?q3CB% z1=+#w&<|gzV2&`9arBjF2+J;=x|%??W##vBFnoBo1rs0tFi^#0*5!|yn zZQS~_Lp<{zvpbY*Um@7O&*Oi1HDjEU71>sr%WXa=gM*Joi1+-uvE6v;%nULjD3b5g zV)uQmL~^=40NnExaF*8@m^@L1PGH(#^qWOQQ02#6Vta*W8_V+h9;0*SFiqH{4u(vc z#y^_C?w^;#^N$!`v~@Lg$?QhiSu@EG*AW6_+M^mtBqa|!VY+Z4K6Ls3 znlCat{1s|(@vQB{kq%=$aI(1YPX(Nl8c)~K3eNmzn*7Yk6&x2Bi83nAkbA`|$WF#saN3#yakGX~7q*8;RaKDs zk5{-|flSv5I}8TxDRl13amd|{hB!eepTlw!v(}%5C;5>y#V!pWxGW+rzU>`n8*8!3 zYz;|>7zv+UmC(MX2yXd}p=OUvFw;c{!`7`4M9onV&R>$iZF;hS=2)}aUqLjiiNC=w zX5K;_^+a;vAmddsk6irK^RQNK3zeQa5p#b(06hmaL6VP=$p7(8B5P$pZZh_Q|JMRI zDEz?Z?rp*6`>e^G=c~ABKjhI)F$S)E%%rY6N8;N_N#MLHmX~85+7A6h^4(|=$ogyJ zfah&U6y4!N{MvEF(*ulSaGAR}wgQFIt;l#$Y+I>94}P5IO#JyA&Hwj$ zKQG4*?=6Xo78RIX@4#Fu2eReaOt}774$llkL2QLG&39+sCzf{$RJy~>SjzTT+3he> zFOGITNki>GH_~-PlRIH5i$NvL5dGoVMM-B zLC~MZ@}!dS$PTLp*yJIRWL_HE{!StX1 zu@0n0Y2o^Tv#=wem)G3X#Jb@&iF>_c&dQ*te=eBYZlU*A569CR%c0vym;c6Y)^TQ) z#46qwe3-r$<#`yamm1U4tOL4x#!)g-FM zSboH7*-=uU_k@%5mBk4TT~OCEoqDcM!z#(eWX23V?)6P=WcEjxLSNI?9qjp{tQNY0 zD|s)L&ENgQft=)vxVjE$Joh&OBC7)FDW74e^e`S)boX_<)ie|-9z05tboaxKBIcWY z(F=)TDs)|18kRXMCi_(VIjJ4WIH9s0s<>pjMPnG=?W_mIgU0;qGl-6hoJjGOhg@YS z^BnfE-FwGcTH_!s>QvuPPF`{nbS_|C`l6%c;`lBw7EHi(Z~B3Ml+iKEr~w_1?<3N! zdhp*)8T@m*0*)|`-&y-|bYeG}x=$Q;ag935Ah3>-!Uz2C<6U_1>rCRew1IQltbp5t zc8X_vLqQt$*SL{kvo;8Jl-1+7XM2eq%Rhv$d$H!YI>=FypxwXDV6F6aa>?!l$2d@U zr@8?4r!`TF;~MyNAQ_w{B=G%P4MojmIb`}HTbL%vvYb)7#JSfUJ=G}PaDaSnqTC=< zK={-SOQ#;DP8)Ji>ykB*xn$EJJE{Ydhq;p_O2#mtriS;Y=D@lhE1JySlV68dlJhB> zx$&Km#bW1rVOS8AAnK91o~`X03|$^k!jS5`ZFd* z=~L!u{~bx|W~X841qbr^YI{fcj5;x(>;+y=u-Zpf6e31MIxXe|YE5o~UtjN+2 zF>Nb@+tDK0fqXNPfxXPT)h-ba39Yl}!nN%Fm7POQehB2q;D17oF{|P94JqN;YpPhb z=?WY@wvTsvatf!FA0QP;L!gXxMr`z|gWHRi(aYD$Fx}FMxLfmr0@YLO8Q+d1q?iNO zCXLJgi-5cm1?tM4``YtzNdERa+(a7%TyMQoyu%mRr{k2OHN;p^i_`CuL67`qu~whK zG8b=>TH!=>6Ter1-6h{FA<99$+&jij9A|PArd|xDC-PNr;CmwEUH#Y*eS-18Szglr zq(4MSC}Vs7UNAj0nVvID$9iwpqx5<&SNBpC)n1(ji-s(Ed^GE4VLgWPTjuh+`_G{H zk8Q+oxC(d$sp8MLY+ws@T*lqZKg$UTWvlBV#jH* zZbKDvFmoNtZX_S!!dXrsKcE;gmd4Tfx;ps$cCokz%IvzKXzBJ!GB@2C{1^kRJm~*t zyWQWh_-9)T99UFgvBp~h^>o_Av;DNC8t!<~1#fqp<}Wyl&{EBh1irY#J((wi9ol)| zdU-P)Z7>uYo)?I<`e~hPueei1`eyjS3rPjk&SLwL{WPk@Sc`?VNko2q1hc>@N`S@z!!UPq>A%RB@~FRal(CZh4G%_b+D&G0WBC z7JksiO_LCEyx!2YavHcwr5aujl<}>M>2zXXHQ6jx&21kdgTCHT;vL?Ub$d1KOMrVy zeI3h~uF~))iG(qZ#z%P?LgNt9gk{0=wT>3HQ`DFS)@nH|z)*>zXJpLeAcV)Rim3dlj%N!%$w{(Fp zDh&r4xs$OgRQQO&4S2!KhnRfTga6$iPK{?g{PRZi$-`2#JY_}pvkn4-9kRlKzbV{* z#z(1n?@%1HKNUP$p78zb*5KYfhnO@sa?ghX_Zahiri@xKeQ3uHL?A;WC z87FF59_e?mgPVWkuxRy8$WU2C*QwNC>CYe%d05Czd7+B4*L8uJeFU9tla0bJ)3>YW ztt_u1pQ^5MKO|*Y?*0&HZBL}CN6qoT=S=uCDv76rF;`959WW}IURbWhx+l&<)tfmT zGlIY4xnNYEIqf=hib!-wZvsjOcbMpQ2$l^??dGKY;sLzdhn@oI+TX_gXJ z7nVZGsV}_R{zm)}ZcWO~ow<yL#tB^T(Xj_482X5C}N_zguK->X2l>Zq6 z$FG~y1#AvejXZK_%>mAz{1LXau7<@UrG&!wsz|l^;E4)=Eo3Y^ws+ z1*68V3d@G@A>RF$~$VRw(Z!YWXK7~RZck;tU3OJ_sJ{y_~&vx#lbCBhU zenyap&kBMzrW@?{$S1-#E#Ta*jx&M}!8s3kTIl{3m#?lQL2mYt+NOxVdxTjPAfv*M z`ua(T9v)gt3U9>n3Bd!HbEBSo@M?hh1dy4bk{{nCthG$JlR0 z5VIkMX3FcL{sHC{Us%X5XC6y@QBCZATSGqM=QxFi!H{+r8lNg9`We2NY#4|U6lh2= z&T5y?N*lC!uFX&s zwXBA`%J72@BSl>OEELYlo6w<**&8aKO#VhjaN%c_k%U|U({1_GaH|1s3wZ@E&IIu# zdxdx?)|V{0E(=As6fpEb37q?ALq8oc!^4Amz-~+PJQ?=gTDz`>{Ml0tcFl^|;1ve8 z4hpo9^+*33l}tYLJmF@xuzqT`hp1_BbkdGA)+OOcOa_hQ96EJychhOOG2Nwm@g%ri*Qc^KOK{FmYvTOLg0tnNg*(=!aPz7XX#Fg9Lm!<2+BNt2wZ5!l zA~T=dRvQ78%$InscdwW&|L$@cHqKZ_gvFkMjh+o?lH^A;j;Fx5T{8GAqzaag{K2bq zos*i{wa+*T5k3o*W5lRp7SOw`}~%@eoUGj*rqXt&+dKVecth1 zHI8x$CTDI7xxX&#Igw?`vgU-*WFHlL+}jKnYMa`nj*?nfcJVNb7f@@4r7_##5bQ8Zppk=2 z(R~KXWmqQiPg&>Mnz5I}dDvGhBR?YSJY=@b?sz-xEAuC0ktD_8S`eeoGSX^GgPl@kK-gJk!0vFVry4|Y=wjk4<_zm> z8i}og7`x!!khWEey75<^EAghvFil+!Ph%{M&N62mYKEez(fP#w+yQRl@;}16Pu<|0 ztCUbXOdT)%ya5j@{rH??Z8)Vln55N8LKJ(x=p5M~?tuzBz}|;tR^-%{c0ovYJMOb| zB&*-f1RpyUyfgk7OjpvR&zPpCl$=j?n&0KrYUT0h-92KhCQvIKX|)GYyQjr9-)DVc ze_NrGe4rxcpR|r`fk#U9{Jgt0c=_!za@V4lJ5Vo)xzCS5gj5KvX3Rr&fQ4rBPaUr8 zdpxGRfJ`V30J#$^t9#rZ&h|{E?l;nK$wm*Nr|QkE_{#RWk>}x+Y(D+c&U)Uh8e#sR zxqR@A9t`T)MW&8cfz8L*chmPAc-Xm}?l`E4I=eDpnk)v}zzd?t^Rb*+XJ^W}?#9UJmSlXJ=D=#xq_9^pSzct{Nr>J5}Y!%E@?51~v zS$`{IJ{#x0Lf|Z zJqbpPU0J>BG~E9oM|ZYlVpXdR3HLtCDU6oKzxRs4dqoU=IC>bCJgk6@>;k^V=``D2 zSvRHYb8h%iMf@^59BS-bXlbjIsP6Yx@?=S@VA6|!LWkiU;yWzWXLs|hLTJ=&=Z`&m zkKg0dN&7Kr_oyb-~vuwLM>3s)hwB%d19>7xp~2B{@M{Pt-SJ+JtZY71F-(5!%s@@24a ziY?9WHpMYld*H(0=6So`upTR^I+Fja8b&bh(7c2&IJ-xl8vS73BRMH#JUr!umz8nw z&^~z9z)>kLw$HaN6X#*a@jB>b+yw@W@2Fz2I<8t<3$-)K`70+x=yZG)QSGeY4C%j19Z4f|9QW{ZO8Up<1lxbRd9h z%Tz}h%MQ@WOQ(T9wJ8EZqwc16@SI>dt%x7g`n*+&{7tk4Xr%|KEj&vAFbB5z@@ZL+ zn#3~QbB{rE(Omj~{T>6^@A2=hgWRjW|AcAr?yzlg9Bp-{x<34&0j_P3Ig@#s640#M$&O9k(cBQaKlrOojb0W27?fFy9a3 zwi(f=CFv-Y%I=JVeK?m;^^{+!DH+9AUBVfJLzAtkVStbhhXB7n{}p%42FM4Jbtk{jxgTsOM~eE-}Bvpe(Y z+~e9F{$0Irap*jdR zyTtqa0y|B7{<8t}^DFs?QwX<#5f6Ex)huDELn}LN%BMcr-s69Kw4#j&Oz| zRohge{4fw)Sl{K<9ev_CKc+SfSJf{kS2Ff<(;d}NS)l`lX?U`E0|}MeBrx>-4`n_!t;1@FTAw5nM}MA6+I zqTOY2rrTb)dfbjGG*{yV<-=rH4szp;C?YUjv28*qohM4i<nSeypEAyUehorHw$pAA`<}h9oV=VIA*}fzR(V(r8wD*p*(>%|8uA?QR zNkm4r?7jW&-}%=c=T&;n{ap9w`h4D>gFcLlV(v+rJ~wiDPo^*i#Vt7eU|6l5GdqV_ z2g>|_A<#cx2^-Hw!y&B&bO+Pl{LW+%+w0!kx7EKzGv=_a7BeZ)gBCU19@+ygyS(`Q z7hj>FM<%(_Isr8570_;UCH&mFh8B*`!l>U%h(=hApuATOb(POR_jeVl8D%Vv%E%(Y zBkyq^ezK1BwZ|a)MI`OgkH@CpuH@4NEv|T?ae)D)=B zcWR*Gha}0_K8C$J9*MI_%F}8vu~)_oMm`dD8UO1k4j)!P*3Gkog{cZ?_^KZ6OU&oIB<5QsU zpBD`+oq=Q1(_ztoCShp9Thq+2SGuH9nBF-iS^v}k=G4jf+n}W zqWBVCl82rAW*ANmY=y?>&HO|iM1Q9BxgEI6^bl!08=M7mdUnt+lcwNgjb>;Mn!@V^ z^Y|jmlAM1o2b109P^UfsRBIm=+l+q+tr`J0`cn_tt|dxq$> z;06eDFY|*$rRemJvDUXGbMuQ>4#FlD_P7SpCzrh+MuqGg_MNhhj50pTt$U%$y6Py1&cxGf6$7l5y9V!57V^=F(qftW>}M+; z0Z$np?9_|1uwsofJ#$e?{AZLO`4YKCuyMb!*sU#&Y`W73gV+qO-@`aFFID(lvo|QS zGl%#ZuZ9IZa=7+m1>}4+qz6`KqC4Xwbq}Aj+cY$xpVwpRg9AebA6s)`y@Z#g6 z@aFGIx=#BEmi#zRJly_pE{tDysJ9W8rJkbg_3C)#y%;uE@pWIKS$}1p9XTsw0FUey z(I+4c?w(#m9~7$N+^8hzOj;&rUNIb>ga^TFy&JqB^)Z^HoF~13V<07)dA46(20a-k zx?+m~>mR%e=N}shiVmBIwX-|O`8Ydb@_~6}r=`QOVIvsBwgJsvGJa0H2e+nG6-T~3 z4TriDX=Bf1Jas-9JQ%arvzB#9dv!tSf1$K$sR5oXdj;+TRtu-u7oxw1EBSwyD?X6L zJ1$I1aUV@(CQTHd*d`{re(O2u+sdL`uUPI6^J8ppX8j#+!=PH!#(&dp#Jr@bq<(1) zr^kFg$JK6uuXs28t1%v5#XpC{ooa$tRVHG&HGO3H^@$|=kSbozD}j>#e)Hi{4Y-SL zBK8M%aczxEKi51X(d1QBP4MrrT*!GB&o5ZXx-ClMi2e*4n8fy^dZX?@xN{d@^r#pu zCmbdTRgIhxpMiFlmykiLgKC{>D{%1^8xj#c7_3Z`@p^p>6y}>zr37Q~SLGa{;&_}} zUj0inrPx`b$$xv#<^;=ojHz{mzqkGsmN;jTmtQ78<6o8$!zws4V=Z0sJp)(ESrD6Z z)dJ6+a_nW9i>^6SAv2D7%Qq#!FB@%|lEye%nmOci$UTmeXT3bkj|`*3Y1Eu}w7s&8 zY&ICqB^XNMuF*p9sC-9vGd5seXPtyCuYA86HyFE;Co;DlW~pG1JlgCC^LRWKYk#-BN;jye;(nS9 z{)TV(pLcj9#G34pE8sc`Wbo04lkk%Bq@9OmqW`T-mH}xN#yst3yqXfCtX~9STNF?@ zsu7O0%hLDT<8c04OL8H^htp=WvE|o7xab>6=cQ}n8pZ}#`ZSGSlhJ_R0#}j3)i1fy zL$cU_0U(N6L$z|H#Oeq46VFFsf}eGNL|M^Pa<(sY)xg?uo$%ZBDj#e73PWNO$TdeP zxXU_aYzzxPd#O9sRT+-$!wbRb!f^hZ0goOZtjM-L#?4^*%$LuBl5EspX=8EN{diIw z8N}^qWEr~XF8I}yMz=m3i`mJ~Vb9IOyr88Bjdiz^=ktDZ3ZvM5P;dd1qO7P=h?F?% zaU8Mr2{!B4BE;c(R^(#$LU?J$xYMl9VuM(o&Su$=5BK6prqdJdBim0M32g_5iuttL zkMUdBecd2sGDI5q@a>pOka6Pze`#nbwstKgCpD6}j(Qc;;N!vn zd=Rz$rG&qCgh88SlW^Y(W3i520%@u}1}B)-G5>o9oNZO5*BLh>@bh{S@r!ZKr>kOT zB?TALc82D8l;@{?o+i<1V&kTadbAuvo4OIOE$jgJd`<0~Z|Kf<3l=dBU= z9x)cHvz*bm8BOrLbr^QecmPie!-OM3855~DmlS?t9rMg@3@m3CZD>UAOv*r=Obb#t zWgho+Z2mI|5#UgEZh<9PaDpI!lp;AbgQlb&d9n4NB-zJstObVR?$ez*?D>a^`hm-GzqC_qa_7 zedn=`+CK~E6}J1^8J0^NT90$X_x}?833Y)&Qz_9SP7U*K--F_MFaFl1*SJwGmw0p- zLgYO;d}db(#)nqZ`!pR-=va`*m@2_axl1UuYb6O2PJ@wbW?s214yHP2(l5-{ln|Or z?4I7^s%2F$%-#>ydYq-w-fYHhawDrEhI8ZHq%q)&5EeMTr*{{qpw0mv7Kc>uLf>L+ zGq)$KG(#e7W%BdF2V5!kPp1BU{K@Yu$DQ^Rftc2ip;a>Ob7|FeS`j*_?2W z?OXS1;f(e)`1L@~%=Q=Ck-f|%cOq+G?g4o`<#G%rOdmo^FFZl#+yXL5XaVzXGCzOW zHE8-Zm+rX6Jo(g$Jf{Ynmfmm_l3G}It)13BV!q9qENEZf&l@uSTh+0pEz%~2fi)vHO9r1l1ZgSF#RgyS4TI%d>dK%^e5wa{$U!sx-VCU z%%^?45N>>qpxvKFUnyIUp;K0pc>&M4L1PthLP7}qv~{4dzKrLbHJzZ% zD#5L9zeV{jB8fipp7q1326O|7yTOmXT8Pg>x0BBBCT?gK^SyXpgb$b9sfzPNY`NY5 z{@YD>?aPeYY+z0NM$18E5AP|IllW5o*&@Pb5#H{5*z<5-U4<-I9pU&dX=kUuMl+&C-X zn9p{#R0yD&JoP7ycwb{CaoBK*6SB@qkM3I#cZQ=iOmiN2*q-Qfdfcv!T6o*}ibRK( zXL+=ypmI=KpUxXnEZvTx@47_J~a+ zd6T{2KGU4*j&#BeZ&j-KI1UYq?a5C(#+j=z4`%^|)$8Kus(0fsI{6wL{sz2wgtYi* zO9FXYHv;zD8-_*>DbS#~mu`ME676;-LD$QpW*pN}Ml>Xnh}b4L-J^w$KcB(5myyDb z)BR{)noEqzSHU{Q+x%Bi1CEgsY4(tGEM&gHlQ5TylpiWOE0xUIdq>gVover2BuS#r z*fRdlAccH#Ja{A|#4|40kP|T6^$_c2i^pdz+ey|pH^KApADDN(goGSyhsFO?aoqwj zM1Tx^RG7m3e7eX#t&Sa}m#U|)wb zz0Ejm73tQ5EKd}82APP<rx$d7*c&_dw z>uimnslF!oI5HX5KMmtmOc-bB?gO|Oeun;G`_RFT_9Qn-Boq&Njm>|P$b#_oP|8?# zTwMXURgIzDERVLvbO|vXdPk66rz|@7E}pwIU_0HZr;evZQBY!Yi?`5jKx>&9#P5AI z_u;Q1w*Kmd?t+mmxGB6>qR;Hge}g{L@=3IjF-+D{#Ca99(6V+Nji+fSwcCRD zc2^1a@t(=PHA*nAp(<4ALzF08pvBTgSokoKRJ`#zn*%K7iv$qhAr}Vr79iX-VLJt z_tmj=c^X7${1N8Yu)E}l^Q7+AQE0Pe9ZbExP+Mj~J5A%!({v~Cyza@-#Vm8GbRGV7 zC)2P23Yfq#Kgomze96groG`|N{3lR?Jr|U4T6{Jv6YE)9 zaGo4~QUiO2DdW{Ze=r#|lVQg^` z?4F*%2kBkLb(>cc@43&pnlG{_l@%<>K%IZlfD?3Qk-jCX1j^HXi(XDeiLWNvXcX$+ z?}LKvxB1vhMK~{X7dbxc3U_qB0_MaPLHkAzYFx$G{yn9T{8@*88(E7(BCW|WUs(vh zDud$6KjH!G=9BIFr!hETiP2w1JFC*W;Fr8jdqxT?N~HZ|V3I%J{~l46OBX`Ch#i zyl1+L ztvwFIrf(n%mw0o(o+zWt6A`TQjib#TQ!qI79=JZU;r(X}7MJG5k+>Xfu$`xhH*Y1u z6|0@}IAi-u`J5suzH0?y<^k)OmQ0+UHo>@DE!4Gt0ZzJS*yW`k9h341ZC?elvGUkE zsupI;Po#zKQW3whUaIYLxF{1@QF1~mr!z2`mU#|C#f7O*5c8NX&NmjfMxG~Yx<^9M zWCiS;=L`NFp45DFJZ_5LNw$}57s&h_AkLJoCSIy{;77I!);&Y0St(63yHm03wgqVj z3E@)NzGK6rOqgX~Nc&1z?<&oJ*~_B&W$gKPD?Cq{WR`>NG(`j>Ke(%AORX}$;-7bQ zWQ&#@xOOYzN58v(t@m7pm{TSjzL3kuw#Ef+evg zV*M-KWQl;FgvqAcJ&DQAf^%{&6kh~xm&ryH-qs&k3TG^J54LrkHWLx&cLf6 zUw%-l3g+MIg<%O1v^Rp~+E_-Cyb}q>Pb$LIT|3F+je216M-B}eFG5)J7#e=!JO*xF zLZ*G}7AzymqCFJ}+?_l(Dhe2e-2St$q4g$z@l8FR44x^O=a=79!h1J+Sl9Gk>i;1Q zlbkn@h`b=d!b>J%i&M|Z>)$41awzMd|5glM^S|+0-sdsjiShHlFXKW-sA9pTB=~Y7 zn|@0hj~zkTkntg!AI^MJ-eZ%A*2Wbuo6U9iC*1*`z;^zuZ6TgjJVJt2G;o&;jBvkq zC-@~P)n50wf?eBKZx^oyrSWVpIUoV7znam>Y@T1~f1d0sKEX}N`YBqg=q8!xquQ7^ z`$4ZH>sr9}GG7Mz5Q`B5;2XPFUhS`z_-eF|q$2NPL2fr+68sT0qkHrYqWy9)99*S> zc6SrOy+Ml#>KNZU^E{c+*~@+0CX456y(PYyq4x2pq_~@0JfY1^^Oi={TL{N=KT>-$ z4g4v41w8-N@!Lu-Gw-nndEMT}8MB-9uhYZ8z7_ji#NkHg%J2PzoM^jq6OY4m23JdWE~Cz7Zfo)%8_`@ z|I1l29o2As76i%crVCTG@JCq|tbRJith}H7{P!=ASDR|#7h^Qt92x*OPs`FfPET;! zlOp2s-V$<{ugt~n3iNr;pu1Ay@C(13{75t8zKGP(QMDGrH{YQB%tLZ2G!u^Bc*?(@ z!S0e<*OSv1%edw4L($qi7uO>ne##BYVI33U z;qYm)BVFMtEnXAvMHa0O7j#zs5>1>ZmgqL$*!;ON|0b;OY~go|E5culso3+RnHyOs zhb?u5038SD9G3UF8eAsHy4sl4BL8eD!2nsdn;(jPJA%Pw`XpMR$UMU{Qi!)8m@D&8 zz)g&8;!=@LznQ3_VN*MN(b~wbb*e=<6>n1FC<76U$2eg^p+vX&EY8QlBUoSdy~$?B z$B41t&6W)7u>{Ue76Uv(z&b{j>gpSd*I1;GX(>-R4Q0k^n|BxT%L!dk8pl`}j%3u} zG2BYlgK1}RRifLRWqG=i73EL>x%}(i5-d$#NvxhEbKNP*n6xbk{@Mjmnft7Bb|_;v zGIrUrU5xJ(nnK=>I1bsZ%rhYFhFr~IH1iqT=e~C&7Zi?j9*k8o*Q8$JlUFntgFqcPzNMG0=cZd!h5|0h~yU9PJ9ReNYZ+QDe zDH*t}4fae>!2zXW#v+iW^XgKtWuPV5)ECS>u{6a8W>;bD-EL|)R13w2vtag%Xx@W; z{yFyfP3xA!_?HTprsdD9rmN}K{m*bjTM3!IX&}h&Q)E3L*B~}GfQ}s*hf(g!iBy-l zu#eqFo=kNlzSqYyJzoh6b#kGqYzb|#osPdPFGF9(VFAQy;hL^EcE4C8YD^h{vK41Q zX5~$OU~NB+eo{en)r{cEI3+x{^*R{ObD^uOm|vx6IZ+vuBv8&a5g!b?LuQpZkf3fQ zoEw}g*}Wb;j_7u2HQC^EfO8NG#s@1;f(dt;KFj-t^W3%()wkAk#6%VJJ9;0U*+QL_%8|4LpitvW5q9M6AzwYlK*(HWtT|QO}?FByVrrrXjXiW%^~~fosV%CFvy8C4h$9qQxoyb z)h~(TUQ;rYos+}6E5J1UH~)5gKHhd<Ve9at41C@JCQQSm>lv8LMHa?Hvs>3QzJ? zUW`4jXiDsM$!x#slrFjrcn^*u^!c?V0ztK9fQi#C9}QMOV)j0Q$TLsJ_dWt6>!UOKZ%zz zEss6(dV9!{1FR2%@yEWuYK66OsWg4J0$$D+La((M-x*nht;}R--gg9B{CJq^H)x8cP*CKQBPyr7Y8XjBQXv#LSl-^nkrX-ET-{ z`+K*Up0M9W;<35yr;5{<-nID867hQ-xn$CWb1S5m_%uY{*pwKkoV!RZJ+U zggZmd(J1#}xadOxG@nZ09nz{<*S0lT>3NTHU~I#sif16KW)t1c$%tFCkCNF-BLqPU zeu*Y6WXyKPwAon7dUMh`VD|4uUiD}V-mCW}L$=@I!e7d<9*Sa#h9lL<9Pu!rpm^B#!6(t8r!5s{34Rake`;aS}NWEoNM+B8o8brhX7Wf*=+Nrw)p zCwwNGdHSO-k_Ed*!O2;SEsu*EGZ?B+6r?jRB+Af zdN?pphPKwRzC3G7BE348OE|88VLCbReq#}xEvR>b&r0AYiE>^Mb`#G56dJzFTVj}LIP?3X4WyCc@5^vU#@#{_6v@Dl}POT zc0fXw0v@)=fz7AQ>8BOb@Y~hPaI(x(Fp53HE+iUu=q?ZuV;vk&7YU*j9sGtl{TSJL ziL5X(0=M^!OOtd1vb|iWI`hr`bX`FfoJbOky`^p*HTE0kN^K{#H?8T`!HPI#%3XLJ8%B%b;&7ARMl%01 z3MU;Z#M&KuNU5hD7$&jrj>9D|eP%!pT+YQi>z9yphns??dS%hY-ehjv<{h+&v4GA% z3@m(ni=Vo;5rx+Ch>C6<*Vm$oUy}Qv=G#HKT0I`^x;B#9!@+{ZeI{ac^L}#Trzue| zSHlFRCub}lK%;-K&yQU~yc(@J4R)tKJSzdpo6~6a7%kK(iHDn8g80QgY!|7PMkZ;k zgs9E(XqtT+YV=z9BMvN&e9fD*t!w07Y9%A_VzZO9%5dk23)lwwxuM( zW`8sKXJI{>FcxCjxnbPVgdd`uwL2we{`FdAEZF$~d`2ARZTg>skI)E-+fujH>m!$<_r+U{QiH{w+)f`8X}gT{aeX=UyZMS@*fZ zY+2M{_f5yn)3nSs9xV>+BjGD_xP=>8k48W}>>Bln4rT20{bC__ohjy>?8W$c$YFAn z^l{$~u|7eTZCq0tNfiRsal!XYSoHCaaA+(0{ELO8Yo9m#j#j|W;*)SL-GrW76OR?a z`-q0h5iU_v34c6kh4z|c>i;H|-6>X(gK5`!1FI6ev}OzOG#Lm>*T|z=b~fDA*+m=L zH8J>14s_*?F*9YlJ$YM5)O73MjhOAH{+tBAL(()Mx(^E!O2|BSOK9g=7u&!ap!<9l z?PhuNaeYj4b~oZ0%vEtjU^V#cYoY5a*_kiQ2Q2UB|FkrsOV$Rm=~+3q7KY+Bk5Fhn za)dfRn}ru16@caDt3uxF9iALiOOyteLz}k(x>a0Dv#D+LD8o!EoIr(wBP1rjZ zYhd@F7+T)0fz}I4q3(P-ugUIQ2cJ3-Pk6^YV!zj%f^azRU{AMBlM&aKo*>!z5rW*) zKSf*g>m_G?Q-dlh<4ySeqnX#+&hpe=K4ih~ZqBPz0Tmc`BH(~0J@S$5aYhwEpu7gZ zr2H~|F0dozOI6_1bjI)(pO*M4XPO#|f6q=QwpW8WZ>AxC2=9T4*mR1ZjPsOPmz=pH zFLkaKhsXJlk;X&eD&r-3#FT*V@}<;BdKxAebb;aI>IH6$4X*5KL*`Wy*qc5SAC3qvpmbUU^0)Id>TJba-4nRT3IoV2s)q~b+03@g;cx6k__#{P`(Ky*K1RRQ_0 z#}>x@P(W&lj0*ma(m^+gTc_%HJaU)Hl+t>NB{1?lwY4$wgJ>QA&=d;D+ ztP5jTvfP}TsXuK01aV2%6_C4@3lByW(_<&Ka1iD~{+Dxn%eKoHzSoj8-0J7HFpt^JIj3L}XGmX^FTCk3t`Ob6OU|wG!JvB@Vdsr4JX=i=isu|yKtWgSC7rhJe8PDn->nrq2 zXTHiKEDxLIKmzv2auY`>qto>$2>&}r6q>Dy4}Jzi>X0V>lEW(;d$5v({WFA}_DVRg zt__qbUFoTParpb+N^<&nlHhc{iCFdhJ(5|nfe7ERx#)8)G~FLToiyt4z;Js~Q+$Xs zdol=n7Y4w-ji(t~$pllGPFsEZG#}TcfELH@f%(-iI+A&-^dD>@mqW!ud{cps_j!@Y zbp|kH5bI7gD1$`BakLn7a5T#%@AmH!D7{h^4P2MX^(ybA>h@|FIWh)X=H29Tb{mT| z4yKcmjxkWg=1l7)kDzzY0XpSJ92zixreRI6AnGgIFOPpiEWIX?^M{mCaJCX=!f*aU zUk>hhw1m)yR-6udewMT6M-ZAtjc#b7ba4XYuMOgFuzTW|gmj`1v=ScPmO~fkJFLU& z2H(sTp{BPF`PSRSMKd1w*~m(eKJlsMLlfiM_p-cj@&funk#Y8PtjL6tVcd_MKSXb= zc1!e}b4=T;{&yd;LJsjmN{Udo&4;w>|K*mk?AuJ^%b;fMK z;9gDa?rDYm-6DQ`0L98>hlsW31Fk%g^;yi%m3Zc*@3P%JNIpfYDR7(w`ff*qv)5Q5TBpWs4i3&bHTmzntE!2_m?!NS%hk1|t`GWyX z*u8ioQR=VYyqj20?&1h&I(LF@8ZaA&gcict&a1+{h`0E!qn5zmGKgNu?)7`y;Ayu4 z4PiUqMYx*um-%rK*28dD2IGDokEKllbzI+40y~$d@yL8EzdECdf z!ureFq{V}?e2CNW2*IwXAEJ$o^^%?JhQBOBq<054PP)pkd0dJGx}M}({tfO4;}rxI zT!M3#yl9OA>y4dX2xs;T<8$6sVHmr!{7o4OTdv9A&f{V5kIkP|W0}7+>?~M7r!a3!N{KVk zbkOJ42Wy~d)u1b#&zJ2h#VzaBkrP`|x$jm|xS%B(=7%1q|IC!} z)zoO1Q-4MHbBD25>3IhE?RWy-n<}7>LNA;sQl|$eFt6;KEyQc45BE@B6*o9GL+I2* zs%)%_?ZcYkL)dKoNm>zp{<@kx+T6-*VHv#%<5S>}%{H38R1<%CC&JX47)=&#@H-9cLaG_sbBLIfNR_OvKUpmduk7$nEx1z?7yu$=Mz-a5zdA<-^Rn z7=A<0Wz<`0P5$kA&Bc$FM`W{2%=%UIaNHBzx1gNd+%gcnofYxj%{Ew;8AzSDap>CD z2X_^3)mf{v4n%Daq7^n1v>9u6QxoeL9c)fBUN&N;{6>;rBFC+iRz{oeXW{XTxgyqY zguM?#LC3P0uU-BOr=6=HenAsJRaOZ-ueZajYp!%4V+hnFt|q-Jk_8sLi8!0TPnKCb zl0N3=e|94i2Ivl_S^pYw#<-0{^Y#($vZ*|q$09%~Hip`4P{Lp8K``^cPX6X`CEQo` z5JK*-j$QVh-4N=R-gOw5u=UaF-I^17E{@c?jXq%-h zI&(i&GS3&R9fs|D;v^c*D5kLleaRrZ#_Ge5Ev)N&P7kcTwu7!=`*A0gEo9dC5W#;> zO~f5tZ;4aqBr<)6GD^R$f}PdB`3GUyc=Im%{6b64`lc!lxtamC3AuFbR8>4VD+VT> z@aKoH{6eO5Cb`ysd~JJ0Bl5+2 z$&e4KaO$=qhOAG4Svv$&rS>w$oUmq`gkjv^fj>k`W%f$W`F=A++){lX_Kf%7GmbsQ z`Q9wQux$cNU>STxnFjbtHqaiKL@a;Kx=#qnh%XO%Bk zB0m(*D)_;b%rKfQj7OP$2gu81y4>v~X_o76gr9DoX{(|fW|r}6XHm>AdoIG$!o#G5 zO-#w%h0yjl0>Uzaazli@dQMJ z(cqJGp^O^(#D+rUr3|6y`dfTxSw~hZDF@LBMa&q~4yUvg>37ChRzG4(;)nQi$7V9d zPGBAAxyR7yC-m{jl*_Q^N)bP}bci@nFPhl-j{?tVMZDk@1u^TKsLTavu}7^B>DUq> zm@wpr=+(sriB|t7T@BN;dnD(){lHTEl;KGpj=aGgJ;rjTYSo}udX&0+)WpQXOOie* z>BtH^y>J=1yIC4a^O#qpJPJ}2X3`fEjm2}7v&b~F5N^N-#-}a111^!N)SY!1SdHv~ zYsp*qIf1XSFd&OG`|W4Q1S-RHk9~Vxh}r{v?xwp2>N8!=MfMG?sbK6-B9!YxA_FRFHQ+p&8mjI@<#l4wsRcQYfB17wQ|?kjIrlwGAxU6 zr3C>R82vdBaz^eqdw0QDoEwrwddsfB+D#hx+Tab0>x~pD-Fk^5o?j%3>}=r_QN$ts z^-wu>GF@k%fL=!|$+>saxsbCmqT}jWT*Z~Mw1@Q(i(E1#xz~4fO^mU*lI-1B!`)^( z#GZerV11P*y|tNXH7DIk9PAc28YyFuQ4`Gem!`8b5>Wq+C3)o+$eFt`ZSzGw%(gA2 z`L}g&%8WvAz7@~==ZSHa4C^Cq=;wy9oUAirs_z=Ij^$8y|&3>B2` ziGi%7`JylEd!eEh21=$){Gn~nu=3d@<~KHgi4H8ETiXfCA8e)NY-hU0Yz@(9Oco5i zY$AT+`jGftaU^FQ6;S;_zGPPa`I#|TqSp}3^u63ueOcT+Gy*PXMAL!N+W0r%EKJyW zjQ3&hmx#-~5bYX9{cGY-XzW4^<1Y&r|0~C%*N&2N`3CUkBb)zO_t3>h$hSRBa-QdIWO~%iB)D+zF2Bv2bzV4Sk(3?!@M06ouruarP3d;}Tqhn! z)VL7akPt!Y4->IZ=6lj+Gnt6ysbKEfTJX5^m)AO&g$rdY$aIkfch^S^x3p)$`Jy~p za(y!1ajcZ|iDWTu!`jd+GTn9+O!+K}Po?j|!HYNe36W1Ry81jxiyRC#-&o)D6)_~9 z|5tMXe&U_Iu|(c@4oqTRyI)O==f*Vo5iWJCv%{RE?Ns7cRecw2yRuJ`hbpO3z@}Xf zz`c)gY!sg12F(j3ZH@tqU&wM>>^Z!aWlwE;mGD|bHKd1+7rb*W#_^tO$;6A38M9Ft zGsP^kz-IWHM;kF~$O=-X?#FmF(x?>W3#$x6X?;XIe)@2b+`OU7-5}EVF|!%;8$Z)m zr-q{G9Ud-zF62%0M7ZV35t3^7h`aq=5%bFmKyA!vI?_Q4&zfEUSN%c!1_O!~?7Q&( zj1mN;$zk;F09d9rky`&3k5g|QB$F(UaesC)ru42(I5|0m9ucab?2Z=3>{`sHslLZO zd=lx=m;zz{Nuzs0CLCDgN}vBT7U%3NBag=j!HuzP9X|xYUq2Zd_Fo^;>T;s-)e07= z$m8iBt>C0Ri*`20p_ybTmV)9{rsRIWw@Dn!`^gf zavio(sPrimPVGEI*N;@er2C=ZC6_LoxaSSNju4Vzy5;cpgaZDa)&W^U1!~$Ghe~hP zlGe@s+@K;=yz9)vEZ-Qq@dNX92umRDPzrC7H(1=DagJEFjf5P=OS~C*4*E82qSHo7 zi;L#?kN9$$*nioD3v<{Mmaoh;*2l*7n- z?(}%i1k?$<3L4hN{Nt4s_#tOGdE+4s0d0yHU~&$g-=9TgXB&%;oyjI6{X#g`Nm_VA z^Z_RAEvBbSRq?BJ4><77{0y!iXWq>swZA9Anp{PEy|o(ho~)!l&Q3+yq}y=ke)WRa z@)cNZx15-bHiH!`Yv2_d2X-lHEFZ-3`vuv=py4^Ujd{H`q&$KzgBMXwit#ZPZ6(UP z#&X}^s^dIi8_a2WP4_U(-2Sx?E_h$y)90{`Bv*S9dMA||IhM_DvzU%;#&)lkN;vQQ zIWW_^BAm_UBB#gM9bJUDVIi7va(?SH|TY(*(>ZKW$EjPbboeG<%(-fuSM67y0jvc4@X z#`>HTk8z(4lFIMu{KI`OaH3uzxt+EeWNnr3p;r^AJ)J@?a`E^s%98asPv`8*r9>54 znUdYBk|oo4o3bGJMjwCseLYSyT0!iGS8?jB`zcC25Q<-W(#uTqTt3-@bam|(SdRaQ zD%&c^p!+vq^KoU|HS!9qG?1ZZ?c(uNnI+j-9Kc;@Gm>1NRIIbGR4eDh3O{-W4em+n1c8Mld znnW=c&<+04)kpX#sGQ^*j)O_;9omw06Xx}9ql?bPVM)(gvTag|V1KiTc)++mw!?HH zA%kS`$>>~=ch{z6tS=xda5MSteT2Jfq>IyMGta}(JnAk#0^c^rLggzTe&rK6e4~9I zp8R1v+j{oy=yN6JhV?=X{eHaOm_>H4cYr86rWI_y1U4JTQNvl8cuT{A9I$Q|xI9!6 z%B_zN#f$IO8a)&q#+|-!o}jt2#CWCBY8} z0r3e-uovsc&Ik|Ueofu2KTDE zl97*PVF^`2?HB1VeFMEhTjxJ{m5YD|0{1zApEE9{dX!m;3w|EL@v$N~r!Awau>eH8c zJTqy9WQPBnD~0a{GG;|;2;G_(k1rb!kww-cxC9Sr?AYD{s#m_y-xhK>l8RZzp@d)H zz@z%6Bg7^40T->Kgq!9TLPNx9dP8?Oj{WZ*$!$7BmJJ;svUDpv%tlsxJW3WE1{ zCepm1c-%}65#90L+*0Ve2xD_CX%mRrm#j^8n=68 zLGwgcYQ3fj*KBej{wuo8_Ndq6%Ofkue~azmD)W;Y-3yZF@VV-Js90CQm~z(OAS;Jb zA6wzbyqVPddK@0!u%1jcpUA2IV$8Q&JnM$ON^=5LaO1iXC@6i;|4b;w=C-BeX-g)T z#rC$Lf>^k{_$0NwGa3({N&=@hrNWvkukq1#o;(^|4zf}5IC^b|giBe(e7VkH>j_l) zbDBe0_Ub1OMJ6#cOQ?!@PfFo?bP8YYFj#!?^Eu*uc_bXLP{Inv37>s>6IHq*CH|!3 zPX>&L5LnlI6W#GTMm~<3Tw(b=VNSZPL*EpCXQukAe8=S=5&4<$RGd_(uL|C9IAMeu*VK}%gV^F+Clq>njVdWbse^yI_s{BRnOKLQ_2$$<~|dWE_y zPnxnVm$)480SJ~uTlW0VHc+PzARb$-+=!x;FUPg1VdFBE7oMF$hccaCCr${{XHMkl zmulRR;!27?-{YpAQN+N9>5z8RjhaNWj-hL5Fw54%thbiU^DL{f=}-%-;D=%Gr#B$2 z87Uk*^aaa<6cN+5)nGnP8Dkf;z=?y?XmtwncUALHv+_9Ei81sfJGWDq z-)8rrhrG?tMhsTBCHd=XxRV3fna{f6u3S4rqqoN6VI@y;Bw>%>bHi7>G^>Vr#ya71 zkpkN1G=ki%A@uy;I9$?TB{}nTR9G%m<`Ucz)lgUK;TS%)5Tu^P^24^(qk-K@@=WxW zt7UnInO_6h&UzJ{aqbZ&=T(q|+5up)PaWS5eh5E&BB3VR_alt{ zRY96@96&Fdm$YwzHe<*%o?`hg$MvMgH$@=VV)}dP)L~Wq)_OhBJ(t?!ku!E8q^hK1pUum;Jt5Z$5>=%I3nv z#+NK=o=r9<+e22`fz=x>hhui!2e-Wa{KGRZ@YC@k;`-hQj$0_>q7^Nm)a^u#0+^OH!HT#? zln5Fg6yo+j>qy(HNw8;@8g87D3+;Dw=~G`Z2CQSdv&Sd6Z=F*3eT_eSkqxCyX5&#x zRf_zy&J*l^ERCK~SK;5)uXK^Q9NN#n48xjA_&f#1`2CweHXF);Zio{0E+~TWI^p#E z0B!vBsSs3N4CdPtg*b7X6&cc?2wOl7%?ko0ov^CU<8jCXPvZa0o4di-jM{Izz+yuR z-SSKoBL>}o7JmyqeAR1Q-jzsx-7$sNGIIE;Bwx}Sm416HPIstcO`WKG%1xvIV=d3>b<9CT<-?4@ae??p$braHG&86cE;?WxHNbTi`TsHgnCFwPQ znoabWSQQ!P%vE<{ukDSUWH9WRA5mYV((ol01EIWG|1mWpIvgI`{ z-oO*t{xUdxl5s**yP$EpB6VlEgDr>bh-lnNZjZAH{@u>r<7dv%k26#-#i~To{e3uX zfH*|`EXfJe0aaU7d}x#aS9dWzbGo#6L8(7^5g#Ggvih4SD7INL+rPV{h|BhN!t$U7MzYd+*+bBj(Qh_OJbTvNM-Fax{gBOn)A< zycT@hR#FwybR1G{LE`opnVk!+Ky&j|FjjFiQsTH<(CsTRm{g6wp1A{$Ae8rg}+#769W-GUIW33hNd1X3e^lYU%E2rZ1 zA|dEwgxRkScE=x;Pt^Ncpel9@o>m@AvSm|*IlrEutU@6%h+7GPb*gxY>3%&jv*?AB zap+oLO?Jyn=W?IOh&(puajKf<=ru9h$5my+r8STEp1VATnJyy^YGqtZ+EBc-C{Uuw z_xr`;lELhb=Dt^8^6?ASzONzXb30+FI%DfCY=YM@L#VB4JnP6_O0rY}xjQx*82+yc zx@+oa(M&BoWK#%7M#u90bVCDGkE5Qc11 zM5|A?z(OUMiVw%(*2i{4H`7wMxUT>`>$Z}#dOI28a&j$j`R%~ z%&nZSh`Tgn!EW{((R>$mT=OCdvOTZyqki|{m*G`J`tx{jV_tfF#@+pFzMYO>Io9MM z_7dj&?KdXkJ6E5Q%K;n7qkcL3qgTLK0VC+zYh^fa(F#I$xpHTFSnpo)IT*Yprd-ejw+*uJ-oJgpf8 zaxABIbCn4G?fYKibF2sr_t}$~KL)~p^~xx>ARBhQA#}-f5xz@WPM+wfag8Iti5hYa zN<20*{fDB>f4vYJxsM-b{04`bmy^|K3d)RCQup=-th?$={rx7e4!&MkYQ0cUFD%3^ zKRaS&G#UO!(s{?#{JwuYN_$TsdliXnao*P*S_+|LMP^8LvPVeBNKsMIqCK_G`##sH zw2@MzNJW#D?StR_J-`1w66d_H_kF*v*X#KTW8T_XiV^TaO^xO8hWV5~HMx+n*8TCGTsjxxNMr+}j(E=hW$zObLa+T|EoAA5>h z#5A1U8n58MzA(CdnmQIwehMd~E%=4aLhOw@N%95CfYX^Ljr9~YHSVF#hvJx5$ATF3 zWiMDf3GrwH^Krd$gz~$}sG@!qwj{_=?UIkEZjwiK1uTQwBPuwB?HM;_&7%w0+5XOr zwIttQGMC$|iU+^)Fs-(Po-I|u*oeGNf{PxyqkMC^$=Mq+%*xf2@7SbjNIvWFeFb10rx7eidc2!8zUG~6)Wo?Nhy z1^G)V=$;q|`4?x?$*YaT9V22%mKJTTpC(013YO6q)#nOpk=~&rfPw4XnU^12YwT=YC@=F@@&n_eJ za8E(ZOH#(JH zy6y>%OgSRSOzl|0?iBJ70M_1gV~UYj>R2oZ_<060Io8ou|6a0tO|fJgq4Zs(`|nxq zu)8{%GJncXw|jJCx-#C}ng@%WCh{{D72@4h9;9zaC--N9D)WsqFXHB%lth#0BGehR_)3PJY9^TvtGi_XA}~lKKc_hxr(UumlU_7&SP6fsLBLE@#n{UR2t&svZTemw%|;f5jx zjOMbXHqidfTFlRI3!d*Q48{MwU$gj5hi%i zHCZg{(@N$jZY0yju&$H8iLm&G0k!%Wi)D!xWKQ%NPGg7)R?H5BA)3MT{y$CZdFBV1 zV-N9tuT@drr5&nf+@#5jFKS@i3Q^k^3O%NDqW`%^#8G-ZybVypwIBlRt41^b1XR#ItG$zPAr8@ zEdz4#a0kYal}#R!Ij`d&hfaeV zn11QbPe1($_f$V7J3Xerr&$_!Wbku%^u>iXXE6`(30qc4eu_5gx#OjLpvuhGj<<2frF!w2^&N>lXy;I<8wJ+V{Iv7jjQyHgPhW}KVgVVxo zh`x(5T>m4FhJikkIWM0Qgng?|kcyk9xoekIa9j0jNoL9}S_5s%E8&lq74K!5h%=Aw zB356S_V`f|+qWc2=DY&L;OEDqc zjW|5b;hxUXLiNfpsAT6N{nP5`Wqy-+Z^DHQ9o;xvzmO!VXTjf5%)?e$3$AZfXam!b zGZNR6Pfh2!>eU+PRGbg*uHK>kuT*i-i8SUVxX0VfOhpH`cv7s?JUrNb4&(0!~Gxz|2n zfmG8ItYv2*p}RelC#oQh2$t+*_w8nxtduzN>0CRvwp1QJYrco|b2%D2l4UU_yAf&2 zaopHU9lSN_6+Cq9p}we%K`f`)vNwfac(MTP7at)S1u0z4Vb)W>Ap$nzMf!{Ra+~}f zK<%X}VNC+diGPVB`BTq=W`QyuV|<<)ReE%ZMG$IjcOxTKpX1hiXUyK}XRu`XJ*r?e z6sMi2gn@JC@v=)Y@o&s_QaKdYbZfab-Mi$!Jd z+?(Z+R{n&|N&&*mm5hn^I++ZRTLJsnS>p8XQnrhkN=@?uu~K;{2^lei3pp((+I2ow zGV^DCRzw{d4jNH){C}-^c;=KHx!jh*oiJm58*&*!QaxzZtswlCa)P*Z?iKWO_p(e- z4*A>i9DXLVUe}lsh-s3cIn{yKZoHJVp77?x9y;iwmj^dRLOOk)4o+81l6Wb1rf1`~ zfi|Q@wwas0K?$>VT$Rjxepn;RUuO};KT>cfPYGY0uLa)t5^eWl4DiXUnKsQ@xOZp* zdSBWp>4bHfr-(WI36gB=rO+5OOtl~;8@dHIr42kagVi54nZ`-9wtGQKnF z9R~c(B&`R=!qVxgc+dU~V4^D>bvF>J?begD;xNG*Rb%n>Bkg2G-bNy(@@S_Q4=pE# z(Cn)*XcuBZ3N4&CDK!<=r5*$k%Y*3)wnG`eoO#{NJo!aVs^~MT111c;Nk6bmimsX) zc@*|UxW%CZ`LQv?zHlAb+A&V`3WVABjOdWqPz;Wi7#i=Y zVb$_y@JePAEl3Q+v|n~4@=vPZ;It&X;JKbexl9Ei%OUPs@Cfe8452%(WMG${1sQR6 zKR3Tn8s{U+T!i>g$KT99zy2iay&cZEWyqpo;WNlM_=DO{WegVcI;el0&-*=2#F~`d zWd4h%+@}>b4|CMFl$9+`iUxMZ!an`pi6* z7AMJ5y))c{1|@u&Sqno2p)^EO11t7ag3UWierR$MR!OrK>Inm(u~`8-E+&A_Qa9Q# zJ_dh}vmleZGZ*}~I~Pa4UqS|bUk8*|%_GS)Z= zWT-^X84#|9$>}#>O40*is$T~l|1Bb(8tI_H&QS|ZUW0XnDotQ#27|*J$i}%BxCW|$ z^Y0fxj8Y)&4`utuV`&h{E=9G*$?RUUlobA`=KA(CpNZlsW**B~?xdEUpPp1j3VP|IhealGfjv1UR>jB@I9?!XNzD-RE)KDuwM$#u0^*0Zb z?Us?6RjJ(9d2%>%j}I*LK1lC+Gp%O#DRR|kpTO)~FRImApxBI~vs>$@H2GyI8Jm zmD5}JRK1IOP8);fD?c$#^(2AeAY<`y<4$5TdlPwhLLFTfFplo+F?837N9fnjdbrlF z=8nH&J+>!dS zL%ibG!3&m=+%&uZa!n@FD=8tU_s5b9aw`|qepVCh{~E(BtJy=>-q6J1`S-y%;}x&Y zcJaB#6UYhsu~0Kl8iyWv4LbUp>2UV_na{pIHNUP39G4o4$I1Ukye&=1)jw=cvG)n& zXAY#vo+0>~>6vi_g!>??g1=a&)&F#R({??)c|RHkZoI<3DrJ3SHxh`!!OM*#C-$YW1$0Q!h|IB64`s7=1i`v8cF6=~GVFvl1p7Wfsp}s754kkSt zX$;HnJbSo|{5+o~xTBnePycNoBkoUyjZD+a{vHkWeR?!iCj&QTTM~_R`?)_0l~I>< zEKa3<^jdQe)(<{InyQ9#4(DWXa!)15PW?&uF^_kB2_xFgru@tY@i?b!H~BoVf~zpp z!nJ<6Ae!kNSK1gwoh;>S(1|1%Jvd`KelYxa8Csa->BGCKxDV>BCeA7_^@bz5fs&Fg|BZ zd&UB*bBy=$b}1Ro+XIHlqg>Jz`0Oo19d(*;*~&cf*}x9uS211GnC;@3p7W?D5H%t< zl4gHnZdi>n)A>cLTdMR)Xy`MkuBNaaft|ELz6gMkS4OLHsg5C6s^v)=z z&2IODjL-+dM@!q$eW#ez%ca9m8Aa@mtOc19$}~Npp=H%(ToQsYC8ti37lO8z2>G${x1 zaT$>|^9o)FegpidCwzNB2<8{>$#$^Hdqs{M{T#QeN zJDImo7t&ZRqbv0;>yEM>jC|#t1%k8Hta~NFvm;oUyb9)4wwd?CkOKSEYlroCnO@36>v<4abiPmz~gzV>7n3e z4ErP`-%y(Ai7Gg$wjMfcE>oWU&NitV$)O)M!qkLB{62dxIn`?j{rZZiaXML|;qM*& z5aT|xe)H-sL8GFHDEJPm>Q>!O_06?$(~mnaBDaDc{oh9%AQF*j)kd(7>7rx(-@#7p z-L$?V5YNbLB2T*R3+`zfi*w~Zu|Knk%pRbQrxmk6-E|CAoAD5%r7elJkt1h%Q3FTx z-G{r+!ssr>5F1<;1e?8%@wdxVaj^YoXm<6ZZf&fy;Ccs43|c5OuxrOH&9UTS$2xcz zri$O}^Cjne-Q)KdE7Fo^+LZ~;Nvnza=EO?Q`6QIhs|n$7e&%alK3RmiUW>`DifnG& zFgd(-@;xLT-briEFpu=qeI(q=SI}*5EY@lJL)bJY=OWno`Edc5c1qFFtMB3Frn(i0BTF~ac)ynGeO&v|Dg-akHx3>dWv*7&KQy+s!kuY1Kmj{bn- zWDyXJCIyI(Jog3JxE%g+yn|fE)A7dk%X9&mXeAty>Z5UuWIiqQP8Y z)mM=_#1~=n+g-DB0d=#1%q65=ocu$bI$9@&1L7gyNuzG;&B}YCi~H6?}PBY z)LBw#HG)g=VIKR_Rp8Y1lXh#f-1n(hP+v*;n6hMavOP#cnq&3jhJO`{dvTS(% z5KNkw4dp*%`Bhb!cy$}|jCCo(GR7`GS9B8w$4{m4PnibGcnAwjL5zn9%|S=C#}7Lfpqp;na1MacQRr zhKh^mf-g)5UYP?0L0|Zs&qerd%U&XXFPj^GSq)$1hC#IJMH)5U02hyB`*hX`Ub&rV zq+jZx(@u>JGzdbaFc%`*b%9G{dzqB2Md0`64ozWMJUO{+m=GDtxBO1RgXJrT-;bA^ z{Rh^C_k(q*oOYo@W-x!+r6t66ii5zXxL=ggST50XWZ2#3s9QZa{3+zKWs>l~n6qRA zKIOLDQNW^FA-oMgLXZDbLXmAcDCuhODR#xIdu|``i`NAM=08cR4}sF(bLe+7ws^fdk93-TBwS&A%pxV_r2w<^+yr zEeyg1EGzW8Xgqgrz7D>fR}UMH^-|k%)<-{*XT9f9yziB}7_h>M=*RkU0}Yuzk5Q1k z>LS%Wq=lpRM8fM?Rl?_I^6|q68}hAC8`iPB$>Cj}L1)zvnsJzAKMAvS z=T!v`mG|g_QDf26qY0LC7W}n`BHU)+N%r-%a>+tD99|a=<5D-#7M7KBJ>^VnmX8rE z?PbqtZZa{fF9+e=!6@JG4?+~~2vZ$f7)L#g46a!L+)&oF_n0x6aXNK-8i;>hvTn80 zGr5uiInk!NM6N36HZ^A)2K&izu%hQZe{?M4>(=sQ&#=+3He41Hrd@%K6$hzVCgakZ zoFyCQ9}vuT=*8`mcoMD6`b77zOsLs2@VF;SQHQZL=By+UNtd|ZZ!GimG6U-NKBitb z8B1_MD!i7y&4(P75!+0_zAn4)>%>a@+eGiXZ=KbIt6xqrXu^1MO@kV-E?c820m@R z4c5)2{BFN)40kLc`Ki-j1A9)>n5XN1KAih6199?Y7cvhX2=*Boi@Q5Nlbc6f$hkZ< zme6pY0luVg=J^7^P$?ukj8Afi%vtW$Upm1L8Y_0$a6*l zch`3>{mRZ}n@8Sjn;0PCOE z_z=$m)El{kNU!;sB8D9nIo-Q=1JrI3=uOJCm(glCT3FuY4k<1@972eb-;6}!cxro|y z9?Kskw(!KVw3+LksEm`_ZoodnTl9f-FdD|5C1!6&aIgDi(Ikm^X1ae-8xw8xPpE@f zcjTo-saW*DgBXu^$<1W5F(WYtM(pvU{<=)>T9hQo$;yn)z!^iAkbzVIjE*ay@tA9p z^Ze*B!T8MQEHT}3mQ%Q;hG~nNz@RXK*0T=c+ibR*n%VH#w>nYvLO8ioXaaF;7G0kI z7#0^Dpb0TiI8bCkv==^J;AED|xv5i3xy6=&&(sYWrX`80`;ucv_$XGq{%Nk&^s~Y`!Aqcl# z+e|L5xyaqvs)5_@7DJghkmes?c|)FgD&~grFCCIFbL|RpZt+VlA%}IoD22lL6)tr5 zh64O4y@XV)StS^m)F)c8qe7COYLZpL#>9F!wx*B|&uGT+5JOU4%R=WF#*|o=4~{2K z(p2`jkD8DpInOu#D8$v<*gMfo2O>VQchJsIn0Isz^*u+?C&iMiQ5w!2meWAZGhbn$ zNdmQwQbUn+3w(0j!aMnXMC2zuJ_Vmf928Jorjd4k-Wp{V0?7OicFL9<*ZjK;AFLEs4Txg@t-js3(JSM**}Hz z3F0y@Yr?J40);~6_xs%q$J2(;?JU#X8F-NV`s~Hc)Ye1wfJTtXj-n?{4o2^vRZ#t4 z4j)rW@zY07BIn-9)v+%1j!O}6++h=q2xlD56&p$8$I*f$jY(oPmsB!wa|QHl(!k4l z-y}KNsKd=T(L0@V1+RctEZ5vnTnQ0BO=)j-Al|fFMLKF{a<}%%i!{_zxYEQs^x{O; zjnW#&YO3Dzt|!tkwbYsvJH>KqsVcU;@`w5J&e9?2LFlV@j*!m>1ieg)b8xSOJ=^7I z&(I(&d%23#Dfn=UnU>Yd7!lO(F@2|{gO)5?ar4z}KG0c4++68T`nATuuUMu}=KF)# zeJzbS*@}vv^GSc1EEF=X;LC4sL3itAIyxy3JHBrwfBr2I8l6hSgVzrb%>W~4yvaHZ zM?Ho~hE`OwAQGzE+fE&RiD^}e2Re)*rzSYc60zLrdb zzOxE=dU2hEbyM*=5FKZ4A*Yfa2sX1_=k=5xvS`3&(!w|`S(kF)(#tXQd2=MrVma&W zx~sT5Po(khcz@`(xJmoQm|%Ta28`wXm>e&U4;)%0bG~R2^QMkINH%;e7OEt-V_R|p zk=wliF05zwxU&Ti-(g6{EoJP}#4HHNoGWNLrY@4nNaR*7*hfEfYhaCLBxoqT=JQ!^ zMYc*RVd*2d{6hgQ5Ks zPD;dld6pCJnhJ@HZ0Fwn5K1QNvhPwls+_VRx})}S3$<9+o0=c|bi75U$Ohw}&U56^ znvtB{Yu4Avx@hC;ep7dra}mz22G3)fo@)ZfkE>w7#VlCz?+|rg5s8PGzEr$5M+rN(KYX~AoRu-*dIHDdkAEMa zt*Voj{8hugce$`m^$Y)2oQ`R%liK&pBkmWQA*M_3gJ9tWYA{n9y*=)-uDnOWt%b&7 zsd_E*ULr?o8N(|0V+S-U>CvUkJJHa!mF$na$O*eNu=sZwWc>)DBmb~-mxmbOPb9zY zTO#A}t|Cu@UvlS*l?GYy;jG|#ih_vV#0S7=iz~34`Q{Xg$s>f9Xj%iO{apb$`UOMFr$koho6caKWx=#$s8IK9Ur$nJBY!f|?Fv8T~hc+H8)%U=>T!=C^`VY#W9%ix@*`Df=E) z4MT^zNLY8@i@&u|9wTJt>KtT<#2q<$cGUs!dcKy2a7aVA4;tfx|$1PLS$$6m+ z_%9lZo4$X5_SI^+fv1wN-gO(fEF}ZYp(@zOvYd{a%;_}NnR4glMj~%Im|J@Oi%8-8 z8HrXi>XQPFRq2F9zdZQH`X-FDdQ9A0*dA@1I>zPK!uZ@RbO>X*HYhuikj;+;d1_3n z@!3L}r%i+7Ls=fm{1M!U)S>tIG(7ci3Av@Wk5lwj!ZRs;psjR^Zc+)x?{B?Gz?+fW z9o7kMbLAEMx&0q4bYyY!mC@$e9r4%ThX|JoptJEyamJCs&pXBR9aT4iifyALzgY@#9Nh`+pTNvP5a!MK=S(e+KwBr{(iqm0>`-a~Rt5kIA- z2?r01BL`*V;3~`Uy*yY9E-%i|NB33mfNu`W&e!6N?&hHX=xt;Ss6d@7>&J`>hgFlz z=(F3J=&}7Sta^Sxp!Hq@M>+q3+q07Bog78fU;0kMu{>ekh8csC$j)(70GJM`-1r3I z+g4GVD=feBxfs;uM$BKlItOPy+e)01EMRhm20q)zJn%zw>B+7Fj1w;>DbANTS#_4( z*6#!PI4kPLa&tRJA0a&lCUU#4YGc>Wckpg@A0?~@#3Sx41Sn8GBRLRXkFX~4Qdhan z*~~i)Nw7KM3N@QG7=s%UK+*1va0bmqV|h#RFj5U<+55fl_zxJ`Hk|HB3&QXnN64=? z=eZVVHuEREl+1jk^*T8A;S0EzK9j%rl*gu3$4T^}R?ek^ao%plg2&b!G*Kigp3xOV zjx}x&)Ei6^ce5PpGUKOE_JJ{wxBr6Ya(=>p5zQzwE0av^S_wg)6!C^yw%=r_*dv{dCp<36Ntvny{?GL`uWHzYv$??!&X`7|7;YDdKKah&!vS^P$>LGjCj zRJJJy9aYXVR=^=a|CKMeu(E&zKBxh|;mWvm5$jl4BS$Zf3BtJFtI6UlA8u7T`*%Ie zfut1~v|+0W8aUU&l3A&Ik*Bn{a`J7W7Bm{%nNNGz*E?Ve>*Wd3HOgu(K1cNQ=kweh10Va6<@*R6^*g+F^Mt${W(=c7$l=4&uVD?{M9o?Paq-3N zMDAL+pxxY9EWhCkQ8U{@`erdERZ13U_>83Iu7soR9mZ+wvFCJIr^(Gp;eaDT=!}KB zxOqt!7^R)yo3_j2s39Hj{gf{q&-!cTME8Sof~D|oVLM)%pG*uMIKx)v0ei`M>i;+M z+nHALaGa3!i_I6bwy~Mtox+8E*-!BV({MgUz|pxie6W5IF4kB{UOOXq)LI3Po#>Nj zIBjfK@?i%1{*1XUuo`PDw(}lnzG=q{;`CG*U)_EJu_pic$ml=}(6lBdeG53vFeRM2 zKMq27Mbfwy<||kq4?Bym@a9zo*!6HZIXvteH<)?am4tn;CaI3U%5rVXuRSIKMuWg& z(|A;Q*a0IhYvit#PQvNl+lfK1G(4_T$1!hHVCe!&x{YaxuiLhe1eqaRR9?R*VA@%U z4`-0J0$MKY1jlI}yzQm;_|WSy`SWHXsI{tMj7Kf>uiH#_4hll!%GIRd=VL+Ezjz$b zxP`1eKNZqEdv4KBPZ(R+IR~Pa z4B{t{bS(d1N9GzRz(i{`{PltTe61PuxJ58t-g2I(N1o$eisW(N$a={+|9^ddAG7LU zdY=vdad{U;Mn#hmfz#lA0?VlWmkHf>4$z6l;W&ScC9%7nx*$4)b)y?P5c88OV2wx# zi`m`qUWhz3F>Jy2rTN4?z#fv=-Q;*#3%IQ2sJuJV(j9jYJ*BDKwR>ann_(L)@#~_O z)YWlLz7Ra$ec^xgW@Gh=tz<}f0=KF`1?!c? zic#|9zyn2mFzy{(7OGO|`$4$l!449C)SFwyvZ4=vRD$c(5IVn%^|}Aa2dQ~ce9`n| zG+FON_Q%z7i~W_*Z*Le}H{D1-PRm7?0~Tbd_Y%Rg4Lu_JoM)0=5Wmq4Wjq4{4(JJ(F%&qJW3|--64;b$tF1mJem^;|ESo0UJjZmIo<@jL!~Ki|raf zR|KnP-<^Mh?ZH zNil?KrfOmp#Y$)A$WsW0Q2@z;nflB~80R*q1`u2;42H)19&XPo5WHfzW<*V$Z# zoT8}7G?QyP70f<&RUCdc8Aj(f^K_JqIDA4NQL_4vJO5b*+lI0Jroa1XFWX5ucAY0P z7*+pCQa?6(7m~hXH9%%6pB~Cl$PZpPqfFV=WutqBgF1W3y7axAW?VeAFe7h|4?oz~f_J4l$tPf?v zB&IBKC0(6%LcM*T@!ZxJa;9V#q%r=g+>sm@^4f;J{dga@j<6)wJ3b07zL_Jcd0WjT zIUc4pw{>yvpZj3Z@Pbcs_<%{%o{(^Z$&gk)2o*YBfvxdIs-P8wipO2aPvZ!IpS7{r zdiFPxRkel4om9cL64v43JetO-JiwjHEXiz-<=lNv1x+4?Lvr{%S~0@_x2Zn@v%Tl} zxN;@b2=9dfhi_7s$PpN|V*ojCvQjv#wjG`PQph!{jd10T3htj$0!r?aXs<;e-XF?* z-P*;15Rt0LBPN+^X>g}f%p19PCwq_ldBM-L&&BD)io9Ex!3D89>4M1bkTvf(wJTu# zUsgv+T-J3#-b7>Z?~~Hzh975;ZOqGO;#VY@^Ls;CSKW0RV&f#>q#4t76OEI2?6zQc~ zS7R>o%~u;)c7XXUgC@eS*&2vf>!BfhJN5k?$of;(kaaE@g6$+8v%?sN!DuREu?}d3 zr|}Z+O|UQy)e9DrMfTgd-e6^vw!aNJ>Hf4!BN$(cFOcq6qqt0=EZ#fx1_qS;p{f0< zm^G>nG#c{wp}t9|9)64{C021UA64+Vb-+evlzd`D6{RyRfy zo%K^e_n{)jN@YWrct6d0a34oDS`v$MDGOS=3$b|4Hu7-LCdgyYOZb!9kak*u*0;2x zlxGP^8siAFrl{i6yjHm81T0S-gw<6$$tbU>oHaXFTYDEnKtL&N-~7MKy9hjXed9B% z3(&{$5Vcfaq0(u-K3);KwFO>XoOwK zs`TXKAk6vAe9PJ1oVBV3YOH()n$v=5qzUsy&n$wQYoqzxZ-qGgf(J?F`nl0PvN(0? zJxILfM6dnQ#et{7fuu(+s2tWK8uIHo(3LWxH_w#uQpX3dG$`dm;=Ayk++$)CrUHw{ zv;3N88QeI2mim@W#4EY)A+KvH|4B8O@dnqCR_5t#dZLO`_$b)nI-lD6u$^p{Jz11B zihJ)k4(&gxk&2Qc%A3oxEXG?{HgYXrVe<*^o_S18G?+p}BlF&~`^Cwcb@WKUV7#tU z4)U^*^C#VZj71kWldea`E z8h2_ABC)U21iM+@f5+J-n32&(XN+U%-(u|G9wxs@lFa<4e{#_KwlxU}QUjAmsyNa92Ryl8K>Oo^@Nnlb;>>!l_A%X0wD*-{ zC+lshj_DXXw-RxoEE<4ET<@--rzX+c5)k)8y<%a%v%_>Uq$eSv75@Y zmXcRfcED(VEgZjJin!eM7v8!29uJSoVji=VaN-ctGrO4Hcy$(){vOEqIcte!+iY%Z zkGyE|s7%h`K@k1CTow7#DUzAryjNO0&p(jN_4v*7QkL0dK8N>@572pCK^XPz0@*y- zL*SReGMkku=D%0!lb7FBP=$3E-D*&v?@WU5zeVdv#(~S+WOHTwd@~om*gmHIR?Lrm zI0ckUZ}LaorNkY?av!<{y<%MvrmMJ#1*O!hQS_WJyY5J_zO{n2B5)UUPN< zN9jN2wfN|8Pm-(Z+T4nbE+r&z$`sK2B!gCpuOW4fGnHjC|JJM!tCmyTe3=cfExwOSTP%tE$7S4Fb|zUjD-yPtgwPAML$PqcBape|#kZC- zrebg}{HnV_lY{l}q0e_XJi=O-l=cA~Qj;X!o4+oq*jG^oqbn!Vu-kz+OwE>9ekm3d zr>Khzj-+#rkq79pamsioIUH=YU+}hVdAN+}7-sCb-o?BEl_n*Tc1qmjX0nKPM+b6XLwzK(|>ZH$exN*}ZS zrhr<=HGYB{;+6}`NxHa?Gw5b~Jhks&RZ`Cz(D&$Qn?-VEWFhVe%P%LcCDBVS<_cvJ zu_V)#jHr-?EK5}+hf<*A$|Bk$8;2KtEQq#0%4J%BGqL1i?^~Bq)&Mb z46af^%V%wnwi9S1%it7SmaE0D#$^;68pU7M#Ho!GaAbHGbh{GIXQI**A=RT zdRqpN8C|J#%W!#IU;7RkFRbMc$#!9O?PD@)iz%F}W&YA#&)~rGwN#3A63sU+ht-Y| z^Y{2C;-0fj5ZB7@KQd5k5+6w94SsQRW)DK6${V1&=ODFj4?@3>7s>cG4?%0b zvAFY{s`-rP`sA*U3Les{gZ}3V)NC5tA%0v>K9^tS8m}v%jY=L=zDTEWE7)EsJOvuO zZ}0_krNnQQZ7`P?xSooH@3Tq;<={JLVl4mcnwWzkKOW#)0ff zYlTwZvOM?qo!G4&OETPd!nIIE99f(L@;cVEd|()g8Z61dA=ay5>=-pP?Dz#I9N+O1bU)%i6Cv^ZPaZs2)>y}sFniPYYH!Vn5ku>+wyifEa!Ap{*jp~=dV{n;ID_?xuVr`n$auzd)uovZ zF{n6^Wu>LJa<0sa``?}*I944%yFG*P&{l6^(KDJ0Qf7G&ows1T<{up}lx5PJYT<2R zHvh{i5zUt$C$0@IxFbt7u(~uKzE$|sPmcQdDo+I6SLAqSV193hT|@=+L51a*beV_t zR=Fv4-W`lLoV-cq7cb8ArxyNn=!ZGsakNiIA1j(V!MkZSKXy(l2Bt@of9fVsJ4Fev zFg`%9+d=x|ks*$Rm*6cke}VGYLhMV~PNXw7!r1%T7lA5dC*B{mlpAqE{w!8XR5x_(X$Mn*Aag3d!|Nid^E3Qy2qYYmx8#&LgGHfN360CF%t zg<9FNthC!(sF>r#ue{ue+ln*DwKJyB8l;L3$3BCiqig87$9j0=TLlcOiTgZ+wNI%R^Y3auBYIK1EizU*zU7pGg&Cb^gy|UkZ$A_VFbc z_Rip&ys}Vm=9uK1e|{a)I!F>6I_6648y{iF4Au=~s4PfOd4d;NU&iIV`yg$ACN67~ zA`?E{5^l==fCXke*}mKfMu}9>-?sryb+DQLkL6N1XL7J{4i~vZUUX6+TXN1f>Q+am z+nJL7LFqObbYfnG|M@K=MhBz5$|WL{^%Rtq8;cirshP)G4K7(%UT8 z8OeH)%vWFGMzQn8YcmR&-5InsLk%kwGoa7*7O$$8j53+ah`{#^_vwr}KHe4z!iw*mp*XYKdj9s&P4;dG+OxQE119N}G5dA5xP<>Ac*IyRG zPN^ldy&wc#URjcrJDLR>X3rJ1AFJaE?T^ssOsBobGHAK=<@`SJ2Ru6Swoy@?XVz>4c|kOd?E#}9F4`p%6^lSkZr``raJCfQ~+x=C(yvY5EL-p*Xj~G zZYX1|zv3Q2)R-`8_KWpaZ;OQaBTw-;nTqJs^aa*Fx=GhAAB+X&|AAoM5~1+c2jnND zk{!R-gF2hxStlys){V*ZO++B7%v(lQ{3sC|dZQ*9GB<-eZhL@kAESZGXT-s~gLOQz zj6=5eT2h)M=A>S#;-_){L4@c8<=TSSJ@*v3t#?y!DVF8G3S`YAT4s^uEEmr%&EQ3( zsBu{!y6;^^rnYfh?0H2jKb$1#BFPWc!Mu~nFhBPSUw*F`!#}Pg9m4-OQlN-YKfb^) zlh^!@;ucIkBqWK!@-U$!5c|6~5U0NvbC+LDM3WzGWL=dEjJm*dX76-Zz%Qm+VUO@( zE8_#qk>+w_`b71S=Ot(R-tW@5?MEB5wD0A!%~Viq`UZX)Y^Dys#^9%EpP~KRBEewi z6x1uT(9$bJztwwiit`y6!1jdNBFGwoOgJ@`m@;g z$HTOQyS!2j4?-?Xa=A_eEGFY&?P_)t(BpaLdFT&i8Rxk=(Br0zGCj9p`IQ+oT0ay+ zlKqH@vky0c%~;>j;$%-%GJPI66pt@yf%KZy{N|+%?Dsa3?AT-q57-U8sy73ID?I47 zR%6_4PzJ9W=2^_|Nzy{Z`B;NW*fCb>mObS4A3tuk zKn33|eFx>cLg*^iZL~40fRXQ`_#dYcr6atEg55WcFO)&axnV5xy^(q?&&AevcI5um z4T5e>~Fv>+a#jCOCHQ-Dr1Ot5$rm9nhH8}(X917 zdas0^0K@CTEISu{lmJt0lCpo`|iug(XH>@6KLx%>0prO)9Qd2X5v-i=!zoCuL zp7(=FmuaGS!AFpENac^+561czE6B2&7dagz6?_(&3SZf6?hey=b`ML1?M6^ zC2a}$8>IxAi)B%INf%71(Wa~4gy0;jljP#3bDZ>8MU>O1gugd$(-EvMpr*4FcI(gJ ziSRkL?mj_m#Tz&W6(v+rO@_SlyJ^JDNc6U{CfA%41dH#!z(>nB5ILhguzIr^%Fhxf zju}^l=6~x^tB)s<0$Z5Od_?h4rBHd9aT1tbaj@TkT-ZB@tM8B%4O^PQElmxjnU$>L zAUqA8U=!bbL=xBUz5*_i`>2xVSR7`ePO8!*1rMrBvKqwHEL~sg5{cQ0xQPAD>MWF_ zr3*q(&)SjfxO$#@$o$VeOgFf8AeAObs-XC#RCwBQg(oucxa_}`YX#Nbb42OqK5@e)9;Dlnb?{QnV<@gF=Y{d#5LHUaVqG(k zmXyKEGiqS*TW1gs&P)&o&Y$bcmyUhPV(i47EFT`-@`-HtpqwJaVRP=-NsA%0>5P1#H{CLLXtDg7WOsE;o(U? zVdm*_ennjizEjC2{>qHy#qRiTV;u-?_szJnEf)LEyOUgLDR5wK(gBkcIB0K09j8Yk zdApG0It}5LjOY~EaA#r4cS%v{KM8!v?zzQ@d-;=AjhLVyB9ir{z}YEbfA1#qyG%(*>=T38?PvNo)tqVBcXCTs|%h?wr!6o(hqecXuHnb!&a|vIk#MZli5kAh#jm3`ljIY2f~OlhL@kF(V3)h3 zh*m11&%JiA_AB6}e$-*~{v;yD*w>mz8B6415tK|hP4zC1!F<;mc%xy$uekFJ!?N93 zM}#sA50=L$)HxXlRL#|}=XgqJLMijzwX>+(F#uR>r39r}jSw=1R z^Z5$`{4)z8=Fn6?wLz7)wh{S3Oc+YNC3hevinW0Mi z(z9@Pzb#2}_T$FKDdD@v|6uFl|7c{R0d80(O%jhJ3Uu`~aAA1U;GAFKrH5OM8^F1b z=f5-le@pZ#vePJ#%ett97Fwwwx#j}3V?USE@lT=L;k__rZ7S}YVncj%l%Od_8CSRu zfaGxl8t^Uzk4!s77Fzjow~*ca84I^xJ&fwzQpY{I<&dd1lmFnCi0kFOi1@)uE|FKn zI)#+MIq$dY5z6kjCUuGO0yWbdJe0AK^eo*A@AeyDm{6IB1%(U8zpcj&rXun$*%nmT zTmFUrCs6a8NzWRF;7xuDc_cQMYsi-sb)3oM5;{WZyLNSy8_0y=b31rL?j`#4?;&Hx zAXic^fib_Yz^3hBuLPwjs*-*!L=B`ofOMBFC&bQJT8 z&MF{zTC$)zTMk`MHxA}xV}1prW942Vm$O3nD5M#;yT=f-AKM|B-TgT#9Q5IM-MEDb zV-}G-%Njwe^lZ_vz)xJA$crAEqKfNc??YqhYyR1r4ix)RLN3jl2^lIfc%`-$GA?YT z=Pg56FT4k741Oqhe9k1R=H&o!l;2Jo?yzj>_-ttL7)y0t+`?`4i%7~x8_w>5GT!Kp z9?Z#Jr@wH2NC0^exSBdFmdBgddYR^Qg}&Uvw86%oAh&;kaHDb)zG+M$PWK!@;tb0k z1{Xo>X%kw=ZapUtuOiEoUkmPgsf)z6XL57%y=fJD``om6GMJMU8#*y-{v)0|Q89)C z6-v0a_aCgdew40g2tn=nr$}FU70l91ha;Z) zG$sEbE=pQRE`&L9bxx8v*7quOY`Dl~V<;NA1`z2xW4VyIGI(u59gOJ_6MY@Yd`&Yy zgZJZ1-k0%ma~AuM$oCbTqMJIJzIp{qq!`yr*8nd*E`TrBl=%OcX8yd;jf5EugPG~< z9@KFMTn%T?kmI3vd1(OAg|pmO)+2DU_Xpf)e@rb7X`)+h3+x=Wnpb$%i~(n3h<4yq z_>XC==CiY5i0>hKo_!B%em{eoHlr+xroKSyF}nuuuu|JuSIB|e@S#|qPOSNgS3Z=I zoZ}Ag$dWP2)^)+>%T{z^JnM$|>p|>hPUi-ShT#CIf$2S;X%b^QSYOSDfbIYI+G8SI zecPK9E=}cP_2u!a??X5&IzzRJHPOH9A*{2C5h_*8+PU=G!E0D z?>m^!WV0s;{o&6o(P8_~6Q+|Nc|e!XmB;zVd3f>U7XP$73!g_ECfgo$a@rD1yJoZf z_#-F!b4?yPjIt-mGd2o-u5A}_N~MGPOumvLCUmw#SkG(zKye)=JxnG!Q{-WBt0Kmj zzk}mqr)hZ9FnrVf9@^SR@pIm@zL>5wFRj;*?PmiyQ*)LTVjV;Oo9(i@ zwXiES1$;hL3U545K?T#Lq@qa?23*w9_qPODYBH8;)G!9ZgwsTl-M)`4XP^64br2;P zMh`I-N5u4xAU%2}e{yRg-il+I+xtrH1KZP@AEkoTCU=@W;UV5VYfZvBTC@doA2$wG=&f3&Doi-X{#KT?`?*36IWWfE(G69+DHD3c_f&0)g&vT zO3ZQ~X*)@5Vm+ABIdH|qkS3*tV#kF=WXHE9+^GWQMYM?l>*@Dsrq4_a=zPt*lcBtS zg&gY>{53e+2ds4v9*dJ}E0+m<6YJ4oeG2jZu^C*M7w*Z!VtBaKl8ZVj6kdBR zIFqI-T6H6XGjl#bGs77B?$lFo4fx3S9Z$ldn8lZtzHx!@7Aq>PPQspw1 zotYF5`pW+Nrq@bYCCl%T6|vJ{)MUn2;s3%^uPQzwyAH#nMP%euIVi4XIlF!*@}It6 z#y`h4+`K)4oZc}5#!qG5b;&fCFx!d_$$NnM|H~c7igTx*eHXdR^BwfwtoJm)noJd9 zV{?UfsHkJTGa|B1-4sqeRb+h2YN#3NOn+K1ZfbxtaXa=*aQ|!^o9+9^It?=@4^>5D zj|>=gz<}<1^Z;KqEF||YI&eDgmC^9vedhHFrU~rl{`<>$;oDl?V=~7=0e%=W&(GO>*s<~kt(tkANO-`<~vPN!5>puPQ+&^KWTU~de3-D z>^@Hgolk5Z_?H9Ht%s>yj4J+R{e5bZqb-V;v5u8}?&MmxBmC@V_onM%Ap1#){-a-U z)aG(B=awVLPEo*R8SU`%7DrF89BWwae$resopVjr!t#MHFudjy4cRaZNoolgeUYG+ z7TK8R%Q#fw&$uRk)^p(&3nuRV^nL0ioFT}DpnZA5Y=6nD70bSpn>sAFHbfo8-F|^z zwhldUDFp9--A~>w58#%>4aN6?)sTNFjJn>J!{2j6gERkxxd>%b50fiS-?*1e%xm2r z0bynvse@4t>h#zT>Nc}`+C-bpJ`8eiHZ9Y{cX5AV$-Q!Z(S$l|*p)(RC&|NX6(tP$ zQw-}4ou<2GwXnGA9gOfb;Lo0o#f#m}gS}L1qUEu#Bnq}IoI_{H=3)u!)GiAc$4QKl z$L_bkL0UPQJ};NUJ5{al_@X0k7*&hC5-DVKj0u>%Wu7ti?|XN`j_T|P#t)O%5~pe7 zEFK?{0))rQ1QI>zyx%+sjd4?=~dbO_s*5_Hdy z($|x?ssE|7?vj?lecpU1`~R1G58`IA{1NuH4KH3xDnA5r5phg&c$xtLT0!)DiWYVr zPlLb0Pr^>s6qL~Yj~K-$LLp&w}Sb-!I>{LR~>_?BspUF)#53e`Ss?S zmLqM36S=nIRr&I0qDmY?p2FMDo@!DhK zaDrehk)H91`+Z9h=PYD?U8jxoKlv7P3VKhp8Wh04Ko+AlTOcGZfUadTUo(0?`8RWw zu=Zm!+Kh=M6Lz?QJA1d@^vMDXqouU^AM^0!JckQC%LRwMW{D&ntGP9D-qeKgvKCCd z4^yAA&U%$Lyt=iNJg}Mps!mJ?j%ft9eJ<2t1=}-g_Y=7KNbv4~NtW6tam!&YJII`| z%&WXR2fX9Q(ueG`Ec(zQB9ptA+cHTBlWUoGvGgttjMPTMS1~}3p5jNctn{h1eK38< z6&kyg-J}-u!R}L5!kRhmND&UZ2XY$ z?lYl)^?K-DPlm{gg!XzwV2l{^7S0#rKFWRxMONIkp*>9gij18>d0V7uKzO zJP#6sj?nX7BX9y^7@qk&)xxvu1y0iUAf^+Yz;=%c_P9hq##LqN=q{D@Cg2Ad_;>`q ze3nPS=MDg#qt+fFXu89TbS{~}EveDQsvY&Pa&k5OD$Be9Q(uAcykGpZcBX~y+(GV! zMsYt3RB-K*I5@T1pB6A~=c2l&&~-ju*!@>3>+geZGF`U}#8TS>9aWtt!{DC3%6ljdH5VgVzbg2OQMDLapF$G9%7JB|5{|Sgg`9+QOp!zy z2&ucD94_c@gT<+i{KIE8i~*ZMJocKvLZ%VPPAG-Gt9G=ic?>T3+Xz)AN#>K@h%gF| zk;L?su-07x8+2m8bgep#-I#2-v3nz zN4qEE2F4KnwNDZ5hiIVjcWH9@$~fxqHw1Hs`;e3O858W59BMgK4bJ@GNvfD3UNNZE zzYmYc<824Y<7XAz3{TcK+Q?X-mt5(g%5a?h(VFN5%L-Q5=it<>Tgatu4=`dmUq3Zj zVrmj1^f*?F)+@8f-`%z_rBIH&S*oC2Vg_Bq^a`aW7t#?tkDEABP84l{oTtZa$~{!Y z8IC;M8QaDehcQ0wYiDxbG?{aIt%$#0-iKF)r)k{$Q2ZowkxVc?DlpSA%`&$iYS~&g zoV<-;yrYCK5NIh+J6T2}^uTsp@rclitQ!$2*!|EXOTTc4W&aRYa^;93;;)=R z-9Bm!V{9HX)p1(*PxHxO7vYo=IlMdMFSHH0N{bk`MEc%u z$bDfYv~jFMzCM+xHf@IM)0hv+`~!rfO{V4SW-7IMJ$WBiAdow#CJH}52Q{4ZuS{E* z7z>>>W&C!_BvegZ%9#2IoSl?Bp4#*m=I9)xOPQWlZQ?^*w_X*jYc$D{tWmIh5IcuV zYgWSh1*On_S%O}b4#AfX*ON_tmfUVBRjjxu1X-!4bkYXq?|PRE-74pK+kHc_+J0Rl z(mjS?^;ec(Q%a6QYaw87?mP5+&*_*3@-Htc9kd$)2jF}7CvE$GqaCvX(Ar;B!mAdJ~gI%1v+BCs8o6+a>_1zs#;ri`vLGXO8?Q|0;LXfnc@Jm)rZ zg_bObbs&6j&vz{fMIXP5B+Gdm2Mc9z!iZ)tG9Ds&aEW=7L1lL^wY|==s2w8cSR=vzuuj2$`|XL!QALmmRlz&|BH;PmSu{Q?6n`DL zNQQ~daSL3A;yx2GBDOi6rpCzPyQ)ff`F%d$>)C{}>|)8D-l>dx%kt47FG2p=QF=Xy z@x@PBFBsb-Mws?fedb#%(lITp3+Pyd31=^iNL3-LLkL!1Sk_fazd1x8k78 z(VwoGql1rrvz@^yL3n!LAMTpjObjIoVBa?tjQ-sNJ_f_+OO_oFOY$c2hUdAfU2HG< zR0@j|L+DQSJ>f6E1t*(FJij0lH{^ShTUu@0YW6qIZ;cu3D>;5F8+ADcVnJ*LYgV+1 ziWoEVfBmy=>^9U`Ax4r-EBOZowOD45MtEJyI2 z;<5PXsS62-mWJc*$~aUj9!}|UR5UIZ)nvDlyGx9?=#9EKR7IH-&7{=gur!AM*9;mP zHt|~zHsOl>86;rMG{}lq!ZEDdDA{8ptzBw}12)>c*a5uqLw~d*rNFyer~A}ULKo_3Corf@e_)$ z&{G}N^Q6hxTtgZ)G8EGc&XSj7{kb!&WAVF1)nK={>qa%yJM#%9InU%nBjWKu>|vrI zsN^E=$zh#GD*SNVNpJat;j>t4;znfzdlYlfG~0<(NO?l?T}_;jCrh^P3K7;Q*5OyZ z7o_z121sIjfbvUKaCzc%I%IhWPPw{+NR2Y*)OX8@GHxRmHRLvRRh^&YS< zQ^a>)@<1+oIjwVNS!RtT#5ex4K*N8QXh>7-;H~z7k0KhRghB1}m%P*4M%=ZtgdEYI z20tGw;I#RjuyE8Ky2&#Hhxi{P-rc8 z+azs!8@(s31BFqenC>?d@3)fk+6Js*sFL-}mOAz6(%*U7IsL+DIl z+U5yyvfud&Kbo}Sr#1P+YJ)NyQe-pPbO(uF?VmAyZ!0F+JtFu2&46p63fQdn3|6mN zKrc)V!%NIFkSfMP8`=EzfZYrdA%_ZJxc>{*3pG|!CFGYpWxkiuDMThh z9nzRzal)@+*t9Z~`TAHkq&@?ZqW%d#my1yE{vPtGXDBRXo}8kr2kl9#nzDwON+&RCIWNdPS11$S2I@b+8LG$UV zmNB?$zZ6l7LP1i}2=rC!f{8m@>AY`Rcw%cA> zqN)SsgEOCZVywbB-JntPmUqWS3^dCm<-SUc6T;pRC(B^C_Zh19NgJhD&)U&PqxmHb zPf>Bv4iZo=4a3>4Vo?|mjfDc*WfOx<=?lr67FBMS{V+^6QzGIUg)}`w3iTqJp*DXb z|0KT}5BjB&<4ufD?!y=t9Lp$WZKUlNg0V=)j=Z>RWKrt-6wO|5Cw;dqV1kDN>It8M zVUIeM-W!8hyO4DHdU6u~$z#tXF=BSfhMr)4@~$suNr9ayca*ZuUxRk=pYel+zhG~- zuyV+Ei|0@NNW`<{CrI&L);STPgpbCu{CnR;`bK^%#yc0llY&lR_QGV$8MBhCtyP3O z9_rYYE<@awjbmA%Q2Zu$j{NiW=Q@~g>cspXuyogBnqr`abF->I_S#I|CN>VQPCP;a zgV~<%!*;58=2Z~xq|1)o#}hr)M8ZTy;AWhGM+`QQ^mQ(9hV9Zn{>c%aX`#a3hwCv- zm`l#x-3XU9G7taFM)(*rhjuf6SHt|BL@&&oyI&?Ny7nNOoA>259VTS&i?s;F8{2vR zS1-_P3S;;bQEnycmc2HUvDX4mQ|0Ulc-L|SvD>RCu$gI^wck(Ma{Om~^4C}%Ll_^! z?5rF$53fh@xLC5)`#raq<(i+U<%3h)b2{qXP_$(GiPyj_-o+pXr`$R~%69f~8s+j> zryd3`TQ<-$9rf5gp@jT?E)TzQ6i{pY5Ag2^q(fNOm26Qre2Xc}9NN#kmjOwnaqDgn zZdAv^+&j?RYfIDLjYEr)&+yS|zu;)PndrddI&M~|H|=Jh3(vMjfVKK7zW&iK4EJm# zk*5HD4`aR3e>)++#+^p&2tj{1OfuA>1i-i=j5cAJX1|m1fRu4t?`z16HKO!vFuG;f z5S5z6Tn_7=yTiJw-`&1LFQ3)J?p?{SvlbRU zZ^EDALQ?AD44<~L9JhWYd>cNEnwPQt*~gBQ#=a5ochp2hr?R-H@rUT?XH1*bNP;}y zN}i?kv*yR&BoV3NV4p6B+ZPVNMEyfFd{QWG&^t$F*c! zGRxuUWJ%h^Sml4;*pcBU=5ssQE~j%#2p5;e(BLwr!#|IQiSFn4yzk;!(fp0UJzuw& zbxfQdLi!ii@a2Uq_|@?>d3ahGCb3-S&cCjtC(A#>nPnUt??#b?K<07U#xkCM8E~QA zieA>ekB5#}6H@b6Fzen|QL$^lptj?Fl<~dq$dReN{`|amZFt<^4M|vP2Eh%I7@l7a z)vdOaI5Qrg(@r7^%@8zhX+y#MDAIA!3r-eGV3%e*9phK2Q!}e z{0E@)G?+%kup6$}C87~-#I=o=L7&;}a6v;tw4Ln|hT8SuJ&?(lpKiy5iz(#AGIc1h zSH-Apg|NT(235(>MEQq#P@*Eu&vHn>LVbH8KTjTfhp1xb_el7pH;4K$Cd13}AhIaj zmz%Ow1LtIkkq_2!bk$Qiv`l3)zj`5`JEjBGbW_Qcuvu`nP#Jg4djo13C+Mbgs(4I2 z3#`_SvDkVu7RRRBk!5*{;m9y0EWGsqrfVtD^pn3ZOjAF1YW|LL=C2#+nns^~nGqeyIst{B9AAsh_ze?B{NW32dhM zQIFv|_$)CIrp!(hc8vawIwM<1bz(kT%~r*+3;w~Yg}QXfrh05!l|d~37IF@KN+_67 z0R|PJbVR%k7BE)N(+hFDe||a!tT{+*<}`DeRti{sD;B&2TdBlaN{}&(b>N1TfoT`J;W}!d*ZdNAD;U9> z^ghMl(M&_0F9YKzC}99efVjB=I&*O}E+1=6wr)`6W=m>f)>wIR@O(Ob#p|L$pbQzO zdxF1SUyYe5kFmTQ&TrmG8^eQf--nIFf2gs=&$myoo$a@?7g&I(PaZ2y z#R8YFPJgnmKiSZl?AhkQWv`UST5WL>3rndj^Sp`Yo+Gc`nR1kM2#&Vt7|c~YWOM9t z0P9=a6wiM@&zKLTN6EQI54kasY8WH)0=_w3p%KRSkTUJXRDT!0bw@6`%j_U0?e)Mx zT@!n!%9Dg7V_G*V6k{cQNyZ<4ZcoWj96!DXR8yj<%vD`{+tLBKZG`Vx7K;;=j*xKo zk6a>qs~Rv5f1blGn#THN#z>^WZDlWuO4a9hJa_~7d0-pVj2?x~&RXQ)u1I0c;x?Q! z{4MdRaDv&oN_e!m3G%AuP%Fm&nZ4YN2wW|=U{yKMFxMPz=eavnjn}|CWw~Hk(#fxe z91M%~CYo&TJm#v36KbR2o16upVd(LOF{vK*rO zeTb*)sVmFu&lyol+*tn3k+IPRW_5#sL=Y`4&_Q{28_L*Inz@(x=X1`!gR?Q~sTrHY zg;xKO%*txP7=1HQ?34OIk9{=jkLaz8fPlR(`G)ugd~N@Mq;H=F(RE5_b>kOY*tMS; zu?$6$<56-xH%joa#w07ZNXn8-*hN+-D&xT$1#sTch-Mck)GFqljvYCCJJ{H>q}~A@*%z{;?D%;TEqZyfTI-s`<_!6{U}W#%v2hwVThZs13o6(3y!rbqnLLRWWTK7OKuOz`oag3xgW&Apbac5S9WR>L6rsE&k_xE>&b=t z?-HqlrYg&`C&SKKuC0ub6-7Q*&xC>D3V58|V*ZzzZIrr)qu3ksP5K`}l+0IAw(0pn4QIej z6EB>TCs7*%_>=D%@YKpzWYLUiF!r(}USPgu-vL{CBPaxq+PRVPm6?J+>@&s9F^U+S zI{?9{s@Rd81y^^BqE_X1v6Okw_W$0%`6(!3c5Vc8F26~a4!MPUVlI*XDaM?-nhf*H zwZkd{36b^ep?J&qCq#b8=Uaw$;hq1UlWPq_VPKmos`eE^@5q}pGIbnwJA8q^TeWzn z+62_y>_EITG8p>52IVq{SQyR$j3GPIiD;$?go`QS9fgmBy8Q!| zL+^IpOp^8+TRangf_9uMu`V@-1$Sj}cFhx*d{>p0cST|AcxzJlcMmrL*&I`pB?tGf zqlaY}`>4j3PgEZn(|)^9oHfypT)q{+-LqmD zw{<@U_xW$Z`gmtm_aM98kiBv0{yR#Vy*_f)zvWP0FN58Y+~}Ltck$zfMI`sTl)ybU z2mi^s66MAFVQ!TH-sZH(#s`mt8+U$1-POfp>{S;ibx}mKmCew0Xbyd_jd?E%cavpk z!5u#+C(7QR$Nh7@OOG;*MTK?5Ur6lYt;%2EDeXg~JXOTS#4Drk%qZ~x=|h({sH2mL zJlQk-hlQA>X;$kq9m~j?5#)`#I(FN1LGev>>bIaC|9p=pwew3jF?J_?X!Hj3Q!?l^ z_Pf-+>9m}W?W|-rY+0J@*`gamJ?@* zxK~Ysnb{{xR2h>t8YX>s%fpHW6r3$1KNF_GgXKyXzN!yYC+(;EZib-!*yH4d`C~y6 z^Sa#4k+w9-+ePv=F^&D=Tlg^1nA*n%W1#$U;vsLtDKA#VzH6z_HuM1vV|+Z3KGRF} zPV#C@vz_}=isa;l(9xgN(IZftj3$ePR(tB0hclDxJ?IGO9m?2xtqSsvO`|`V#&TBO zp4^Zq6#TlVj+* z$L8L}3gEOQsp`xSe7o45>`Yj|IaH{l-IzS6P)ekfv2^s7r9i2ZA0JT|kFoA6h##%x zCe~`B2UR9}uXgh_KkKpR&nxnFha&J(Lh$;r-Q;UfK!%5X8wRmlgOlbgm^UDgla6MB zOZfu&yzUOl6j+ljhkpx#XLpEFi_b&x7fDfGxH?uA$r0T#{`~8rHvB15MDFjL1&_b6 zzsKnlb4#!%!L@zvy6j+aaRqxmtKJ{5Mo|yx|MJHQ|V` zWMWKIVeUs2G-Z7aZ%l8}Eft3NPOKI>r)%*mMkZpVKlACiD?o6Q0{eMA9L!Ix)cuCd z#Wm!|hWA_-(?e9O#mURySlYne2<0rRb=`gePx9+=vLKOMGMENNjPXT-3t@-<3EIJK zI&G25$=$vu7E8xuq2+)V8NO)?cpR6*bN|8_mQkMm5%uAM-Zpa0XAd+uD&ot(zhKmh z1@z;^(YSVo3{gr$!Ij;5SU$gt@#mZ92t5T{+?fwHySn-JhC;OZb&`~CNaYG0lrWRc zbK?>I^p3+Y^h!z|)N0C?_2HTOZA4<@YY4QL#R;sxPjjw1oqM+lPo;^7$)pnQbgmj2 z{Z|K?pYBmlxuKYL`Xk)biQ!vKpJFRfKJRq|HL zmp{0q7ZViUk^^Y~cFY_9o@w1X-)^Q(j90LR-45K9$6I`VAB#1W?nK-fz^hgUT^2nB z{qd^QE+G`73;6Oc7jBfKjfU^b#a*Od+?oho0h!1jW*w`NnY3vKD8$o_1xUZ4$t8r zt;slf$2SZBg0uhQ9th6qB+FVBz>X{L(vFXkc=Xe5mf_j2Ms9 zCNL6mpV(8eE8npyu8#E2)_`klSB##-7;&LNRB`T5?0@yuCQ;Q*E@j7~(F}_CotRStbHG*YI&?8U@YkIh_$R{F=wmzkB1REo3@b{1LWpN zDzJ_`3DW%S7>(EyiZ`eGlfeG#f_s{#SqBx>Ec?%zlZWiS9Gy@(sLw2%7lNOEI*`CQ zR@|4nDp)xC1zfohOZOLPV9W7LxF>m$k0^@6^{p#N)wddM>54{4P@pRv551@k+iN#Hg!n9ur%4;Bdr{g$(z-bO7p=cV=f1n-PH zL_tj#2K5=^RCUa+kS9uy{dwiSc9i!mCOUPq!BI^XK~y`~ExRI`Y4Tlr$ku~GL0e`k z^Q^`YTj~v`vRQ|hQZ}soXF!jK-^LxhHF?;uo~w~l#wU4EuwEyWHsyw5j?q<8xMMuG zAWjOe-u((m@)&HEzw%=if&k78Yu+n1fCr_0sQGUEf>F3{&sJ%5UoWA>2K3bL?hi3*C1Nr!h^Ea_68 zN4UwunrO%>bC*E_HEk7%?9OL2^6@D23|A!wj-TU4OsU76M=9C8VH#wAmq)*|6(FZ) zM=>=Rf0j9t*8Srx{>Cu&#ooQ7_X)u24Cd|Wj|Wdrb?SWK5h^h)@p;g0Zk{a5k}Q-X zDFy53nQ5VTyW5{+mQCS?|5HXu)+h2m2EzH*ipcG)f{qahyt7FnW=uFk_U(Gi&G*#A z)O7{$3U1K)1^SqwlMhF#TZE~@b8+P2-DHIBaLCV8!{d$e1mlh9w5mq@d;Tp+4=LhG zlGQLWpc{@Hh@{i*s-owu3SXoGw#hooH8T1pn;JMCaDE4({!BVT>yx zl?X37OZi_mxwyAKlSEz6gF8!<@x-luShdZY>O?W_Q0GbV$0l0vxXC2z9?DvVkJwGZ z16Y1=-Fw*QK7k(03C4mYt4P79rQCV8&mZedWqyosdKiY{jqF5dO5__IJ_XGMR!H`X3xAg>w}hb304$RCYb zZt{3_eDj|IDQRoxGw!r7&FvkjHByC>W+5p3i*X6opU<#b-HJ0#J|Xj_&w`DpfWsU` z5Ky&{dPd$tcj-mMPxhCLNiZ=4Ju^H=tPC$0?b(6{D`Lo332*SsS3)O~Y)G&+ptsy^VbOD@ZKkZ_MlpSF zPw!)>Sr|%NXWzo)?^lW0unC-4u@vg>`!=Z0kp>8i(<^2ua)yD|)& zqmG`7%OHMcC^g&8ZXd5!l3MQozP9HN4r>S_itnwUVWtxP9Q7E!y)dJ7vtA>_AsN3T znM;Dvcx}8I$yLgx+zx5{d$k5MB^L0mf9la&Et$+|o(7KWzunbT2+!9Zr*U4|*n6x9 zR-c<>Av&FfYknRgm7Y$puR;}@k3R*^QZ;H5(t}YlZDh)!-LNJ>7OQS_4{|J%BSzwy zH`1hilt^$+Oc%3ec0rp?BfWW^@$_7Zz~f{e|FW|Q=SJKkhpfMFdSjLFpTqyp_8;f< zF!{gd><*PGT;|h@51ZNswf9Bru6o3-e~@qU`g8-{4HgmM?_%x_<0x|ZwP5_{E)5zt z3Tx(fz|O1B_@uBzjI29AzD=#=!ZQ_6;Yt$hV%*WQWe;&@_(GzbG)G|9(IB#W`f1Qh zZxN(~MnebSSmk?O-?<*;C6TxpD1$c3vYlsM{iAkg>AQPsIP!NH?CI6#m3(4RLE4kN z{U;0B)0OaMc`B^>&C$y%A0l_nnq|6`xVuyY+Cw^uGu#nC;n6z>oB7Ympx&9SuxYPF)Jl%VhZr-JaN0w*87-6~arI7JO&+I0DZ1o^wh8mh~ zRv@DyjA$R@t}Gu?Nc>3=S6ruxhZ|W-=8#BQVXBGYnXQoXeID<_Jat>X`mk=P8cv&W z8-{dbf!k|OYQ^S%qg4jft?{z3`H_K-8=Z(*nkyWNpNy*ajLAT6y6`&Rj*Ux8$y~kd zAQWf)4hvca`8L6f$-H>sK61~W;|}`EiLU&4&25OkN0&!xph->v{2O3>#IoPfa_22_ z=W07=A}xi!HyQi)z#;nmw<;DGDv+1EyDS_%OtZ8n>RaXpj3k|D>X`bk7jU8`&0`){ z@+y%W4|~t8V{>Whm`b=Al|#2g$f0Kq4<}?U^CztnG5eDX>DH>}q6}FsY|3N!X<<)Y zqSzdc=E=~UZtlktd7Lq=4>BGFQC-Gjik9jFy^n7*XF($t*r$@Xm%CWTN*Ol^-$TLs zwX`xR7}IlB6YYhyf+IO*qK>EST$uY|I>As4ug!^rF`M7tEx6ESlI4*rXZgEiH@m^BpnY`-v{g=^t;MVx_xoz{CxP)0 zmMNpsqI9Tl52wc~)seE!(9YW9e6OZD9+{y?wr;yeap72;K17oU=Q#^=Zr0%xTM;o0 zbpk$F9``(}1ha>x^qe7^^P`~^m{{}trSNuZJ$LouozLH<|}pE)ERqmQzVu+eqgryU$Y?X` z@@5Q#I2SEU+n`ELss{3bzrSIPSvh&R-5jPw$YSu1MzFDVqA^J!`1COA&kEuNHt9{c zyflWKDn0($FWCI zMp7ybY2m!@OG|r?PkUeh`u!gdopHaf z`*pou&zJggKl-5257(}}1B0TiI1dkbObz)-PPoZRh#{gp6Wy^g$};>4Th)#Av@aqy|zme>`t?$=-0L?h!AUA)W! zGhJ(l$k4%I;cY~Hc~=-{w~4&{tc>3m1(S-Ys`SR-bYv(MxKji~L!Pm2a=S@)lz@Y9Xup0V-?DEvcYft6j_w&IN4pgx{g%lPsp64mn`4X>G zLSmwQ=wmr;%v|(^IP1UQKg@~3bLJXsYafGv51dSH?PBNB!)UVRkv(-78ifB6W`et)8aLt!V_20cKzY?``Z;9)-rA!E z>bE?3y$_X4Ge;O@U_%Vvs$k>NuO#XBDq8TJ`D%`AfgLxk9G)}HeEyxoa97EZB)BtA z^^-WV!AzfeS_a`o@l1GTwu=j3{IriXN)QyXl-AGj!}i|G5TiAYYi2u(nNa;f{sk%v>oNXzT&k z;RDD{OKn^~Ssiw}Skb$q%CTU623XJxF7K-*&Y1U`vA~~G+us6g_o^WKyvOtN{n_tN zegUPsG>F?y0T$j#A*AduRrxK%XC(<_dAf^37kl47p85|Sir0~*31%3ZW(01lL&dHm zexR#CA>6UsK_0$S#R=_AWLLoyI{hK*SQ)@PGp2-F{ZL8rVPHm|R&(Gf(^_MZj0&sf zWulvL))s$AdiR}M_gD_iHwThta-2G)F&_B6JMf^uQ)IK(T6%u!AV;aPDIEExg(fmx zWJ;0_o!M4~nv8d`!!4JKP1C@*IfW#S*)EU0WIcms*<|g22fXiX#`=izg(?+&Qu9F- zEeE_H8J6qlDk0-{?WRyu+|GSr`M48dU48Sse-+DWsde?8^K&+`@7J9;;C%OxcTAHs zu+1eAvzO90EPtf5c^O20sSvgPw3S@j*~IZ*kF#zyc2DmLBgapDfqtQ@`fX{@#=Yb$e1u!EHtZP z-6c|(nzflUvd?yUQ3-KNv8JH|eK9R@3wTY+77aAjl&Ge@=PuNpq|@Uyap*9f=-(;l z>zpO%YqS%R9gz#Uri#hs3h;&Zpn)EmxI|74w1d?}bJ&^xeyxt<`$Hmd{Vc?TuGJ(5 zl;}H_MS8`0wK}qAa0M(sZZL^;Lo?mROimZW4oXRui8p^u_a(l_SpqgDco7Y{?(@GA*huhrta&agiJ{Mvo&obgW~`|V~^CC0x! zVd?~N9=}AFt~W|D7kc;YUc1AzP$fwK17t7r$&c#LQ8O28CQKxTtS|f5&^j{x>?RtO z>Whp2bAid$RJ7}y0KX-skW|TFs!n`S_-7`Rhb-lOvU6kLl~9t|=u1ER_QSD9?!vj{ zBe=;X@)#T5O1O)%k_yI)zO$yOuOIx@`bykw_XdXdsI%U5ZJep}jc8~G&<%+OIBs7) z+4Vw|SIv2e*U46xt*gT33C1xtizL%-InWj*M6Z(xaHJ`WvzuX#Ro`?#@+*bPcaa&M9=5%nK*)K<%x5{u#L81N_=q_^zgZI4Gx#}4F)Cl9O7HgvG8=efEe2rQk(8E7wal~g)gxF{b`~NOe zfa6~W(-~b=c)2$TjymLVp()DftNpdFH}-QA%Q4OPOa?y=;!|Q{QQ627>LxXC&#RO% zL@9=_ohZ60UnOyF`r5Z+jn!7hgi~Fl;7}%iz`7Q-ho^!dPJ`^~ zRmF=PWu#jEEPcy7Jheqdq@viEzh3YiU%q|@BzFoK#onXG?r%umO$WNH<}rGt&V;vl zs+{e59aP+|0qW#_}mGCB)$If7GhN2VZJB zL-lVfhc?+)xM$O7 zef}BzZI08ZEF3gh#JjmQV%nGpm_AIGxKhSDI+sRv3Xag+7lZKg!z{9!o_AS#^ z673Zqx$E$d-gvKprk_5Ld;44Xxsk8YYw314+4_>3y-fq}=tq#iKj-O_L_e(ay$hQ- zFOmC6YiY{v!H)BNO(Em41{$_^_GvXfXUp*8)@V2z&ipeLjPvuokenz$YPUiO`!!Iq zcwhD zzO8>v1i!O*hd+p_?-OBtlp&eGG;@9IA2nt%iKQZ4)-`<)n_Q>BMl&i7fYGx%+q$-Rgb;K`F|WN&>qopD45W5y>Dqwm-F zr{@`4UU@laj;`QjYqe3WO$aYWw(w-$&rz4@S&T7;Bb z*f3}!Q4eCzh3rqDPCJ|*T{&YLTl?nu$1Dpo`p^#&vRlF{ z9IC`N`Ud8Y6q02L8aU%)5y{K*rGwoD;9Zv@@_Dm>PapjX=d5%F$w?IwI*2_({a=t^ zTU%;bL(wuN9zN)Xac?sR;ERI-cw3r4-8Zpba@Gs)6hEDBR+F*c!w)N0#11dolwQDY8*eC-NyWSRiwIo3mGDx|r~5&w)xggsjJg!ffN zr-A>-(fKpzR7-Q*UZe_(%9BOfOp`DA)!FB(Ia$WK`8+=pdDR~NnN|cwbH`!g@i2}S z3o(;*mN|dBLVefh;YjEIKj&3+exddGAK;qEJd~ixI(TuyB$lIozs>8jMB!Kiy{dCJmfb zQrvgu5A$GmM(?LkA2f;VKB0m;j>h(#`4!=TnD%)lwCbpG_M1l|dvD=HK`D)6dgJ}g z%COP@B)`JD3dhe&fxD^W+5STjpMCm5WbUq@_bPp`MzW1{ZI5u!O@7JPxkq7Ms3R$2 z{?*D8lxXP;q=sdISg7p;L0`9X#cXCC<);Gwl9th0cIIcxUxV-&HrxX@0n(Z6eV)lv z`YQOJdnq~k;uSw{Km#i5jewy)%D8Ep*!fWZj$A%}gH|zC-s&MKq+(vF`1;Ctj9%;v z8+CO^Ljv=tRH?#(qbv`rU537+GGT$*M{Zg@%iGp>lb*;B`l+0ClWnc&>zvx((ugZ_ zB0-q1OHLk9!>G||WcTjFblL(T>Uyb2r)SdJJC?|Iz2DcDf(ViMj_3@m``Kx2&ZX15F&OZOq`qPaV{`)ek18 z=+lWRWvD(c2K=*gx#)Ne^kl5Fe`ZNk(x{1MO_?OG(vN?u9*>zGN1!&mnHx4j1)rt9 zAg{gFP)m0AncvF8cK23J;h_pz8vY}b*WaL19hv{?bPs78^C>aqP!*b%#({JFF7imi zcB7^F#Hf22&1V|j`nxNksi#sDc9zZar&{`S8(+qDASIE+P&U`O|MDpMP{tP}T`R%+ z@O&;kn(?go1hQn+6S`Y83VTiR$;SEj_|F?OP}5TY6D=Ond&}6}r~fsOo+}VP3n|C8 z3@QAL+(a&pRY8xCQlflxG_9HIi|00Mhbeb+M8-1ACm;BcGiq_Afm^h&vW@LZf-CvF zd#PCA;sS-s(m5-tjAQ#Nf?0(-9pk5kSE>}?_A?DpxU01^;-Q|SQ91_!Dgrz;y^6@L zRiG2xeer$Rc9=KRiF0S~<9|=z5tkn?>9u!yI3qQUl%Kl6t5&|ngSZv^cKzfY*k~{i zfS^ySpRm6U50-w0PS7M3o6PXhc3GIQTsNU@Tpd2^c?He;ClbLmrjedZCjazi(rrOL zxW$h3(z^T-C9G_a?9RR3r{Pr2)Hwjp=&mQOxrD*Hw58rHPM4wHW*#^Oh`|NY>Y?p=ww@u|48J?@qPAtv4IV!CfMU z?*(Es`Qi%eo!1kgy9UbMiXuX`&-#=>QTcZwyos&e#47PPCF#iegE#vD^_4YIP@@*11 z^iLT_Pl_X@s~qT+XOFPi*a-%?t8l^nhvMl1b7=F)qra{UV!b3b*#Z0djdXY~--Ma-Lcn188Pc_d-E((Sa&yuE+V9OH zv>xjOgCn+a#mq~fH&_|YCM>4)`x#4WfH#EvVyvOZYUp^jomd36((CD}SW;X`{1->^ zBPy!UF7YJ@JW9AnsqAdY%_PAqZqu8Gb@1<~)V?#{1|l#gV-09p3CMus%-`iFfN8as z^y!6fm^CgFw#~`lymss3mnX7N6!e-JR}8^@n-oCjs10f1F3*dBxk9aCykMHgj_G$GuUDffG zxRaQSBy_+x#y`wD0UBD4938JL8G9<5i|Khp2mfQ|z?%Z1{kNMJ-lI4m$sPP|^4ug; zN7LL0^0(i4YW`Y`trOVYHtCUQae%e7=Yy%^fh04~VGNL8Tq`MeR;T^= zw*=AP6+>`hYzE0K@aAu^uFvq%>Tqr4Lwb~TOt{7>L-FK=;?iO2xG%nzILq47ZjR{{ ze|JENcCM&rucjm==@WNl!6|CIK$AUFkX$)c!G8-&L27>lP8Fna66Pt2Y8HT4=^VWj z>4zs*c!P(juc-Mb^E-v*s(E++b}L~iw>HMQh|_=7%G?}kMgy3eY5@dQMIVG zMhpX)KhR}~8uNz~Fx|j|o_XwpPS&d-YyNA8x#PpI+i)8s8P6eJd)O{-$Qz<*t3$si ziSh201bF;tGV^+>U;vwqE0tNdDa%VP4Lb*yJnXoGIRo%y++T85w~?-8yUWC+LJ|_* z!%x}#8ap<+fp>Qp$FbK(+gL)jD_o_XPaa|n(<@3hI`CV%+i~uYHu&nFL8jl-LA(7b zP+n<9#f7z46Y(C(iwn8d9slFS)ssQ&jvu^%?QI#qvGv$9Ui#=Io@qS+HFL^1v84*i zU3p8W_BPrX^$;hFV*YJ)ThZv$a*5TJvcB0~r`8ZR+!q3`+Q54*tHzqNbZGphL3Cne zvE06pb&I*uIG>@oVqib8F`mf(TwjkTeguR6(aEI$2~`aDOCWNeIr_!rA*NV6!Lk%( zF1lS0`zz^zLN8J?Up-Vfrv}cu+t-&f+B;jf^datSw0Qwu*$$RYbx?ov}t zOZ@kyj5t+xi-Qa$xNFz}a9V6g=5Wk=zg7q(TZYr(FU_czRSN$#lyI-u?sCGK{$N)X zMt6Kv#_@I)Hu?;&QpLT?U|x6Ta+aW=H_yhj{~Xj zu`V8EpU>FkU3|y42DJPY01+b^IOnwjoO?8aOzl2PbDa{=$20-9nLHAGerYXbgSz94 z)#k8ls~R@v{bIW_A>GV4!!lD7Afcg<^N${fs=Jh-+OCyOO4GqJ#`$FJn+JUE);J7M zI0iSK{orDlXIOj6YcfuDBked%kzq+8U!jFN7NCYpZDsq;_OK95{3`fI*7|))O#9xB zqt)KQ^|hzS$jhvw+@g?7n7xcDF}*HRehvKluUfQkwyh+&u&wWGpV25p%P_V}%FpHp zy-&hH_oPtG8<9o5Y8dG)3+83V>GdDJI5qhkI7Wnv&Jb&9An;Hqvj608O>($V{*C^eWS|FO=;9ovd8Z_F_#*No_XQ^U|Ge z8qPdCf$79XwVrpLn}Q0jj>3iNG|q$hD$iP}zOXX>E-sYe8(*!06M6V|F5J9e_Z(tc5OnkGDsJVLVuAKXO)EO>uPayLj;UZnn)hA zTuJ(pEV4yq5e;O#<&Hh`z>Ic?wqL53jK6oYPs8~fGZ4dZ0EFJZ!zUf9#_~b=prbL7 zRNYX=BTxR2;IMr(u6{69PL+i?%~_&+*$#9VC58u+&k(r*j2qyYL7M-W(lk#Y9#=rJ zyf8SjT*T!4*k{yaV=Ufb=e(ERJnnmp9L{~wNvyBPNvu3sC+WFAMEEn6SG20b z=Qnu>*sM){KV%--m0w8XM<2R8f@PD9bIDpqMLscvWn+gw1f$LN1Pj>y>sBk}aK(+h6)NgdpCMFo6YV`z$tJhrfoKiy$7c*iNVSnyE{)8i+SK{wR!qIDs8 zxwo>8y2PTxFXG?~SLBLQp|n znf~xU4M*F{54TT05BDtWIq#4Gs9yhdU1U2%r+#D|b2{kn&OCnkX4JE;9QD#u;NPBH z?!;P_r&!xa+P6QV*GpL!z_hO`jM2Qf^4rwFodvT^$mpTGFy(&A3LsoON@5<%Zs4-VzfTfGOcrQlyNEO_fA9cP#(Y zq#1oCyoD59L$b_E9XB!l-nQc7^qMo%D=yB5J@;irb;1aI(SHN%Rb5YB475NU&H}Xd zMTlbn6aSutfQ-FVmx!`PWWLMKxcT&9cWvx~^FjotjfKZ#hZ z<^j)(6S)9zISuBpfaO)?>wXfUmVkz_ z%(dBm3dY$b+<$|{VC{A#5Uy{gXOFVpgoD}Snuj01@%~G^8MqrpoUY&od#K@JNd)nT z-bg*ID4t$IA#isKmm0!4AOs3vu6>VcFfY^1LH)o}{3-F}vsPT?mkuA}T}gDN1}ZHo zBd1oap&jg;Z+NyA{FQ8->YIOYTd$v_O);7%T@go`8}j(m1|Lvo+6Oo~+?>q( zpJslhKji7S&>(h4K3serG@M_G_yyKd!9WeiRof1N(R!wD_ZE|}-BvW0?MzqwSqnxM z3%RMLhPdtAClZ?!LC3PW(c2=1q|=l9t_*clYgC6zst;*5;}>1_R|fqv^Th{U7<(-? z6D~yVAri3w^H(>Jb7vR}cP;A%y}1XjuFn(gtkIC9XytI*gHKUacHi*}Nh7UsHGK89 zWW0Ie7>wJS#=SbAi{cx)P(!ZJu6KSIb?^qLPWBVsyJsz((roDH{Tv{xRTEz>{7D+@ z)abiAzSvN|2WZ(W?(Z%`yt(HaxjLMu<W518&ch61!;|?j>|8fCs%U*82wh(*A z3gP_OCVnknjYG-{z_Uw(?5sCHoxC2h<+C8+_r*rc+4}~pZrhQhLdHGYno48_&7h@B zOaC-r0em>#DYD6~lLSn^)u-D;M=||2Tb22g*j@XDyj01i8$Nd|Bae46U#odHxj$?_ z-ObqDL-wA6`zlgV^wt(M8y62%S3OxTum)b%${`c)TTmO8Eo~@A#z9RNrLoR0%bGVN z?dn4s78`@RBj3QlZF9MlURm@T^QZ5eUrrcv_26$3@;;eARKl2AI}_n_j0Q35uZcs# z%Za6$KON@ogWrd&gLmVu@@3P1paJ)o`S3+#%^23z$T~n(4eaQ$9SNA`n%H;FpS`M! zuO|v1(kYIP*Jr(=6J%kC(pr9fNDa;pqVR0gB%-v3?TZ6hAE<^W-OIeVqaUq8 zjAIr|W=OvyV?G9tB%emd=YN)3{$v=->^d1gIleHhnpvD-7rVVA19P^4k z?~VOyef)7j2%E>%@seZAi#sL@$`p0UyPfJ7YS~0iO}|JtDh@*18y&>;i8U`Ptik-= zVAv&{NE94Ya5*NDVnvRgvtpUM4Xkf>vl6#uqdI!J3t1vIj@AhDadERcTy62-OP_p4 zL*pFyd(?rHvRs??pE{xyw1Ey}x$n27dtuj^Q4SkdHe*TZOL+J69MRn@MD=$`^S5ES4V8&)-a#>8Ci9R`MrY94)(**D{g{+w=L(E!20{vbdWvXKk4rjc2802 z2j{+}@Z0WIpd|St6ZD(1fmC!1Wz3UdpeKwLyJW~qpHBD- z$@k8Z?eCS*`*k~UyJknX_cKKec9yo~W{6%NRg%ay<#F!20;%^jrtPGDBAX^R^U+y} zIJM4$oo`~!c_!Oa42mWur_NEsU<>SO8w&lu2}JFm7}I8_g=56kA<)sLgw&>uT%9JM zzrNMr`Ny+S)RWn^;qm8v)`NSnRfS>(67WbK*1beGyu7AA%)4oR& z@$oG*O_RrXZwe<83(p8+0O=0um> zn@YFHz>HiMTG7e0`j`u_G4rKpv6Hp5c%Y`^AB{uc#e7zGs|tv0rX^j&@~YMs*27f4 zg^KWuAktsUP-)GP9e1Q;(gC0Cek&FIE^R^ch6K>I@*;Z*G_d(XE>Y~Tpk?_!I4EKvEYVrPZ5^nIR{h?R z#~zR9qIc1lt`rL)T64LqrLw3U{)a4GBqx#amc=Cz4McOqTmJQhYE0~)4vDila_MlCswmX(8*PG8rU>ZSP-j z1J*I_fsO#m_r%haLL+?ErV845J9&(#!X;}cq?u17lbANO{%Q$Pf8a^enO|$R;|4JQ z6yeacH5Qu_P6C$vM<#7m!pWaslEY1^v_(DYXWM<{crfz0GE%>;+Vd?Ft=I zE<(&z2d+VG0RC$12R~~X>Ap-=OjyV=ajYvm%jY%vz3_xPUN5L8Ov z&!}*W5En<4k!kOq^B2#&!t6#5m@vGO6EkhLb~BreV|G&0sV2Db&PUQx^Ty%S-BQV) z#{WO_pDF90rG@}Duc_n>_SNI%_$>JEvktlEFTjDPnn-rl1v;B`u$JzwB=&1f_$%f$ z*gh)+*3X&5GQBK2vx$=YXhM}_{84_N6STcj8Rm#gjj+ z*2uKJ9H>vTCvHcT(Ee*xAIHp^F(h|g`c6vJL+#s19Zo2G0V8|8NX}mYj#-{WT80mx zGe`O3oo7y9Xt|kN8>x;Oxf&4Xx|(`3T~xgN7Wh1wz?M=?IWW5 zcCzwo;&F?)7-m^L65Zd_Upnk|2Rz@>PG*-VVpK;f$-AXSuZ*n088XQH@FkpLry&;n z`bk{2<>0U5nNfH$YHxGl{UWWAa>`?G2|`eHOW%5S2FRK%!WLcwBhGj~pn z<)+=`zqoYdBPD;hlb7A7Vl&gP8speKJ(piFDgi%sieddeePVq~mGz3s!ShGQse_Rp7G_+8 zF{fXN4lzDYhCs`4Xy73@GENn5N{Y#n>BDKVwlC}F-3SM*7I6(bb4du13iZJxLwvK|L_X2B-sy=38FA%-fnkiu1y zsH_{?l}tDQ^P)eC`cVx@Lu+22hSSJcb1p}v#Aoj}o)1U-k#`IVE~an}V%8b)TOU53 zy-II3`Qe{Ow_xw4`=XW4t)(#1$niq6BiOQD0~^v#>`{&O2K(aU;|D;XJ%^LG7vReD zPsFwD6;<^xK%)=Y#HH#szjU4yI|7eGrTITDB1nib?=+#sqJJjN#LYrKl13h z0fw@3-fp>iLQ#4J>p_Tw@_V*K>6#F^ak)gdY9XDI=EHRC#W4NeZ_%pCT1o$o+kL!B z=lQBQe3JkSr=I6;_@v;-euyxd4Aj>_U{i1Ap1=${ncuQ2GN?Zb?jk2aeXyjST2Eeg%imR z_P!Ua_(p0@c~PAq>~k`ABUo>Ybm)8^jDg#vFJ*T?o9lEy-awQYpH6O!ix;PD>%cWSU0^*pi+Hy&7NWK)^v0Od=hbDn z&EOp@JCMf}v+v{4z+Xf>|0!L`bjZ|@G7@wDIe+{2Yy3FM3vz~4bCzs|NnqLJ=JvgG z@EYd#IQo_(y7`4njkqwZrrO z>d6Bs6ItT{h@GE~8EmXt0UN6*4i@;A+&7Ob$uuA*8J z{<>E@+@uF}Em%iS|2gDv3+vt1(Sa*>N7BrR@9>K(!f9y&w|M|#x$o&BGg5-+#jh+I zu3Jm&bjI;k<7&`s5W6pX>kvT~^L`g)^_}yR*gQY!&=S}jFDLrz{tDj@-VAtg9XWTw z7^k(GK(C#&(1W-6h;ImjU>2Ydg6Rm`g`Uv{AjHnDp8{e&$?0_WoNO6(|O` zFg>F0$b59S<-tYe1fBAVW%HHg!0)Q1D8SiT>N7>#@%F>R5WY+muODSul5(~~S>%hx zEYlPxvzR-d!~Dsa8RS5A7>&E4i|Z~Ssak%9e_6`%GEG9TzWjh@do!M)<85d%C=nmN z`~%zG=EF_R!=xcj4VU{g5xo>!>VMi7ht?hher~?VeT}B1c0~avMcts{|9Gk3(tgUvA(> zbsSQy3EY)tz9u#utu9Jna@Id?Z~%LKE_ISfE9Hc+EtM?C9o5IBT+DX;7L)UcL+3(z zhwZ+Pv7B1#j6b5BS+$b?LhkhGHglN{a2wR&dhmHZ)h-ze?Gj-{v(4U z4$$nOet5vl3j`X;qT#=)@mo_2q?Q~fJI`yNy-_|f-ZzvgHTa-o$r6x`UCDjSR>!A# zam4V&1A5{3TkKfHI+1f0bBh9G&^fM~1Ra)>+|5?Smajd;v0o~WnUxr7gYf637P0)I zkCo0pNjnXq)}u9XH|y)%aY&J0J@F+*CvwkG}>{GN1$UZ-Z$jggPaAV-1{#VZ2Z z&|_8?tPy-7FiZ;#d(`@NuWhy8aBJE-XpGC{I3+d%Ol2(ki$S!ffw9Y=j6Cii%ch*j`eHj9}ispkGolpWjWjtp;Jq&yOU2UW|kH@o$oul~rV5gq&pdBW--|s}5f# zRPm=D)?wMV9N0ERmpo@3^tBfnNm1B2+U}-}_XLe3cJUB?=s>2`ybc9Zo5{r0P90xg zNF@nv)9DH}3;nv8NcKE+6)CJ`jB)0rpX?n=s~F4om5Ts!PP+11&wk*TWrYw~L`dQY zB^+?MmegKeLlZ{(Vus0Ka8?@aaCuoB?p+lQ8>3DWj_DHLZ>N&wV+YdgW?xihXS-g- z2JYQkmhF10&U(R?(@oiaIN{12xZX99v-rq*j^uum;O#9mk7-%2*d5ce75Uh-aunA^ z!ElYQ+`KW`xbZ2wLk;q!il>L+%!!TU!{vVbrxP707yAgb>SvHqlQl7KyDofTKD{G{ z((%C~gd<@I-2ECA)MS~s4z;KB#Y83C{IHf~8OHJx{+F56iG}H}by#kS&AOP~w|n(F zXMt1IYRRj4*BxdhzrrsQwnEv)_2lueR7~DMA^y`$)^94nmWln~f4kRZuS`%WKncc< z&lG*gQev`yF&8xS30-5@<^FReZr$m#BFE&t%r1$82KMUmN^=F?m73`cZ54*K* zQ-jAtP|-mb;%ELy^a!g)muX25)_Z_-J2RgKmJ*Au74){bFP=ZQ1^AFU(Gjchl9wmD z`_A@<5gLqLlSmX7e&*HAy+yrJ9!xFtiENY#&hL`%+r7@S_roDsm%%jgwaE3jwRGij z9Y?=IF0igh1&_}BO7=>J(}m-G(f#2TDB8N1Q~ATXCpyxJV*GQuo%u-1?W9C)z#0Cg z3u6X)Y4qtcujY?pc~wgo_wcBg@908x_exOx;6W}O7hsKd3vqFpNH1S!b9=&JFz(D3 zdB4|?cxo1Mw&y*l^%Z4&)=SA4mm)sURf7$yh5!|`|kDuR}jCqbckg{&BhG;XcX&2crQYFE{ zvJPW=;$TJf6yknd9Z&h^5t(%hX+WC~YPc_hyJ}q`<&YYQv-90PeP-$o3#=Sv18s z&%72#__it3X7zgvw#|kystKHHJnNZq7J|#+IQsLc2_~%2f~`phd8LF(+;d9`$2umG zN7qzv&iAimg4l!lru$&Qu&od~Cd$EmRx5^dg+Ou3bu#KG%O6cpYmaWRXE~qD2ViQ$!|-hJ&sQ$-(B}n zV~H_3bY+rWhZu)}9$zI_Pgaw?cjY8)Pjryn)qr5{8vaWg^KYEYhj1Hxa#Mx%q=z?< z-p6bvsj|d{yaEipWygQcsKxk+FJY{}j@^5O_`CHTnX=l6UQ1=%=70n;PT_>8+KOfW zCuxFyXDrRpWIMPaYVdc;ah~)1!8*c?%q` z!Z*yX^;32nf9zNl&RP=-ucqmctIYRegG^W1zoNJnMg#qDe3FgWZ}&JRhjx&$Z0UlmT>eohgnDRDs)DvP8S1lqK#8 zU%9O>f@oH-297*XL~bVj;scc;a8Ua(xT6}yDKr21SWBL~{d1))(Vsm{0O% z`tfT0>QO%L323$&kbjjbc-rd?S@B>a#V>I<>@0=F559A&8OM9P2lo#!F=O_i~@MoTAgmv0UnI zB-h=G_$>jkxWtZ!S*ChqO@|6j9;paX<4)4R8pc){BM(bsEk$*n*3!~-F*2^$O^ z(&h;)f4W=+0xIT+msvMq)9FG;n{b%O{%>Yxe!??XCsQNFOmho50(+tgM0Yo6N*d1< zb6+-j(z`>ok^IOc&ur`Yg>!yj{&jzN71quLc`Mi)g7u>d9IfTr>F8^ zv2{os)8P9uJ;E<#9(Cn!WN*-2YBhWy>yD`>vePwrhqfk^Tk!v9zDEJe(;a+6&K{dY zpC5dW%lK@_TbjU$N9Z8y#{$D~Z)s*fJ^b-Q38Yn+9jhHZ>hW#utdHhX>n(4>kp|?C7N}og?F^`bs zfeLuJE~L8u{P45eRoFL^aH_rfm|-ph|MT0tS*3{^7SxkBPI7drOBF^&heG_5N^T_M z+b_;d@7u#p*`SFQN|Z#Gz7#(lCBfSR(xAU;5Sg7O#0y_kp{LS>%1FieOscw#~8M1JCb%MRz;uchFiGlQ=7s#VP zHT-Co)~CroDP=vI?mX$T$Q2dKDPv5VdS7PBu+R_Zh2MjVQzvu1po9z0cJ*oU2i^(M z^iL=8pb5N>K^aDx$3W2263&CYo+G1*NXP2Cw71v*ZLSs)msJho;1jQ~WaV}^HC3I& zv8-A6Q4PomA4(@qlHePrRh}3d!{r$b#KwE-Fz(b_dNox6Blp%3Ve=S%YF;Id92VDi z<~#0F!`R1pM67gz>b*6`2d%ZlVxPCe4HAvXFZRM0GiP$ib_jl0Gy=YoXt7Bdk0HO~ zVMiK}j6-Vp!MH!Dk8z}n#{1#8-)G>b)=ci@JtfIC=8?(CctYz@4ZjZlOr(4>@2mY9 z{~TobyEBno#Xt?b^ob{P5-(A^`dF+erI5Yokx0SkAHG`K1)Brg$+>BI7-y~m#rusZ zpIL*J3TdGJx0D<8R2$#D`a$OY`#^13-u7=$F&Ulb&s(KOqM4H$EScTN^*^eDJD0~2 z*@GKtw{0A@kCuSX)9;)@xHcvQvz-g$>Fo^A#$8d0kRw}=SddtO@u!nu-Ln1UI`jM( zqP15hCP?_6eq_W_54!QWHXim$B6%;1`Bf&dIA5K@_8EHQ z^#K)@g;a#g#wY1cdo8Tns{koahKX9vT1(Hl={a_?vvNCQAB|d4ODdX1(=&5?@&3T= zKmwO=Cjy1|=;Q}-#4?219@oHub0|@X_ux-mQN!bpwLntMGE?1}IQE}99O}1N{J`rE z&RAa!&%Sz)`%=~=WYa-{)Thv;;l60dcC4S57K%=N)R27TzHm(wJn3W$9qca4CP&sb z^1o$X<7&YU&>RxO$v#rVo$i7@kEQ)Dwo`a_55n97L>k4`(s^PNN3Z+S;T7XWFJAta z+z1lVF}yG1Kpul(`{r@e-8ER>Trr6*i=q7#wJ@_RlRRki=9ir28Ku+}p6~AAG8X8g z-dAG?o!yV#X1wT=F=AN$-yiPl4J}Mg>0vXNO2U3Nn|ZHg9@^)2q}pB`Bi0s>%f^eS z4BL-*hpYs7(k;sHtCmFf_vxGS7hE>MmQ$9n+vow$EbiE$mk1-$j7abY6-*lakE9&g zOE)|Dp{Md$@c)}4y7adaFV2dCs?6g=`bCIE*+pb|=TMeGW{jpkE8(=ss{bSDJp5{Y z-#^~2)81Ppi83PDb>84W9}bp`pFb`##qx2}wpvLqkhDtE_(a zx8I-Op>w^j`*pou&li_?gneuNu$js3u*?0@uy+l@FWJRh;5KReo%FAN&yPQ%jPiMX z{TfcexCX}7cn*&H^oYeZmc`Sq>A%Cierb$z54VtO7qxhkz7AaU?h#zR=1g*vR555` zCUJ_MOc%XstzUm?zsU)1cn?8yb%0S-ZW-8UBi!0^2Nr9abos(6E7nj9= zcTXKBe4&ZAoD2Hzu@NiKsNnesAYIFUCZx+Zpd+3#rsa@)L<+Uo9c3Du3h)?LA zQ2>s6in*{iOas3s3uE(Q=-&_lTBd&@LEce3Ww}cWqeS>P(wM*|H8el*f_&E9O{X?l z;h>mu;urixW+Cu2s5iFCgFdL3m$a7{BnEzyp9%RX9 z(MwsnEJvmd4QE+*Th|v{d#ntW#&M+fxhi&_U{_ad4=T(t#}Z8$_+^;ps2$gVhjUZ< zXTG-uoB4mA6XkzK)Sl&!T4&4#9JH2usmJ&gBXnTfvK4f>dK&%;Ook^tD>+RgC7kl- zH(7J2i-wxA9q(cf@!yfjFI-fE#yeBt%Hb+5hvkw~7nG5Wo3GQ53g-D=P(su{HHvO8 z?7$UK5wPTdGkLgB8UHQRf->VF^sEbyK{1)I@Mj{Ix>*-Lt{1>8l>|Cqvpk-A+DH~e z+wm*x>Tv(p|DX9eOtURNUraL14%79!t?|=^HqtcWiqn>q7!1SB;52tN;YYVk!J#67ThOb9x4cATMc-N4F)a<*^9R%>-4<@Nv}4n2xU<-PDC{_^ zgM*o8;Jda7Rbsr94%3$qaiNy;8885S3;W2PgfcockMSi~hQfYhD4*k;fVjmM{@S&0 z2TN3N!{rRZjo(PC-lQO}DTW8hEnFJwWBNBq69SHf)5%QpFL@uAMo^4#o$|?iNDzhn!Pjx zTR(ZhK9|K@_AGU5(|tvD{Chx4nHS5GG4>xUKF4neW4?=Y9SFY=Ngw~xz)X2{`0!!A zXwlss1{7+5r5}zHzif59`SmAhjF?1AUW8!Hrb95mxJ)ROttCDht# z8Qo@d^>c50%LZZY26>nsR4%Md*1+Hq`Rc{mt$s%lwu@u=O8dxOTnxcESJ8{O58SDC?{b^{WDT-ystGeUidrEpu|enlT2q z$iUKfd#Kl>P~6vk8oE#A3NKHs!vOho(9AeUoY=S3M7^BwRzv7!rrqTSEr-;5%Q^8X zb}yJp$#PL7wSSn3e?K5d7rJr*zof7(tgnCO*Tkq`RlPJgFVEvu?$)EUTOQ0gr$?6B zDdRywZU4+aykspaMR+^XdG!P}Kbv z1S%oGy^hnv$uTnUzdosj-rA^`)j@n+73eP0MqF?I6z=?NIcG7e0~ph`aoi z_EtI~XuyPE+__*57Xd&r2Bwme_dh+^#o=(*xZoXZulYjHLi z^Ib?^+6H6&g*o71tH8;zd#>wZeV7)IMW5#A;>=tfcrN3|doJt2nP(bd#EjWwF7q+Q zi@uX}^F64)x<2b@_(3c;$2b~)la)9ozXbhJH;LD6b)2UCnp9a1pdlf__;KJ|u##HG zl?JP0Y^6TvnyjU=9;vu-cnUn}TFI@kRl?+&zx`f%8}|FHVj6qSAQA6AvlcgLd<(2gbr?hWlI$98V0(oQ$|-xgwgy>oW;fpx*DamLE=VSB{}^*}MGt8m zIf-U4_RH)sN8nUunJ^$q*3erd_qIUm6N?IQBuJ#`GXEbq_BUQ!Ric8!(bmi$LJIO?;w z;z>xqp0l`!Wx-CHf&Tq#{F*)y`ebCm?lGohH_K1eHp#*Lv-|15oox5e@Q2b3&xJba zwJ1}c4#h;DVVC?z?ywkw)vKl8 zU)lhEsZTT77C(UJtxjaOiV7MxXOP#5lPGTdf^+`-gf%nDxslx(sPIP}igJ_bidW{S z(xVIcs@}Z8ns&7GDTH}PoQY4qEVf&ek_F>^=&F4o=*@41?x19+^K$K2X!02LTnr)> zV>R&J2{BO==+SQvb5Stz9cYBjBnPsX#`s16rrL99t7;h523&&Ran9T)6&=(Lk%B8b z>gjp|9n5j)A}Fm$*N1$@BRAq8Af%qVd!Bi{-o7Dgqc1bf#2)vBcaqq5rJ|3hfpYok zAa&M~=0en3H=`Q;2>Tlh$ZqDH z*r(S+!sP;}AYUIhs`irG9=1F;t`VbZ{(sK@xUYoc+n$lLL4@|r4@SZ4c`)Uc0=Mta zNaS}+f;jbN`XoyY3v$)qNbmtZeQ_^t(Eb81#B<07<_SEL`I9)qW@^5{6u%CVh7QMM z$3u*dov|$q^xDsoXG{p1=f+d0eh;m6W7lslP%voEDU zY}87w$WjR#*q(66oU!Pcr)c-fJ`%W`@^c*+gZ)(oe7{r8HTpB1HlU)PMW5!y?n<~4 zYQLL328f(h}UsEr|89rq1iLFnwnh_-{|-!c=r|&>v-peU?C@=F6k_ z?H3a9-zZ*SSBtN6GhoSnU2>Y~qR&$7?e&%Mdw zgN$v$w1~>Mc~rz$Ve+=y!MC?Xh*@LAt88WZclfn7%=7#>k686q@HbSF@a8)TsvGpk z^-5**Yg7h{6TZ~-OeikZx(peei9-DX*1`A9$T|MuL8yPChWWpniCdf<-MpXi3ifS> zx=U_ckFq+-X1yi@10K@3g~M^3#uvhCgz>qch}p)PPz%LY zl>Qlrxi6^@sN?9-zldw$B-->O1lPPi3I?M-3cCWe#Q76yxQXq4)RNr}-Y$Gk0?s${ zip9r=h0}Lu!OX2Dz)fsr_|z`(hTMsIYgTKlu+l-d(t<V>o4Tn9si2f_sh^g5x+KYbs=L^_VjD2H#H)Ix?2v zydCg&V2aancK`jgA_k)15|JOT!8#En#3xFRQlBKupMmhmeF8~g`JHj`YEX1>AuTQr z#rqalz*f_Rlf9sYlPjg*?}E>C8vFhF+I%H{4HfCybjEcY^b}%W*K?{Yi!JmoCc#G6 zX?fR8wE8{|_7qOwf6Wr(0r>*hrul%}V*9+&ERFumRB&Ji9vxB(VZR%>7}n*d8YB(> z)9QEh8sLF#e@MfaRQ^N8aLENv1!wcw8%foDmeVYHL*8lbqZy{bxWi>W?rf2GISkliDb#;%XH&5P0wB ze;)mbb-m4St$8-N&fbGk4ZURl3Qs!crU}}5NWW>VFV!V>;fRSY6QCx`NI)myGS@DG)z-B{zbxM&Fl6f&J)j^u{J_ zA~<7Ph~i$wiG2i2n`y%mr+^PfN$Ke4qbEGGJ2|pZ19{ zQ3WSpre!j>FH{R%p5~HozJauTRWfe6A%V@_k;3}P+PI%nhW8Up=+Pnd_*(c1=ztnd z)6#@_mRL{Ln^L-yeRG>em-lNmhePA=mC12fu&bH-@tyThG-Qw!M(e1?`c$+Q=Rm!F z2Y1s>9gEnUM?Q@1b7S2%n*=b`r#S2W>ITePln)&veaQA!)|cn;g%q4vNiBDU;D|vx zp|+}3SWrDiY&A)?e}}(IRPdexPpU^0^5VsbIBByOo-NZO4PSMzK~WEesGp^Kndf1x z))mO{OA;Q*9VrpZnmAA0a0pKNt70?XOe8rY>BhYw>@Bksv?R^coFd&U4 zx!Yi$ZX@ZK8_X+~D4@$@O*j`9Mm2bAH2ppV%*XE)O^EEq;cM$*SL0FghGp(982%vj zisR|Ldd4XDbqpLV%Y_?yG{v!~y6Y7{}Nzat&N@|0hhysT1$^ z4C`kgM2<4Un`t)v`n>M8XSk{&7bfiG1L-Off_FpLK&#J64jyUYyWCt7b})*L-JOIx4@qF`?nT_E z@ILW#SLyyaKalnAoe9$c<-s+)iAFQ#Ja_{`h8q!s)4KR-L=Q1o6Gf$;7~n*f-|4f} z0+$!j%?=rQ$0!5hKJz8ww(|XnBt^)p$$)uitV5CliBU{+>vY& z2zvCl{4+do>;vqVo<)MLv2Kx-8W1|im4>i6UvGUCCM3IXQ4yLr{;L$@P1Vt~YAvkj z_(}%-P@q^{%Y0~0LGfxmCm5lI31)9dol6je@3sJ{=RaCvtGWahn*k1P% z3s#C@bZ`#We$^VEUDbuR%1Di34N#Qvm-wtpmQSSmKEW50{Ta^k^38n`f=-6>c$iky6bgGwokbdn>g^30Pq@E1wc z44_K}%VV_iC-Qu;0e|26Gd|N!gmeRT-|=C$*Q$3U(tb8=o5QlD8yAAEP?39a&mJA* z02IMrrsKv5SU3GQv&CjHzgz=omP! zndLfD;R!uM@`r2UxTg2SR?UL8vv1s!kJ-ff{CnXzc60wHtq*ArSJKsElF;Bq3M8*z z!Ntfap{%boY(4#rh6ickO<5TT?i2F|JR5NLA2Eon8o2cZs#u{^Np1_TQ@+d)10GhB zvIT7-!>~BqwsSZ5s%aAMNCiCLtp&ZhgQ<9JCKhS(@H8Wlb9kwT>qFHcL??xIy&8mb z=W2uL^5wkL@LDw8C4&14^++1?_OKuVQM-4H7PJTBvFB^yV~nEkVPPV+P4EGWIi6(l z$V|LZDT2n8%qGY5w6bdgFf*J@FK!4$>xOf1dc!PE_B&$~Z?ES%Z{4Rq6jZR=>0|%i z9?kB3o0pwnd5R>?+K6!jjy@+(mju$|QK|UMD;KUm(!Ufs6 zFmhHox2W0}^V6ikQ?HC}XMWLY<&R`meK0SxfsuPYABTmsnd?3yz+a4IG3d&A$~EQU zyT)R$9wI{y2dm-kNDa7tFO2$!SYbh;Da0mz&B~tIfW9%WLA}g}4E!WOm+$P>vvMir z7#}85vI|abX%n6;a1dvIk|WauC+J@t6|5XbiT{>DzG!&@PD~WT8$&&^wnz=fR%t*) zogaM|&%DZ0uEGY_WMNGm>$Dwf>fF2dFjPNbeILuaiRoSk`j>G7f(&I7DTX3y(!>i!CQLaHsE`qKDXxsZ8lDDJcBR|MmQWGp%mJ zRHJX)-5^E$yk8p@uRlf4I;CSyeJ1o>qrxv1c9Ku&*3O9|W`a`+yQ_jU#KmjS?YdSt zd4~XGwpIzRPhfsR&k~}q5l653>0t!h2ja+e{^*-j9G!Xu(zpNMWEW|mQkgNdT>Z)K z3rxr2aal0H;48P}_F%l+sRM@DW|=oc^|)ZW7=Fe&lEMIWG|2fxW_vEC6PX9;s>?c< z^825VF(Ji)En)q8dqJ=%d#BhyjLCnzUPC781T(gbi7CmBQo+kza{YUIpid~u^qgb6 z&nPLmkZ zGP_@s3EJ2v9^)?!`S0Y!)i+ErKt~UX4eIy_$6C;M={q>zWlWYyF@Aes2kF}uPAAk2 z!LDbr(3@$_d%HE@o~hCBqrj28Emg%m_mHH%aH8~00-hg@P;MK|eM?uvO%e^*S(!v_ z&spNDEMrJbIK+2OXv3)5_n@@Qg(!|@d&uZ^visB-T6HW0i@xuIZw9GO9&Vi|3Xg{% zjVnZT4*L$?%_g%3>(PxLnND~p2cjY;k#TzJ_`^&S?l>-{qghW@+_S4Nb@>#|*pj`o zL{c#8S1n!jL<@TqzLCZ%1v*86arH+ffMZQPhf3`CGV2YwFfNGx46#OA^?KsYy%H%I zYT_^(ZLq#$Mg2#-V%#AF$Mes)T}$>FNbn#eZHxxalm9^4m&~Rw_XVSg zohx)DD{@9NO|eP#K?vs;_=FYZaKtQyDOgc@9MQvmGR|nebBzS zl8$gtLgi~R!0rU}=v?N3WGqmbTN(VBjSYBYsRUYIH*lpkTDag;J=rufl%7a4#?d6!c775hH8V^vcXh(MFwtWIgS(S6S*;UjB%u;2!-z-)8R8M zaec2A=*lhQyT3B_+FJ>1Y&9f)G3<`8t%|4z`O-topX}|u9xkdV2~P?cyXNFR;QTic zGu{YqPa6VZSDuJI&B?;AEQ{wn&V@AnVg2&T%5X?=Hl21n6!Uw|L-erO+);gjc>454 z&dlWj4K8I~U;lElYI!GrlxZgNbtj-DG>O}3rHVG@5@J+(mKx4V#97+eu=H(&P&iI&C&%wgJoQu>n!lD7vP&T}T7QJKN3++nww-m}h zmVJu;$|qs*nO4qy56gB1NXU%N&2+(*Ts+R$DY=VeNY+R-R3E3=zpKZ(hGNUttKb2f zM4CsNu+Ho)c*-3nCBKv~(y)*Y|+T(01XP4hL~ymptj%cY=;(|Bp-k zDY=~VhTpt`WdVA`F!sGJX)9*$y9y0(+UZCCJ`BaAsn=k8eX{Ua@kmLQ%K+zvDo4PT z+#%QA$04|6u%x) z&&lpNNrPP3&U~+waEh(`$;t#gDe(c#dcV zIo&nHIiP7K{Nt7JZAdSn_R2Jn48$UNmXDZJF5EO)fWyC(l9?yssF%q=eBs|tE(&k+ zrPz#_^|v8adjN^l*20{U0WkRDZ+>B98cw*81!Y;?T-b9fygyzSjCY%{$0F+wWt~dr zvmFVSq=v?-)ucJol{PWWr0o5AkUrlh^pB|(pZ|BOe^+mqI{=?p4}+jB%u6#U18)uF z!NlH#@FP^vdWU@fY+uaYyk4=g@OKp_)XlEO%fTYxE*~P3lv!r2sGMAov7&X1`6H#h z0XlM4ak*JK=oOVubiyA{E-DdUF3kZ`V^{8^_CK-gav5;{A}3y=Xn;0*wP3eX1+O>b z3+_sI-#^CyhS!0rh9Gqz}0*I67*y;MH_goV`nR@ZgTJ3E9mw>OqRC3mj-7F@x6UGvu z!IMMqn(tnie<#%mvs=)9dmIS91Q9JKc6(CKB_RoVbdz5q3YO%6+1`m{ueAy$)TqOc zAq#0`CF_qM*TGGFDrdy*k|T?ipeDS7HalsfzJPTPG0*&Y^;%SWk_hjl8#oggT}*VZ zAgR4KsO2CdJUzdNwB5=S*-Tw5=_Q`dzfVtsl3JGgex(C8-h=61mSw)VS^_V}JmaP_ z|4+B?Z}Mos9lEJbAIqeqpyXI8zu`;+{+pQ!cS4NFXvX_`llhJe{pC%+O$^3nv&Hao zlD%+yak1EcV@vf-$6OF}ycX;=0e-V^6pXEZp2hWj?YV zig)TTNydlYaxWXbYO+A>ttF`qRK@Lg7#~As3q3GU8*OLy5Y45J9Z%h1`JIxKelDd* zTLazK6_Kp_<}@i;9ls2DPM&vv5YBHA;MM^K5M8;F9x_X3UC%t6`Lmw;Jwyp_?~#Rg zuOIYHgbJE{{X>*zXYf5NyYz5WHh6z*;HEQ1mZ_kL1kMhli)2kv6w^dZ4u2K7*TI*g-$5fNF{m1BLtq^pdxe;QID+#}~B(O}`K{)K_dX!Sdzp5yGx|&3(-Qvqv)Z-1M#}Ikji0Cr^YBi1?<~2Yv^_8nBgIsy|)oZJa`Ms;tml{WhGo~)kvbL zI~AN@p1Qr>aJZvgxW2+cytqn%tmRM8rv|L!EJaKvbiLutB~MWyhrQo3^~keNx@c`_ z1ou{-r-R?H9vScJU>uhsY-k%P@$oiu&g)^f#vTo{3janF?l@5TUkJ+H_J$10rCeH} z8fu+*PZr5MqG5`IaPi4Ha^~q({+1b=A*m+N@Z%m`cjFd<)@^uJ)*$NmoP)J`JS;X_ zK$Z+t!%H!Jq`Z4Fy(+^rv0^`%>{uz3OV<={^l9Ka|2s)@=BcBG(+9HFs)3K$6^}ES zXa90U8mB2%z>85ja5(rB9eO1V|CEVE5&Jt=GbOKvsi1g;0vwC+rXF`gahT2p z2zvffSbMt~hZOPf!{#sv@m9voM=FR+?jYJdEd=dDHiGf^)!gLyl^DVoF=Yvcu9VQxX=c_r)a-E8;b8nb1e^;AKP6E zzB?pSnQQv!s-z9Qu3PvKaxE+;QUsOOE@Tqp-sFqh$jyRNboKHOoX`5O(p}P=4EDER z>XvvY*1JS*W~<8<-b_bj zomC)pwT^%2n~gDlMPPnenj8yP!CSZgv0l~yI{!M$g}Jx%Ywz{57%y}}23Rx1ixu0k z2mCDR-{-?F1mnO>?vSxli7O~DLHqJyV8810+k=^gq?^hAwrfc-1o)#{tDI@%!TG68e&Dfw31*hu?xgW%`!yQK8pf!RzH>6|Q zQ89FnN#Yy@I_Oug4uk!YXzZhb_}^9?SbJs}&n2-Q99{y)?irB6GRDsEkkX(A$HMH)Auw#lx{!R|qM!5>ata8rJ$#cxM7c;RoC8oBn^!`?25G zUztE?4x7WiO#<=Kz!uJh-C6RNsNg%VPsH#{H=mGJhd2H{0=tkFZUcKuro^!xD~|xG zGIcaA^LK%XW6Xu3`ZW^s;?2(Xs~Mkn0_!NZQH5*fCe)q%cJ72SHrKg2E^Y$r(+O6A zz`O?P`BMecy%>|(EsXzp_A~Z|JZ3!%ksG%?sc=dXUMb22`D^XmWcIz* zIHv`>2Hj%c)==Cu^#+)Y+brrxYQXht-+{}WLqwUqE4}}96YJWw^blin5jGotJ?Riu zx1@_hLIcRfBzf^u83Q~u`2(5TTF2jSkHdI12}oz@l1J@I81+I8>b#Co&sU+Cz4HbP zf>hz;KO-f{m&~2j-X4Wf(=;$v`#Z6p;y}HVL(px{e)wLzl>1)9yt~JXiPyu&bc?<| z?(KL-+Gm{QW3?I6KFO4EDeu$4X}2(Q+8uB$ZWLKQm*Aq=BA5^`k5o=qMc?8+a&z5e z8Yl?GI?+i8Yp4|3_-l$4Ga9+77bock#&r7QT1NJUf8mS1#^J1)KHzsgjaz7{k4LTy zhM(LuT6aGkO&rDGts)V6O|g@Vce8cAxMVh*W_O~$fsD;~gYAB-v%b6fB&d8`#Cdrd zOi&p_bRk z+!_2C2l!<}=Xxj7moLC~tgns8&!cV(?g*` zHjEz>l8PxNJWL*9Oxkmq4pXAo@1I%qI24B{2SVnKSHcnds&RM^g|e8#ow!|^B-XA3u9t&Ngu~NlY+G_4{2MQ1uDo&L;PxE{#a)d-fD^kb1yCIhj`cVBImbssQiS@%x!~LTp+BceSSw z@f|gsIJKJ$u=S_M*$w^IhW(&hkmhvkUmFUO5}<`%W?T#vd~iI6M26_lqeq_NiJWXW z>o9?6TxGY0z3Pw?JD(ZN+P4I@2b3y8vYB?VcKjRzo-`R`x_BF_%1~f-zno`)jpDXJAl5iQN+tFO+DN{KVt*p4ObDIQnDm-nU5v2O$L?}?w|=x+GuC`l!}$a0wa<*dad9aKrflL)#%N-o!~%>Cd(m~X((&6=gd?RJIipqVt$j=$bPn`T z7uL^v$*YezJjvkSR@GyjMlL*B+Qe;VZwjM%)ui+7HQFI>j1zU5NzC0Y(auFI+vOhx zQM(Bd+p1vi9j4<=A3?2SUf`Zp??6YG!);){qlk1(=p2|rt%eW8f$F*tePbD)J&JYo zXyk#Fxd}P^Kn0hD)R2oGeCb8Y5FDJj8SE8k{tN;ej^>CI z7p3B-@f0==AmknMu~ckOg{LlaXegWQDQXu%FlR33KTRNB71Y{4+hYf+paWKu|Mf&@8Ue;W9Zmiq;ck>@JgZ!codomdp%Z5%71TmcFkM?16UUC@f>xK zZZM^?)2ng3LIHex_let@%=(5#tMQDR` zx9!2%uVliuwUm3xm@U%|z^W^qLht$M;)1ak$eug$;^`A~QPBC8%$!xtN4Lgd^`UIA zaML4oqm;0d@t^gij?n`zLvhCWo1om3Dx9TiC$W2N;VhB(f@Ke5m9P2HugM>J5Q4qq z4uI9>WgIt19qaT<$bYjQ(*sOPsjhubf=8X@qu3rk(ZURReI8JUv9`G5{Af5VJ|ap_ z;n6cW1J-_@MeG9AuvbwAUZyxvX}eGyTXqV>ZLh&@W;Iaa3MI2Gcs4lO)Ue!zWoB-@0^B@?Zu$uio%Ht>?Db|hdJ}+b6`V@EKVp=y_JIh4)HLf*@z5H)y3O4 zwcupG(v9GKPskMP@Qnsaw4lp04qbCe|w1zAH z%sBs(UK6R%d-RoE0+<$~Hc2R}0EaDT8s6DMahADmvMJCI8VgbdP%o zc78knnlsa#Vx!wI_Hhz;jJZO_`>NnJ|6DSoT8G*y#iPxo9B}CzPwqwvP~@x$Z}k^a z;ragor+-rvY@l8A4xwpji7N3vQheaSd@+cu&_5EUS=y3}%|i zDIyz;>=^LS9*t> z_-{M&!~fBN-tl$(xF`vFF|Qh5D@{(Ts^j++vM_f+5S81FUQWm-f&30S{TnAHNKajTLaQD-3bfc3XJ0s*nmE>f_DPW-xw_KX0N$G2SH$ z3a(j@Hdl50`=2bBkKIWx#Ihdh1OLd@Q!$Q-!|E|$C3_=`IYa(3wrZ?GIjO%tkV@)< z@xA_Xm{GWiYha#@HCHTQqSscsYiBCHy(NazOEz%B2P@(1;R>+4riY$p+@aTR`ueq+ zO|ngxNM68Emfu-8RRvG6p6`0CSUESN{`4w9{@>&Qk9um5>Y5kPqs9mLt7k}4e#W_ znCA9)*DG=)@&cWF$`0k+rofDkX2OHTDI68|rJ4kN4&m2a>t!9FJRCkWlovjM$1(jw=WpZHu*51td-k$@VC&eEF*^}yM?)Z}&*x*1@D%f|#=@9Igv7GyO zP95*tl@ZgiPv{($ADP8`eV4-h`Q_|A_{Z5CVumr+%|%OG6K@NbC+!jKuVlGnqbzXD zn@#3#WxrVuMR;61g^nG25_lif$ z+lRrgGo7>gsD>Y(n1P*LAU&0yhMqqe2kD4J`0%Kmq^f(k^US_EF#MG+J_!~;lde8J zaU~++r@;+ZaDP{3ieMo>QB1nwUAMqQ5ulgjymV+;j|Tdb&9WX+s>UWD9(O zJgu7Z63e%KfQ=0bWQU0^4*j77-s3bgk0`aFSJ-Qa51LAv7!PE?e6|}frj5_x5Ik7n z1vzfg++cmi9xsgOzr8ki+G13=5FQI-dDAD!*d*aukBku+u|*T_EK-NkNyn*t5$o?B z83eDtxUJ>d*Bj&MaTTPyGM+B* zVcf{GZ=uC^HJ2jk6+cRs?bmHI?x|v$tg1*sq5sq0iy!&p5nZQuI$`BChRGwH!0*!n)*X|*5AVaewa zdly~0lXZx!?EU~-?oT7Jv)Rr(SPz2tE}_r5Q*ovv>nL~J&doolhjQPPq2*}@W8)|@ z?X;U1C&#cEK$Ww-4bH$ zw~sz{7>qNN+sKGT*-k62ycZj~wfF1rGuEhL(RN*UHn@)0s}SR>O%!HZNfYxm%6Pt9 z3J$7Ypeh~mIH9kZ{P)e6uZ*roE%x`{?#nT*r5ff{l@U6A4o$urjAPwaz~*xTZi1a5 z{@pPQhIbdz1I`xcxX%Vw-nzt3TEzO}DtOp2(UJ^$$C#g5a?oS3lSZ(7dd<b8I+!7k%(KAEof$UrBfXYf2Gg}WPRfU6JbLxxrsgq{^ve;!BU1>&tiot(Vi zBij5-8^><#B!3E}=v40?SZ^+ZS0~t;%TWzqbiX8$&;VK~KN544robsPGvU%5DnO{`6&i zo2V*Dzb@k}DGVV?pQs=(kAbe)8d{JXg2VF;!|skQ;fO1#;^S2p$R#a#@r>gJxR=4} zRM#}{SKmBE%ei^rrEf?+Xs~^$jj>D}PtbhTEG&)4fTq@Jp{0|ZBy!XsXMNY>aQe6! zI!yRU3LlK2?xpN|Ds==RYnF5F%m@CYqlAceKB8{ET6jwHEeSC?&1(qNv2n5m2%bEo zzBWAWO3Q+x%-O_Wq>WMc87I7XDm}yIt&HRhZ04$kIRRSYNY8doq3kq`wqw8X_|pE~ z5LpE_&pVDl;JX4&CHk@b~jWn0Lw8`$#e%5=7so7CN(dj z35VFbCU7f+#Yl5$8K1=eM3MdZrt@kB_-LptD6ovc(pkx9!F0}3pN&Z40LIJJP=>Nb z9~#>kias+hL0Bm(^sm>2onPGPs@tjfht2aS#qHewUVT&zR)y(v zx@n1@5`I6{P8L3pqFoDWaqc0>gkJLMXMZ-Y_Or=2X_`C1g{F2K_h z{(qi--oxVzX%XahW^orYbn)?VWmu6NM_n4&8#B6>{QVKfAC|7e_burVqhv&!)-m4u zpHhqz9uhr1;m#)2xI@e6aQY;(eIy8xub=bwN2pL*;YRL6U8Q$Nvv&?BLC}z zjXWt0g~AJTeT6)xoo*rLmYVPrn?BZ%lmRXQf*6)Y>6BUeU-&ew%IstcH zoiV%ajDVxP@96rIrnvi|H5g(bZ|Ee#M`j{09BDxUjM;n2MIH`s*hQaM>fnxD(y-Dj z&N22-HIA`Ohc^zVi2XYO&Q>oXbKjXzGv*t&-MR`&G&ge&ueH!%^I#}c+(E08l5pKt zFx8N5zQ;l|ux@2O)NurxJ+ z*6cM$o3ncT^W2;L`WYPgJ5w2Pj50*@O{1MZLRp9PW$;d#&&gXUi}$E~ z<^J4wO#hZM9%f`GDOo2)qh^1`yZhpyJhh!u8qIDi>+;F;<^US{gU6gZrEt+cR=Din zGRY-#Pv@%iWiXGueMUdf086ncef6#h_qukFzme*xtEu0)L2QmGz*y}Q!Y4kd;#F?~iS%-Laq$v; zY=|slT&sFMC{u)MoJzo|&60SqT`?`!2+E(FrTLFia9dys9OTM{6WG17&)v#-0zD3n z^O*-VvWH0h7(-j^EOAzzJY;w^3Io{f;LMuR{u}Fg=1aVI=q(YZo#LD1SeDatAY^Dq zQ{Vi72s4L6N9`Wb?4C^2`j`m=^k)$(OV(w7NCtvj9O=c0q3rwR4+YiL!Z$)~ak)!Z z|E_Mhoq2eMR}jOstozS57I)uZKE{$XE{AC~#WM%Ou851&N^um*?wSm}iIaprhjsC= zPz7%C`t&BdNBg(W4p;=tI6R)Oq&lz*E3 zY7NCzGcUvUEd@f4Q4QF8{3Yl_`jIM6HM}{qne2(Qp;fVrdw+F1{N~qjN$kd#@_!_q zhdvdry@nX`-F>u*o>@`&=hVLPD~#cSey& z%J2U9{sA73<8j{SeqZx7Hwu7YE3#gxiNd{wUughYYlt}K>I3d1$}&EdX6$TwcWuln18(NXn` zi8_aGr!+>Lona7nBMspgBhP=!C=W|ZgsT*9wQ=X@o%HQniwNxcq_5u<(Ups zj_Pp-D}} zL=3m=rCLYXTrFG<7NbXrM|XdcmQ=U&a^qds>R{|2Q|SM^nXk;3;z?Z@+*DH_1$k=t z&_Mxgx1Oi%XB3%7tAWg&YRtE|RpZ^gj1w}MkVQ@!xNr%}vwwD{AvrhjK;d$*S*Olf zJ+?#DGaLl>siR)2^ikWfAKb|}&HtE^gjNS7aJ<=qjH%YZ10to~xqZev9mbbafQJ*p zoZwn19_HgASJRj5VmppHwpZ0YZcZK8IbW{9`hy;?<3`!BjNv*<2<%x;%ZsDY>N|qp zlU3ZY6RJ32l^O&%bkog8^>DGX2K4*$o)7FQ!N_wd5NTS)eLtm(r_9>Po%%b})x@4X z=L%rzs>B~)cfI1>Pa$W!3-h4p;JDd#;5~92)#9V@T9TCMv=Q9J4QwAbhxJ>PMbKr( z4RNfp78GBY&9{xHW!m5EbY?na@D@M+7_AAlM`qA}rEH(&637_xvpMNmHR+I; zHtxoX=TvKfHo719L2gcyqc?w6;^Vy$FjJw0Yg?>|+3KIjv5gn$!Z1g)i=6_(nttNG zyBEp^nXY%KlUoE@5scFwq6N#uW_0i0TAZO@1cy&FaJTBr@nWh5X!fh3)lnw6e~~;q za|`27Zmh?y*D+A`#hj$B5TXCgk3?nkR%$#q76sF@;DYWiu6ddYR_bblRo@_Lv(^-6 zuQ7v)mZqf6h*tC%Rt>CkmK>kXdRnh{lGR66(xV%bi5Fd_$#`o~p(~z_=kFJ%IZm(x@xMc#C&q)O9VP#^CS&p*77j0a0 z#~uUgqas{=xSK?&jiz3mL8y~`1dQe`?263{g+k+FiO5*LXkDlvX$spUkva8WRN^M24REf>2; zb)*|}+Bh!hG_~<&eTa`)pEB$IJ32NT-yJv#o;HcxDAr{&YK$d(lk=zc+U&cCp8(OG zH5K}PFvPw)zXvCEXp8)$!CjJ&0 zxGbxVTtDqWx1I^Y>DpTXy%o5V86{HB?e}~4s=KqTvHuJw$Yo_#Nq$kd?t~ON&#;}H zwJsL0-h@mgU&@eAC5x02y=aPmn6w{ny6MLwU-5D?_t_L@?P@&y8d|&;rA+ z#0LZEiaj^*#)TD-EfVvKU%Jb#7Oi)gBtHgj)GOo0{n`*`V?iHZPr^e*eD6GeY`g*b zKNG>bK~Z$oYWBY$>mgF3NdD(U*6ka^LrH%VQWM9zFTZ~!Yg_iw+W+^r$W}m2;wbTM ztxwWszwf>JjM;T9tn68FKHuF1i`;1^Ct_N6G#c3Y;ye2H+F2D*MNBA1p~P^b1A zI62G{mN~EI9xX3J(n{~*V;DL|2U}v1m z-?~$ZF(=-^U|8M$kHY z==d^@elLi`qJ9XBhRb;|9qCQHCWNq_&{QWwOn9pW(@SUb(v%wXtI7b&)23u=p(^Ug zRg-x4Lo|rZ@atD?gKeBZe7U^^Yn{Vk)BfAU@#YY0u9^ZH2d7E=Dj2_UAi}*CF}ap0 z#QK>3o$V*9gVA{AWq8#+n`_Eclm4t}=Nz10uT5D}pgqr=c8pEKlvz?Z zVwA!8Z#2gR^M$=<`}sU&c1I}ho#79@t;N$c2IknClL73rt(cKTmVezsJAOxEXF~?O zI@QWepDV=0A%<}7#9exSkO@|U87!=8Oe$l!At%Ke){A$NI4ofOeQ$fnc;j_cr-re5?$+6O7E&n^)&$bEC%{Qx;C%k=sI64YGKwp_5d39M8qxS2@q0=Esk*}a z8*+N=-d8}jdHeB>T|!*D$O?9OKBE$vgx|70z_uh2Z|s=BybVcEet9Z6sH%zeN~$m@ z+l4M)6O5+PGcfT~h1ln~j`V_kJ2#~6G>z(J4AS4M1mRB=A0c^#ix(V)>lz81Yljd8 z^R3|Z1%G0Xu-Kj*Fk+e^Rj zr)8-a_Kkis2tgy>DN7!2cD_&P#K$3v_L===hotyvj}0% z-#Ke9#y*-^$~x?>(A=UM*nY+n+@Fj2$0JlQ@E`MqhFH+qs!4eGA`fmSlDKH*W1kYJ z4Biz_Xa@7EjBxo!{QE}myXET8*Mu>U-2Hl)5$waq>K4(6*@ObB4rY!Ji~BKkGZ5q;Lq3P{#TQPAerU>NBZHIO|_-UJ1Xu)wxnv8(evWgC_wsbd{3{>&CK& ztf3eAn~P+aKL0Ij0b62~!!mKTN^qoV3q3JxFiyQ`0>?G8oZc=j#n=%^a6ZzPjA#8~ zQ5wa>>4P~Ps~3dA6RRLrX#;mBjCC6ww1t1`y{SQ0G-{2BeSSg+QgOJ%WsxwBx$>dD#>;p3lyf1|1ah24^O$8@+R+15eg80joH5j!d7QDO7$P$qV zPmRbX9<^Jk*QRiMxgj0$l)rOtoLCmDQyVU-2eEyzG2WPF1_pMGNx$Z%AnOr_ivO07 zF>KGiZG8{nOV?0oN)S2*9)lf4KgH>ZC&x_J6~A-Tx>S}rjWSXr9^ zw|tDr$z~PYnWYOs#>eUE(AOBah4nc9E)}o#bd>FFvvZlz|2SxDRl_yEevxxehtm2h z{jg`I3OwjvE7sOyoC?!IlGFDo{m`U~gQ^P2&R9SGP^%CR?zM)wD$nVabxHWPG#&o+ z(d5@GO2Bi2cv!g4oeXOdpZG#}=u#=3cV9;;G40?wHu=%e^#b%} z`@x)y>SE%H644O_PaHiF)OK80{L}~`maZ_XQ@YuIt>i0&Re};K(Jq5sz*Qa^c zgIP!6Sy1zdl;;+=vcFp|wJGu4cUgG?9Crx`%ciIY^me+XXi zzXI~oEU~t0H@4$ zNq0AC;I@5QjN7o1uOF9;zf+Q6(|9{lzh47qT>ncRh|kdY5scM*vV&+Rj&RPZs>R>( zui;Z?0Lf+yG^2i>$&Sg!w6iP>6F;Ow=@2J!mw6z==Nmvyj0ctf8P7Uod5Blt$xXJ^ zXMIVU5M|az6RiZe+~p4$B~qgMEoyK{i3}bMWoJ9vo%K6gLN@yZ(z|SycCJ_j*UUNI zgU#pj*sSvZ`_pi{MEux8VOVAow`Q#Y*1y++j`Pv<#K(;mf4=%r>TBKF+x_vpM-yxAnZahSCVt4ucntC3 zL2|#F^9a_&iQCk{NqU)9?Ki=x_cTEM`Dor6B4bi8udancTOhNp__=UZ^T2!Aa(Hr&SPs8?+ka!#8j#*G2ero-JHC zv6(&$kH!({DX{;~YHr(6mR+5o0rN8cQTG+bsF$q=?P|IFaNVy++uy-dmnv?eye4kA z(@NZz+@uB$`nbfoiDYbTmKY^4zxUc_u;U}sLyl{sS`yp&ju}rk-;TgDTV+r?KY~+? z(LmJ;T5$bF1U*u#jp8R7&~a!gpS5u9M4u&-;l$2&l3O8B*m5%&lKKNV%DngYpNQc019!U9AOs&D zzX}~U|KkEY1=1D$ySbN>!szKKIylF%lO%Hr)IPKVjmAgA_J9`7h2?aXU=AS@FVeM6 zc6eNOBB=c{7Jp2cE90}*xvUAB4=Jo4v+#&6yht&phGp;Z{4E(68Dui{pef$%7Q$tp zN^0KO2VH7P$&7-l{IQT))F1pB1l8u`xtR#}Npnc(jcs&%M+Amk{|LESZQM~85nfF& zf&Fjq(?{C3&|v932;b`?d3-M!SNXFZPi_h6a%SwBh`+@9uovCNa-cDnkHe?5cJYcC zG194n0(y0rClht>b8`WyaVqCmPKdxmNtw{+t}$`@sEuoHS->`}^K?qgYg9l97yR!O z3rR!IY2M+j5C?kNK*9d!^xcB-xUhQ~g#5Z7nKmaLr>x{5R?VH$4+^A!!a2pvOGvjRwBMx!8n1t3XusxiNckQxIW`Eym~Q(41L4+ zc%xfM^tL6`DT;Yuw(o>t_xf-NieIJspM>^imm)k(QMh3=cqcvJyDB2^N`ef=<{1%n z<|UieR|JYdc9?(M@Xc!w_H3SAg!-2E6AX#xp#d0K?X~l70damORWQt%|NRS1S_j zBw64!C!AaH#2ANK4usqPGN{IJbsYYed3d~*^Zn+@(9(r*{~T<|Dm4x4y7aI2JU{!i zFN&wh!_c1b&c%&P!?cfuv6UCezZ4PreqtF?kuhz16ppX#KEi=iXVN!M6|1ipfRU#M zog2YAF8gaj<%J*A{hA&|8moZwSrLtGtHz-w$#6XWJLkDgfFIjSh_+rJ9WF7(tJ$?= z*>ai0k$IN9)ve(1tD#i$6U#FHqA;_65+@vKi^&%KVc76g8WtkJ{+)kGcb_o6@lz$v zULu1%LrjSp<8?IeEMf1OJ=F5y4Sbut8jd-S5zl{;DIJy4+N-6vrWvCsbRbmg$fhSLkvD!f)M1MOLUWW_plJRS9wc-%3k&4!Hs@NNxoP8&I&94&NV z-`%wlKJ@qANKD|9;k3FJr*u^ne@+vEMrjZAXDr{q8#>Tpmc^INW1Nl3ERa9b#BFoY zM;+B3GVRp^>RqUZ7q&H%^c&5RYw4A!+4c-#PZQ$7e1Od_2ZCbccv@T>f%kQip>|>< zH;8F;V_EOd|8w0_CK%wwe5N4}n$6EKsKe4VIWVcxobarpbLrP_NPN0HkUiHT1{&0-qkywmoX2_hSVg3> zcKFU~61WALh~4J@CmY7*^HUo0VI}MLskJnO#8FoCcYq9MRU|>%w0GRQ1E%=OPt<#c z|97_!3Tn&9f!eFQ^lvpD9Qhhb$C;BMLJ`J~_)PAY`Oq&$;V3Q5gr=iExJNAGHlH_z zZ?hjzL+4u<@a#TZ4&E;LIrxo?z=TJ?#3Vgh zs+;-0GrZ=a2si%vOsH`&-|;sR$GB!gR=O#<%kD}SZLALM)^%t!ntof=4=*aIL6>8l*jmdFKVE4gpT{TC>JvJcUQZ01)i?LE(3 zUsd7eo6n)C#f;@NS=RW99mtu>)1Q;0(M0kV>e7C3W731M-0d3pO$bi>v%e81ul)jP zYo?O3Cs_V5{Rc5}SWFeu8B2f3ZaAQ)$W0L!OAkzb*xTPxlw*v>6{8^k?R`GjGXfu- zVa$qdBT~wIM;ag4eQn!5sxvVJCnj72^_kh?!f(HEV`wE@Qw<7v2yHjjWfi{a) z&O#u-y!a9#NWMfDywgQU|4LkGyhO-4yf*%{1iSr1>Eqhh7&Mha(1Jv+rSCB2^I>!E zuFv$q5Y~CRyocP*599yLufnyuZ{W&3Q&PA=1>NiO$)(zD^i#hee37#T?lp`Nj}>N0 z<=?gS=1<=}GsdPU2T<83M|GdX;1#h1MlboznRcsTT9q=~X}L(7%Jp!6fGR9h9me5=P-9&Yk*%LheM@ejhv_;98Lz>8IB$ba#S%GmYphPYj80BqG` zT>$@Lary%u{u^yh<`)Yw?Ug#XG1g7gM_v4JMFoyIML9WcsYKJ4Z+g%6ZPSG~@mD43 zzs8adnh=B=o~(o0qD@>s_P%Q$>j>Vj_Rte^qp(Z&9qYqd!$~fwvd&5o%=40y2L7l< z$8XtS%XH?fMJia!dh||}UZGiP{qYpzl7Y88|MxoMpL_~~^G2@ZZKgKUX9hu6e#M=^z-$dTF=Yzhe`y^CSbm0KS1rh9#vyFa`axPQ zpP-|U1mS|vJ#eyHLp+~0Vpw}5(9T=LNZAUlN(n?}Q^`y&9NV6}fjxi3r2k6hCp6cD z^Nmw!gCGQ@f!ATw-?>Fjm+OiD;+{H|0qfGjs{NV-ldHhv!yUgWEiR>N_(Y zg&GK^Ln_6Qw;W}cUOBkr+&lr!HbQ*1hs|16V`!@>^Wfd^h4F7!a5}H`P`;&wdHCb# ziq{&rgwG{&MJM>RVN9#MYX?_TU(g*B2jj1W1l}s1l)RP1u}n0DBPmnK8>TNAl&QlX zy-76rMKIngy8t6otHllVx>B`M|F}QdXX$CinBDGNPKwXf@mJj{F)jT$oImiB`(7?Y z-C{dP{&0!*XS;Qev+rPbk4)TRq>UK`Lhy1mpzRrq9no_EeokA=B`DkCmV6OB`cOo_ zA7b9@AwS5KqrtpXp%Q&r=6B9;GZLZ9cGD{Muv$-^-c5~0$H-K$-`2^+vGXTQOC2^2 z6DI!4Y{U^`3SiEE?&KEpzpbCrMig%^rnz}R7&&Y&q#ab`l$RGt*JVHK%_4cXurqMR z7o98y2!oVRaGcs_mm&9751P;yO&L&K8$Obl}kul~6X)pWL)! zGnGmw>1=bP_n40~c;sGCjbFpLmN6e`S8gxYSBc&6+vgR-+4ZYAvaMAraa8HeBHi05 zM0qtm(9r(Eua(MhB2ds~T%pE+#`ut6logml`t->X%av z7_TCvp+*Y_#P$cv7%w{gzt_k<9!&Dv$)!5#qUl2|n7yKvmR#4xIfklm_ppdM1Xf^J z=Nq_wvzaSq{F#B#knb@r*&lD&;o(p1fu%;lEgyVj8&Zh4IX5`?+IN!;Hi zO*2ZQ zSnLM*mv_RMM zjES+=ng4zIJLYW2f*CVrkdZcO_&mRav^|?jKeaO6WBq#A|3ZWN>1%^4#<+s@s|K2+ zW{+EoC%`hdoBU|4SiIE3!`(k-B#`C8wjN_1{#!ff%w={gmthPigFZM_?5o009Vsw( z(HSy=7oy#q8dAN?iauuDJ>Hu)K$C0}_l5Pl-KcPc<&}G=Pt9xejLn288s4161yu|u z%)j?VPU=S)b9Ji@M6J){pRBLP!NFhP^{h6|TB?UjDjDbBIFw#nV1d7O%7cct93LHB zh3BnaLEIb{Vp*VrV>^d{@kBBGGD3z?rUjsEpUho<$@s%pbwTH76m@03h(5=J@bt_S zUSUNI7JbNt%6M~e9Nd9o1Vi-jUIAt}svQ4e3pdv*^xkP(I|dq07ZVH-F2 zvIwhJTflm?ht&Bi;-&(YpYmKxOv^NJY>gsR+}lL2S+LB`xs%X$Zm0NdS(Mb;IPObIY3{JXRPe|C*jy_PwrHf0fvd%NwOq?*0Q@>E#vTyaz4$6pJ#sZ zC-(5p<0akE=74jY2pl=(D@iYn#rXvk!Y)iDhnP#wOh+B+hzomH2IIKgi*RLojd*gC zo^+48JlQz>Je?-g!xNXjlLs?8c>g(d$XABLw@Y1|oi6hdPhpxZ`<+@dhNqA6`(9n; zvZgkQGDW@KMf-wa>`?WGhnh>c)BBk(Wu+#}Pb{J@uB+pN;pMDr&z~QmR)xRrz65SA zyWh=bI}}fQxY8j%E0}w=9LNpi2~SB@sh67 zWIK_5-^ist%Dgw*A!=tOfyl{~Y)%*9(gTHLU+84|AS4`R`*Hw95!?fbA=U@|@2rk5 z*2mUvv);YuJ{umLO_HExk~MihK!CRg%R^W68HygG(7MKqW&Bq<+bv}*i@r&q5qgPr za;xE&tZY)8sZV_!B5=;QT=0n_zI3nxHH|g2(JBs?SRup|?cl<8>fqWIEwGSl zrAfyaA0Ss9%sy(-jRj?xT=WK(`ZjSjYXppeTuDBef0cCmg^L5gdH_w#R^|PNQ+o!rv6GrsYZf6{<>rj&0$@<;nw#!CnFc)CkaTW zeP7gNdA(mxZ&Ci71y-)tgLTEue0WqNR-Vg*?1%0o#8wTJc9ao&;!gi|GOu{(Mp&vN z_69UiyMlQWSl3Sd1KrH;@)TuiGI!?ES}Ti7r|ce7qjH%C(2UsMXN;imHnPa?1oNE+;nK;h&+fBO{B2Y-u8oL= zzz=uG&Z`!dj3ruZesmV>$(qe-Mg9R z=U!*8|6D$`6z7@7!OpQQoYiy2JF5Lk>=p;oDX0G8TT?@qpt5H1+KsbhKYTa1oW0-y z6Xr2Lzn(T6H87?l3wc~ILIOp{Q@H*+jBu2Md7p-r)3-h%bhyz;Vj>^#ZXT7mP%!~+ zB$yGyDMH*5lTVUg`_S3gaKj%+U^Bjs= z&m<573rXHdmbJO82wMkjq=tQi@%pY)a7+2O*v~ae`Z_$YclN$}#srsLW}YI=R(|Ts zFtqrX&3GLq#6zsl^1}8oH24w?PK;rl(UdWT%EV?aj1(}&hE%Y<%;y8p zFj1y9WH@s${XHT_b-v!5w>`$89IE0}^&(P{dqAPHei zB3vCS&sD{@VNq-ae9gW#(@ zEKb=~1T#Zcahc*D($EYQc+Hrx2Bz8=Fx?39CVbHb#eo#TcE_pS5%`KJCid^B>o z07q5^kjgry@doD+iMt_H+8Ti$8ge0MB#<%DS~#=863ULRrp;9`SZFVWzMHpmuNhn5 zz$5|ad(_bu#^E14ljX4bY0>nm3M}tVf#xFCP2kL!=NnnKi_dj>(vtadD>uU1J}&&e zBOrS^Y`x3W!6V@80DYX)Vh6(ux<$JxBBdmVbXD^?G_G=$JPVL!avqz~H+IDV^QD|)@m1;@{`NZNNbe6hHaeCU}*g@Pd5 zzGE|t_Z4#ejQZoe2p5>;QA5v{+oR=v4i-+o&F|?Ojkeb*eDF3SWo&mARVoB=+8(;T z(iVN@nL@#Wbf>cE6?pUOTW~M+BaOc5m@~7gw?||7T$VAc+zhAsdUL7lJb&ru2;%l# z)HNZF@kp~^@;YyBxl9$`9MXpRzw*))=AS9*G=|E$eEwtk4;*);0(QRt%PsVC#HYj< zzJ8X`T}}r0@^%La_HUCsjH}0tbI}kMI+?s;-+SSep%7Xlrei)(yuGsk&XPCW;fIVf zc~>7kzmKN-na=Z6#Ij3A-T2pqtQ%$9XV&#>PU4obXKx3~xLrC)ZFL4=R)!FY*WPi? zscu5ww{alrbC=9mWzM=vImY2mlBhm@g)@}i!h=H``9p-5?`iOgAHGvqgBYtcWbK*-5i+gyZJTpJ5R9i`)Hxu~y>yL&k*crj-bK^ApHC)9x9o9y#j21G`F@~O6Xo7D*c&)p>)OuJS(zxaV ztzjLb73+Txcg1=+Y<`iiXBX2k zeS)!X{vmLDtHe3=DU=E}KI!!(#(A&|X4PmgdV7!m;Kj#Ij9oNR+C8np`BS+57GSc9I!OhR}W5!Fa9Z5Hu^V=bED!H}4DM zJ~3@vj&|Xwv4$>xy>D`ngIlEBXjL#?rYOBLNegoa8-x1$ue@r!42QVA0o(snNXB(N zJd+~;XZM%1?uHe5ZPtP-bFKK(@l|+rnFQ`zO(O6{fQMT13GSFg_1{P0DVqYgiqYKi z&_OsgW)kc_*g)OqF@9QXKbVoXiywYB3G>ED;C)|f0`h9;-ysLPcll9cbv?96QUK}f zan8F}R$-})1Wu2=L`*c*kz1KZf;$YTfSLYvK-g0K zhwph8h0B7aps}NioBvIOkuNl1r|C8NQ;+%icWHv(z|p+CqzN~#&W2m>r;~?w)KTBG zhFAp8pg!y!^lru$Fz6O?E)Oj6?N3+mI$2Ne=niL{r_-SQ%40s)GYaz@q#(~=Rqjmx zdDbcD)ly!Rv+VN)b?Dd{?X)GH^$bqTf#%!*QXeY7cNw+h$b3sW+&u_G&uxL!m)>0L zPc0O09SWO|@1`c_<8T9Gs<@bK;ZDV?V(LB}i1ksB&c0-XdMnxUGw%y8OshqMM};t; zr;QtEBw*dLzerI@FqK=`7k#GuA;&C!N!%2waTep=qwOS;QL2M~l7~Z2455GS#^R4t zS+MD80_Vbh?>n;$pyqB2^-O1+xAP)+Uo)9^e$k5mHB`Z{e0%1z(ZCeL-^9i1Bt87q z1a~lB>#58D=UrSK9*l_ww+A;#&KL`v@Btv=I4{{YB@AC%rNX*aLLwLoTF1`-*4~&y zr=E?$nj^6==*0nUexkbc+gAm$=4%9XW_syp&p)IjMUGx8D8-{`@$mY^ckVOmA^I?* zh-l9Dryi*mXmP*=UgY!@e|R}v<`librD^><@cG61`>t7lrI$VZ@GuFLAF>@c>tXT# zWQb9ATCiMFPO~2A;O10$XutH7_seFT#Rd}i+htCChH9cLr-W>qwVS@as3_}R(BEb5 zopHn>SA=8rtzg0Q$8@@i1dkj~gO8`LNGgXV;jy92yE1w{@e(tS-wjZBtr`rIUtFPU zHc7C2az3nJUcS*X9ZdGq1q%~ndbpK!*A55-$>L=kzs3s1!CDZ|QAiCQDP!01Qo_s5 z^TUQUVDi{lSkPca%G zfzM9{ll{!gedy!=%O zuHKUmm7ncM=wfwzG*+*d-*QVM0q3bELd7sSZq|Y}j5t>f3r=4oF7a%i`=zT_Z_%_4 zMyrw|kd(QeJ93%*rbZU@&gY4`zc6iwflIDKFsD7MS*r0;wKq5PNL35>E0}-}l<;h3YoEiWT&1QzFU(=RA(B{&1HY^u8FaWBGEWF$E6)Y2-xf z*?ZydcM@0?L=`{Zz+&^Qa8`FBKY^X+1quTp=QCpvc}HQ#41}kz3e~+=)EFo`4~mdXfeO2To2i7u0XFWDaYR{lE6c*jk8>>fq$3} zKVyhLOrwf_aGzOURdXJLwKbMcG<)OP4iO zcjm%SHz03O#ui)4WZER3hhswJg{l%W8!*|cXu~%N4q=WtK@(wa;emuQ6 zis>gFUx}OhN&Z8R5C`iFfob{SRB6#r-0{vG#_6Axh%ZOt&Bs!Z$tIJQ9V`PiTodRs zH@df-<+es#2I#IAuT3~7-6`5fW)5JC0t-F-e6NFqP3__@4y?lPtVp;m>tud=cAhUC z0`(KG(#;@LA&y4WK3Ma6hig?`uN!1eqp`b{Mmi=;FU#e(96Ntbw`+kE4hj|pYY^X4$m&zTeu=3OI$m`2)BTu6S6H=@ave^6ny zu}eVJSpr{0*z9HvKC@QSZ4J?=G2{)5%H6^FGG0?;m^Lgr@txjO*Ttll0$ACqNsle7 zX1>#Ohz+xed9Z!yiJ|KuCgY=Z$V#c!m-Oe#5eQ3vx*+QTdB5p=?#DAWjLdG^M5 zZXwg<*2lB6H|`Z($XGF=jhZmg6#2gH-!L}f6X<$clM%-17+O}-oBdQ<6@-F~+u-rY z3F5M@RB5YaC-LDGrOwTo82f^Gw2FT6Az>-FJ|zz#lGMo%B_Ym`X+rYAt8_ZG!b=ZK zA>PN8pZu{Ax1Y&{WS1Fa+dwT0NoXbMIt!@Z;23 z+F55=pBAFrV?&=YpLY1T?XY{~R?bPRg^LV^L*BYQ^uC7#^GOk?2Jhi=9;jmXc0KrS zQ6H&+r#fnC3E|h;H@w=CG$ertHe2$zjLqt3zOR#v)DNNDbxSlVQw57QMP8w}5@U;_ zAjfGE*<`AVADG7I{K|#eUyH%-le6J*-$X8Nh!BsjGJ=(Uadca;2;=T+gM6+#ze6b* zHBTgh&NMZmw_k`S+Wr!Qrc>0k*$D4ml?VTPf9Kl<)hPTN4ati`7}LZC9fZ?+z2(>X zhvE3lG}!3jLY|CJ#}zgPAd8trN1czySX&7sojS&iyse2*)pC%l(uXcfsK8|(5vcx!mhVAOWOqroeu6>i(vuLVp0B&&E?JyUXZ`a52rIs*c^gufCdjf`C z;z2k(nfq^|89v@>07(V)RQ;G1PK}TUr~Xg)#@97CoSmPOTlQZu&S7rrba2fh{Zii5(j<5&UA|87oxO%vgQ zRBKo&xDM^nz$&XPL;mIYA@cdx}Jv>rQ_G!1C%bcrI`AW42EMdJ= z5ovDZM~VjK9n*v%8{H_+vXD-!gK1ArgSgf7oODLaKH~XTQCfOf7jr#2N!rif{PVt5 zm??+`(X!uM`FIiP20Oyanyd7-MLZtx%!B`)W{AI*vYm3cF650gqLz9gC|P&~1}d)L z+8wR1eU}c@Y82C^I3>JhRZhl)oaeRt8B6nD40M4d@hLRIj5cS+P12+%*zPj!csjg3 z)yYk%HNst0rm)S-ED=Yipy}fz_?GKHZcoz0=~v~z`_W2j(-VZ94~{`-voaUqlrQZc z{;c;rj|tPmn7}dM@b@ln+$R#JSZ6|Au{k+N)o{RLeXzQJlrG)-8jlHCeo#S$C#+MkyE*9jO)~Yl0#u}v_|?9wLbK9Irc1= zGYV~#W<6BvJZt-NzCWZ&1*Yh@QONS| z=6rQ^CH9v{;ef3xc|J!S>sJ+#BIQYRS$Y@#A4zB77S;E4aX`9;?hp~_6v2SGXCoqD z2ew#)B6fXk1Y5+yK(Sj8k?y%?_D~ieij-m^sfewJ_@0;FKQPZT&)nJfoVC~bEV(nL ze!rHN1F+b zlh=no)5`dMNXglE5%No=pNyb0S= z9A=D1XCKB}oA#T}-zA*Fg>^;HpwAuyoQWkbBfj(^KuxtiT@%?p)$;%uhpg zEh#jIo0EQwt*Yjr1=FW*qEELZ;IzsU(45Tq>a1x+ErTcUV#Z-&`iR&k?ZG*OXrhq(tg(2Jk*@sWH3=x^Gtk~1W5W7?x&^SKW;CCSMK~+25F(DL5S2+9 z7`*NuIpwjB8t&1?pY#V=ylB5~rG5wAYtDxkFD?>=QucdoAkgo0f%wFfG>j^*fcwWr zF|Huv=KZyTNqWnUv>J0GUY`u#+`6UKgW(vL#(Re{o(lBIs}`zM1x`~0LHE0_^rPrH_| zF0NHXU@uUM*C)BnKLIZ}EaJ@A2bTDde%c-tuH+^q5>vKB=vs z{a^mZMYBx(EWO>y;1V|&pX+AqlhkIc*g5o*L0R~ zmK_AzcMehe&J0w3UJQ$ty%kD>7fSDp3-|MRcn4G%dy_k_2CmBqJ$@zu2NWCx!Mrf; zVU9kIe)*S(t`t(;h3e=%^c67`?%`*4YoH+34d%^Er-?=b@zgvHBKAj%eOIO;!y3T2 z#sFgfNfrNH)P$dV{Ase>S@fKI60$CL2(^l1BwuT`kQurPl0-YkO4|3E_*!=JHt*iz z$c343y5JXQ$M_z%RNcWb^At55l8ZG@Yk=QeE_|iT&Iw%xpssF4ui2f&vj0xPqBrxn z`3J4=tE>*p-P1t%NO?3#dQE%^4)Vq$7QUw16 zw+f&C>X6jBsP?hB)@f>EX{aS!oAs9G4`gGEQz5inlOcX#?DyKO1zYx~(y;TaQ+1Fg z>-M$aRkpsxpVbm*-|SB=P<6ah^qLI)H<~Kl_QDT?MG#Uqg6mo{2;*c&f?39UI`Xy| zE^>1M1?8Q*<;Hxp36_9W^gyy>1!F*UD1vi#ELD4Lwkh>1@&hZz}%O&l{T` ziNG<{nfw~6jn*R_;7HV9dg)&}hQ2I@IdcoRs>|va++Vv-hpBQh#(z`vpslck&$-cx z(F>o#u+P?n*H^)RDQzU*YzzJC$T-rC>mhBPk8q?_nIvZ1@4h*om!*mEhiu_$_BY;s zOED6b6A$T7C3kMAVU{}D2T-Lo3vzmcY$cGP*_8QgV$1DM=g&3UuV z8pD_FFix_87B9?4&1Vguo4SFUo4^>1>kMGS7oXEFPW-zomk1mN;L0w~(L5uh2Bi9w-=Y3+B@lb^XSgYfre*Xw;-b=eaGw(sz zE)b?^30Jj$zzx^LaBu%*vT}e4F8%etIbR=?ii5ff!yP){q?TKnus^p>8CFXSGG#jAiDScEbq5 zE_P5WB{iJV+e0qm75=+2>lC}fx}19Ylhdez*ABcODTi0laloE`XA$G2M{_ONn%I5V z7Vb49Qsa5WxR&Y3-!GjLzuuCEdC9D^&ukiL3}U<^RhFGMT1Jm=NWcRJVnH>iSC~3F zRpR*HslGYClKB(X$~Kbka~t@c052TjDFU~;>)cqjw>>1sa*zMh{Y{sP-qk0EUEZ4$xb#;iHLue{{mTJ$&0{jZ&Hf0;4KIinS>m)y|zlgb72{?V$qmF50SPx;d z#wcq;;9-Ckt$cYGw`{9`l^cI^%Qh5Zp+pKB#8{B}MS`&=1+ZzTJ$d2Gy4(E!64|43 z=zHep?0;<+ICm&<8#mNS4s1*&Db5NKCv)bJb{PsUuU_I8j7h~We=1=4NeePkq=(_F ztfBDiK^onh$2dO{$Ze730uOw`rqQi%+5RxWd<|UtO$H1nx>L)L1l*Os3&N|Gan=@w zc<1A1qHr*i3T3=7>G>j-VQ�+teX(9HH9hIbSl&6kmO3dh)?9ymn_cTBx#}i@q$G zROgK2PS^n^mD6MseH@&m1PQMU_*TXM9FtzeH0{x3%TYDFyYdy$-x)ynx_P0QkqErb zjNnugY|*RCAEHmRP{9&2H1l(U-0#tRyCe@yzEePrfrMjz=1T(w&}n&+4mqWd2_`H% zBlY#2Kw2<)K?#g$Izik9YGU=_cVw5JIi2a?g$uPr(6#9y=bEg8H$9!8z=N@il3gg3X(d)|)wZGKH$Lln}V5k<=8`Q!$icdi9!!OSJj}q(hXeCR7;%Lh> zwj160k-Sl$VqVJ&CwDCZ`7S3S&$_&q#=5}lHg9_VSTXAFr~~cxa;`$4fp1E*;n~W& z^lm=O{@d$7NVb$OUD=9!kT>HI-?IJPjM3%so%7_nIL8R302Vd&S9&fm5bh07KRXku8G^ zG4QkyYR?7Jk*CwJ{BIRp_Q>P@acm~*JHnnv52$sa1?ITgz?I@fy!*oaj!$>cBH{58h7 zka zd#d=H`SwF4(5+j{eLZT9;~I^@^7;pQ;G!CiX#Cgbfl*;>2hv*vGV82J#{eaq{Jx${ zN?b%#Y)e4h zLx*7fz<ZwBjd zxrWq@`8g-8Z0ySuy$;aC*GmS2HDpq~`@NWQ*}(5-K``Gamxj($i-A)JBF>vt@PI%7 z%d1&en%P-=x-lM%XMPm+IK@a@y|xpd5Cus95itM84`Sc^jZaT|hq1?U!23@(7ZRq4 zfrke}XTQ@_^G^;wj;V))mleX_`g$laF@f|^7F5D=^otJ0Ls|F&&TXVM#>VSIy!T7G zF-s2z-}*-`@#pzjNpG;BGYj%9`xB)F1~~qrFFfnfpr+|8&-L*!;|~4dJ|!b+#@+|+ zX<326dI_HIEa*G8FS@3Ry;{8_ed!!})+GU>_wRd<@Z(w*`Zm!*ptTE-HFTz-_-Qw{Bf2w%$khIeR(z#d3T$ zSxQjyb{Gwroq*p`c0>A+<($qMWi*v}LE<)ErFt5k2rlg0d$d`o{I^Y_t*F*_Zjakx zgrUFfq5AnJUXRPh*^D0>6(&n6RJE{ch6c-M+@^J`r=Wg{3QQ<8=)iSnDW4{3#ghkWV6mYM`Fm0wV{E>X zVAW`9!u*Xx4sL=MJAH+w%St4zRo#7AQSo#Ql+I%utrg$+lRlp@rbN+C@uMRtxUG)U zH?sbt@2BW8#?9*|tHC-ZT={afUpV7i6DUb$5)bCb8*=R%*+oKVVV5`PKo35KO+U$^P<#4-aY1`mY=%O?S}t}JyXTsYfMNThsCR8Pc2(4a zwbnYWtUw916Ai&AN?vlcT^Ab!rV!Wmls6_4+-WWbwWtbiM}Ji;{M$>p}qLB=i}1~I37mYbO2+AF;-i86;MoYq0=lPzCx`VC$Hy_g^^-o~L6H>9 zEv}K#69%Kf<3+H@>xKBvu{0dN?bLm)fG5+OBVdtkkob1YR zk}$nsGHIToWX5(~^s!cE%ztIN*|-S{_mzO>)!&?hE%W8BVjZJQpQ(=-j3uTbcxd7( z%v|FyUDGeZPtr1xu?Y3>%|fP=dpOdmiuqV6R|JD~OSy?M=J;l{N#AU@>!*hL6J&PyBXNV4((tUoSUX7s$~MuQ-2qKJ_0S%c>))oqhEA9p zNWf#Zs<`=HA?|7^fzm^>Nk=m4M-Eeg16j+cD$DYO-^3I1m`0; z3T}gTga&4ss==mYU;6SUT=dF=Ce{K;FL%pvhu)AL{F)2~QxIH?sv~e``ntedB|Je3Ey`9t4 z!nz&5$#0FH{QVPeuwXraU?q|(w{oL7_uyOZ~FH2fiF7f(M$-LjPs05S1u&;KoGV3E>+QYav ztS%xuQI^bS{&4@#n$Sp->F;%{&nrO%WOf+xo2;79B&-xa9BQfGfy4Yj@1MC%2c{4 zL=#s~bx639$4@9~!ZrTYutz$87(PpQn|sUNZIj)I@7k^{MysE&_U>p{zwczTfS{VnU&K@{P_?_2#HqXbRR zW;uf_?`BzV?QhJ(K80=$WgUq1Tfp;=78iWQ6#p|A-8b9KA`Ed^{19+G9mm^Luw2h8 z_8U#MBv!`yczC)wNDBARgX3*+YqAa8Tk^!mQo9?6&S{0C24~5wshVi*_=`+wv!iR$ z&S3WZtuWxnT5i=j9hNH}0gEG}=*jkMw3+uDEUeaZFIYB>b{IlWh`gkg&B-zUvFw9Z z75`~9kAjnhFnoA9#|*95sGJXbty=mT-L@vlh}^(k0KpQ-r$>g#Sl2+ zC)ZM;iN?pA^kNr8AJ!*$L2dP&-+rvz5jj z_Q1hQMKJkA6sP3O`WJROz|5()scNVrYDo!P4pJ4r&tf}hq;N@VD!DUM6@y=~owY&) zO^ixFrK3k6F-Ci8*)kLuz-5%<(KUbx%?gM3BsH0l~x?a4ghu?|qx zc!b`Vk%3nW?nANtd!b(LY^nLnC4O^UZ^ObA)(<;L6%u}opy3Y^@KE&;#?=YuhOcJ* zq@(3PejiWc{wd>Ho!6v(>n{HOEcX62_JYITv#3&vC8|bqu-qa_{Pt^TSjPr%XJ_kzBw z3MVOiCVBlJg{b=~NUBRLaF)p!P`i7VzapQ?y1iJocVd6?`;b2V9%=^zW*w&YwA`@c z(J&B|Y!bTeq+y#JL`oW zILA!{wUYP3n#HXWqd97@l%2swIT_*~RR^5Y9NQhpKH#dgv~g&+Gi*4tf@aI+;>F(;pjfz_`xVRdjmdhT+xv+o z25X{8i#pu3(xhol%{cG%GgvyRn_Cm5ipr6nN%G87bTiWg{(1i-+s77*V@o`6-(3-? z>N=6x7P`1~wHx@18cLf2(h!%FLHnBm?oU6)>UqrA_2bg0zMLldTvUg|X?gsNt4;WN zZ8h909YA)ndv4EzpTw_uC(XQc2B(eM3W_&`!uJlvk|;?Jv65AgsMr|c&SG!Sy&_K! z_CuB{X<*q*Righy2?f&__q8I9*2`;P#|3rPgX7HiYxstD&ECVL2{TCNTy^|!Gs{FU zeda@x6)v5w0IWMp`1p(|)^81j*hww)qKzTS9QA_uuW`JEY%2Z@ErWx@EQxGC)&=Qc z3WL}0qMvi@ag?t;=(*JRTpRKWHK7%3S0|7|?-_5z{&(M;Pr7&ptp(d5EOs5YK1Cbl zGDpA_5=A}m7oHw&;P)r}2Isb25p`!6^=a>>?%EhR#soZfR`D`EJVvLB;b2ZVH)NCn zPG!6xWL-kjc?IlW*G}3JUyA1n-=i|iEMF=LBuoF(#)@Sl;KA8Zbj$B_wgakz8J+f8S;GhNP92LAsH zzw%T&R(TO?R<3q9bYAw`1&p6%#L+Oy8nOMg1GPew(xjDnfNH*OJ zCNS6^~mAz;#v~2U@?6Xy#XxEZXUsB^y~TpWFr-ciUv^9K*$^9?p1X3Ua?sf7FW@JX<7 zxf-S^slh{kAL?9|fELw9Vdli8++S}!jI?5B*H|%qbwUv}(i%zo{%BrWpoy1SydijG z4&9R1A2(U~^<|V62~yC-k>%)R0!cr{V$BWIho;HFv}!;hK1(QoWvjHg!%6!kCPh2? zw09c?*4_E8hm`#Hi_dU>h0$y;?`ZXlJDaYF&z^h3riBUAYG!{lz5@_&%uASbWvujK z`4T_B%Te%pj4rC~H-m0ROIlHsjaghayf)p-?OSb#OEWdVcEDpAc|#N1w|0}&8K-$^ z$tzqpJ{Nok_9rUujnMZW>nI$jL#NcH;>**|;JW%h?&Kyh-ky0Mnr@U7JTVfZ&Cx=r z9AHP*FuqOgad|LXyNC{+$+%&=_QA|MD%?wPwdBmuyM1iN+doY3dg5qs@lECxl2XxT z;WJ1+VMWRr->LDs9c&qOmd;?Q&KeVzGFc!*_+N0ss5Jz_DbeXN4*Oo#8e;XkiD(>hTZ8R9)MeG7nY0+sne32l6&VlcR3tu%$0(8~;{4J{`J;)^!v(PE?QJ?J#1f54^kHeDH9yy*6GNHr!u-J`a@I~6ji$aK z<9+?9LaZBZxhMjkOT)M)#tnZ|>EuIz#^l|d@AEfk%RNUL>hCc>}f#jkisl2RVgkKYQ|5ocz5Bf`|(dGtSSxTfa&C=bd!wES4?O zh=iaqoY42FRPwQ=r%$U19vnRX*Ra)4CZpY@R_zrm3O^d?z0Rr%=6f1F+$(BFs%l5Pn!~iO?|~;*2}# z$aVvqe9{~2W*+Cu<#_za^64{9I1vqjGG-@e!{+7Ez;3-LnxXs?`-6escJ2oEHd6sL z_ZdO3y1e8+rtfXFF@bFtAM;ix3ekY&+Ul=9;yec#VEI-JSl=(1x?Qox=XbQA`?4}` zR^5czkHt{g9Z0lObnxtKA$+k9q=mIP7~8XW~yGLRxS%mm)VtBL930`CzLkk?84R z>wY!3I7pS+WV~fP)c4@q%x-SsT`lZU?jkkKY;RKKic&`rv`U^B~M zFV({VR_fu_ z*J!&fAG&Wa-U2c;0h~XJXb$r) zHAL=*YyDNZ&BLlCC90`?IVL$b6MSwQ2n~ah`3mK~xT?k2@4uztWa#YU8ATU1Y6F zDvb$u#cA1Wf?sVCrZ>Hp4B7I(Id5O1hjPap;7aL7UMDpj_Zdl`r%;A$_^ZKssRZB` ze4DO0WQnVk4B_;Of&AmB-&l995mv95LwI)2GTYWfrr8EiqyDZa$Ic$@KZkN-UfQ7Q zyIXx}fv3(eT6k1pjtfIxc%n!Lp-2F_2-|v|s_~jE|$sA{mb&I1XH|micB! zf5IOX)gWj&M^ZxsSlZo59y(jm1RGZjWzYGJoO|5h&#JiUgFQsME~f5sxp-IMDJ<}d z;smEyr;@K>UtdORofb;GbYQWb4#i*ZF!ysUOtk3c4*9BLDE&@!rpHsg>jqc^e~8}T z67lA1u4v^S23lT@WJRwwZaL=x7OKN&vxOLqe$;_S@&oR0gF5z}FoYG~(&_Bktk<~U ze{-JS{tc%lw?ImgD>=sc6yCq@CZ}|F(da2>@MYBw(5m8uKZH`r!S=soeY3p8&W82Z z=nCQQVr4ocl(EZ-9zuPX40)lggg1_8gNEU8y5xd7M!T~d8Rx>kbpM7Ea#~=t?Mxz2 zQb&HyZ=&=kgid4o&@UlTP_#vd`+Jr3rp=oG@Be(H#tZc^TizRTHplTdtnzWpvu6-r zU{5Y>P{B_F^kCuK%`{8F41X4zL&xY+pDL9vxaszLxDp>vPBQ=MbGhGS`&L^TP|LhD zd!oQ)!Uk@}2My%*41*o^+h~Ky4;(LLbAIX#u5OwF8o3(75-)j)^;G8li!lYKr&WC9 ztwJ1M!o!8N<=jVY1I%8m3F7U^bk-Cl$`(UEI(k`x?tUtMWFtsUOb=WJ3KXPK$ss&V|267W?&K24%o>h{|b`a z7%{d_pD7tn^DvvYQ3%;`QjR-njOznU`{wzg27Q$C(1gve)A>=V zt*Csi0tP-CL;?yFG1&YKSu|rMee}!)+hRoE{a^<-lidw_&0Jv5nmaV(j4PTJ2EpFN z0|y7qZ_co8%Q0$RQh=^GwQ%pz7vaM2>C&5QPJYiygp1Yc z7!s}t=c75gpg94%|HMJN$}-Nq)EfPsYQsVC6Z&wD0;aPpt;jT*FBr!duv11r#O*xl z{&gT48U_OcF^X5#+{M?j4`6uW7-G_^g`QvruSJvT-`R|Py{Z6u#%OUxDf=W+8rA2G zeE&=p$NBywH)THarIX%bpbq2YX#M5P-!iU3>2Of*JxgtTEb*ejNVrkwC3L$VEDik` z?ssHc6zDK!kwtocP?|A-CbG=hjC0wLxn>V1aMs0)n`*2R=OK+;X^e&EmBH8VI={5C z8MB{Az{z?L+1uX`haDOP>pyDKW1?SZVsGTP?uI8Bqbf$fyoazdrL;hrBF0@66kgTZ zlaPM`JaSbTYE!~#$uZ`WynFy==c{th&OVjc-22~b-ASGY}xR1Kc}wnBFnU!n^iGuyDRCHw?5<=9vmaj2T9kd2qUCqr6)W&)I z7oriDO4o>8P&{VPNBAa(aOhx(pJ2pWA8bVP}Lzqe1TGaenF0bR3~2>6_=HFKOT?F99^`#L?`fHdyxE3@&~T z@pT^f2{SvZ!J+aTX=DuHT^$`{Rl5aszv_b0KoM-7bB{aCc;=QO2iS9SF*R#teRB%+ z;9Rkbdy=b$7ROm;gn1)p7qDE|LVYN<(5Dt@k8s)uDU2<8&7BQUWf{pIM1My-ZSSv# zi93E0Id!R6!Pph=y%j;vGY6uvTL%|K4+g6j!{}G5OjQ0{0p0G%-3nu@+66|ymu1ig z3L2=9pb7bZ^LSU&`#7PR2i8+Z=2dE<@1$NbOuCy6zs&elGoqk-JQ3QjLP=m+FM04) zUUFrZF?KHZg*~xK)Y>Qw1x=4&Q;rPTIYtTfs&!yn({Wl_!}wiG1@O(?kmwpS0CeR4Y8cI6Cuj*NyYA9Og2NDEwdcOv}P&`D!72I99B!Qgc0GVjxx zj~j$_aHYQ^snt@&H_!B8!)1N)!#<9ChqLC61wX1Z)0xML?(t>*I}F#Ou;)r3`SYFa zdR_`4=`zcn%l2Tw7E?b-ks>*Gmfh)?&g?M$HT}YT5jV5?!|+ivc}tRu+b$HqFhd2h z?1w6jzAq0UtSje_R{|OY#=sw4J>ez4kLZ1|4C>XclLlvJtXB}hw(a#|pQIkV_}0|# z{qAF=lI^k&)!KlG#XQxI6kSrN?EuoJO_HmUq%SwDBiaG84zPZkL(O(1$i>`25 zFW9b7&9#p?pl_Xzb7s{-)~(M%lfNNS#S!6te}*T*Fd@q$RA|Dqg&ZyYk$`c!Ctz^L zGHywm1qMWF!g$MaiYMgpw-IBQ=ST4{)e@K7p9G-`D(T7<9(c!L4rrb~CQe9WJ)tWe z!OSh=h{|Gik9cSfzsjc2`7am;+m~tD%e1&1Blbzkher3!`Q=Qj8ORv&iub$uHF>S* zTTuiVk#b}{>(lwm`+&{R^Hf#w7se_W`;F`;;2JCR(eA_m*p*{V{lfC_&%Hv}zV!gt z|F)A<C?ffHO=+sXG>m!Ri|8t^j{kj7+nG-?*W;D%s zCm#mgI#nc-F^fsx`7y4=V zYib3YA0bQrG41__xe4SKCeR2CmPx;=)yG}88C8OvPsAWP<3?^?QbXRMhs0z}qh3rW zKjF9&qG#xG!54Hf;ND1B7x{{cS#F}B!W%vX#PO%>a&Tk#GYFY)N3wS?rh&f!+sSUF zugy&Gu95{TASFKD>Yte}y#==Zi6>5z1?ap?79?UP`sv3RY}>FC+P?nBb)959u6rXO z`R#V9ec&60e>LpW;peZE$KB&hVAp(k$?!OBj4)(*3g2hE1Ib6j9v&J;J>vcj(81Si zr{HLmNK4jPppw1->SGo7IYZxK>|F{kRtJ)=##-oP!NH!nqp4HTAgmte2kpz>&=U!I z_-e@j2!An)U(B?)b#jG})h17Fd8lJ&iz2ic#!zr|!kt@9VMfDsU-jq~EVM6%4ZAOs zH-7ebZrgm=c<7mUxHIz$tvB^6&pJw``DtS9`&q!(eIKdqX??u>MF0zmGWfuN zkBqxg1Jy~6qjblue$;Kz)Ylj?{ADAqOjyv1Olj*9_M`7n*a(w?6 zo=kJXH%CQ~dGHGNSymITZFPfH(l{!sk%vv^YGKu|&%$^&bu5<%Ah(yJ32J9?iTg>2 zdbXVVdfghGOLZZx`6+$ARUR+xeoZv{Me`lIEpVytWJn)fNgrP_!B-9hQa5iGiz3so zsGZEvkJUvm<+m(3702#S5kl~Dzd#E|dgFdv1Y7*33fE21$98vXz)EX6FFB8SsCaO6 ziQ(R_utgO!E4b|3MmN@(;`)4bNNc;rU!B#CUyheTe2P7Jyx9OZ#f^qvS9NGXq&GIG ziol8OVHemt<8h%c?4R#la5O0oQx`Js%1T=j_KWc`ZYaU$iDA?xApzyi9)wSq)VQrT zpGbNm)BAR*a_RcGWT2l4}AnMRs{kD(a$`pa@L zUJ~>-E`fWeBgkLIHz=rOjCXc!FQ`qxi%$;1j!kPh1GZB*a{f0tt({35ZaHEdFM?4o z-U`J|?>2M>l1gBAMz1 z3qJ1QH+8XRZ;BN5hg*@<6Y4nrg%%Ws#nFhE1k7D^5)NhE_tj06m97u%0FS-5$?h49 zF_PCsp3Uq}^G-YBho|g)w6KgzVj0rwo^BAAvYftj&%?PN>)=G0tix~fT(=a%+S4j7~PQ^B;gddHRTg6z-CF4!u^64ykb_m5Qo)%!G$84cBftCr;`Rdt5LfF=hAmV@y_7#>)20ym zDUW4WU3S6Dx4PVF8*_~8ngqWTKhdNlJ6vQj1luq6XcyQk8OQw3;nq~ z)j?=m;|C`~-_SV=^e|$aHDra(<{P)?;Hu4xO%$m>%DYt1AV~onr|zd0(;P5ms3{nB zUGp_m`+=)|R6&PhGP#=QfCK+6f~v`N;<|la_;Qm7&gxflilbQ;vdRe@%$LwpwurM& zRKxY~SWYQ%wB(TE_`V&h<{xd`zg`1IE2vWLSsOZDW$b0K9Es9a#?s-fBr^U8eInzC z7uJcO&dN#X-{OVi*=)bbeDk3v*xmW519VzA(^9o8tR!Wi-B`jkzBESncNS2e^pW0X zvwhunEto$qlXqJ90b9S-z>cGi#FjC`^Y(urOJ;7Q4~32xUMhkJrASURLKEwhJix2r zF7_0@LKiw! zI%{Br-^v4tV9xpw7cdrw&wC*qrEwOe!c$OuZ3V|Qnc_n!%bVG_W z-!#z#zuN)~)s7Tz(qeg7izl$|( zN>%*2zK5jwe&wGq@AQUS#Zc2DOLz?}EMH5&{lAO!y{Q*UJ}-iZ+9|?oyA81LrVXS> zY^Zl`9xf=QFfN-wW_bgB%Dqoa2dJCmwfr2qT)D$k<={=rAh~ z{yo*9OE-Ao!v)N1v2rih6*3fWzY2yu-$xdlOU*^+Y?dt@WJ~5UmV#TjGQ21XqkC>K zJ^5-Zcv`A+5ud6gL4z{-{E$-SXEO*2hJGH&{EJ;)_=Y_vHxDIo_CvMs-f(;Pbv~Aw zxl{bIyaaB!MUYQj0z9)t4W4WoM#c4vvH3U_#*ua0^J|8v7%mHeU3s)v#}VTXvJC0^ zx56v&ZzXk=8h!iIPwzDG@NJft6t(c@GmEieTOGvj7m#->FZo5N4c~KbQ~S>XtYV-4 zUe17D)6t1jMlxM!d0xy5srMU#ZwpEQRcgR%F&Ib#&dR4Z1JlXtmB+wDCU$1J6D1jU6Z>mD6m4xz`d| zjzbF@{(UER60K>frz5uIiooB#jEiMj;!T~waA@vos(CUW7j!ki?b2Ob`5P5HP7NWd zvWxx+)?u6zL%0C?RC8t#N`l4kGO3PpZ(zFd%wBRKIe}gnsDts#f0GCs6qhb`#3z45 zFy)9nQ7^7*(x)QiyvT@B>30*X<^ zopmq9Xp%vN0(_7u2d;1T(!$O&_;>a$Fk0*+1H-HdrM@sYA7!9?F=lNGx@8YoSl`x-qH4hpnV3}> zZK@Z6?5SVE?D_o|Z``!+Og?v@7QRil1jE8=-fC+uCbRurkn|x(XKSP90}a?cK9TM} zYk?2kwV`sSB7e2Kh4t~3!S0jei4S`x_WlJZ3JIc;IYThy2s;mK@#j8_b;W4*%zSC= zr2F5Rp=FgbgggxA^Y>-r;X*Ma5Cu}<$g-Sl4z7Sxx* zs})zs%OmzU+gJpZZ)?R@yocbC`RsnT>M3_kUkCriIl*4*#q?oiCT^T^4{SSjak;+( zB+}~t&G4d~+BmZ7e>2>jo#ig?uYrse{fLIW8V)o4M6yO5r?c+c&;TC9V;R=a93=Mik+xF_C({pX;_bQX0 z8rF)Id^N0au_ygn)zQQB3pwhsjWO;VaNHXa#O&VA?O}exF^dN?FKa4o-(Yt#7*17n4Z#@kD{#hty9js3;Mflk)NCd~F zj63@Je>0qCJwE&A#DnhXl^pMAj2YhQka4t(b{{oFftMVNSbu`g*=2^tv6I1eUj=O$ zWP%y~e&GK+QrtBs6ZdOBgML9%N%UMTbpK)rpAx51gX4L4w^;&Vdvv&A+IuC}OLz8p zAV)f=Fpte2@<#tN@2S&<>qp#!q?&#t-%AVs{R6l@^AhcR<%vpP7QvmsDZ&qj^l;{> zfso@ikVf^-!{e(Y@R*O`b_UuY9cBefvRi0$k`aoK^-V zS1%KzcbCDl1UYX0|B-awaW($$ACH#y-g_^lg^bR9UzMy-5kAR?viII95+Yft><~qw zQmM}UK37AMnF<-1Wh6qw{$1bm`_ErJPC57czTU6v^?JTYFLEZYdr0#vepR6+{%}+y z4#p5xPkW8v+k4=I)=DnX)(9(;Wns~{GG?COgr+vpFw^Lj$ieBQWIt(o|6{Y8l&Pb6 zH1(rhcqgnX%fnOc*Wt@xS^mXzRm?r84ZWscWJ}MhV@Hh&d8_mUKi4kQpY;mXzK`IS z)Y3b}yN4h6A(WleaKf&XC>VWp0H?ph3}0;@4we}n-cB4#rQ*;~L`J2rzOjpP7pzvjAT~xX`1VUe~XQL8`G28VR?kB`?-F8ZNL}Cc%O*+^`8x2g@uLo8g+H5Mx zeJgazK%=LD+u*H?1E&4ueR9*-c)H`X4E`Zy%k;c*qIYpL#4dN@pVRy{J!deemx`Eb z$rU_p_W)i`D(7U+6T73{47ScIVpAiuFygBL1oo~F6h~L!bGi%ET~z0P#i`>84_WZo zxSjoXH4RVP+6GF*aP$1_zvT2F){Lgy~lWOqfs#(aZYsmCIEyWseNFuA0n#R;8h=N<8S^(&fTJ zOz~XZc!>P|nW?&);FMnhFm%Ha!L2A41-1KN8EeBQL>S!lob>7`E=UkZN3nud^9c|G3FrRj|cpG#3piU~DV(zZkaffv>;g1oIcK zvC5$e4Dv?vGf8hz3h)Pa>rrfWZ*NqfyyT1*{@nE6Zn(K$FoZ7p%%Y-fv1R^1`1Eq6 zu;$=Z+^Q|WU1fQm*bKO7lLib5+s8WBJEOi6?SIS9`UVIs_%)*%cF)V;#}RMGk-n2{ zH4nwPZr)-T>hZL2f>q5knCH!Fm_6z)ywcghB^m@uMok$f)m|pGX` zbx{4R#F|dh-9MoL7KilaVXF$hA!hjh{Oya*I^w*9Cm3bQy*6=W)G2@bkvBA7xWeYgTH#H~$hRC+5ZnH`gwuyq zz}%Igd=}j?LnfGjFff*Jna9ZYl@1#d6}aqi*%G&2$E3RY{YZ7}n%>2?$Gj6BmpkGJ z^8Jcup5p${e%2|<8=l`d$ZV$+;T_v15Vd!Rt{RRn|GIsFU;XAR$d6M(lMeEPPZlx1 zo5wKkZ#rbJSixDV>*DQ=eV|V~vT5Oca6rdL{>=Ay;rn(gy#F#BeC!+9KYx4FQW+0- zRCkGgH&LH#+5^b;3gt`FbdX&l?q6Uy>zfxZc`<&gG?#jUGML)?e(}3fz6j=tZ?S*c zb&ws}o8PuU6Xk0BVd30Utk-rgv}&FO))}Fqs^#QgI%x+=g|=)gwxUt$SLiqX5|_H% z79Z`ff^8F8nM=6}-e{Bo+jpr#@5)x36Mq8&MmzC^Z>T@S78qB-e_DD1*co$ zxw2!0=;6rV&2oEQ`IR#IEbIekJfhga2kCgXBngV`)wp}{_aqVX3Z(kEFwPOj>d?Eu z1%;oPUgVpK0;};^oYzFs#*1CR?fD)y>SjLnO1lB8T6%M1GRPaym%;1Nk^HYWY8V@- z0{hf_*!Z4wy!ULOS zOau>c#j@=4MCxfeTLs@qr}`R1zgL0|%y@s1{Z~%<#!D5rpr$A2CUv3igg0Q)J(aI~ zsDkAN-}qqh7}oO90o%w|b8O-Ou9fcoPuGor`hjnlc7JE=6E_+H+z$#TCR|3_t5tA3 z-%w7^gRB?tfX5B&ARsovH~juzwAE~bdXsFvUte`>9NaBE!`J_Iz%R7N z%=u8oZGA-giKr#ymz6Joh1BPs9j+X#jSePtJ^AI-jxE_8QjvU*zq z)36lAKCb76CmZ6-nQHLOGn<(%)x`{xUJz1UB`%uli0>1lVPBOaANNxa&#&R2MBks? z9dHFbmFi){;c_nLof^guvY_*`m@S&GjjJt;DH~WNEILtvO+ygo&DG!s#~ESxICVHb zVISj^w9stUZ+>cSv2VzeGRft)GVs5=QrUX)S7ZU)%k9I?Y`KCva_V7ImMnjda?`8+ zSwPvj<7{<|Ee@UI3SEA|g4#!g zE_K8|CV$c0m#jk57;kk4&~bA_aB97TQ}*45{p0RJV{HQWVEZtM?!aKF z-on4sz`#&-xHwOV2^(7Qdv^o07|?kVs*DaQ9nx8SbD{$(7DNHax`+aPd18EB6m*{q z|5fb~gV)OAv zFr4MYU+|$0%|_xOtHdzH8V6M96AcBC8@YV$fI72d2hla4AMBo-5f@lHR86dJ9>!as>_rsEj9A%bJ2+_&JHPmbZ~)RX|F6eL)@F>J=*Zd z0a%VvF*=(Rg7wxU?#T%q>{L;L?1RXb${FFz@$wLVBSly>z!+^~L!olvZDwL9V>rslgRDbD&3QA{-Q;@ z5=H2wUeTBlFY(H#N=WjS;rp!D#18|8L8MCttLf{Bi8p6K+OH6i?`%C>^vnSw=G(Ku zE~O|FR0Ta__HZUYY;c~ZHQ29eWqUvBVhg7XMypN>w|rV~RO$`z&vE2U4(a2b-D5z0 zvmSFT_C&TZ3MyvDbBVuPaI`PoE8Bfa3pxvMwM2l}L_0nxLK#m!?E{<5qoka9)2hAj z=ZqRRG2ouWe9cvUL6E$}_qjHvt{(x5BeH}Q2R%_|TolYBUPtgR4Lr52FF2Y~$K}v` zbdRcm(B87##obpiZ8`&)8#DMBb4de#tqcbx1K51sBUstJ7bbsN#eJPXJ-O3mz}vr& zJzMC2KIEG^RPsV}Gr~Cw2SQy3agZ#_@sfEHM2*nkJt$xQi87Mc zujjDO!IT@it_n@}^@RSbI#K-mHB22mmA^#Xxw4&Id}Bl~s~h8h56KTO_fvoF>v9u3 zS{4Xf)Lt?77nG^#1V}X9BRGD~#iaZynjftBwSAQ^Csh+>?oMW3m$_gviUylC zxs?l{9{IdVW4J%@8=JG8GOhC3ko-iQa(M#IURnlTOBy)UCHi=rJWlI6&#|@^>J?h3 z1&4M&7q>P$AmR zX^0hc4zE9>%#M?8e|T8~+?B}kI%(>-CEN-i_5_RFZH#K_wh%WnKqxj8@L{+ZF6p}R zm9+OylvM!#uIc2ZPs11gw!_V8JuZmuo^1g^aB5%+Yix7JS9A`~ew-(qcz6ll{H}v; zbzA<&T^;>^ zB>NtI>RSFQ$wsXIMa)_->;17{l4)Zf0Jj4 zn0V36v>PpO7ENvNz;XYgAjOyHCm#(_afc7MKJj5bkrI4#=`oy%Yv5Wo5>uKtkm@kS zl>J%xQWHk@lpD>o#yD#2L`oO)RxZ z`E31nGn73lf}JID;;%uu7&GNMJl!&Z|3{goXQVyWTw2HaG#26X@ZGknUnB>|=%{PJIMWRT?Hzysw1D zqqQN!m1mEB7ouihA#Alx;to0MqUJVbINVmw77Q{%#}x|jdih~tYJUszT7*NEVFRiCP3NnUE+@xy~;E1oA`ZwoyLo{Y2oK{w(#HU$;@kR0ltr6z{_cJuhO?k7VB@5 zW|Y?K*2VqJ$`E#+I_3X0ATcUxV3=|;j+c5#nTX1z-4Oo~v@rMj` zamks{u&YFe4GQzXvEg*5>)gg|rd;QnM@v;O`7e^8#7mv)UUpaVNuf}xr4O>w#^GN^KtM>A&^F5hhmiN%=*oG{n(k|l4)g^N zwukw(NHB6(6a3k&#+@P0ZOZ@&tXGKSpOeSfW26d<%NW2cX*d13BN;L-tmfXW&_=a5 z8R}BJ%A88=Z~^JYSw1gBC)%G$Op-OEnbRrbEHKs@VBAJo_OLq_cPQL|-6g&G+P;c- z&Q=q0>d&zY<5kgjzAC64&=uZ{|3?3hZ{YZ*2wsc&5&U&~_$#A=*^IMx*z`3DxU~M< zuPAHG?i&gdx<0WzKW%XDvp`7d*()5*$|c>q8r-JY@TQcN^Y7MzS;qTVy{iLWoa8_( zh^fBSaewfDQ#&M0%I5WJ)bN?wPrf41hH0F(!@=^=V5V5bB`ns)`Gd1kOr z9=DwN$d6Oc7ymP~$M@oBkk@eJBXYH|<)<&K*iQJ#{6b>IJR|?oO>S(w5$?a@202zW z%r{L7UoS8LrTFtP4dLb|*$XEetT=`7_sxQxA?X79JN@fRSjMnE4c5C3Jg~K7%{RR7$*AG9vB8_ogo-lJ+ zF4_-jfa@W4{0%MYnJRGvh}p#s_%h5PUzxkZdf&iT6_~WK5}q1wQ`9rG7aq_ulj<;Uwrk<}dON7> z+azozM)cj{3MprxT2%v=kxnxA^Lb_(V}S=9^O=@ z@1lx-!kvNJJ%eRi6ydOo_n@vQfjcoXK(hN&2tQa=K~lR_10Q_XknTy%!rowfXCv5N z>%~7NcA~?tZ@lp802}XUhkDgfaLvnERG90I70%JL#~j9ME!M+ZNBYBoIsI9elYsJh zk0A5)11@lfAu6faK<0|(Mi&itnegQ71A5%lvV^z(N{Ir4TipTGR{i|=g}%NB;( z;p|?~FjQv)cPT?1cgYNbmcRnm)nkD#7x+nYN#hDH;d=dQIB;?T??t(ZR_dY}vvMsP zr&)*vCkml|FEh@!@w}wy>v1V7%y5e`YE^ybU3}jNuRQIrknS=X{wKMDZN$rc>;uMw z4zs_77I@Xf4?^dLi7MnMr+JsW2iF7Hs25jp=aNErQ?-Ztv_=>2RH;CCR|WgHR~E~* zzT+*I#tEf5^x48Ap!sV9)4F4aSJfs#Mna;v_^<}fK4}9_o=;?N==q(0RsyeQYjTg( zw@IF?-X@*TS19Wt8%LR%%W|yGxMsXGf$sZsp2wWj#ETP0z>3z>EdFml>>y93%g7K> z`~%ARmC!zVfFo0~zDmC@!rh9U98?;ky~qR(|9--nDs*tTsS3>IPYVmyv|!7*TBvwK zdonqd_m`{S84Mc>TalJpg-A;pPNk{b=vjc z-nN*He3y>L8}>n;qw1V#(H+UB>_REa_nns(KCvDNqtvs6YWhB_lCJ1C;yjoBSslZQ zT%|cvnVpo={6L!Rm+Ab?NL8G2PZbvb9mpox9zjR-{UCdK4fomD4!^wB0^iu%?7=Bp zl-NeYwR_E?&|c3Z4gZLBPhA@u6!p-ut3M1@?G~K71zdHc2}+l!^L=PHdQ6$-hf%p~ zHtjK+zp4?pSx?w|`x{=`*8&4Gr}8FQD#&+s^O9-f*z^cn%qDGTgJyp&aTfWIXNAJR zQc3m4P`tU3J{dav@}!x9xSjB<{V!;;xN6`Hpr9iby}ns1!PZ=9Xd z4xeSS`PU*9{4kb0`&uUv7sT&Ow4^?taqcpM0c_{3-u$Flfhf{Ytd95dRG8?9g z0S~E@{f9BL94KJ;Z3Yp}54mHX^|9)qI&>&!vuj(l@FGvM@wp1|+%8*O`y?8YiXHfP z>Vc|QH~=wK3EM)Y&5fPZ_}@xuy;4`8hfEX|9(7?@7?%AM4YypdZlQ4bTMg5mni zT`aT64KLArt8=+i6!usKKNOmQ{UJHYed6kj4se9{f~SJ(u6(QsK(PN;!yTpj)ZCLA zP#AZf$$T*bn`6ZEBX-u6DGg$uhi=$DpYr&}?{Tf9`|TLq7ev!$vUl~xm}5ej ziyb?;QJeiGUduwI`J*Xr)Sr7=3;gU=*f8r`Shk(ION!ocm)|Mjo)w+EzsEtgzu5-8 zb7(i3?<9J(upiEGBW)yX82_4P&aLL2U@^~wrOHxAd^2$ZkJoYz_WHQsl$DeZlgLw+ z=K^Vf$1VykYdf)`@Ez2j?9cBZZNID6AKsvEEUV~eiza5#5Rtr|OU_lt`*R1wGN-G| ze!)*%;AiCbYGA#1X22!v^Sc@hKTqHjzNw(gIeoB-T*HD^Uc=tBb7|aU$qg|+FOi*g zLaLu1G*>~xBi(%0kGI0YKQ{QZF$#V?J;C)`sg9hWq)v7kcnUTmQ=oazb2l1X9sHD|FMqmd1!k^0u7%uxPa8HlB~A> zKf~SWT^ydK0%{4eY+}Q6d`9`N+Ma*hx(k}9`f?=bNY1dLN;kyNCUc z!u%8`rfeieNm4CHB9ghM;nrC9*9NX1YGpfy8Q_3<8n7YfoRIqa3$9y98kd(Rzi$V1 zybc=&jp=$U?wT8#(R(4>a~o%0<$*T6f?)hIC~Y7gV2GLoI+gACM-9}mHBt+V&MaXL zsz)&W&wjxE8l0W~9ZB(?BB^)LkR$zh(G>XAT_jkyxZ%9bQPhQZj$7ZPj)R}LL3wQw z`=}?uvc*p!R9Br-uFk`f?JeBO%)0EESb13^}r0Gq)e&2ni}wmCt|jPmt^sUS-FW<`hzhf{LH%Pgo9$_ei>{l&zTjYA z6I~7bnfaH0y2y^XJ+VO@@>BIStmNFzQ7(AuU{J7J%{IR6!W3fzzx$PW+?r}7%rG^F z>A_u0QAHnpwpqcAwWe%GL>X523vdV;xEdFAOt_%{zk*J()Jf)8{Z18T7&M6G=^gYe zJR1CmIq*g*+9=eD;9CjLM8xQ>Pql-#PBFWgX@F}v8_+v_M_8p%hVMJY;66` z1J0vb3v1egVAhbgOhv(zc9&zMY+enuJUqVT3G5i?#OL;CV`dZeR36;L`bpey@e*IS zJGNzL*M}A{bP6?4{aQ_s zq}vy2z|VfYh1Un$@T*)sypT-f-%r=Z^;Kiw(}YmQ*1KZ=kx|gB16@*(UD0^wOJ zdoZRiF-C@iYipdablMf{9Vmg((QvCj)zYk0K-N@(FGZ|@*kf~ z{M>{d{`7KdY?&GbqUL(>+Q+W=q$&zpXWrv>Z=w!FOHUZPavlpBUW_7Qi#cE1$z`Sa zNj`iFm1^eqD`<}}QV*Q%)Y(q^TNu_-4jbd%bE>||G;?=NwfFZa3_(M z8oeWE2dZ;9fDa^p`+4$Tl{9&{*mMv0kg5ESwe;Cc^r7hTDkk1ug3hI4xcA43n~-r%QlfNHs;g-I(7-r_ zUSK7(3!m>>J5zsOYfsnHyd-}5IeeWGa1MrBN~&mM}RVd{5h zSQ_8rM0}nK2l(9`&Sq!kqcSUp(S5YI;Z|EEsx#xIv-hnqUDQ6N22G#k*d*$#T;^R3 ztF&bJgnOFU=iq2?zjl`GUgL`Y=#0&A2^M*he|7W*7wF&az-(t;$Lnejp+`QIiz>24 zgROQjz3m;#`=O2EU{$F$erWwCtgWkuc@FM;Mx_QWHW?-Dq}Dm^iusfyaP8X4jh^Fz z+6IAO8Ze~P6Z7!Eb%c|@?f4-tsV_223--NP%=&#x$7`Ps!2VPX?$o5)lArR$(jDmT zvy@HvJQB{lJTKfXbVc9PC^)eC9QUz}-jAN{FlEDD)}Q#}zdaXS(0n2p zeqU3{TK}4(i!*F};KAV@LGmh>_=>kc%*pYWs53&-&Ip22E;9|J?k5v7FyC$~1U6LR z+7dA=Q}54jR8Yl(7QgvZ143Aqx;5&`L__KbZ!XQ>0wd0b!r;_4CY&=c#w@64FIdFI5!80XvA)~md1)DJj4`7$4~$evn3yQ>Iyxllq?q{J6& zQYO!^oHRr9v_%W|ZIXpqm&$xS))h-6Cws&HvZ7lZ4RA`t2vFOh!ZhB=mlyfj`(5}n ziVu56{Rn~fFlS~4n;lKukAGI6zmOAtPrQcVkHnB<=fZ1|&p+^iB4k~d&Js1#u|hc! z`aUz@(pT%@>Wkx{tzR3v|H2S|pB@El<}txN`6mYKG4WgNw1gi``GVGY4sgPC2OI3> ziu=@j;XjkNLqAoC@zu<7D1Wq?ANN{|^mA1>pxB>z5|1b>C=rG(+RRXGs*TI&Xkv7(16Uky5*(GS96izWO)) zVW3+3oQ1czpoR7b=x4cA=ymG~o--(i2|n`tLSod1_SOWuM@g*tN;H&rdVDy6<#>q5qod#i|ezaV2JoG_as&Wr?`2-_UCh1#B=h75esPD z!bHy4)lZ`FW4u&L@gf#+_G5jxWvjs?xm7quO@L#~uQ-XmGRAX1c&Cs01@%G$!NR9T^!Ni-}AUdMIZQpf*B_=54TLMC^~ z1Q(A6h}4!BpBj^gD%2?Adkp;Cp2=!NlpmqpV*UAXBHige z=>9Q^xPL2oRMbIdOBYbpbzl+euA^i2BY1Tom8(_q+&(7&(15Cb};^jH67@>8;$L7mjGPCjcb;pwbZAJk(fA-LFMHvJYx zl@(xm=mY4pq7OgdIr--|7(?XVE9}5QL$s1HgH=s7!s*wD?OZ90Q1Rruf>bd7&~Lu1 zCYa^Cw!}lqbS5`@aTon{@QFtNJi76Oxlr#(>iL17uzIV|6Iph zF<3SoW-mL8uxOPz3?4nscl=`6a+z;`AmvXUU;0oR16}3e@E{i!^~#d&v!ow7RdA6! zdH+5HLUeQ-EBZPBS5J=uQ&j~neS{LuKV=CM`}VM~WxDvO#TuL!nX;ktim~RE7*;jb zaSnsEF(E_^W<+PQx2JXST9X3ARo0041y%&KkA|Wodw$SiE!yMzLE1?_wx`!Xe7Bvx zGfrc#48hS#e3qXk&RwGdOU5O#O#@u< zua_B&zxu*gVN;Q$@ojIZex5qo2)|zpf{RY-Y<$)L3|~ll-rk8^cq{E&V;tau!D)7! zn0V*DSVK}9Csb7wqvat1P7HS8Prp{do<)j~F<=_o?~;z~X1l42!H^p$qlJH7j)k>> zEo|OwL;SveG~}K*CUl+}fVQ(pbI{A>J`i_nOrs;1ecHi%-}OavJrS6ncsum(5XyJZ zufKl5N>UazFxE*0s(U=y^F_pN3f~Rqr*7d^mJkPH!(=GAlEf?wTyW}=D6shQP4r~v zU&%BF3-HdClbrC-#2i^CSa9Wu(7v}4!}K3P+NEah_+4TeP{v{1h4XAN@s1K!9-{ls zb|HS;7nICtf*ISU@DC4Z<2Bn5@GP0YR6Shq*S;uNIfmy#hS=kY7vmsx!Uv|>;fmca zM?>}?^2NQ*$GPQIU^Z5fe{Q9UD-t!K^mP(DQ%gSBr-$H#g0ZOcm0WpuVh3b7Gd|he z1n-4Rh31jB#n≥3cHHaNu2T^LBNdHN+FdBj&QZs@HI6>myh*BavH6lHxM!2~r>9 zjC0z!eHe9!sB18#r4^{qUkry;Uvf`RsbI&QKYY#V!|eM~OU!sr9`fUkqW*VW@cyi5 znDX79FQU%Ax}W_ay2OjE`f(ZMm)?aFvu|(*t@Q9ohYkF(ZD+?4v@qXPACi==3RNpA zalN|$UJtZ+vkc-Fo&3jF{EJ~;XDm_T84Y`HujSB61656k-{@D&nnoDor_Vh2t&|fh zEzL)}@pZ)ap31l1?}N7U^da#WbzzH2u+&5Xp6{%=w`rM@!J|$|_46s55)NJWga1$Q zt)Q^i5_gieY5Vv%_h~QnpHgnZMkk%QJ?@X1b7#R+uQj5efRW`B-jnaeEfZc69~Bmv z!YI#CZ2qNE9DW!OkdDc<|Vu@M7sq-qodsy^rb22t**-WAfeM>4CTN?Z(&V1R-pw|{t?q%?B7bWi&7 zst!iVXn+tP&!#PSkMnHn;bNE~AN@%aZK}tDLCiU3XzYR$S42Uj?>LdV&p>=g=f;0} zEBROhT^xVN6`Fb+*{kst__m}G&Ob=uyy<=IRb~$|YVVnUiypR^YeDaZbAs^q1Iis} zfZOx>@iRW?p~2fQI4Uw?hjXCpgAYqjt?V^ z?iZ&HZA0d=bcZ7t-aiEtQIqqWa7&_Fa7}vVZz|G9L1_~3-}8jmLtJph$tak5B$L}i zdhFjFp1|)!RQ62tqw2BbU8I)O1A{6CX#RRA$SeI7j9v5a#G`v~ z;i>|^)?N*3T}&X=A&)IstAg22H6Wu)PuRZ?iRWJmS35oUkC7@^82*P}ZyUl4rdZ3r`ubaaL;1*$@T&MM|9GzodR_V>^}zgIZHd0LlkI*}&RNioMs;u?41F5Q zIsyh@UHdH1&6DT$K2*ZOeOB;q$qzPovLX7ccL1*|#BjS%j0ZLdFe3B;XF$*Ipr2|m zPyQSe&gp(Vz(Q%EjSx93 zE|iQgla+d4xLQ4&vw9>r>{DScXZFW!tD<1q*e{!uVy z>rvrkYJVJXjeOuum$)m_G_c;+3BEtt!S;}!FmV4cQ2Fp_XjE1yuKiRFqn@qe9YVD5 z2SJWO4j?NRA!4Jw-q!UN0p5ty#w!?Y|2HxZYvs&ta=I4e%QdNu)UX_R2-dDkt zUkZFmm?|b$YJujlz3lI^bTs@$oomO9MR;1Sd_wJ4h*`k+pPP*FwbnE^x8b(fYp^rs zbVPyAyF1+WPqhCU-XG%A7O*WqeXq}+K*`hHoY`8CIQ5&z7p5pka=wwiv0V?oe^O;% zUzcP1KQSzEd&%wZR>G=8;x-WbD<#kZo$32oG{jN#J;fOpEslma>;3u9mke;ADhKZ! zhcXANJn|IPLHo{|+^iB^)FL0qjrr{?X0#@jz0`wD`vRde5%Iv~GSIWr;)l-EL7z7Y zF#JRUyFAqbr|U$+HqEu1!hHIFe91%C#%nA<)tEX6{NPQ!oOs1nVu|QCfPvc#e)k(q zG@fe-77B5!{8KS9eF+?#WX*m5dRFr6#wn?8lSA20yTw1HXMXe=3moqg4R4c`|&Rr>`aBNKf3Wg1Mo)xhGToiKwuT613P6PMlf#(rh9 z;Hc#@Zsbw=&U0=MIy;hyWvJIFuo_nW)#g<9#!3br*e=bPHqX??RfXzM7B9zw0^TFr z+yD!66!}-}n#5}jhQi6`*{6?AICn=B+`B$jv2XR(Jn;@YTkBzrryIX5zyt&PO^4fY z7VJVlXWU8}myQd~`Ms=AUPA;=v^-1yh_B%Hs!BReX7C|PlyOb12B;VKuoOD;Md62`|L+Z)h<1)=ZTdi=b{VUw zGsn0&(O@v)ndsK@hm!6lEvY6yBS0HH^asJhnr`8t!xhXYHgEM~1-|zsRh+ZZ6uPhE zv4U7-9JpOm>U$hLpK`CON`dcj=SPyK;)4HQe&m5*7MyC1?T*n9XW+#Rzd{)$moVv$ zb<9c=oP8redgga^<)XHPvYa^%e4Du%8qnS0j8Pgp67m)OqCdd`%S=A`mkKUqGGI2$ zmc6Mm$NZRR=-64#We02Fv$z0Ia)@C+mw4kW+B@%=F3;Ufq*-N%4V=sW$s#(4t$o%O z7MYl_@;AkJO#`KRPQQ&Hu(94cXl7>fqPY(z<2Zu&hd^aP8>nKQLnRD zd^WN8G*sa~%b((l7khAx=Ub3J7R9$t(ZuuWAs};fJaf6^h)d``)e^vQ(Thy+_tHR+ zU-g^~Jlz*veaC=dXuRN#xwyZhLaOKdw?L7)0MtOxPh@J6bllx`7{>H55mh!TlwUvI z19HPEc$d{?IH(WZ(KgkI|2=WUZIw|_IN%PKO}$Qyk7!@%yqry@4F13!51_~*fvcv1 zs7KBdrOe(d|0o}^Q3uZLQf4i8CAggO%eQtlbEk}Hr(gP8%KkcMYL1~lqTtOV2hr~! zCpV{RSgLl+ETOT(|=j7N3Qy6Glovqle>W!S^zgfA@Xo(7IstPc&| z1;Vz|h@Qp*abUFg&$epVpx+yOg5p@`WOF$c#9f2Nu;70 z9{$w}S{}6tF9w^VzFjozv^dVKzd`3bb=J369$_`By)ZO;7I>Pi7QNpcSe~x3(C^vk zvk*l2AZ1-ESky9>-Cx0QiQf%~UYE)>oUuin(^jyl^cgF4GQpj_HK3vDs4%<77>_TU z0rT=3S@dZ~Y$Of5?%h7|Ffo1qWuu^`<|+5SS`*zYs1x(=R8~4KAM@mIK(nq6=NB6* ziCCQ=%`3g~*2eKWH9+p399!7&4m0x_A+1f3chb>9Rl`s?ACblKh@o*UmhQ7YV?`nR zyiu$f4YE1Q`PYrKW3u*y*vP(Y_HxP+zI_b8^;5ZVLo`sMP7k*Cy2o~IR72HPWk}t8 zLRez=9#dX5f}VXpzN^3xx7bYu(~D+od9@?voF^YtUL4nCV2RVmi{N0bN9msU%eeVg zr8LK6c3BtA6HMSq|BWo?5oNf#(qYChT~1N4R$^#bDxK}QPEEYl76RT)IYQ%mNAiTw z9jE0iXG?$o%~t)P_US&B-dcqI8BMUHUYVOBp}T{66^z*z$-n%gjQKOQAjD!YOFk^% zCeu>bC8!mNEMbFwAC2k|MrCu5x6(c;U?hkSOd$Wsy z1vqZpLom3d#M^&S#T$>zpt(4oWhWY-iLZrJ!&jUj;EnuJxVg`rkJ+t+_E-P%QTD-1 zEy4_^(tXfB&67KnZjP-#CV`Ij7iLsqjOKwfLn`kU4ld2bj3dNIX?Ebx6I08ZcBUKh z)0o{dF}|^^hUFbHqI<(WV~tuHxTT-r=aFAxlCdn5ov~-RJI%=J5)E^Dm2+dr7d^pw z6pW17O7{XUJhn9ow#&x;(xJ5KV1Z8dx+97XKC{aaTD=2|EK2^)19uu zUYnTe*{u0{8umS#1lls=g^T~p@VMJ-D2TP=uaghfX$|e6*7>n%zdg}-8a>OwLEJpP zADZt7f%U#^Y+y4noTFTz@9%n{Lb(uIHZaJbUS- z6Q0->V&@YEHs_rAkOfNkph*$V?TlbO{xo~L?S)-(#vDhiEt`R1ka*-HYgwv|CQZZP z<*_v3XKydOR6>0^Z*#Z{Pc=}T>kF={cd_%M`k~F80I=Npap;SPB0OP>;QeGxZ;~fl8c!^#1$$xM-xzMR7j-sW{tvoVB(V>B9Hbh!W6)R8!^yuSHxF2XKa-QJ zGPA;wtvodD>=AUwUq-p^Do~ZF<>s_fSM>s2@W{w!W`k&UI;;lO-M_>IZ9OjU; z9MDW0MGV8++=w_$e0;`-vSW*x+L^0(a{Xfn-nNU|e^4Zu*Aph?J+7d;YCCy{iq7k> zvz81`ek%i?@aNpjXyW^gBPM)B8q1S6Lp$SWXxQl>dhA3Q&n={#CiwApSLwQMDIxIta=J%>l#qP7c;kwf&VV#y4PH>3^arrTB=~L3U zy8U2B>QQ!JttU1rk>2=lm1uCPU%A1bxqi=bGC(NMz{W{d;F~&@Y22^CCw_OJIQ}T- zSYd;2-dchB*k{a1ULPBLRX|@WRoFUL8_ypLgQn-TY_y&OK9eWCj^8IP-0g|`Y@(oi z%v0{Vsyb%qIK#rCaJFJlK5p@;fpsxDoWEJDBtT{d@3lZ)GI*Z`-XoTR|Fhm~j&&jW(lg(Z`fk)JmBHrvaUoBuws#BX-*w-Q)+H@84 zX1a3rBW_Cevr?%C{zwn)k2FF-b9av5wc7!$={+)b(pj#Jvj6fU27u12{q+9&h2~lM zer4B1+>7P8IQmzmG}Gj5ppH=&^k7Agh^=~Egga`lf~J28XVps&HwGy~#4#~*wKT&U zd^8MN^Hk(AxlvN#r!CE{8k!iR%)0;>8zRe!PvqkQ&4-kaP~uOGR>MCT=70+eSio;F z9;hpY`ql3I`4D13e3OSwXTn)ntttMcdFjw#PwwPFV&mWV4_>|LV9#tl@#XPZ@OAkq z;Th$a#$T+1q=SxpONJWu$XP($(sZVzR*28b8JHUN`05<~jQ5_l5ij=)uUxN#iv5)! z)7y=G_+pCn+vA17d(7}{b2L2iw&V5B z>R{gHk&rcQ1bZCkiQW29ko$c!r>)SB_y8d=)~bz_OrspJzBRZ8)d*&kh2QMYAU9Eo zcMYZe{y9xhYD!}LGRZ&CqXYr<<-Tsy@+D_$WWjK!oJ8#bX+*?5{@-l>_^1cwZHa<} zJv+H;bOy?vrOcXBCL84Hh`OY!hucmSa+<2Jq4qvJkRQyC@m0bV2m8R@9}%oJIvsQT zk|E-xF=sSD3vFhG!8X5-OqF~%*5nQT-#M=q=Yc-tIq7l9;fmMNKFiJxR;DMiDJpK* zTo?cjg&&44oOTtT1WVwI*HXSwnf57DRY6w9lc^jcHtFJIIJzvBdtRZ7a!0}`6OqI| zPqN3gY2Moi1pB`vB zUtn9;I$^K#jxZ!yPZ$={iLWBx!Z6EO{GAXT>0aQpaX9-i#~$NyX%1f@;))xMafsJ& z_-Fo{O&@7V%rOA>!|Q~~8HioUP4F~dhgTLWW2LDMyp7+>Jb&3Ey4nLj|GckRkzDyR znI1S8fqd#^6Z}<8Go)vo*lC?TTG79!dfw*dlK(_|&>)bjS?Dc)ET4O{am&$8bV&t8ZCo1=AX=O=qCluQJl zMlErQZLjjF7fk$?PtD*Lw-Dowd{FW(2`s9eSPj%&(r>vH_qFY`#NXyLzw#g5#hy}@ zQ(hJN1^yALzM9}5Cpr(Kk8yt|YGC~D0O)8q##FpL@LA6+V%o0~ZJ7b(9}VaEtsI*H zdB@c;!qW;mZjE6-LP~M!$?I?dQaC$BecU@%4-U?&Wf#13@$y<_@~)={D`^+z-4O

    koeHJW!k}S>%^}s+&$`Kbo;Y_{Mu-VI5x~u)-g!nhK3C`@Z;HK)uNLJoU z;FsT*ll1P?z&HLH@H$hLEq(U}zrARHZSxiQ-A^@f_wxzx{#G^8Y4=b z<%yB>&fV~E8Gn9?4ss_wp!&Tt1C??-AMylb980wpaT@)2#T$nBEOrK554B+L7TIHVQ55y6#BtvD%y8de5v)8c9q_nN-6`m}Y{rXs2A|SteYYXOAC< z+x)Nl3>W)>_IFPQLTKOtmRV+rOahRSy;9UZJ|9o!-h}9*v-!q8q+^WLlIr%nWf8Hz z3ZcR(h0_cskH-OJSQ8>oiDm=^6Q7b~T?e7uJr$z~n=3_AdAb z?&#F_E3)SKDkU|%VMDp{p;uYvczv8}X$fJGw!&~3G2ZxE2E7v8`SA~k`S4j0;*%oS zn$ae>fHb0C@}At!a&25!G72sae!&JsxT6lu26pnNgbVv~(eg??44&!4zoXpi!7G-~ zFzg6h@~Rr;TB_myNILJhn%_5!7wx^rIqki-GU_~^J0ns?D4R48MOoQW_Q*(xL<1>p z5uML-?v#?5LX=L+OpS9?6Bp8QnBksLw zj0NhQiwe8ZqaPvtLiP)-!GV&8(+tO`RbAUCD ztc(OVn~$QB*6)&IgU$OqmZwbFz9Z5fB9(veEn0~4FSoII{wdkda&U6~dN4VcG3bU{ z;fUi_@M4uFKcn^w`ieRjJ3W&7%rvXRy;Go9eHwk`ZjCS5ci!u#A5nI*Ky!x>cv0C! zmojhgOtxPbyLKIa-Le=jO{s@H!E&77jXb)WYr=2ST{P~z4Zha41;6Uke)1ROYMPS& zK<2wzZgYkJEnY{$;9E^%>Dks;#kBge=Idm}0>&4z90D>&7Sqa>a^_8a2*ZbMCx@Q< zNy029_nq_mw6yTY4c1^GmITK6XJ54shOWO4mAmd zsQ#K_g?Umnml>CSlxa41D?k^s-q?eh>Q?HaP=T_n$ESO$8L^DdkzBi$!|lNpa)@}j*m=gv5E}3LS8S^uDj{w)d$LPl&t~h{cUk|q}6}5Mfn&w~g{8MU9 zz#69YxvjE-&tc=~tCti{bXT#ELlw08nrrU_N>=BCt-LP{p>)DBGBR{HCF#o;-JX$`Lwm+BPt(|R9``wgW312Vq zo3gb}tCz}A$3n(K{(p|OlHNcmwinil?Il&$G_YoND3oUu&{(j>DE1!z_a;cR;D;Of zPhi@wbUb$^&kzS}84O-uJ!tI&34Z8$2)pMUB+Amp=z7u?7HxPmM%hf~nTHyDJh# zp35aCUNP>3!yq{Lc0U~_F+(-mp+KsZiK42?&?)X32xv5SlFd$YqZzlnP(-KORAS_g zN|^ib08wXtn1!oZzHd!6wVfcq?MI?u){-{SjvvjEJ#pH7K1`Xrh8Q=3@xG4B(5(?A zXk>mLbdwc0zY(gqZ@W1RVtj*+mpXX6(iDUXE%`sMtI^qshh|lGF4b2ZYv#y9&%>$o zmZ5-o3!?z`xs&1=ZA{4whN=h8>8S=6T#_9DR%4Fy|8)M~f(U{C3y)=7_W@NL{n;Fx z`X8lso>e&f;uRpz|N41sc#jKRK0vN!9(Um><9Iw}eOL!w==5;{ym&bZCiY0k8EHKn z*E9~k-QG+WEp|nNeUZ#>+@EyqWlTA?AAH>Nmp*6vuXC;rux^1FU8W$$*sew>f7woU ztY_Q<#uz-gF^^7qV2W$q^`Xq;k+}7Y0E=cvL(n=aF5^7o5LN`kV$0D~ahWTMSmwp# zTOdhMwnI6mVAwJJ6}@nc^}4>Wf#i)h_?`F5&_PK8&)XF^+aW9m6siuo9y{qbp%#7> zDKVBi`lVkgmFVu30b!|(#C(=E+HDC2tHUaE)(BUWXCCjnKeiGZmV0{o-31meIz>k^ zfMxYjKaeHU_}y$r)A+s)xM?ojtwhF3ZPb7(C+5*rOEd89 zR$rEIW;QBF7pcNXV-M=gdI6T~*#`=9Hj<6ZcPbw`13Ft$>6*qqPyr|Wt|>vF$I z&K))HWB>XL(?O$=1K{a_4qn!-5~FV1hH~c?l9elmh7B6v{UDb{RH|Z0e{~r7;+Hr- z<}34kbpc%&#eJQtjgptspmY6nI{mjL-Y$!T-VJ^v^N2Yv>JEV+JzaEPycOoDj{vy!VpLsq6}S+2&fuC7V=3#xs#AOD*L+(H^0J4-z%zc|Y!qrnNlW`Xo~`F*{xZZL z7sfly~*5#*VLI(9Tfj z6ylU|jFAk4&)G_6{L4%a+|X_%@Gu$bRM-3-ey^MC~OOwEX!PmV<6d~Tm7XIq&T;~^`-r_>+(wj~0_ zK8l9=q)hUGdAAClkAy`w$7#YL7nFS-0fVZRh)U0kYLZ;%`?oAQ0a~{-@X;S@n07pb zntO=RGyWROi60_Mk60pSWDRNIPpCz_7CNzA{FrA4`29QeP~pIASkv0Vm?2h78)WCO z>RxfMyen2FM8fF@4+%?`qA~Nvk2*D#zBxrvp|lOm(oIRH?s`e8^)~MR-Pxy1S(Yk6 z6B;kd(3Qhp;_H#E5dKb%J5;QJJ$J((e?}o4u4{$6?=oiZ(jbw`V^?%!^R4s2#oV%` zjPIJ|*5}D7$*IQsLm0!#@BrEV!x*nTwg>)NC%qM-g7=TA!v2}ZdH&~1%=pp@t;B`f zw?=^HmqtU%6$`qY{ro%Z=Z{^NM0&P;$G1KD{!cNlbMf zv2#pjE_fVk7cJ~;mT1>%_jxbl7$Yl*dB2lVW$30$C1}F@a!Y?HaId>qcT%ARd=EQM zi+NofA!`od`>goRRhRIArx^P6xN<4M>L{*f6U%^U^x_fLN01W@E{i;f&lO{|SDX&r z`+MohBo`c38v%cZ9p`nKANAYK2Ozxd#07h+;e-B`(EsI8I=HMHod+Wn@ziSYp^@s>r?_u0hb@)c|=*U-WhIBQC@%Ty{ zb6AKcjOT&*X=~0lg8kkYYv}f~KzgLp1y2UD*(N!VoL_H?pRNT#!L66{CG))mfjxu< z-R6yx%h2~Th2%;F&WY_8^d6|eXcjx$xZZIJBG(E%qU5Si?VP8Ct56dmZ;OP>G>9FI{3|W_1 ztR`H1FpqBBk%8IE_CxzvBVxhc9qAiqfNxSSox4N>=kx}G!;%dCLZ>sP)Q zzF*Bm)j}1IH5)*1!dbe4aj2#y3E_950xwYSUsGfF6V7!m<&HD<2nNi8mRYlC&_fIS zbv+Wq#(qRw%@T!;BcU{H178?ZjE~kg!l6U*oFH2sWu9ok>zBLe{2T!)+ZwY>Yo?!B zigb;f-8Y!MpXbv48sfL*bD_wwS-e(giTjvmp!n}KvViUB0{#qxM{ibBkMuA2c!0it zY&=ii6#7bRZ%*OH&yr)ibX}}_XAXZ(>C%gC)!2`n?aO~XB9B=2w8Opr@GAH)ed!>; zeN}Uz?zyeV`-CONzht|l4;+_Uz{+t{n=0fF z2V6q^2|UP#t8>A7mC?sh7UFw1Qo}p}Li{|)a84xM$;KEIJOg5nH&L@KjyO3f9CW+% z#m2v+YL>T{_|FvOa`8#pxGKN_5|g*k-#O(Ny151>dz+KIUD=X>9(jF!n}=yyn9!~a zW$r)uiY)@v8a@x|=N}_01~czUb|6f*Ize65I%A|RyTguJB8t7Gj&u9lz>oeR)V;nE z4c^tkreSHsB-I^l61?E!s896C5PfV9(tv|ONBHf`&$h02c3)=dah3(XSQQC34flx6 zTb=RC&PX^u;~`nTR+I5PJmK`U2zoJ&V)yTMC|5Eg_Dk1EN@}F~NJ~?i3jPrI2pwV)wh}k)ZcywCL;t7wj1m1*0n#aZU#fah-)9 zbjNzJz6pv4-?u~2lY`_J+nZnTb_CsLT{NIu3Aeei{C-##zh^={8oKe|;by>nXB~Fs zv!=qEXNENVsReFkXZT*nB=Ta{4-}m;^k2C_wK{m55^7!1g{p6H)YzgC;}+b2KxZIX z59=jgOZdKX+b2SRgVp9i;72h(+0GKP2S-7JQ7+jtOAUq2L%`)?8XYvq6o+XIgFP#k zi7Km0G0XV|JQ+8aQ?*q@_Y|Ez_OBE3VpW&a0-1W8Ox4v!)i9Ml?fu$p0p4<*4>I>2 zi7d_UNK!&{z@PP-42d*Awb7$Mcu0muT$icY5@_XrJY+1F%oyeYJFOsM>jkR0-T+gd zTSG>!9UuI=3X>j-;p1*sZaus2*XAj}-GFH{dyoJ}DbEKy;7P~`WAreZ36EMn(e%Ft zSYaOsc}I8gDxPY%;F}e=f6k<)3J z3M&LCUN^tbGatD}9kcHQ!r9S`)Ah#*pPga;XVyC)IH!oQYaC#InUo~;g)#0L;sZwu z9jW5SGQ5Aa2BsF@Av#QRxT&uJBmd-5n>KcL(=~-lN*&^UPgswkM-04*x8by8*sOSE zEPS#LqCwqGs8JXRYoCuIC%sK^waajr;nGIAP}U({Wd{{0H+g$K#*@4!foD4uxZ1}m zIQy$Q#NOXQ?F}^XnU6AzcSOGvPm3kmuCjgedHppt++h?55&IQs!XqcFW4@__pq)O9wKdH?rsTs34o|Fd+^ zHv_ERZUh&)6!=87FDSMAEquEa#l5-5^zDvWptpJ!<&K(Tr8p9nAND0OvZknVAOsS| zb<#W`%kta~fR%3Rc@s$y7TaBeC&%TvvCKaiE^i1cX6~muh6(V&6JvODJ=5>SDe0Pd zc0c<3lb)LFy&pOsuFq)^pKLV8h<}mLf66stVx)sREr!8H`&G2)+b1**)c2nv%@fVB zLnHw;Q~KBic!6c>{+fb(v^IUuF^U(-8K!BaTcA$K^ zj(>Tg3g3JeLr0bx*A~I`LPJ&vj{HMz=*{`@YpGvW)F5k2kl5u%}EeF=^lt@*&Tew%S=wi zO&fO@JHp|nFsiCoiNe$?eP{a@GdC0vFWBkUOD7a)q2YTKs4zare_=i5J~?yx{FASV z5stB)0hty%#Bv**up&MZeiT0-ehW2luZbrZ3nFOty)_c6wrzbG*gv(5G3Cj47iJ1H z`D7iEE-}3DeoOAK{rJcBso?kHEPZgo9CO$`H(}0bk@I+GluwC*Eu$83y1&$M&_0ho zw%DmD=h4{iE_mqgBkui;Fv83M^iOtBI}K%AK28lbsUPQKa;_k0=b_lqfE#mC6X&K+ zhcUWBTE?5>itb2w)Ukma;DzX858yDz{nFK%a(wdZHkhV5b7uL97-XymL-{zGb+{2d zLT`cpIDgV>P%m)~rhQ(Th-?AAbdLcij`GEfuehK2`JWxnAx19hIPr)dl=-LAj2;ub zY&sn34VH^k7qC7f!yB-FOEl;2Adfkb+VDhe5RHG&JgXyk*l;j|6mE4#wF3_DIr|me zI$wa3-p9awsV5?nz$VF~Ivu!vM@CY7-2jgc9t|B^Woeqd4~APYO=(Xm86d5OD;uq$ zA*zZhJT$<&;kICK(w<-9-Gz(Xd2mH$Owg2OsN1LetT5Vp^hxm}dh@Mp?9&_1T@e=m*!8;{6Wl zi?KAa2JYWX;U;!zp~VeVkW6!?HjeD^Hu(fD;~h^vhoty!y=! zj_mp@zGERo@1TWXy3dw#WuEPGf5*YOXF+sjvm;^y+x4#+Mdq-q_c*l?@N-Wa?QT+M zJ-l`>$My!_R$GFtEc<--ngaKDuL|xzssSjolXlK$os!lE;P#L)qJJL6l4~bq`v-+m-~kBs8`(^3?gUS`}U z2hQ!9A`bkl3OgIZ>B2)9_-o4n*b!k&@SFx-lT3$$2YcwNc$T+)90slHa`>zyM|@Sn zyhhdqWRsd6s?26R#f-zOBV~v2$A>|Ku*0`!MHvd;T!t?<7juRKmC<^kIy}4XLDQ}< zzCpzS$dM!yT4adLi(}yU*n`w~s~MW#VcKbDw`k~=&l0h`WnVUGuaPz$Ec1aGRh|5J zs|p-*?+&C+X(6VwRZ+=92wjTB^i7~4ir*T;;zC9Kn{ERtZbeXY_T|d|XyM@@v%xcD z7M*{BaWK9{LP(e|!FFSeSswzCxgGR~t|`9E8vzw^YxyIFY+n#`4_Z&FaX)HRuxg6{ zM$bs2DYGu3oRkFi2NF>Qe8#Ep4uYOna4QT2cwBn{$R*tsD~io5)WM$`6E^DZq1Fdg~X8;37t&zCTa zEL2y=CyQ8iIPV=zs1%^tJ$o3~eT6sHuflU@d01Ae#+9+`;ihUiNZ*xA4_#q8q;MhF zeqBXU2N~h+qM7jFZ4({HazHY+k#MiWK%DT{8>Oc(Ugf0SW^D@&49bV4#}&&j@iz0a&qGss&VhJ^p+<;w)@F1!Hh2OTFa%UGvdXE40@l1)t< z9MOmIg06Zdh~}K|!39B4kR6-JdH&Nx$rA^V>j0qjhpz3KaP09B{(Y$~rcGn>%%^*FzL5}x1~Z`lmF;3TmQx$YekVI@ACTxy#?349 zgvh}W^y<&^=sNK}%vBJQE4phWhBLPJWuqKt=-{jS22i2Rs0cZAIGL?W7k++Ay5}=r zbntZWs4k*CC(TgvZzO05M~m({JK^SZ#+s;&UL@Pg;G2sbsJuDPMpVY4UD%l1&8TtXna~D`jp*<&!7DXxBQBv=gWU* z{x7EO#1$+6fue-hV;cJ#^C;K{Ib^dZ)3+Zdp}N2C01fs8r3=cf2J`9FGNc8(BuEo5fMp!j*JEzyGiSnANU;(alcc>7< zzAc0iDRt!WBF4CW77Pa-C(|NVM?5i-DPpVnsJkFo=xpE#L+Q!B*MtXMEyWXJvf%{naD=dTP5 zrgkBYc!bR!vf87FkH7?fFBlGI#1HADzv{Sliyf5jy}{ef5aaJBx1iya7We56+kk4^yiNZ41LYA$!23kvFb&V&GrAy_Rm`N@YAu$@R@4Sm<K+$G99KUn~;fY zzh<=}3XZ1ypv|88xWjx3D5&Q0pQ0VGm%USl-9JONgy`b%>qEd_K8=oHzGamwBOtJ+ z(|1d91$OVMhk~S~+)gcJ+%ZA}dcl)szhQTWm+A0wd z@VV*TBH63GlJ6>(@OzSsWEjf}Jm@zFR#bQK(-g|_gj{pqY`;2K6*UJK!K|!e8f0XJ zhMWT^ztiRw-$__T;1YDHdUG;Q4Y6a(LiUU=pmHpyqrhfw{jMRzzSsn-EGPA8@43wX z=3+P;a;C20)dy8zLoDma`>VqJZBW4@*+O{wDUDvLslz*VHz2igw8+KfGy2?n4?T;| zal--yIM6Y+j{|?T$P|snvP{RRMv^j62OsJNz=soS=!3}vP>Id4Qt@g;t!l8uLVtQ+ zHfoxw0FA>P;QU`9z5c=pzed@Cix?@-^o^=*v9RWYgGlIPhFblj!8(_4ceiNZZ!>=w zR5X~BYUQrLy6Y{b@WwXy*b|9^crJCI~dr*_(gTRBlE9@4&fF zRYA^TJGFZ+z@yf2Fk#mkl3izrE_bGbbp9<`?dE`{hZy(ohJiRYY5tRWX`k#=rD4ybs7s^V)16a0~eSa(*fAhC11Sowg7B(21 zAU#Lf9i(6^G=0jUDV_Fc%5=`>JL5$wIByK~j)Iu(qnw>U3qK8Tf~P%Uv}+#X_FF8M zRB((;Qg^}FeO|Ch{v*9*$#Po@l>2&`lrHIFKl^AnZQDu@JTbvkb_eNruv`3SkOR)i zWgRHBtz^?N#(s|)$a*&C(Fe{KaJT*gIC)Pj0oxf}c}OD+4e?^L3EWy*%C~GoEZA5LBSgBK#~uw#^O*_z zwhC!Rwkc-%MS;SK4P@M7rcWkApJ%drO(|~oYJxGwp~Fy}KJLN0)VHWP`!me)t0UWXx}waV|IYbIOw$|x zI*#pJo{7e4+>)$_((Ti2-k3dMybk-*x4dEM#80*-CJ!Vj4{yFF^k_ap1GVo84J-u)1Lqcu05A zJ#{)LcrX$~M|bddKX{>XMI>Vdmy=SaV-OpAc(MIBl~}mrwT5AEIyTYIyX7K2sI7rC z#}w|vT&4jsFW>()oR<=I$0Up3;_)jaDo!0u&Bnq(K??OaY>x|6q97!-ABk&J#B+mP z;CFmK$xSnDd>G~ekKdS6*V&h`#Pk6iKGjJ!Y*xXQJGG$1;w0^y!hA~M%1|__K|Ik{ zh=zKL!FY{5cimJQ^R_X5b=X*XW2`;q^O0Z?J(5JL8KXn~2oT7$(LK8@(drq%p&@Vi zjjYGym0T^@B`b1!3+3_4HdR<>x|ROhn1McF2VrF0SW%(cS;=8}IjCj+rF*IdSo?b# zq!j4TF(LMtsUHQIQCo)vV2R&2>BWot-^1-g72NF60@VB$ z2M2Xp#ciy+*()px9NgJ?&UO2d*b{)?ca!BJ$%?%FZEQIKOwxHXPi zm{mI*d`kT2tLt9)SvCrMmV^>NrZ*NWaDa`AKhW~qM#%4XfdL-Z_+0(-Xgh*Jqq7>< zm8OV+y>j5uw2}6F5#Uhy#qjj|T2hs1h~vmi__FRcHHovpg4$`&wMk1{Hqr~%&y0lF z)GqQmUITZmaD=(-o9WMna#XWvfCD!y$;HFRB_FSx;zIYxN^Dm!U(jiFm^<|kFZD)% zS3WQ5>roxGow4{>*3Z8zmkuhm!$NkidG%?rNUh2Xn^|r&AowWfc}5e5zj1;%*U9wo z7K(!h-GyV-nFN-r2Em89sfI0s2{) zLc$F-I%qE9^D;5KOY9`)mTO>Z?JS5bDxsCrOc*aT3e*P$iYg`cD0MapmLH4d#@^Dy zqY4C;_<2$D8D;2psTm%(rjpqo7=M1b1#Glyqt2R4gWahQ4mGFwY^54>V0(~cD?RQ- zo;pS(%>$JQkZUt=XNnZv#0wdJ)IIPmuZ45*1t2BYGN##M7vI| zr#^vFHMeBt{0Ce}B(8JnBoi}`b70>7Om?W*<|z>bv*i# z_5Q3nM8z^*7{mNa%bjNPB zvpl#3w47|E9fgc9(Xbdq{a=Wb#@v)V`Kk+{Z)7Ch%NggPg=zBX{ps~9o``JTkZRaX zoTS`P`Q>=nnbS!vJ?wCsz?b=CeEG)kN(_vqkblC3o8h2@l@i@4_QWq>6q+#>dOyc3}Y(w?sL6=Nc8^NoiO&Gp0&beZHc1qM27r}x9` z*v^;z{s;6U7v3pi(dA=rm)Ds~HKm zFSOGYg%;@RQ(_5!-j*BoEeaB%9|RKB3M z7=J+>4BP0yjo71rC1=!O*}yrpYtRKe|MeVbt??t>BQ$W6XE+qrf1=Kc8tC(BJY=chB8P{m;>p>pXYf-A9dU}~n3%4+t4Nza=|u5Jb2Vt@4d4=g z8lw8-#juFR($NBTuVgd)5$PeMC({g{c20#a3Log!UuJkKA{g4MlK9V8OYr8@X4tVz znUi|2g7JTip>b$BV=J9U|D^~AZ;3=%`X4dJyc>?suHa;11=yw(4@&V5#Ks}Un8Y%q z|B9}%d$%?^S&xFo?zOb{tp}&L^HR#da&_?un z)B<~d^pfwsZ1*}>8>Y`WO|1{H=XXpz9DU>@!U|&yd>RGjM?~CDM|IS-V0k(=&p+Ga ziL2OszoUB+nSV^3agrVTa<86?g?MDB3-ow2^8C$n?7u0zE>q>?o-1IXr#v(s-bk0K z3UQQd0wg7^C;fA^a3Gxo{z?thoaMO|Fuu_L_pK-Ud*Y}lc9!;b5?kgAdLnUxyp>z% zla1wghGX48?pCDR<+$Ww@@Z~&g{;JLmpVSbstS)Be(;^I**)cIJY=cnkcUkgcu{`> zBt6Wd2?uR4Du(SwQx=Op*m+`mS|sG>9N}v9)lp8%5w3HS=R(CsX8_JJDS z4A6sZ{`K?+(?W*~F@(iZ+59fH%g%i^AC}}lq`GxR_+euts6_4-Z@z3S(NuTpZ`{?Y=RYPWjFg{RDY5U}(YJe@8qQevmvlf|R+f&KEy1Pzc{r-j zNj{#{z_Bgiu%)w#?#w7rNRl1e=10NUzY96P*Q)qhX#j*Wu_tlCIW&IR z3SDpak;FgDTb1Jk8FroY!b5%JC8jVcxRj5#uEXP1HSkW8-8v)Ga6UH^3fcrTZMZS> z`bL3e*?Mw2k9E5rn+Tz7&3CV?1RY5;{El+we&p+5Xn_szFE`SZrRQ<{KM54C@gVIL zwUXGtn!YptW`CBa_!`f$Gne_Qm5lkbJqntqXOk(**mq|0P*9(Fm}WM6pp;!Cv_0A> zav9RErm$4#ukfvq`QRO*i%ZeHpKKGGuITBZ`O zuBI?1$%QLiuY{uO3asaPGR<=kVyj02OlciRM&HoFh+mVSYi%dBsj+vU8>*| z%i7tqg_!?70bUzlB_HnSqGrTY5Ix>buUuxivy*Jjd?QVkk5|IME8W1fu)kz;j{xbA zLC_iPNCR$Bj8M7{|2DlM&x}~kVu=oz96CkKPuZhnuPuze_(44HyAWlTE&)NbBjUrrPS^jpXUDW}FVqU>O!?*C?1> zvzc71Q^Wd1ANb~3NcCs4K4r^bNS-o}?Q4qg(c(H-YU#jzJSUF}>eNA$6He3SoyYqN zSzk|(AF(iF9_-z-z<&8h+Qjt6BsRlq7ZmUli)?UgD`N$0$S0b6*&cs@4-^ebrK@L} z;GQB87;Sju`!Bi__Xalf?P0mI3K(;Z?WvhhvUkLJj2K-BQ4Yt53S)g6&y9f0C3~sU zA0Yo+I<1d{`&(5> z_H7@@UB>Z!XDcUJ{6Y`?r#Zl#6anoYC`Rk84Y1zoB{`|A!)`;`pmFRJeUd1^kv|i_ z>a4S9^Z_G0_c;pCN5mP~Y2!b|Kv;H-qmO>Nqv$--6aG#ld9TzkP1Om)CiKwVhZ(mm z*}Bgs>9@K9mv~Yb;;PCutzn$5GA(HF+C^;`2PWd{61cv01A(iWxY95bHoUB-Lw4Ap z346W{7U+vD&bedG40Z<}*-3I-G_d@zbDvN0?`H{4diVfVySkHIcaKRjhn?>8#_OC? zLHXCpFyYr{K3`Xe9X(4x&MKD-E!Dt)brWIM?vpep#s+7tX8QS$MWWCacf7QT_1HQc z;TF78$8V#Y!6Gt@E|RLjkqT|#E`NeJq^qHunm$ZAUQgq-ZPC=l20m#O^8r6~aY^R_ zXxC_`KKq$2x-t^t<#&ru9k9VTrW;5*-X}e2EQ_5y5Qf%7(@i&j;*vjl{^d_Y$qL0p ziL&g@zMbrqr~0V<+6=N5s?)y#tWOzu@J;R@j+GktAu9qB-<8q(3P!ltCW^%jM~Ozy zv&9qlqhQDWh1^o6Ip~N7K+{$SI{bMVc7)%D#+7@?@f>4Z_|qLi4|TK5vL4oVn}Ely zV!qk2mhFWvgYSIl1MVEnQ>LA@t8GE#&$aF^%Gq4R{F0 z&_su7+!R(1x}&qmy;pizrKbmW8?R7@YQ_uATng=nUx@}aT$A|C)a%PYRX^26J*glV zGeL$<`Rayu+26wN)-D2zz46uA>2TBe6MbWDi)E>Pu+hqougj=FbuS6r8sNh9N)&Nn zjv~YinM|wCGhL-S$->3^A{>sbYWDnRSoN%xDNZOE(ikre*DF9thFW zXX#9DGyFQjA6n;6!U0tUDul z7BoETq5k!%NE^n3%b%nC_cUw#(=Q5gJ@QG{PSyd(o~aKHQ>mV#Dbv!K#+drVx8`Xn zYLZ5{U%iym5-Z@^r<#!5=0SH&uEYa5l@QRCNfI}+Gv9#uNe1kr_t@ue^kjLugm)tK zQ{9qSMe9D#-S`%m(sqaJPgh0f-)10AJe5LM?t{c!DQWJQ|z5Hy{~uMCBY5TnGW!N zMJk`Ls0ascZidXuO58TaoJknRI9*#0QqP+exZ{NcdZheBn*F;`I;tDSjVtG_vS)UJ z^)l$SZx_dY6JRLYEv~L?ASF_)f4p@ZwAm%oeGA=i;xx8@*H9&OFTEun>Sy#Zif;=I zaCWZ~Nah&P&8w=>M*Aw9?)Q>>WOM8V9d*zT&Zdi+7&mg>GLV;d6^+^}L@Bpu*zm=V z``fC6A0GuXF5ggU*64-{Ti88!^F$(dR23C3IQDttzr57M1JA6%ZWQH5&Mrr%859!k zt8h_=)NxI-I+T9dMs?YlpY(7UdsikA_@a-rbvEe6HPOKXt?>ezlaILRi~VM};Tm=~ zQQzA^W-%_4!ygxzv}h|G_d$Y1GulAru{$|(=9t7~cz&N&U%~c4=@ZpqrSVU`)kcWp zdX_=DNglB;XI@HSDC}N%ib^?J<3g5K$_-g0io58BMiMqlbY*bv*ID;OwFB(Um_Xe> zRpOlfx8dc|LnO7?fieBOAyT!6?l5HC)*;HUWY|7_%m-Z@RS*lh10T_-wM;uY7zqZo zyTpGItnqI%W9wbIM~Yd#KD3M!`OUGx7belLV(3Edks)K7 zXS2IA%f0HHXY4Y|Hqc4mPi}>n;#`{naLllmrhDk1s=x${#uxFeK9|vHEAv8}FyNBg z1lW=#$?9jGD;2nrZ7uydujRwne~-`@xqUn*YTRU4ehm+SMHB>0sR~J7|hY zrrGb$p_^U})Q$5Xuj4LD#?k-I{4h2rw|`j%>aJJ#u6{zCG$RUh6HkyWi`0=19|3Qh zGU&W{ZrC#^5{kTcini~UuGwp5>_1}XSY5r%1IUF6)A#%LYC|P(#57rjTNYvM{?uoR~ecjxn%Un@mO(cAb+eIpx zyjZq{WiFI^X^)#D25lP(*OL7C{!SIh*6Uyv@4|K0F&|x?8cb&1i6`3y_&InvJZKwC z&Mel(v~knm&*gX2td@Cl@&aL9+z#IFILqd+cS`2(5;9&z9YZI&fZom=Y98i_hbNC@ z@0yi<jihhW#d9e$A%6c(y8Mh4 z4wYs*ac^mIFjf(Nwt9fVQW?pPaT>VpgDZ^NXih&}) z9%@#@qc_z-aQT|}b;^x^14_=2f(Lq5BOV>B7Ate9=hU{xU=@G_exq5ZXDl6z0Xp ziJH4_!@*1sZpeORyxXe_9@pp7+vCrn$@5B>wbYl0SP$b-huILM_L1tju@3RIA#l?= zlaJhFg@uEdUfq3~^sZ6Ey|shDC}9t+T3(7f>r++Z1;@JIV->|aAvI>65Pk?%wbQ{PKcrdaneDqY?i;HudHOgH$>-y2nl zj>jK^`^0u)xkVK(s#>r+dpWh;XNbzbtw8;s3ZFf;8fSkH!=oEsTsrecrY>F%`x!&5 zU*LzUZWql&g!=AamS zh`wSyag9e2W*Yd3;=3t2r6Z^a_i`<{0vxNf0yM%OiT4c`pzvQ5{CUto_HAW5zUuKH zj7X-dr@CT(CSy{ys*v#}-V&JwGyBf@7PiCEdhG$9sUn)%!|dqsoJ7C&xx2ir|+je+!2Luqx6E84StM}y%+GJtus zgoTcMjLMAFnk*k=1J9Ev|17@@-9J(&xT(S&`>TgPMjL>B+Ft7ACd4nDE5Pnw5}ERl z@j_qEhNj=QX<0v(fl7{qpSSeHnc#|kYa?Nn9n&hy^-(-*5O^x?q58!X+g7*1gaz*8 z^q)*g?xp;`4AcMvbu^i%0Z)GYXHcyQ8JX>x&H6B zgbCU>cvvuWmdenXpImT|ekA0n?IQP_JyE`8D%5!O&}=VTOk2wG9U>9q8&sfTIQHo| z0c^KobygE3S0m`Exk3a;1Q{P+QfR|?2oGmL-MWu-aEc}x&_D=_+QGlN?1GaXM1bz} z5|VdN9lK_@f5vhd(LCM^O)ykM(tO65_9cjV^As((tgvbNe$;x&^jGe>o zXf2G%?`4J08(6=av^3#wDdNQfPYC`YBeA}vfng8bz}?q^4*YTspH03E6DPHkjdH43 zk)#iMX5`bIXN4$|HHPxQ$KtR@Lfrl*5tduJaBtmoQGVe}&}a#z+ik2cfFPxa{x&efkq?J~ zj@}G@Qfo2JDQ|>cLubyeNeRu&^$NA z;TBm8o38;rA6@B{*&2vb=D~#1`>DQ)0RN1e3nR9_7oD5%PU3ydx-Z{)Znz;3>S-d|_@K96}3t9SF2wk1dpwZhO~Rc?*3DwdtG0L9irG-HdC4VXl6!LS-AwcN}7tz~nU)=EegKNh=3vP{R_xo}sykyPZdEaay^7+AQL zs+zmt^8=A^Dp7^dAp<0S_hzw5?wJxFHqZm#OV~jX0A?oZ|2|0{oslo0AfvNLg_qq*4dzUkw zXpVpxe9)!9C^Y6om;xlC2I#q1VXWg2NIXqcYh@eRKQBEDh9sH5$&1>`w<;IHT;;NC-Z*lejNs-lXrtpm)f9+N^Ai>&*yM{qyBr zbINeLb`5w9ap5+;XMOb7wcz^5NJ_f|IHF(`q|fjp@e;;n**XI@Xm``$Y^R_zF%ZPt zw)2}bobgc@y9<9SCZGM)F-5^0hCAd@xfpvifnjiP=n}v4f6n8Qul2B9YZEuOM+xuM zsDg2VBh`!%qFUN&$g;di=dBL52vJzQ# zx58Kg2WwpD`s@l!o6rO>q@7Ir$U0NlZs_aOGZf;C(X-eLKG{4MyUb$D!y~IW z#Ok2PmwCC%!>IJ+|B-anVNrEWToe$IZdke-BuvYl zI~M>`^Y4qsMn`dV^JQRHItn$F>gd1J0BizsIreqOLC?HsAA1`-Yu|oFKy!Pgzx7Fp zIX=xz0I|h_?;B~4Q_|z$_vXc{^_mXq-3fwiV~+Btk@k4cNUJU(weWz%&CfdQ&dgJScK;TaY3=ux)3*t0#h9c&0r@BDb-)l-;8KAkZecd>~R z$>ZNS3EpO}=U-hcFef+>f?GaGPY1tOoB?MgK65q43P!KG=*&xG4Mm$X(J%<3(*aOxs2sNeIMA3CXrJycvF zTSXxjxR#(_lL9>UYY7vwwD84#T~Nd?Tj?6h=0DsqEkV;=EW`I?wop-uYab>gv6CiwQ@O!$%WjLW6uM;o6A0rJ)I z##TGbYobXie&zmHAsQ6+D1Fbdr zgCmu=;01@6q2#J^)W@L-$q+a51aH`Gfxo{b!iT~>()>gASo<-KxcvwD>$o{S2}}tS3s3MwIpwo`8Pd11=j~Rs?k|zu9-A&0w==*SS#A(uy@*$9 zmE!=@b5JqekLeYm!b!DS*mpopado@|pSPvovFeieK`Oz*=SeWW+a6~8LKpAH^nrnS zgew!qCK-0c*OZOpbNDA4a+|WJBHW+^`|)8ztFfUC@x>DlvBJ*U*fm-Y zwv0W)3kh43s%KEA#(U|7Hy0FbHO*knV^xJ1uY(t9-c~fKaP>bPm`mKEWGwY2Ozwnt zNsGIELnAkt)n0;+Kg@#@yQQpK zTLXOWITnh2Kk?^%tnlr+ao|;wFFKv`K<_cJFgo)n>))HQ@Hf%+jp|V--KiD z9^HmH*R{vR#R1@>AgqHj$J849pv!H0e&}{7wynMi3C(rPG*cTbe^|hYiXy%vnfeXK z>%q~q%kt0t=zg(21I)q*-~K?E@UjUogm~mm=5~0WxSIj2Crit+#yigj!FJ~tJkL-c zLofiwHr*5V-zdhuu2-SImzHpJl@{*!YYxLOkFVWkhAV$sl5eyoIBerS#g{-0Ww!9^ zz2>-QXc9;+O8C?Eb~q-EGGhZ5Gxf7NxVnoJbUcpn`aD}S9Ucxp%g2fBVoUMo&YN_` zbrSSGXyCW5Cdzq!>(3>8-ti`k=`@60?WTnqq!kJI_l^71nd5}LN#OG1h#3FK7VBN( zVExYh>?vU*d)EblOX?clKU0FXsxr9d^Ehb7-D9YA^E&hs<_Ix=)UmsT5&Wl(@A>^Q z-qN}SBf?5q8F>tE44kCQD;U`MKkr^L1V%SXPkni-*tE-8xwjkkHp8)RdqcZttzt>H zF8GvY#rfgm+4OUiS$fq8b~RM+8V_^4q~!`{gLK5LLr-D-a}f;c{e@RsEl}(JJgBQp z;e&@$&SY#d{9GQ)6dA^7*gS-Ix|e+OMi0Vy=>BfLiuj1mSR6_kKl0!>5GGS==mcL} zHuK=s-e{Q3V1aNd_{)4b+IpP@>9suJCEa-!MP$Ikh0o+W=uSQJ262B`SJ|#ueOzVT zAL1@$@uVCN{Ion4vX6CSLwETrF4~P(&iOWl*0?9D8$_RU;&-l{!`tug!_o34mXf1| zPvv?ruW2W@BEE9hmJImS-(Pz4pE<65oJ2Y+L6}!UTqy6NGkU3cDuHl&*B)ER^d|0tE zo5hibw4fXHwovBeXJacoP(2RjZ8DIvA`d)VN%z*ZFIiwu!kXsyfaaxnJo=p+7g|1s z)(@T7y|G&rQLBrTJA7pq6P$n20(4x|_+xq=0(;Mgg~CCm`;KyH+Kqw6ZbiI4gF33{ zJMZT_S^DOI2QK_Uy?Dt5!c7A`^gHVhK4GKz)g2WmOTGhlZxpcQ6C{|D<_>j5kN7b| zO$_g%qn!CyW|`n?%@ok?@SJN6BW^l68M1cd$$sT;c}(j~VgM`=`-hx&lHyUa{rFX`UY;&H1&H zd;{?yCDxPRQrk$WY>OQZ>JkqHYDvQM8Y4W?yBGW_=)(JKqduUz7>GG#%B;wnzw>h! zhlBKkyQ+n-0yV{t zc@mt{b3V+rydsWqk>HY@lR&rQUUqPl9v<2q3BE74ag~)GIG$$mxTm?&=|){JZVKsP zX8ojIJOgw#_JFQ^2JnNnXYq&8J+K&jfPKvBf;K9_Ft)szSKXIjW9@u6*Ze_Ru&ifr^AOqd1eRR6z_qDXt#N5wStAX`BH~(6dddEnGZL2$C;md!T6UU;@#gR z_`cU!C|lw!M5<`w2uB?l{3nXL70?bmb3U9r#8~PHV=Ng)e9F#mJa4Eij+z(?OP_2J zcX)f?4&zwRcRI>W$aPV5q(59bwvXT5?}9H3L&08eMzFN+aa^c!5!`dKg^KUg(GzY2 zl=aK2+%2(aLMC_}zRB{vEzr_A8Lm%T$ITAf;>gG32QhEM^47PJzpo`%3!H)=-ulY>meE2SL>D=e#HNgvKelKuC0*IA!p0^a{EQiv}48 z+TFDAWupZQTDgXIaX*EwCq%G{%9O5&+N*fgMMH_buO%In@9xo16J@~NO>A-Bp*Yaj zUCatp$nX4!!9Ssd3n%E#RY*DEbtA>tyQP@8x(1{He!^dCeGCq_1&4DfyvY4Bwrsrx z=8~bTGtK<#>JuSnNDFVPZGoBxCc#ppqoP20Yyai%NyhAFjvI9FRv!ji{MYfKW#)LF zw3Pe%J`7rKs9yE#p_MGp?~E`jR~^sf8^QVk{(R@e%jo{_7WFWevLEv($5nd@$op^P z=jojtWj+}^uQy5CoPVR3@WWY&!$&PLM!)=U7#aUvoTc9xbxu-NaNRhzyhs~QU88@K zdYlK(HO4k(POxJ@N3nI|Nz94iN{vmQ%@$aAVm_?)P9=|+1r8ZG844<-EO4_CKK307 zo|j(mS6z)MXDl3CAXO}V8;F)ms5|V=IwqN{je*(DuvK>px1G@mU;GLozEvJPS>p`O zXs&_*UU`CFTM1r`&IEklAiq>*fzkt$m3i_9jrDMEML+n|Ba0s*Z(1bA!rau3?4IbS z$XGsJ+3`JcgB8khyFqY-6Q6$X9Nv$wg>^f>u@*Yq#oI2)0PGOE+9i&UW*@F{X6bpYBDf!lEQ%!MfJ1gj0 zqRz_-C79JI3wA{wVhzUn*rj1Cs7D^=Y@!X8Q|7bX!Aa84Vt35=8w-v)1wwui@$aNp z8Dcq>tB*d3?euHma^+UGl?-@JRbW+_5|c=J{`z-rO}q5pw_kGk@>OvcWdcvRHU$>@?PHU#>0!9M zKg2uj;KERMWe>vrtX%1(y@7bmmoW3CKUm{EeVljP19qkk-~%t8#d7HbShMIL8%aF7 z&URzy)`0v{0^vf%S+G3)lk`aGc}3T)X3AW$p-se>rH_VJAGG-0LvGmV1o5HrZYaGIsZJAl=}$vLI-^GO$X9+NAqJQ67-yt1vl#jwkXvYo$KPM7qx|3 zr&{BKrF35#wngl?#0|f0rhdlD#Y`(%7n2OA4`uOwKDy8e8(Tu)lYCn6q?B^B>w6Kz z_Su4<*%7-v)`OZUUfi6%lguAkuvn#rO+j;9wR$q#8^4|>f40V|-f`f)^`G?PD0Nh0 zfv_?|RdMkoW$MzLclCAPZrdo^T;~>4{i$W9$=cXY)e2JH9Og#M5%2kWz{mxk z|Cl;M$@l7$rdIVV)LLd>dq#NwTo2=`@&gG!rJvHQIM>VF~bY0EnHHCG!GD35)~oh`ih8tGy7g~EOko>PS$rM&(e~dZZ;@+9cE-X_ zF=ONeL>b>5D4zq_#uz-3txOS-LxJv)tu)9(*+>i}!qaFFf}dXuC{)7-H25ABu* z@`a_H^e}mPXLvShEPp{hi`IuVbk9x&4y&#T74h3eZZZMPBSR)s^+-V}b7JT))Y#=x@++oUeL zrz@t1tXA&x*AJLu^c#1`Z#Ci}WtZ{F?%S{??H3EA+}BSQGhldXB|k&6-KKsjtRC85 zD(hl{4z}^IrzSy|O1{YWd!+U9?7}-N48RuRj(f^X*@FQF*f-M)K2$yD)2Ex@<{>Wd zPNhO@X`)`Xb{tA9420`LC3H8>g5w8#`DNM@mNZXQcE9epLtSRH!`Hvj>tO45wzQFWOl>dtoHmd< ztvHL5GiyO?KFFSDQx0vdF*xTSzZFNm&XNT%tnRbaJ@1_2>?<>+?{$hcb#SDQfXEJ- zJYkqCT5Y87A#ynzS}wtRAA5po!(IM-nH`o-5n#S%kXUs~#4CY!A@g65u%Mk5me(1; zl716-*WrYjmo5OczA{$4i@LD8#KLZkuYA}9D|9(T--GrR@qrQLs0@mQ&bGzOwl86Z z-8#cAn*-eWp#u&L4S^uz&8ZnMt{ zbF7S>3hTW$@PGHMFl!R^6g&QtF4?PwrCS4GVG?EId+6ZHx&Vj`bKtvY9mOiwTkvXD zExSf@euAwv+}m)3w{5b=)oLDaEA6BF=nB%({9FKQ*82+$geMnPPKAxxv3vk!s>qkd zL5X`Pa}J<6pE(*r&V1k>t0m|V)C){*ycI1U9K(IjYhZD%u5jK&8#8ZMLCg2GeC)Xs zxcZ9%7XHYT{u#MPv3Yq1Nb9VoSVrf_2d!z)VX-w|j8=H$R2<~b%x1TL>EP@AGWhzs zlxurQP#t^1N3|$%>D*(uP*DSXU?*Y4CIbXNM|cvL&Np>GiOpq1ZEp)<#hF^Tz&#mk zN`CS|TlCgZ4-EF>lmC{Sh)yRIlgmjb_;NN(OhM9|h^^saD;r zu#!!EdsE?^-XHg z`<3F@VHeO$rtbKu)Wbfl57-y}6r*?h)w+*d6X;KuML8U zcGhC0{3537-G=9{LxucH7PumJ0kHAueAg}uT;Fv%T>m1l@Jj|5sTd0O;V*dQdRP3M zMS7dnD@DB-{&=OBFdXZ3jMZ!7+lg*4>h@NiQt5*o?uA0|?lZy8#+7JNP8}SXdBV7E z^!&eB0M8m;$~~_T4>)H!bXUE}mOnPeox!6Z@XQkKE}{3gp7N1yYBKrkPKtld(Mny- zOu`>FANGeI);4^5PsHSO(({-$vW+s*#-tg-t8u&eplAt>(Od}Gyt8!eH*?f>n+B;` zA;K>e>TS;%4(p2|c>5q%^wNlftMvoe_GC@m9q$X{8ymSrcL!u2WpK&qp;%sa6h~Y; z2R4Vah0DeU_%GiaUO!*WufL}I!rX=MSwh)IcPMl9WFn-nd;Ef}6>h#kcaRz*`9*tI zy#6v4RR26@9Z0v?{b;a~hi%jKH=ZvbpONoWw#8?&;zHSBWp-KMX)S!#VyMhIp#KT( z8MzQ#rypkKmEPiOZ7k-JIfjELM8A8)M=mtQmcBONIdr%9dXot@>&}CGr`O!MzydG2O$Vn= z>*UXg7aK`hvZ#5t*^3w>bW!aMQ4{Cz(l>s1=3fk`?%5{2<}pp-ldxK;nIH4b6hHa9 z!?9O}e7Wmo%KEzl;>llZB5`(h`U@ef?IpfkLcB@ybjT?lAYGwDdnVm|d?FKsTV_W1 zwJ-vFWZn3+4*vMjjrh$H6L$EQgnDMXgGJ3(e$~nhM?||r=QAh7(1R6tw+)Bzt@?tv zm-ax}La@{F6QCiND&yEccUtYNZE^)$Y$b7gyl`-8%U8=pbAARR_}} zP2lGoS}h9H*@Cgk&sob$qkEL@I$XyQ2&$5R#B$h z1M4t2+j5UD4)`x?s4pzs5GFd({3$Ft4>lS;LUOAX#&$P?1m_q&`kMqdWG@7Rgb;R7 zM<46LqT$4iM(RMM8Inr*HlJ3CLaqxso5aG`8%J1MZSrrf>jL|F9ON%wIbeQe2&Cpt z4er^u3{&o0RQjY!u4v$vJGx39wqThh&QnVJvj&&QE>(u49bszO-T<;EDeu@7{gQ^y1RX`dND zeFQt}#Z=8>Slqn^Oxx-T4TO#VU1AO4%h&PS)LqhR0MWg>GNkcZyAflUw4>(erzF(GRollY36?zG?RLn zW$bwy13VHq46b&2!JE@bgK=UMl&)SP)_MBjpEAnns$9$Tq~tR)^ng)s3;D)hUKk>T z!le0?!PcRa-y2p9!#vjr`-tngY`lo>davbE$nQMp^h|g={}yY|Fh-vPqhL+Z68@2V zYCmZ=9+0KU#+v&oE_H}j_5gm_VUEMjcZKb)4*bbM1@0PD3%+5E?AbgmJj#uLGJbjQ zSrYtXzX<-m?jo)JXpUh&r^8(1P+^0+KFWR#ftfdY@mBJiL^>XsbYfTj55Hc;5FCVM;#>=?AkEB#9e-qk@)?1!?8XP~ z?QDp9 zh)Sc^op1_qsd;dmMP8!p2zzg6b2^**q{y+u@w>2j8e?D0M8)!6my}q&8l5kD)-QsL zw4372brPJEHwzN=4l;E;ee8W_2wZ!+VNT^Y}YLoel2NXxf^t` z_?Rcy*YxK{GpcZKbUnn6J;cmt&Nq)T1uO3=UX>@ow6}}k>6b6kf~qRTs#@ZGT2vJ~ zdQ&&q&Qb76uE~d}JELJWWkHwcvLD(G_@>t&$oun*4^Fbf2O1$TY;LglQl*TZ$;&Xi z)K4(o)*j869<;BG;u*v*t6X0M#k)h9?*@HrHjM|(FJDO;se@XSjn-FXm8gHi2@_Tm zf02BIO_`&MUdG)Z6!pj!6 z2jZcBuy*6`a+Pz)B z&jO9j-=%AfUnsh)cU5Bbo9qp6TSEj)o7o~>Z1u$|+BuuD#xNP>E#y4+g!qrA`L=YL zt5(6_xz$SC@##E@nztc*Q;4vV?lPOdE`lF_=X1x~7I-dnHW&^JVWWEMW54sml)L>S zEkg`-?gN^`(nO~>zIgBiVS^*qvZc#(Fmk^qc)!`kzqj+o`Gf+|* z_AuD$CJ(0jQS=oXa5}q7{C3s|lmE?w4;^3gd`$Z-eucJA5pi3vUnm!1v>(d@Y_qbJ-h|+<{dto@QMV_6qqx9ur#58X7ZGH*f(dQU>RYE^V9l(M72Ag810LwNq+Dv z#>{P=DZb6<0%4av@gM017!mIbSB8{|dybXi^i3SbnClB!H8!~ERStCj)0NBV99b_( zf&BZ6nIhB)6Uobec78;3Zg!2!@Lk}dV|2zd6dmmyem_81x7zSe+cXP)w@?gFtKf<78Qinoc zCD-ZtyO~vt&_!XF7etL3z(b|<_g!wn4d1=knD4W z`485`PQl$_$kao;?NS?jNxspjTgkzp`DOT9^%@w=T`Vjese#^R22j7*laIymb5ym<89f@syK% zz1$A=Jw3|5>)2yXnHQAb{v22tk)bs5W^tmm^goxqaXb5P!Ufz(KCr{agIrZQ*v z9{tU_^(l~mcKj##ZrW6nXFqol3mK@3(X+x})W-_$XYGTFJ5qPylDT5b{r^kcqX!}u(}lUQ1P9ty_nWp|tO zP?DYs!+UMvdIv4A=4}f6Q~N1>ezrlO^2Ak%!$c0$$6rCcp0|uw-VnJkRn(x*e2G4D>4!C}na-fwv)EV$C6fg0i9nvPR@a*Kew6xJIXB?GZ-w_Ea2PM zJL1cZ2s}<@mHyEet&Li98+ZI9XE-JfmM(8L`Ie@M>x z%HzqScW+W>ILNMwudf$lVCx0=FGJpQxF-HtM*IJzWqf026AZaI750p;&VpV?Nv>v|EnFwEZALGRi|DEq~FtjR3nkaF?^b2t?d*>#>FNpfc&M>HUp2&Zb zckF##J!LFxWvN$eF!ow!s2ci~|2}DnCwjTU%ln7KM{f;Lb8QAxnZ4$#xdnwOlIQF4 z26;-g1&&=D4@;eHv%rh`IH#dEEZva850Ia6Bxx|(Y$}x2&YrAza6eD@ugfW#_M(6G zZqRYNK9@|CIs$_cDSZ}F5J%Q!DHu2uwB}UEb+mI>u4vRS;2bP=wfDp zHyjv{%}c8}PL8REh(RIDqv?#I`SE2T_JW#Xg@K_G*^6SN-JG2vCOoh(firAw8 z`gmx{2xxq?hl@)baRcd;D%&oT&RF0>-9xlTt!!qR;o5k3lqaNi>&KV>=GcB`y^=p& z_sbU#wU<(^#TRZq9Tl$=Enu&}$oc2g79IJsV-Rr9NsE zO$3d1-zXbI8w=+RQucrtIXL38$)xSX!>k=~Sc&mHKxK3hKeeB{!c+D4^ziR zFFlZWx$^+p!6aVvUVqBxY1)LFeU7IY_*c4QPCFdh(iy%+sw&Kq4Y0mQ3W+=2`5np+ z?>O!WafPp#&QX9n=1rJUdy##T3~*}9B|S};+;Pcr>2O9DJMeM zILfA5NB(z>vUj`-J=;A_g~RL8cj8fB%4v6d0JqNT3;7lF?pxZ!yNnHd;w^97UETw1 z6I+5+K5bWg_SIDC9%CpEVa9+|IK0fB+x@2p*gX*{`(`tF9Q8hTi~!sB$GM~23kgJo z`eSLLN==)pQ@yNZk(9%*i*VGNeO=+%@cF#-eHoVLRzcMpU`C|je0gvNh|B-+*;5FU zOihKvmsg=@ITQ>p}z{ zx%dqBynh9@QvTRmH`-}Q6Fz*#Rvsi;pwrJ(XkOVW?XS|HxW1lryoXd3k(BusxU4rA zw`~z4H+$o7()A5kGMX8NxnT2>NI3N6ACbO|LCD(RCz#B##+Y|Y zL5_>~bo!pld!@nPJv~|7ej}_m9tWq}e&EK{dZ_!eH%xglM;tlc8wa1JJgYTp*aOOG z*}9f^#-bfu=aM@<#8B{-oesWp?G$!@{r~yAfcBF+Tk^r=qnfxZP=cnX(qLBbU6xCJ zSe`;T?M*BA>Y)y}lXM;SSsmEFa&JYHTbwdCGI=EJ(tCozN8OoQ@Cw`&eG3YsU$R?U zwD6CH8Jr2)$Js5?v8T_0)jh(5p8pK-k=a;S@-UL;u600L@}wV8@6W7sHL-_jAZQ-@ z#>?#}r<#0i|7AtKx^@)Jb1y?;J3ZmJN_!mMst?*fm+%+wTJhA45wh^ZV}(85Cb)9f zbU3!Eo|_R4@7!S`gwz|!`zJWyd-9#leesOd7-(Z^$8M1JeL2_LWP^=Hp%D48KpN8~ zU-7}}sB%7Q&!N7s2rD=cPV?F5H@3SqQuhAkDq&>49!BgX56+wt-i>?;&xTHf?rkSY zmp&n1n}Ry6dTbK*)EeOpX$VZlByL~-13jOa$ue6Wu%+!CFt(-#>}vO!Z_UuByl5+! z?YCX@>tldHx8}jJrkA`A?MqEV(r7Q;C=Vj7;DWFOxGuZH4mjyk=3yVWQISG9Cteug z6ASb83Z*LxCMgb$T%+VeD3rA7icW|$UpVc$0K81l=FFZ zcqzu6S3pfieSuR(bXe;$SgGBE-y$tywZ~i-I6H?qHQVCugA?G4ORvi7PTshT=F-mE za^~e|hV4IfhjduURl9N=(DxyDFAHIlZ&WJQ7+g{6TRJVX#vQ+xLiX|dqLgs3`7h_f z*2u$b-*n1j2^j^RPxtb!106`e6bo)eOQr2cldr8j7M%5(S#QdMsJZ0>Th9;V=l)h; zYtb#3Fl;A#f5Z|eCAvXw_xt?LWv&P}lz^|3n!=7WX_plVkXdBF16PpmhPZ6gtIOCY z;#kww$0_&cV$$^bR}O~Arat2Q@?t#XcNq#7_zJDXn#gvWK>g?#UNGW2#(o|qvx~A3 zS|{sZzodAuEcwD;4%EWNlEF~=aHZHV)Et}pIHAADRGZ&LAv;;UvC&|(=3khAy3?`Shy*VVh2uGxLx2E?miNP3`eM;U4<79hl`gFNI=5oU*4w zG}1#^A3wOZSHdUxm!pQ^E!Z>a1@k^fJaR8{u-4hnAH4sIPC8>{ou^wc#RJMiNKJ#% zxNyOnbm?k0$AGs@B!4>C9{2X7&fk=NEW$+-2QTdmdB2)@#&vysJvji@KfWl=3ps|H z7F>l+KlKC&d2-ABEMSGzDlW|YiFUn5%6w0Z75Wc1!Rr@i0%$zq+k07HQCK33{bnq8 z47SImPSn#n;TbC=-R9T&?(nx|1;4stlfwJ%QKc3=s#y;^-nW8tgGe=frxkNEM#)BN zlg{Uo9@^iGQDzdn zmYoF0Z`@_2qsd$JvX64F4!q@ww}!;R6~0wEWka&U>Fob!wN#bx@OFV<@Wz5P-pBEs z#RXW?`kEP1m*`oiWO9L7!z z;-NIR``ONe7hRV!uLw)Z6C;h^NT~e#!4q@RD4Q;!oEd%5#WA*ipx12)hlO%H_@o}} z*UH$SQI(1rZLTUY5Uq!{_{e$%^bU9^R+wAj7Mlz(oPC6Co~4gNnxbIR*?s)Hfju50 z3}knorBYGwLhm=!9kcTra||*;{-zt;@E*hOn3kjJ*PHOO&khz&xnw?%+`z~3K7U-* zuF9t>UiS844Kte{Dmpky{-5i6kIu65iSY7=0Y5d|4z&m?tC_is1+KNmkC}tO;La01 zb%z^%BHzu4mA%E-PNis3dIOrO0)(x@$eZ8I1k_Zc`O^!{II{n6+13Fz!nr7I^qw0J zi9ug@Ie9U>ERvu{_Es@Bzz**`CT+l{BDRz8v5{(0s9kiJ&nIlk;xWL~q{QIXF=17% zvlC=mKaJtdDRs2)1hDM zB)()6;Vrk4;KqONL9S2Uv`bF7{s42RyS1_*?S4v{aGiw(MU} zbu#%ENF&OazJqn;?XxwtFm`PM{TG}G$~YI|D5c`Y7zl=L1g{!#1^={Y_9dqKpL+dN6l8y^fM zEIQdm%3!dx0VleJGfyqzE*Fo5{2}kS@W~QG z`_dkMI7cis_QbBl)0O_tW7l5mV1~pGR19}ZRDeI$oLI zJ37(=&-53dF42YO94x^f8*jiB?FJVAMH}n(N??uoL7p4@7iWizlbQXrpd2l8jJHpR z^^p<6rviN}ygvrk9_h;)LhUf0xIa7leoQA!6Rq2Kg{33D^S()X*y)cy*xtGz7AGIW zjSkl#r$k>+*{F`|))|7|`W#+LnOA?BM#-$cj}tTpnPASL+3-U4m{;_$z|6nYhgD%B zU+is%)g$7do%%E8*-sZuPD-ILb2VSru?uF}$HEh%Qt9;18x?~`A5+fugl;CZt2jc+ z{tnz5e&UvfQL=dT)xx*4dgN7~1kX#$cwg!+Icby(drwV~=A5&`uHNzR?c7Ge>$nlB zyz2?I6_fZ#yDqpZI2Ot}+Of2b_Bd@g^~7a;=8xLYo%FFQcwIdxnh!O_+85biTHVNd zbs{~+jtq#nm@l76JaW4plVIc1d#w9veRLwv*S&{neE4AxRG~R(GIgsoOEp=MIBTt7 zw@FPgNG8DpiGdJ&(Skcxox|_^KD=Mk$_hS8vEQNnaOL|yUQ1`n<$3dA-;NPd?IctD zRvHifo8p9c%Fk@bA3&LnL44~L50pp8LdU5_EUA+b=9UsSz563yT|_zFF9Ko0Mum9y z`7u1%f^em+zF-t)g)vsSFejrs&pj_ek9G6GLs-Vtv<%}(Oro{xcnb^G~+*S2W&Ef(7U&XLwiJTZaz3n#~K>|K*FE`HV>G)|1+6B|l# zrRptM{dhYotF^#?SKQ#?uzURQu0J@da;)rp|0`@rh^RQ9DuHBkHO1()7Pxp}GW7Xk z$aP9>v1mWxq7KWL{&H*F`H%XTT%PjBt87s&2?sw_L3~?v5;Gg_gL6p_p@{h3d(E~m z=jC*s_DHkJ`^8L|N>qR_i!hwDm+>%S@fW^#C;7DtlHqqkp%_#^o+H{7HFJxY1@W!( zOc*>IafFXFcf*?s^6xCo2p%`TSC!MJiL(4mV`!Vz0XLjCfqBfA2d3y_)v3ua*M2Pz zHJ0Fyh)GbHroxims9?>5|L^D9dK=@aqrKo(tS`Uyqcd6)hAcEBu*KBt-RBnN=4~wH zbBjFDcvvuOy52@iAzbv-h74#*nZn!A9enuQN$}Y_jBWT%KB<_YurTi#?=y~k{Z{{< z?Q?H*#{By+@N{H8+x}P^SD$ktefTCmk9c#_vTEq&u|RreXraQdPe-s*QBypaYk`Tg z=0n#EC%%p5e5Lbb@XcPrGM?z-A!$Fb?s=M6YeGdlkSRqtdQ+#&BUtNknU~@IdDWn$7AWk!Ogx3=GKe-^#MhC2 z``I;m&a)$!be%E&qFla|UQK)~=~C`(i-l`za>etF?pW$dK9tft_KmpRU;F$)P~Xi% zy1C%I3!%zg{a*Dc9PM}wA_lG#eB8ZpOQ+2+X`#AkLVI1VUKZTxSIe$mHODmDNuZvz znm1jx!8dww@I6O^9oX!ln5Gr4^b>6$Om7(Z)L!1Q+JZ;1x!)7bcomVBHPg zx&7diCg|h%`ILF6aars`@2PoK4NMtoB#6Q4s2*elOB6ZWg*1>QHFIFrnJ4@u?HjvW zC&Beyrt+938&nIAgVuzn?2MT%w!6zkv%~XM!Ej~ZXMX9N8K#%G!fxY(Vw|N7o_w?d z<{tmcn}*V^`zRA+*9zn_T*(jKc?!(+dBAqX>EZXk{lHn0#&g%WWBY@YljE{gTI-mk z7}>m5Fgv2AK*G;gn0Hq0>OGF1!@MrFN}c)b_ta~Db2;=@zstK9;DZNXX zGhWN%q5N&EkZ{lhRa%F`=e8j{H^v>uB*(%meIw@QZG?7hyTiT%pLqE;;)A{f!VUw4 zsDI=rYX3p_xJFNSLVCPTLvsO=y7LUuNK}Pp0dJSfmQS`p)#b5Z8yHq8%X7y8G#l@3 zE@SJ6M=nhag2CP^xj#RR=M?qOqaU!VcuH~A`kGQ_UZG`;z8{yvOZ9rOqKhSNI*gMpzg&I}by=Thg{rrV3hqUnEuLNZ;c7?eGj;Wsv^2lxCB^?{|quKIgcoB4aTUf;|=t? zv#(R&Mq*oby1EUT?e3<;TP)&rFsX^botDt&B?E;UT^7+W0J~%8f1mxR(2QT*8s^~qjqmsM4xQOyRL$bhP zo-=RSL%Wc4sRBS0XV8(EUY+R$qo}HGvt>W z3?jZhGp7W{CQ*lVxQx9MwNOQt4h}*)MTg_$pPifq@b;9Lm}G$-FQ&kteuvn1Yh4^s z)(_&Wws2{N8wyW}i_iQUlz%q>*X<#^bu*vL^Vy>fy5+{!;H^v!(BOp(`EnlZ_L(d*Ghm%LK?%yo1 z!`l!T7jlzpzOqMaZJ<0`Yf;aw6g8}?Des+f8m-6+R$3J^4+>rsawk*0|v>x<49s&SU-EbkV0xAh=)I%~eZWNPpW4(qEhk zR{T4G&Reg7d)itdxt@H8$5w$j>xW$Dk_0CXTmTP#)UjIPsWW>{fufi^e*A$orX|Kf z(?kt+=c>CRdGG({xl0~(mrDcSP6taqYDEcdORNF${B!1VMH}IW6>&_5c=Z|?^{*X) zlg`tm7uT4hYV&+Joz+M9W=LoE*eS5#<0!7%)&_m|QfF2~B=a4qi7#uq!;z~$xx;fy ztQyq|e*CHvUq+YUyskB%S!O7lS)z@e6RcqV;nh4d*94z^OoORz&v+DNpiR0y1$NIi zlY5HR=o}J9-n1udm5(lZMgf?g&f`}r1F$(O7Di1dk+#{sLGgA#iE^F~rfgx4|B-av z@l^f)zd=Lx$lhDSronxm*VT}g2JKWvNLkT98I_O{ik3=ySt&*C`@S?k?NF(-htkkq z#P9XH-~asMxbEYe*Ll64)6y0k;}rP}CE};<-!9<|hh1d3YOy0tSk`?LwA&?u!qPTg<)wrDC)>i`K}RGdO@^5F zY6E;1cXD5v;ZwdO!^X1hwH0*!`q)1THU>XnBfhF*>CmZg{qidQlX}YZ_K~NxW{1dS z@cdh!Z=CvV6UJzjIP0*97df_*-(nb^S?nf697QE%d@XDE}$D+Rin z&l0t1Y2ok#A@F%skg$n5Z7V(f;o={G4>PmH>9niNJf^_{rJ9(k<^e&)pZNmf_fI@? zgFcB;Nq%D~)~q`ZU7#k!kx#reEK9~?u4~gr|L7F>+n&j+9gT41GTLcrCvT0j#aZ`A zPw0J;^|IB%n_E1<=lurWujvfRsSuB8BCtCyXQg+)-H_oe{?!K9@hS`SHawIlj50v$ zvne1sT*lI=543;rd@y`>gjbNi&x78}MQhSURfV>MSCF3h-dAQ>tcpd=ZZKIgjen>v z$D4cVq1AE^yQNRxkJt_}H{a#9WB#D{WPo_A*)>+nYNRJU4B#2Y)YLzS?k$w;y$`fp9`g1T6x!93+y(35}b(|Em=6N9KpN+R+zd8L8)q3u)z#m zg&4kPW$(HbELObuqm!_EyCRON4u|;`KlmNOjVDkim-e*Xl2fM*(VlSr`FNCFe5;Jj zzX6`sl<*;4miY1GWN3Ym;Cb!70&3alL&sfbzPpL?Hd~_M#Qi*Ozk_CAP82-q>cJ|1 zbx9MR4F$DyIq6G(4ScWc4bC$hxUnkDs29W||60g~B`cxHRvY-BQ^|*!+hU!DC(Kmn zsx2$g!&3JY*ijJ8-{$M#mZB)A3>?Gmh&6ENcR%R0_ZgQ{)5d*{A8H6>QIC(v9n^ z0b{d${DhZ2-Xu@Wiy7V7^vjQ=yL|`9FqV$}hS)(`-@Ci|@>$buFtdxg8jEMJmJxdB z7CS;Vw;v~%;*4_w4E8aUT-B<@Sl$3-ElfyXu7e}oGvJ0Kl{ZK0V~k2FTvi^(UjNd- zrzb*Wdw7DQA-+FLoyEU0B!_)%Q0)h0#nf+NQJN~4;p_%e7w_kuxu&RmUx4t3Cq2*V zo<_}&*T5isvv4TU2*>Z;NLtfhwT;^-H_0It9REFHXZ}z=WWOj-G2hI~OAOI4Di~gB z_hHvZ*hxcoEtKg`?vGK%Oh;FEyx4$`-Cc@o=N%Z}`GWD?N;qJf5wOyuTz98{QvVZ> zH8fJRb}4ybf|KD~#yH{pXg&P9CJIJ{&gMIB8sbLMwT`rrrLfo|=W zU50pWS}+KKPnnzo^+M)}q10iHqb_bRWK;`*4)R zn5{N5K}!<`KX4b)e~9;K7upm75KtZakFc96H!cZVn|X`wVDC{M;|uIr(V+8&gZv`B}q&^(RK zE!QAwODmf`(geqQ~vSh`8X9^1~D$~ zV}o0Bsn2Vn27BM8fjt8$$BcZ$K>wGsf+GyOc2?4Tb}6o#cL6LS)r1-)1FVeN0QPG< z_`#kAxHuyf4m{3c?rMhkJCi(^Y*fuW>P?$fN0?Pz1&hwt#I-J-5Z$?f@0oK3&-ZHv zi^T%lX?;f8IrOIR|NVDT+Pw=sHiGq~$C81x_qshzg>w(encHbK9Bms20Vj@fg}sI- znjH+kJ<>(R^KH;pF&LQWEBkj%1xFgX!-1G-TuJRTdXIkqKhEuE-K})7cgg^8kGsdm zID6sNW2G=I%$PYtjr7-X16b`XFTF`~pfNofR-Nq6!_5q_i{6h{&DN8LNDGJLj)j&j z_xSw^3(7g1B=h?SQ_JzQxuKUp?v@xu|X3$&A;tY+8SRPjIe!C*Z(g(pusgWDh9f`4Pj zviE|S`NL#hrF%~?x9cRX=DyTu(zahrExUY^i-uguy zG~@nx97}S-P~!WRzU(Qy9i)n9Ckz6Iqht8w>@tkdzYNRjiRH>d|nvwVrQ^ zFhy}+F}!s)6*6&~*qd z+$>x@YlKgG<$&{@Kea2HsjDj{4O|aBW+Qs*p>=ySgtu?zR%;D#b{xHfF85|z3T>r! z!J)GLqg5eVn7NzkVMy;CTv~!(|J;GZKhK#}tP*;zH3oUhW4!Ae!`Su{zz#-=0;uou zU3v;=y&o^6c3#Ey{L@W_j$p8rJK1|A1ACQj!)aCOk_JhU+OxmLbiJkCLjH;J9KulP~@WqE7aY) zuu|NfUo6xOQNx69OTlT?8UA#e9{K2FpwE(}A_omaEEpLAIB$z!UrF~sun*kNkL3Hh z91+Kpo@cT#JF(RmV;c$oyxGQ2aq=*(wuI`b`z4LEyY^n44SQ#I@-Xs1Y3Qc`+q<(? z%|{jCqs%#0w2_5g&%eYLGs7#qKCF2QiUCPvOd$ISK2r~-wnEd zryhZyQe4050l04Y!&Hh)aGYc_1YBt5tLbk&Pfde#xw)dME0o_}8wQKhLxg17A%{%z zgDFE9AM(fwb@o$sin<2#d8~nMhdkkd-xt1;x@#2%Q>W@)iDXAmDc-n#5sLe$3t@Wt z7*M+bu4a4iY2?Rwx*?5r<_&B%&3Wm?Ab9?JWX(i^<(&*v|e>b*2jrk-#H7z z_bXy-_7eD__nWtnHYS|7cy7B_qC#iq(LI9U?C&G&ZJRP~e>wurMwfA2%6Oc1CJ3(I zNcVhKppMq&R^S`J`1jj=>$)9H5Ra9+B1|M-$)ScgkT2T8W6x1uck)t5%$8%issE&} zo(z+Dd0tGST)`?acwMmL=2IN;$1$3XNg=GJmNZ&p20-QeQ~Y_oB`)Y14nyTSY7-vn zp;2TSc%50woiCGD<>*q__joK@M|nP{cKAb>=o#1PrH+?Ij)AY+-$<_icEB~`f}s1M zt!z^P^(xv8fK|h`bN79NafHe!7=QGir^1qL(zo*z;s3Gmv^V6VEKP%#&9?j?VZy6b zYmttaWEvzO5tJm zde%Lz))K$%*v#w)D`FlbL(vd<={ptbsi`MV>%Lma8QT91ddESJH7D2}^32|%o<1C3 z#4Da#V&h-xxIEV3F?6USY7w_`GP9=;ma2;Lz6=KZ>%*s4ay)VedE`an2WNnWre8YnqGLx!c)>sevx81k6hn9fcf(8JvS zM#Fyx>v<#L!}H$)ESYL3v08WzAOF4!0cQo_oVzX#vEKlDRMzsvlo6C;xCWFKPhg+B z)NxgHC_MA0zLh}g*Pb*P7OqK@oa<|ax|FMV%X1T3Jx2wnxDACPr2Pw(Gr`y@fCsxz zdOmhOjW(Zd!hyP60m=+GFYL zGVMy%e_AM{0<5>T;x1w3*mdz97%qRq921oAWQhqyFCXJG>WAZ)rejbjM2Kcj*2S!8 zsqpdg1fhj^(r#my(*8e}Ymp|(G3Tiq9QOVSe{`(V$N9W`>5qTZ1h^MH6WSD}BJnKay)+bU=l<)JN84#75pT!jdt9 z3_mHks!4rSHsCh;kR*b*1{k>!j(K%)JqLH3QL_Us9X(syKy$;6JQ}?hJ!XpzYvD|# zIZ#-e#$W8UL|#nTW9D|zv-TjV=esfrBvyusW>5|r8?gvF*DMq)s5j*AbAPBFAn*ZaEHRbv(%l!;nWvzM zR_ho{RsP1ip7+Px!)}n7FOlTQm7;L*63iT@F8nbtz=d}=!oW@u&+bd-K{`wBs2Eve z_uCR5=#uWpsDcHar~bHCBKW*An}_B8#Y@Mu#rcoZn3h77H1_!|8D>(j-vE;)Z35Bu zCz8`w)$rqOa_=8H&fhrc;~I}(c(!((Xb*X~I_c+?ZeQ5U1P#2JE`k@|=kimpPNM(i z2XL191b=i_MbB(=h!w8!;;$Zf@YV@9_Q8PF^gbgE@iLTYzZ>=t#;Xty<-2sa>q^o9 z`vk+Hqv>orVNC_sX2X|3E&THdd)(BE`eCD{NsbySW0i#&c!o#v6E~;}OcDilPyg^T zn!`26<6yONv1HIh((Rj&7vS&_*7t`pt|NSJ^W<{A(!&8yHP=q-tgD_ac^~uyx;?CYFZ=}pY3tuPU^so-O9e*SHeCO17W4j z4!$bh9(jm2ynfc@dBwF*+7O{A^HGi+N1XE93{bu6z?GHtQ5v`mmR-nXX>GcAk-TiX zqpx#AZwu@lL;BKzagrgI?a`4w^B%2g_BT@*$6gx*r@fN--`-WIH0=(wC5&ZjefyzZ zdNTACZoTKjDJwGVlK|EI4J6fmrMNBQ z3NUpS;d`JCMigv-3dglP;cmA&)myX0yQ~HZL!C8n`J-^?A^)A+&wT`By~NFJ3?;5rx|%dPLTm&P&x4U z*q_>3J3UnU69*U1g4smb?~p!Xc-1#mRW`wqWiEqK}&EAP{OI@rjUGXGavth zI;m5V;Z*T!t|+BWjh1+58*WhBPI$OcLxg#XUBC!cZeZt0H)oLUM1H3O7@@GyGtjKr({eJyot4ZVcy*d**r`_RxV2XMUnc(XeDk^r< z#5pVIZ0-~)3=(VM3zNCfId~Mmyxam$627-KK%KRZSI6)3MDX+5XI`bRg=?<6!d~-Q z$*9~iJn-#52({M~z7r?4;o=5(@oYGMRo0GAN~ej3p9mK8>GLe92nK$4WX-rb3;d){ zU1lfBS$Gp=ALR{!{!7;L_-B7GajK5^pYj^kGx)Uh$j;lcomqv>Af@ke;LX8jl3J60 zsPlfh_bP;M2#!R| z<=gElar4nfFkSlqd$`LATXRIPSoZ_ZR`A4}g(aXj%aG-ts-pT3Lz$lBBF#N3-(^rf zMwhqlrv6;R5IC){o~2eKkEJA1Fi5H||{(3vbE8q6LZpzekbgCJG;41ci40e$6sp#RHWl0J6S50#M) z%OnZBqxAnhxyxbKk_pT|K@)%druUBL8@?@39lcJDg|#JbC9~+7tLU1`JGQWpSmLBg z20{Gy9o#FZ2Cq)J2YvW@QNVx#X;QJG46mO3pE1_-$%NFYj+_G4Fu`~Qtc=WJ`s;LY zlq>c7{JhS)Dpm38X&+FOn;|)pHW-c1QQlX{ZVfa=veU{4Ji88*S-C6m~* z1q#?t^1t2KL~4R>A7{e3pO++;=ot*^y#hRlo0i0=V(7N%5V&U#-$XumayF zddopObuqx7{46i~@M+h~QDG@{C_kOXa(Ym2pv646srsHb%_c9T2SCzGeaX3q5}f(= ziY#w@PqQ`#j?RX+1#9_)(cS8j_RbN@M-LP}lfQma`C?eR_$SXgMp>_I|C`DAhs^N{ z1cO}8M&?DH-`wZJ;cfLH9(wXO^|t7UZ(rUZ8lE*2b$1Mde#~H#)(I5UM3t{ z(jOJR6Boc+_>#MNSod=|ym2(FO{Zu1;=P4%vHU4}*OUCt)4f4gEuYKT490FFDD(MN ziRjefT&bUSrEDKgG113Od5=qD}w-SjF@JaA)1W^n3B`RvsJBd z$Y=(|j^`xq8d_LUnhDol{o;XpEU>@(M)=r#xb`_cJ3akZg8blTEFf1CCtaBfsa9+F z;t+E@@rFFnU$=>*?-oeEROZWe#M?^|%v{{!o(r-gE-Goj@D zZEm~V4ExU90B)-miT-M8Vv7C}sPhRE3bHlP66eD3(W5AL*Bq;8K7Z)0&W;XJ$C-r; zW;cD|o4;yc;Bi-&vHYAQPNxjz?p_7e`I^G`%?4X4?Ie}6-s`oY|)leQXlI(vORf? ziZMR?lLzv@UrCBXy71=S+2W05`NAF2hfH=0hn`DH_?&xmZwv~B}xqJX?$Gu`b@lMwkR&<5_!|x(E-Ta$P2jPHWr14(qFX=U` z9l!n56R$X*CM8qm35xpD>bn8lpSP05cBE*ed~^gCyU#DUlnpy)G(Gf zm&Wu$-qK4SL(Z)P$9}!p#)E&Pn>{^b`QeXZHE`akiE!$g3vUh^gjMO3FO(9*9*$Q= z?-F~+?L5OPyA4Fg0i!|ATTb#K!nIEG{Sk2ro!>sy>EPu%YbeJcj^8%b$G_bYC?9wt zvwWk0-;4s_M@kD%Bn{ZYt3EPJBRzc(_92Y@igXJb5o@%hW)Q1(27|C&*Q`coc2uiul{j^Ms%{3cn3QGe?sok>9k z{I0zq=~SS68zBK!o-bodsKX4InF;2dhxyKB9q9FVmUvWo6MJEMPr5RFkZi9` zwjnR!!iAK@(U%_yF~eYoV3?#mjn$7d#zM-sN&WnYCqB1F@!A>Ctz)pnUQ~i{Mpr>T z*hMgC)WI?HHbKMWbiSc?x4Q0~bHy!IgM<)mb!?PGKqz@^qk9oHTNMgxsxu{WVbqaC z_xY)T8=2N>72Fu(305VC`L|KOQJk(TPP5Dw?Iv%?`FXz;~-PAGP~0Cj8YC>%X)RhA&mZ9aa;|7oA{hvB@Mo7=Z&*1IWX88Gj5Zqa}O;opZfiyjFi{MNgoLi?Z zhQ*5DSDg_bM_H`h8*YJm{Cj3{gFIHVi(rKMC*DjrZTRWUpw$&CihHYp%gQ2Uy+6`{ z8n|}OT(Dm;k`K}`qYNVIo;a??(zr72i}Qe5_{eWkuGFl5u5iHXoTSOH9B;+mfQ$FF z1UDzr=O502f71jm)@a912WN_HUN01o?u}n`Z_GFLt{LfMhVk@%xx2TF6`xYV-PENO zl%2uX?EXd1i>`QWXBzW-SSfY;?|-v8FvlFX#B781e;*`G<2&(U{2cMfZ~4Ll!pU`S zE`n_yrF8C5`r`CAX~I+kRh-^N`OIhIxYiQ74+qAJ zt9v^OvtB8p?bUerx~-G{JgJ9AH4>rH`GDjQy~}2>aM&w4&N>#7e=u?^=%rP1E1!Y5 zxrlNv$FK8z`NiejXzjYOiiQL9@ zNjv2ID-kY!>&^P@`YrwQ!b7%izocFap>QIM6I}R*VFR&<_>142fo$szWgIif5qur1 zd10CZI@})*(c}9_^6Xvf6iknaziuXcf3OaA2CfC~+41}!;T5_M6G8s5FEjk5hNaKv zfO`3B-cLsh-yEI-T{@p7cSg|JpSa_=nOoQj33<#nI70scMf^~iHSR6)f<Z9_ZE-wY6KaNx0|U*%y*U@$D3y$ILE%$zV7+{nFll?97~#8>S)kbO zvP7j1acV9}a0|-vkBVXrhMS`KOS{+2I7<!iahd!z;$`enf+)1y2#p#y`C&Jm0HJY*YQG)i?J43go}j@12e z{$n7FyW5Me9Bzu^NaNRiyFb&3H^PkS$>4wY5kI10j(ZHof_s~pME-Ue7G>Xr=hxkZ zZr8QZVAm$-IWC=V4tK6ww`P}ktJzXP=a(vWosWQku@&gfO(BcRaZ{Y40!PLWfgFZMQ@{)b>q;b2(f2*hp!@ccs* z|JpGC^Q(d&Bgv4hByVH3zgXt4X*)-`&~2`u_pw~Ew7&{sKsxAaeBnwbDI3ak2b_zq zs$FrN^6}zU!M0Z~SiPwp_B#{~7dB+_#l1}N8FAT$ZreojHqMt?{@o(W22^>egFaCr z@R(r4b2G~^YvC;z>fOq2i)|>2bvGzK`^0_IHSprMC|IMqNH}~)9q+FRfISMM_?Et= zIGgws?`Snj{P)9-}u9p)t6h~u3!QFbN|4%whqOHSEbPRwjulH zUn$j|Y9zy=M<-C;li6#~>B^N@J*IMj`Tz9z#Y zA8p+6h-DBo3dnk8DC6E#E7-Ommb+XVie{Hf!8?65QzrjTH_0N19eRR2s#L)^U-DDf zoZ?%-9p}-Ru4JZ)Fg>5T!qx0Rem3xegYtF4t3+|P;LC#XOEs*~Oa^K0cAnR!kH1P* zf&Yy@EPCc|>1ahySvJ(xG3xlReIhJa>B6U!4!~KylwXk%$d=hTk#>C!bUb;>lNSv} z^}4aJtG<^+*V3&naLRG9vi3q4GD9Do1J^?V`NzL~)yKrjRnRnkGRvz~!}ZVRz?=Nn zyyPt9498A^C$()7hn)lPEn$N@-siJS+Up`DPO#8oH@`8+8aI#gf{Q3ZA*cwIn*WUMi@??4X`WfvZURG za`=;0L*w5Hc9x#CdGqGNu}k~-?Pfi+xHAXZC0{(ch77 z`8sBTZRx=O3W)nGl?q*mz%WksG|49Bm$WZau@q2c4<^`@=-#11=rl0n$= zz7wKV_j9CMPXBK{KOrrUSCkuUxUazv|29CK&zbP`!c8tm9M<>ctHJwHlIX#d{y3Yu zw(qRX6MEUHB3m^9w%>^2>o3@0p)?4>^bFbGrQ}uV?Iq(1OWSp^!^RcX?=O>RuU1C0 zpXp$J;tS6n?10_A>;Nz2Gquy{Ih{D2^z*^5n6njOFN7^Gosh+sP@Z1Nd)mPo3Pn~L z^P~xyTV8ozo*VNKd&}_pja#7Dx0Ov%F~UQ)w!+63&-pROe>hNoo_OQS zVeAO)2|brk4o|lTVURQJZ<4vdTSoBdZ;er{ALXQ3sIl!eN_hQ|CkPila>XBN*l6Gm zU31P!+J};7yl*4?IHN1%QO3wzyUnm*g2201{>2M#=7=YRh6}F`>S3{HF;p-0shQ+x zf(5a`aN41ajq9n783kToqqK=@kq2#nR}kf{pBLSVKPe3{Z;;{D^3+4^>9YeSe*Yv% zS)+#gG9y6^%6Svr^A;x;!`|l^qVZ!*@D_2tdOJTc^#|(s=F|vSYaPgMx47aMnk|J} zZQ0`y7T6*NXwLn>$GvmIgrrh9^2dOEnNlGgQeq_Yvp;`J-5=J;(0_~}pEq9*Pj_De zPOe$ZGm(7#r~M#9?lJefZ;LYvf*{%4PZE~sihDVA96yz^>s}ftuRIuB1|;#$Ch8(N zzY^}>>n5GrK)ttS$>8OANb)n5H0rKPAar&KQz4(@+nNb*HS08g`qLJz>8uo4v)1!d zvMWx0NM6W(DnjOOH8k5g5SDp(@zlO@bu06d#35rZ3tt@7@Z$IsxRSbqFOSqmqw-`3 zukFh+HvW)KU*ZW{bL6BGC#a$0*hw(uz6*cXVvBQ|sPDCRAnShD0AJr82|qU73)b(1p=z0kBy!Vm6H#NllVGE%9mM%$V zqb=@h2!ba?`Ap4@{2KdRK)LrGKFg{aC$nZ)o0cgWJuFXZenLrxU7yZ0!1D4e$W?IS zy_OKh@;Mn)4K^{2m)bb{YB(%0yTu*G8{wZw%J;C1k<2+|i#o(L*ELtMM#_k&UNap2 z#jWQjR-eVQ|2=}|ag&+Z>t5LBRtk*smzRcJBaP_$ELim7lEjg|lW*ixh!|bTYI@T9 z&TbxLpV`lqcIl$Q@i}m)+ZT^aO*>q-IvCbp?k?=+Dww{{6^dLZ@)0k}@z?o!(32i! z)nOWV{b4p-%RA05@BND*hXcezOdheVr|YGMZcxr1b+AsFtbxafvryOX#dla6qwO)u zMgQf;B8M4Z-p$Fd?czgj_00@x-i)VHnuTP+magMV2TPu$t3 zZt$I0ak8_A@cz6KD!MI#l*?cEpLoi0xwHhL=VnV5IUA$vInt-aXR~6;glr22uzYxw zhX>nW%9W|G`yYCq_&TC)&CD?IuM9KzSFei$d*y?E_`lk}r(Eikz4nT?sPuxh6~rI; zC4>B$Lf%OG>h0)ASRUGs)%lxCUsWy=%+Jb8r~XjKh;gH2*vQca7u=Xco@MoD7CV*l zXO>!n(wkD=S?z-HttX&IOoZs$YL~hu^}S-{gha?{)WgHkkUDb-%Pon7fa{Ye z)=~khK97d@@*dI+TK&;!jSuYfdMGJ4>4Lrdf?&n0ovdLFd4yM6gXNWcuJou2XSv3U zf9;PK`rI?7tj>+#G^2z2TF`s>WHK08nAR$Np#LQy5)S`(#l8Xcr&mvaBA){OF3=Y3 zDM!@a?SyEyX^ynF@o5>poqd>mUe8?MiG?~pahYcL+bmdm;}-WGMtkz5WH>W+wJ3L{ z7QT8K0^zgrgv+bd@x#I?;Mx|)1Gd`YD8eeoN)6ay!oa^D^OEWGN@-RMd+!G48_Oks z)0ARGnqs9ZP60Q5jOBYq#L>E77Y6j z7K$35&y{AA&vJsTyfj^+gG;*uY~5hY=g%s`hVQpw<-S&CK$-l;#am&o>vMjjegxL< zD+N>gT+uHx;-ih1!VIg$!qs&&bDk`L(?>WjC2boO{&cMG-YcHVNmek6EBh& z;*ZIrp=HH&$-ejHsD7&+9?jPg+7xuqcVaHsEeAfG@UDk)kzkxUw#HZ07_*6wwrMP7 zxrQ2eHgyzbqUP{5jV@TcigewR&x@|)R7fSc4YJJb19NO}nOrf9eE3^(^{PwVUcbHK zO*Qugt0*<>J0Thl46fi`=sTZJ-97)`kJ+G2Ig0s|`PuUm+p|#ZlQ{%?lI1iItLrR5MEW5gQc%cXx@jb%JzF`b>0N2Ng76eGT_Ob@jt zML`eI1{U^84=-<@2NTb<@Yg10=z41wv@RMaIp*VnPS0s4iIp

    p24>;Q&BGH+h+ z4|k1?6WfOxJe}i-N^@rEKjA74$aogarQa{mX3d$CDuVx@-X}>e55M zcO$@2=>|W4+!Uqx0zCb%qjtI+sz@J%(e0qdFs$dF)b@yYH8syb-3Iy+M?|4pt z7P>c0hi?wwC82pXsCy#_vWDcdvsx;+_`WNgIa)n(f3}^Yrmf|5UiGnZwMR`{UfMaQO7#CO@KQh&w__>%Jjc(v?JKLwVBq zgjO**u7N6jJ!JE|;9nIE&VB?YMUz;yUN2O%Nrm6B^3ryHLsZYnhW?FLB+p4Vo7)>H+dz3)D}RY4D)v<6D`HbK#q6TH{%J5ry~_V9)@r zFD!7B(LAW@XyMmZnd3-JUzn3&DY?0|9FM$ffTWgTg5F~-JQTZ`GPKw8>h-}XG(?4D!a)9RU_Vqzn-?#JO*4-1?*-22 zN%QLd&0C%`*Lu~(Obio`?PCU}^L6m-t2}sK(^32Fx^vx%i+jc0hxUSUIu~CYlLAUp zxA80~;jSvtkl#m>f@;H zsg!k-EQ+uskI6;SGmxLWf0-KQ-kJiRZpHB@a|v^P6a)k27%;2-lw)>l1T4+`%-7u0 z!K!&~pzvRrP4L-s%T?{P*LyqGx3m_xNg32VKboeGsRTG+oa)Mw-$1^Qn% zaL3Jt*rrJuW2ZvVE5o_c1K+pGG$iw0^vA^Bf($b;DJ#X+{dXYaOe=FQA%0D*5GudC z;CrLIux1bdb40Kf825}rr> zn@dS^9(0m>X_2=#FB-P2&JyiOsGFx;5^k@Zd1MDqt@VE&7RytA7#8r%tlqS-b~ zMP!aD*TgVJ@gsjz=7x&CPg4AbE>3xzBB5R#@PQdXP;M7PUG%Da4{o+OV0em%|g6* zW=|(!0#`y`wbkHpriWC$kv{XdRIuB2L~>#-&2#w}m{eTGUf8JO?X8pGR^k~RWM_k_ z`9V-=y4Even=?WlVKTFnh4-`%q}`@op>8Aj#u4iHcv~7QdAW-}8*PB&PNc%7)%{pg z%y+3>kO(Bra?)IN4g6B?2R)pJ@Sz4acq^HBmLK!kZ9x~u_49)2Usw682Xx+VW8h!c zUOOm;w7x2tkgy<$=QtYRzU`@SWTHPirm2O`hY}}y|!N(~< zF!g&Lvwck2hC1#r>*!v-e{m-|-q02w@sfxp5ytoGwbNo?{^dF;6;6@n7vr8Yz8o!CN|4BD3@mf8BaSuYJXtv}7S4kOJc_1+d= zILOB}7+`o6&DiYU9*H}xv4ZyS2*d7z^sff?Dffg?ZqxV{Q5kyNY=FLnhgnCS26`{g zfm)MN{>}Ne^y^A{nA9jIZJtRzXyalaw4X9JM+3aGlkmEiQ`w3dBMhH51MUPr@lw>WWWmWL33R}r;B7Q?3= z-}uIrdf0na3?zJ{&iWe$=v+dWiF5;7X|96N|GZ!*9Oqq+Nzc&Y2XDWi=dNDbIHf61 zhF$BXkPl^KoXpP{--EmlQ(^)8D6y~=X3}H-7R&g@vm^VVXN3p``J3=pQBLSnOV3@; zC??vXgsE0`pk7wa_a1P<@E0Xe@HRqZLA=Jg(o`4_7S2;0^>N6qSa>~VDyzJ%fZcq@ z!X>esv}KV7c^Sq)QDl?E$k_??mjprn<{hjkUkTCD4n7K7`Ihya=sIwPm{%xcGW2OL;35MbFg`%~^v!xFe3uL;H-!c6$?vX(Kr$$_7)k$1?>OQ=^`I%{Lv&10=#gM=H z3!i#jjQy(0AUHKw6i1l}dAH+1*JGu1#n;N&266%24xrvebgt^s1zFD z{&|#P{7M$B|jsdULjV;PP;%2gj{u1bS3^Gx_XI{UmIzZCr2 zvRUGM%A)V|gQzo)_3O2S*0h=pl`KHlU z_>FK3ozrVPKOS<#fEVQZc%>vv`KN|@lO15@nUQ=TVMH?;*Fbzj5kIz@v=G#LVmd>S zJyiTEJ*mlL__oI%Rs5Ij2TPpY`8z)=bR&O_ICefe*n{xKq*1Ub_Xd}qHpSiZz2L>4 z&e~Y14t`3?0;$PreuQ-U%CFMk-L7eDXSEhyPKp4o{*_N7zJBLtns4!45*}cMqb*{8X^-jUjL%pqO{J>Of(hj`&_jtth=RN80g18O-UdXFQTPM5hf9dC-xMyg>a{ zeru=$ZZngQ?vLNv7sIa&xA~G!diaBI&fvpQlH@^F=tO76sy(M!+jGi%nB@VBzYzy_ z{}kmmH-lfRFDrDCLm%?Y{y(OjTR@(j&}^C3dI$LjyDZkg((P5OPayRabOgh_Cx^Hv z@kAB(g27nlw?}!Z6;=?A0WZ1Pp^EU<5&9OHav_qz{3+5(hMw-vZ zD_-(`za7wo&X2vXx=8#Vm0^zZJve-FxG;=#&UKpkFi*(jdp|2;;mSy;D*n!$*3!KZ zxs;fWO_H74>6!75H4;D@bZchd-=~qy1#I-Oz*cl zUIUdw#=?*-cD$F5BmSZH@T= z2Pk)O><-pSnKrId2Y`C>R(^F~C+0*Yi2G-(6skN7F|}b6-0JAyN|XcO@-__uOe|`f z>H3Cr{RZcEOlzYG-ff-&XFqS_pI=*IBH?x4HIIt|d^Sq!s;Xq1W7QKql#3Y-&8GeN z^U&^f{Wq@`KR!|{v_3MzaT7PguKasEXcqZO+A`qZvviT%P4WO93;`9&^(fEO#Fs;6 zfu&0l&y%x4$v@%_4(qc_8}d9Vkk0Ds7d|A#6tArC0^bGaB!h@&|N3yL zA!ieuF+W@zNV*YcgQc*0?M7ZakaCvjdAt@;AbQ_zw$!1zK(;?WwADeqWg}pSmMJ${ zTZS$N@51>zAK6S@OLXeBk1_$ia)nS29O-`?2JhG?S~FA~XOYIzzd2HP#Px9f^`$Un zxj&B_OW!}~l%6!HFmvJyy7awd8b6(Cef*+2288_Ul8R=!zUn;~9H=Yoq2IlDqY!5P z@#Z61^>B|$9OQ^6)&wl4Gf@nE&g2rdL0c8K69?V&lyK}y2b^z3XNpJ^X-+GXCM>xt z!$S^^H^kg2JHU9{N6CM;)o|hYW#DuB6i;1AIhNnzz#%wWlqS`uo;B+C-2Q?6Db=71 z@Uf8H7|Q3rp`77`q*Hrl%^XG4Sul5mY*v>pb3rB7li+V-%rZZpkQ)Comi3M~)tO_> zgDlV-V#j|HSNPj89==y?WFrm}hR`vSybsTK&`eW|-5mhM3noaaq8;!K&C>g?By87Z zRb1T9f%c^&4xa7!s9=RSDaTpJCXHX_n-s8(lapHAFvYInnc)AiLQ+c}z~Djg@Ux(T zm3OM(_+mfsZ>r|m7M7UzgLw0(HJ%?9JD}1x>i5~8Bxv6x{fW5)tob^EFWco>*Opu< zE_$d4eoxe}NxY7_$@Xy1E1#t!HZs}%ye>^0zs1fVU*s@8$<`93YQgaS^E`GbRTnRe z9u1Qr&78(hk&-^$Ey@2#xkm1%S-gQVmfs!% z^ZKskr>FJAiuzQ@j*yr7oTBUw(oX!zy(-xotcC}#E`&3;5A*6OO?+%V2XXQ%OHohK1PAHnGTC)iBtkeZaA3y+k`d5WC~yMjyM)jB&i zaMcZ|LWjL9$7wEUnB^SeA*M`)k6uo>j^)8H@y8T)vx2b4)Y&j@?F;^Pq&+%(351DH zoFyhl+fg@ASA5WLo$zD6K5o0P9kM)gc+gP!x+@qbUMuntyzeXG{^8M(_~8d%ct#KR zABu8;^nYQzC{)^ePYEenNPX@-S4LEn8ImYTW>Z7EL}_TK zD4R58uRia4KK9;w?>(|t`JG?i|G9Fz_uTV7=XqYwBJ|8TBDiV%J!ncx0^7|uJ3 zz(}!!jpA(aesBTYKRuxJlqq=tDVyWK_&40CW$HL%#zcs&uVS;d+2Ey(Nw50$@}nbZU|R~L19WctuZ3}Ep{=(*;^+aE_W;jw>B>D7J6R&n8 zz^mJf`PU6b7*G~RIdPL&c#08jJoH~puFCI;??w-U#JDzgCCw1$ZX5}7=^YtLbG(I0 zx5(RT#NV){Z}jp?=vm^;zL=2zdSpD*HjX>o?JL#!h&iBfwTaUuwuzF*C^%nM#I!0L zvFG$qAiS((bVIW^)#gU0)|%f=e*Es$AS8a2inl30^il$3we4d!(ui5{G9LQ66iCj{ zE=>O892nl~J-5+a3r9PSfg4-H+3e|#xIirwdfWHr5(+G_|HuDoa==I@Jh8e3G}oDO z7uPn5aTXSx`s(yd${^^U2O~%JVVjF-KPA5ucGebhL%vb&VVCJ3@9>zF8bHpjMTbxoUc%dZ}N*2!K7IxRgYZr+V)$s8eAuX+#s;1EjmwTs z5`4@YdHpi-k;N^9k5QES+{F<4<`6@5M29pk%Lbb&s8&2(&83-Y;Pc3#@Y`k!+ivs= zE3WDbS=)|C_9YdF-}18*+;@W@uRL5Iy@U^7^bUqI)b zf5b!BvUnm3y0aSi@^wY{KhrHXEQr4sPvpzR6U?`pE$Fc zcI9)ILQK5|n>CrZF`nU_GmX8(rE%Rx_uSwK3+wBEqe&w)KHpjD_VG6wD;Wu^d~*15 zd3v6)8lD_m&90R9ke$#@5qMtU+jUfNR7EuWxcY;gAn(B4V@u)2j$&zhAiYNr4n7C+ zxtqi+8sa_*thP5X%|-`|C!Jx^+4G*0zj(^ZoFjx_L-Jj}x5qNE5t8R=OCMEh;?DU= zp#GqQy(T?p-9*y)7prpv%gx0W!$qCErbc&dEY$OZr$76#s{IZ)jCK|p3~}3wEcooM#%SQM zKi;tK(+%ld(E-oCre|+U73W9Zw>TRIFpR5U=d|TzTU*kFj1y^mI`Q1H4zC0Y<1Z|A zKJo5kYoSd6THPiX!tw!RMInC~J)Po)53btd#UWrjC1l z&w&e+k7>I=2dzS8K-1P#_NJclQ>Z5I{c6N{J$5x$k$6f~;;fiaa#9T^D+AT@Y@ADG=|G80T?krQ^U78PHZ;TXZXT07u+W6I?@YRk#z6Q9axIK&&jXJwP?MM+-^IIvkk zR3Sf3^sQAe@<%_`rbj#?@)=D{FXA31>)@57V7UL7cmngS@M;k0QIGgb4-Ip`4_;v~ zaqp@&og)CJ1xPo%uRHRq{w?K_lNyG`Vhxf0yLL6s^6|R9j=b znVSed{_Nr0N~mvi4~KwprU^Tyv;)E1D-}ze)?)%FJh;uafIdzrUIoLXX{`9-57hCPES!Gqz(0LMnwj|v z;8c7Y8@F8_9GY+-ppKTuk0AXrF`NMdqV zi9_f7SBJgQ4YBQYA@mA#Wh)*2;FHX$f_>>CzHFc#jx~&i6?IqH5Yi^S?+AyO)F`QO zofQuDp_(~$FE?duPkgO01TN)dF~i8O)HCP{-5m=!xk7oI=0$np)H8>^Fhp@w5#aGN z(u@t1aj-WMzJ01=gL)WY)sng3j4;ydw;z-TTM&PowQebs~$Z`HlWh zjf9NzU%0a-+8C}{20It+W?fSTqsos4_@39Bo3iw**r&@t2!5>~`W&XS-jYPE~MwA%*$EoKJYhQUT-8gMCb6sM^ffm&<5B{ zevK}Ms(3ji7NnzoF(BQ(&#pvRy==AAEsWla_PL!}4%rVioRaHJS*y*g>&*VRh3Zdw z@AIA(8pc>+Tn&EOiqgPnIwNQ7OqS(>~Z)WAjO$WAMlm_MO*bSxbmbL0N(Sud5Dr<~V_Rn`NcTCHm{s@WGWi zpcG!r3zv0Jt7InhJfFsjLalJX8`@vT8F6pcYGYQ50AJ6&VUBc9&aZLZ7L-< zqNa#N1r?oh<5+J!JThbi)N__B`{-{RO1_~98vXd^#0nTcrwUHbf5tu*55a@K8sS}^ zLdlR(npkrp83I;E@oFmMN&lP(kx^4w-cchQlOF-&N;J9nK`PiN@#^e*|Im41XN3>E z$-N+*IbtXFdvY7@UNYjZL|b5d@g|TzFo7i&caf=Hi4g>+RK9((F-jIC!AS4%hii$^ zVe~x$=IqAJ8~=JEKpLUkA72rFW)rq@|JPM2H@cHQD4V%& z`-XcKBnsao&U}yYJ#jtFOZA+(i7Q&I(FqDcZu|kM6P*isE=qsywnX$M?%9q^&-FLR!(tf*uUGZtJ!po!bgC}-#MdbBxe4oaWmk?cMo=Xn4aJ;pQ4&xLKzl?SINoCTqVU6nW=CoxTC?TU7{a{4$u~GEMySZ9WW2 z{KSqp>YBfxX)pP-1O~@k zl=k1Fi4U3DF+|3tHu2&_hdFy$2&>eh7KYgLMT|CInJH4B1ZA*8tA4} z!p<(!U{2nI5lO-k6z#=;5c8i3d83o*l9_rX` zJ_h!U-^mV<7b%Q(%?8qQo`>oOq5k$z7-?$4$41)W7uyCXFV>VQr){+zncByEph)pnycj0NpkD+#A!wU)#|Tj zs2`5y;NM1l#_9RV7Sa2n*+&r`s}K+W_y)+Weakjd&QW&j9FQs%^Ox(4aI8Zl+*zH& zmJJ~`EX@WNniz3!b9C`}?FjhyEMWU!JW<*N;bDam&*yY@vrU0J;nDmN z@)ykOzYKc4nZ^o9m)@2@-jKywT$GOrKEFI1w9bEKzbxtbJm~{F?Jr12MGwL&R1eKA zZ{);FCKxe#1L%hMv*JhcvU_E*f?Regzjq>O7emS0l`!G(+Tq67U^t)7k}ceuKk7I# z!3TnhSF?dS_UN>p`p@%BGB37K%=vV)b6!zdV2e3i9r)VGvo13zYa=KP&OJZGOz)6} z!6OBvuZkq&>FnP(V}2(?sl%3@w^d`o@5MYenzEdR%m@V!16!^?F?iE_h6Atsj#UpP zFJx$%;4OQ?Mz@vXDcb-y45bP+@8o zX{Wo17aXn8*{l%GD;<#Tqw9N3BA>{h{aie8mgdm6=63yA79T_ND90J#_bbKoqP0DK z-c1?q4n28`LfUn@y245v#cI9%WPk5o5uR_fhWjtIG2uoYcs<+7I3;=6+KID-QM*5I zI-}o-a)m2g;uC zrv7<$yR=r%64%f@8St){n@-%n>|Gpqm2P8=iEcQt-)xxuO+_NNJWss%^uPZ3*)n|` z6jjvOKkwb}6YpP}Cgf=>=I4+$E`sz6MfDe2d z(ZVv!`{6g*E6tvH&NFJ78(!HO3eOvi`LY5##H)=U9MO_)I;1FjqL3<#x^anrxS0G( z6=`r`24%D*(0Q{a73x8YbCH;e58f^A^d5eY(4RR!wsZbGiSl$F(zEn&?0oKHFEtDt z>IACt`yaJCX!Ri#bmBg7fpdweB?Q5^4>c^Is|5yrAia=Uon(SRo@iow zsB;e(JwqQg&w7IEb6uuwt}5G>TP*x&+|N%rVTaG(ZGcVDZ`t)h?fCR*un-?KmD@Ov z=Ct?bz|0FpeBCh09iBcPnm^?*!;uzfFqX1Qej0LNFUcn&3~cb!Q1L63Z=+qF^Tt$o`E26h zqjdfDOAEm6{4Q?vUUi&W;+VLIu` zWWBgPjiy+)dw3`7qxo)cEH!BYmjFX<)!Xgj^nVucWsQR9+RGH*H|0UnBs(^izCorw zX|SYU30F2i7yBLzgZ#~}nE!h-EJ!5gt?xK#NMT9cQM;rgh=;j7Dh;lO9^mTt8Djp)`Oy8y zIc675{u;FzaQpZ&&ykD!;&*|(%r8{|+Rmyr{zI>b*@9Y^k6h^e*W!=a0CoEmM9YvF%=l;NC$LT`N z&4GNEvs!5RFbZ@Req)b&>7vCu((c-INJ~eV<0y_8p5=6Y*`|&TGXOxcokibv!5nqc zFI`ZP*zqgHO}Ev-xJ5xs?5dBEgNxzcUssm6{s-PUGF@mXUCf)L>!CC}fjF@@nZYYV z)L6d&l$+wD1;qC=AQkf-&%3+g5lw{ZA%iQ(~f(V<%wT+C1u z`=nS9Gp7oU?YSw{p00`9ulB(xnsHg2I_vp>u3z0uyO`m|yjoXV3_0>&Pi{QkRTey>NwCUQ zgL8?RIHWlpqNc223-=h)w;&zv`D=3>b4|rd-J|(b#qOd)xh}@7n+(GpoY)L?%4a8i zY(Ve%#Pe4}_nFRMU%#JSitLS|a})gQ6Cs&4)=l<#T(i(*v>Zm$T#Hj#0XlP{7+$2E zsbM-)Zw}(#&+LXROUJ_W3kqT%+D};r2E*Zyx6*g_`;f08lyV^}Ieis1n(I14s{dMM zw^2bBD7R9WXOzpI57EGfH&;SvZX1i<)erlrRZ_N;N2}IB+8uXGhw`>I?#&ksG&~m! zM`v$fzq*@a)Ii{?u4RvAX68AUh;spy*g~>4;9&#O~pcS>VE!d zyeTeTum&F3-e;q_49EDIW_bL$PV#h?3OfEF&sRwiKa6@Io%;)5!LsG-OD}VL5*h}h zwi|MKK{_}}epF}XSNI1_Tt0d*EZo{8wH&98hGu2p=h;O}m`P`iloIH1qpmf7p-5F23}63tQS2?-h&rGQrC5onC%nA&A%%<=hz01buqB#XeigRW*fe^ zU~m@IH_JpWez!SJ?Y9jiKNiO7Q)V#urtYhP)H)C z#7?PX&gXj3vDfX+zWwh{$~zmq3FglICM|yGDvNsFBt(3D&L_)jV+!dZlU1awsofa2 zap@4ZZ?)td=|FT67I$ViuG*@Jk3RUr^+og9x8Ob)Hi0r&oqKVruT1cu?Fg7AeaoJ; z*<$5^Ca9}4Gg$kq(!O4{}l6=$`8?f_&iuE2g>7%=?sgUzzFocp_y~ zk!I%0HWl8~LkBn6c!1gyKh}HXXxY7|SA{$E)?h&%jm%vIaAHv{n>b2NmSi?Zz>qfX zz?N6y_m|M=g^B)ci0Vd*z~PQJ`!vxEKco?}LVpG~B&!#3S!co&%V(^i8|5}$_kvMR z|FqVG`pJg++!79J7Qpe1dU*F1oqy{x*{9MTvPH(Rf~;&fpEg_zx4e&rZ@<4W-?8*; z&n9iEVTbg@Ff+`i9{cF*VlJNMY4x_lpg6FW7--HIxi}PBwy8+M)~^r?lQlZ^Awzdr z;EB6yq3nmi3|hZo-o5F9BS$@awH}@*PJ($f3%c-&c*q5dz}|AH)I-S(r=^m{gYD*~ z_140`r6Y(xoXEEktRC7je_}2O>9I4Wo^$|3>nk@c~k_M;k{pBpmMOCJ6uK?E)k-4C3py0Uh!;lKGbkOp8S1i_ zeZ+{^vlw0)P2*OR-ebXRy61LJ*{s`^xb4(5sB7&jHP>^YoZm25^79yX@16-ZH*bN< zAJ!0GtApN=IAQM*cb=oYNuXQ`ls)^$R7mIFtt1@`Y|Eu#cS#fbelg7dTErQ9tK&iK zag*g zk(}K~HN5`Q1+>o|VB$_2%zD`XamwM61Q*iv9oQ*s__Q2uemB4ki7Vi8OB4&EvvA|! z49GAD<_2Ub;^l*5JNx0)(^FwcYErESc-+zefE3t-<1hgJugcm3>_0fD7oI9DUeixfk^WWh$3 z-Aq2I_E5MtVu$3!nHAzn)5D$pe9U}(d|1VU!bpAg_OFtRJtz{6x$omMLWr5)um(n( z+-KJ8UfHw=yawj7pASuO;jl2Uax&z8z1E-{ zKrbl2_lD&=n_y+r2rxZ%SbCB6V&9X?VeO!<;<_mYm@fOT=8u@*CR2X6S@=__2KCm| z8x)a#tY;asyiS_Br;9r?+3)t9AeO6EbZ zJ7E(PvJY(PW@mik-UJuM7f4Q45En~59U{e8e(OT=qg^0|gU(E*pkRy#?3aM!4;^kd zY3y6M(eP*CcZNPXICqveG&r1=dM$LuHSVOTo3VlWoI_f#r0vjNAIO%e$jK&!EEW7S z()f9~#yI5})wGx?hbNGBJ@Ca6P*vT_%^=q3@onSaL_#Tf>!{D!7YdcLr4sD{^Tzql{HCHgpW72@f&xUVD0sMu(@@X#VJ$X#JCIys4kHVXr&B3 z@-j?V@{J2k)IimX{@`*bk`4E;LlzSX!UG#F;1lK12aW*a32&Lw@?My7su9jL8*q@i zU7QtT1tsy+2WpvOR=-t{*wlx8urtB1c^RP4zl_WIr;B4|L_o#5x6DY-6i1oS&pc+V zbj(9Lv9-fdZnrTk zY7MbKX=ju&K8P!NOXr}&;~~TDCYx*B3+u=`aNDn&bSv!{EgFj9ZEPkpTF^uG+dWpu zSv#B`^I9Ee2QLPrF`wCp9`rkPrmUPV3Y7V4iq1bmVR3sAw`4YD#A|uMQ?(t;)q(s< zuW3HRt4IdU$raD0YIL$k+UFbLZp}3Sn?2apt$Mg;!!kITafdk=5yP`;3EbV8ARYMG z1OqpOLD$ILTs7(Kk0wzMV^PTN#ya8Wjg)Qbc}-$+@0U0xFsoBrBC$2c`kiZ`*X3K% z`NK7FUr7vTW;8QRx}Q-dQE$8H{C?6+mnjZ?U zeFk!)$Ws}fy$+6%_R`{z3nrc039t6_;qDe47t4D%Lsv6JajuIoF5i{`)n0nc=A{wd zxElqxR!`?#hH2qN((rR;x0peyCC+^_9l{*?Npp@kVbWikX#^ePc840`_Owk;Ga`hj_vNgFBzZsp6o2sc?I@oapLKzJvM<2sc_of0wdEE2F?|Q!$s;PaPAN`h%J7 z9(I!aM63Q#PW_29p8e~b@YgfaS`-@bYHoVC$#Okxsa2F}OmUU9&uJ0XEYpC--I{p2 zM;7c@R>`&;BL9niCiK0g-Sm4lnC?~q->v)j2)t!s$s2UkLMWDI+%Zi3#ynXsU8 zCMWAqz)u{@8%abk@ODheks)<+HrjqWN?E2;e1$ zr5b^x*QMFrtAPsQm<~NO+E)S#6Y5&CbX{dihFgTI*=lf^c8e2_k!IDboUPC|#=X6x zq4hzv+8CdF%Yful zfrlSfP*(NlX!vKpj~h>O7z-f)o(N@Zra^C1E(wLlr&}dA)9OUY;yax_$L*gia8ha= zj7*YabNsu=(toB1E(+WE@8l_SxK#-A&s}6C^#9sEEfWSOmr638kp3_%20nEC!F?F3 zjwc)ap+q5)y`bxhbp7?YHr&T7^0#`9?CjOc^sLeDY$MzoX}}qTZ54O#wd!R0bs24r z@63xK@o|6llYVC79hq=Qx18HZvt>ukd7w-4x8_~Oc#ZlW9p|yqQ=e_|NgOfl7a!&{ ziJcWxJG8TIyR7VvTf(wCYxP0m!@Q|4hVXRG6+YU3~>bJw(sdhsge6tHcuZZbKi1JxUkn6J{=;RQfx8E z>(;Xy7kbFPE=v&JPwB#I`M(gul!w8UE{Y-_vPu_Omk~| zJ!2+(`tyW2KC{L>zC#C+0nvAt2F z)2kk!YKT_d)_@u3!3Hm-vrp|ZP}IA_e07Moxi}h@bWf5Fy<&{(cZGpV&)wXR1=<+d zdkhqL6td;#2B5@-=6Hu67y8(0HoD~_<^3f*M3k}Tor{B|x{>zH`6w{zz#T^ve#`2(3S-%+2vdq_-! zmKdmFL7Wohm;|4~oMV(>rXDO)uV%T2=|X0#Ds7NC!Rj%|d8+qz39UD3o!&ul2KsA4vE=aevs`^UnA?vIPtyizM2& z)X*q91F}ovc{^PbJiM54jv8mPXbJr;M#e(zRXwg@stV4Z?+g7+ezCiAwD4i8H-u)M zl6Kc0h#^^_5VCtcr{6(my`$S;qT&?Rm?kG%Ub#$=muB#Xj|{?3FV{k2Q2OD2R09Xx zhy{Iz{oDZ34oQBEhhFC8>`6y2{N5T0Dp9SHfJHmR;>~wDbu5Ptm}4=kgI%$5%>0#0v71v%MlBp&6YCdw-TdOm-0aG`$=yf?}dR>ugVk-bCpxHu=ubi3?x5@cZj0Q zC9P2C8Zw5zd!QTYuxvQnx0{$T(+p=86oa41LFw%%L%d0ZSFPul*wlTxn0hw|7F#BH zVr?(1k0I`Ng)%>AfClcC8wwWR#xS`X!)5o|t_dR=tzjGXM#Gd)EXt z3*ER5*)y@n$YC&yv?6Q98=);13(9rA%=oDh;yU8wS5N28XpnFBOc2bu@Q^L+V~f2? zCxhGN9@1cELmV)q0uJuXWzIf|vJ-=1g_A41_yG%4Nz1gP(+e5YNIbe1vG8PfH&#T~ zT)jJtxRgcQq~q#%bJR%4SzE_W9Vh*{WhnSfP?n5akt0UgXu|*VzfL{YM}_`tV6Tw} zJJ70&0mLd)JAIc88f1h`d9g5OYqIn>Y4gl4hr#>(ySTr4+PKis2d-2WvdndksLGQ^ zqxFg;+5fxf^&qQr?-@cp7<#USh6OjJ{EwcpYmd@}wzi%8U1v?y2wMu;SuM>TJLDzo4oC0|d>tchU-?~T4Bgh7!FKMw}I!X`H zeW;10e&()>yGpyuiEp>TUXMza5z>L86Y;(-NciQH-Hh*j-YlpUD|+N(B5 zbxBLs?S332tt{a-&Q!;7UnanE*L^IM{705*VUTp`wCBa~18|H(7)*a_$g3urV^+@w zC{@yso+a97eK4* z8!Iv~LHp~4pqlL18cqH4faT$k61#;xAWde>)G$b$Tq}ueS}qQxFykR9ilX%beY|nW z3mPXFGRc~*viILt2}gIe@K<>94kvDf$6r6Ps_7nhGp`ZiH*J>;a_Ek_d^i~97xEI? zeZM#u3;ZEs0>slZM&F~0t_Ga6UJDDW#=vRYHuh%%^CS)M3bDXP{Z~NN^>wUf0`+wP@o@kCddbxz{$d>d zSBGmYbkKc+FN_~y!-^=EYS1KNFARz29{nYDM|M3#T=>lnO?1M<^cKh-S|oW}u7>C7 zoMLrwDW73yiDPc90O#cS?8PKwY@HYn&rzQ{5UqkI%*H}^$!|89W`mQTdPCpdr=*Ww zIO5(7Y?nK9E-oKhdaKm zgzTRu+1_^+XtQ+%D1WVzjHS7>>)NGY)#o?Yq@aWMZcYPrE|z^{Ht0p~*Tgf{oMwqB z=3npuP;6rzdDd9DcqjQTjkv<|o5d<+YdGYgD89`z!Q(@VAaRC0tCX~(<+>?CZ_hYh z^@}d<6BmMV^hb7;dOZ8vloy=jCoMPYg*)6x&s=eci|MAeUrl$FYSh5x3W7m zgcj#a@yx7Z_;UJy^zn2yY2&BEj{y(Zr+HK#{>=u5Dh=sA$^o2~UI9a%=d!8Z ziZYY6vBKyRUi?w=Q`D43fhRF5`b?uU^7ME(w4^(;BYjj)>N)Lei#RFyXm(Nd`fZ1L zX6opO_gZFyv|UM(6_hPjxoG}3-xzFw;>`-cTb}H8VGo&!xJ>x+Ete1PtBaM@Y1Gf( zW4-3mj`dhPyb4Z{8iyKTu}U~R=67@I<~lgldMsFsD`slL9dM2_l)X-Noj}h^sbXDJZvg@jOZI zpnRY3&Yrp6RvZ73*U!>-7Mr!*0WC;_H?`*gZvQwdJbrK|lzh6(PVVX|v-HRkUS(Oq6%Db0>Z|F=e&tDfu#sq_p&Lg%c#G15=#Gu>b zD0M7%z_ms6ZCW7X(sq+~Jjq#PUWLx`|p{w9)3@e>GX# z+6KSphQa5U2<~5`B}&C+$nlSm2s#G1YxF9(mlMz2m;6N2L6d~(9j?6Y!!Bqh7tmRg zT?`FyL^VBED(|HpU#wAsa#5cJuHo!UNMHJ6D1;SkV42_KWHEE|g{&zn_>yO8xHh2> z)Mx!*_x8A<4ch@f_WHHvRg-VMHUj+DZDq-V5em2GfTGF{$qkR?qP%%)r=L;nh7L}? zBf#V^eb#@wyzE(@Rf2!SPJVAnFC0s|Jh>I0SZ_0TT=u2`6!&eDgxpfZvlr*UyFUfI zA9X!ow`@`6Usg#f4od9O*4YKU`H%D#=O%mCzE9Y+^aFp0 zcEN{Vt%T<}Cz<%n0>>X(2`}!fm5inDtU?;SgIRyLee`YptQQWR6=^Iv-WugADHGPu zn)B;wiYE(v;TN>A>DU|lvHj40hy_Q)d~xz*(r6eeiUwO~cMwwqjfVEjX5b&xJ{TyZ zHpcNMGITNBVhJRD|3rDRG)tTi4svhDO83TDSJ&9n+tuz4rk?8dQl`ggZZnhV+kXK=?0i2Y?d9ST(Lvz&_lIED6T zYd8(*6;FM%d0zpBw{j`xT@?$z#z1AtS5|z2?&qrn`0Cq(x%H(pweeio8&J%xj8Z4| zsWz{UO<%bBvew>~NL}y(78rq^kAGvW7S5!orC=`GsROam>18*m!O?YodO8=+Hz^ zjp^$7l6re%j|lkT)4}oQsV}2i|uWNs_h#-c*N#y+Y>R@`rX2@Sr#s*#efw#IP3G*^N_z2=Az2BMz-)AU@ zi-%ca7yEqBIk7>yYZ&RW^phZAUKwXts*W0|Qy@F!06V|S3X$dmZEdGKPaW-#i8f*2 zp>4=-GdIQiwGGfsPea<5@@O7B$fcjTnk|0Pj`tg<3p-!_#Za=5oCsnW1rpKP=I_%3A%+F;}Y@!d2!<;;apE4AoM%$BE3x z`3L4am?R`Pxbd@xcfnuv0br-2DE3^hkM--xzq9ha^wCo*e40pH2$MD3s&(qvKg1Ir zOx(zHHvB{X=zKxD-wJ*Td0RGqDFV;bU+jIA8#e3IgWKn^t^1Et7I|wV1RUJPHs{lG zs1yO@Sd*-}mm`koXyyO?RTOJ~(){h%aERj#*~tZRvh5bDgmbz(`C9TL&vV}f(_KEX zI$d{k{lAWpW)}%h6fmkwIAmWg;GJTPkUO0KK6CR~!5YfhF^YiTkA~dGW=&ix@r7AW z+Srrd&*)dd8lz$&wlwJ>`R~>6DALuHxmF*Cc#%n>4y&+zt zp5adA8Yax5x!kBEFgv(W((9R@==Eo9r>^^miw?@49S3uN^ZjJ$A{_oH3RiCo&9 zb!~vi({jwI*i9z){(xXp@`<;-rGwL>^I+hIlk7He*cuNcLy=QE#}svO*`AqjJuQLR z23z4v77DptthobGCb-eh4|b-su_2MR`0Dq5aJ0AJ+ShFmr>+05CL?+OwVxNkNMC!l zzxfwt*iRKQTH^T3G+o>*N9i%+KC{HDhUjS!0Sb!#QX$+5Pduly-n)a`liNK}rN$k? zE~c|{#_j0;D^GA*IGpcxqAPm%=0HHVZer|U%1obA1n1W7lkU2shfl`Dg6Hi^4C&1N z@0I$AdbN3@1NyUA}}RSwZFo7u#) zA*l1b36{@v<#ca960J7=SCcEIllH(c37lN~*_~jjrAG5Qy*7@CrubMd7?hVhWE(Z? zvBa8m_?y+GyJ=RuQfoadH7sC%w#ds=ifOj|M&R=-RnhWOT&Lc{;HD9-{FMZyR!S_3 zuGu_b9{lxQ%?(ae$8QtHz~vJSOu@k(#b9Fc%v6#*o|P#kAJpvh+Po#NmVIUoafZFv z*q|;l^T}~SQhXL)_D>IQjmv^{&5zl-OkzvkNP@HjX;Pz2lsVEi4+bsT%MG4O^Ilhf z*rL3e)u`EHkGxQDopf2U@cAe4$eRD^vyrnUMjhG$@8>?1K3=9ITl_Lz2yJiX?Z;`N zLVXHcd$EW0AU4$B%w+JJq2Sr2mH7FFk#Iu#k88P0bIYz{p>FvsrsQgm>NMB->FCJm zcelX%%UWQH!xeV<&TkxTpC;72`@&^SVWQ-;3#_nH6hF)`NBQk}5d6=KP1Ga3*70Om zp*x$KMt+KA?X%#?>L;v@G{%|lr-QqCAL$t*@+_<+&;BCHt*FsK#T#3|w5ptmi@u|H zElJQg>%nJkR>kBi*^oO%QS4Yi=esW}!1i^u^tU(V-54%|x8CJk#Y1)cvt}xEZ9T|3 zm?gRt6Eo`QDbJc(dn_jns?G%iKC7n*TIn=`m8*tywU?hP;nWr3fMZ`+=R?f2AuHik zf69-jk&_*X2oY8sY3G7Mbwu-fOL!fB1+hJw{K7ReVC^>-rr&IdgA#~s=sB00R%M3W z8Ui4x=_*?gVTNkEo1r6puH^YweKcHM2nl70>>2R~_Klhm$OC=y^ZDJ41+wpjCzL5VYm;b(69arpM4PHjX zvZlS*-<@?(sW-M2A3DpzYpMlVgC^_>)Iv$_LeQC1%jVb+7ifPZSYND{EV9TETc=CO zvrEi#n%^p`jRgH$hV1O3f7qjTmEaM-ldqX(h0(9K5?Ameb0{8+jUi32D|Ndh@_1LA zK`e{C$pw5Y^~_&2k|AT(DyB^uo`|FKpt`|`gC}a3LOFN7;UAb5JxkwK_=1HEla^Mf zVBWPV__K@H)aMN`vR^ffy0p9XLJvbMrQU4a>%w-Kwr0|FNFSWo z^oo#js|UDy^}`L9HbPX>2!=?f7nw*KROyd}qsj3)morUbpU?GY_Hu_Q!={Xd2O< zW!nD6!Oqi!QBCoD$PHa|8WaNolfSUm80yU$=5_Kzw6f$)%);Y_aP5*cte>QV&&t-o@n1XH>u7g8 z)@LVdTIC z{l%np)C_^q>r|!h78&EO8#Qq2<|>xFQeGxK6(gKf7{*t;RHgmbQYhW{gB9(jJ?!yi z(4nf#W~!1ux-=3t>6LK1zNurRzYi>3PPxXL`eF5-*|0-XNirrfL#*zi)!AdG95cr8 z6&s)-dIY;yCNIDXAgZMv^t~;Qn_l=j_ij?-=TV!R^J?A+pv+PYq zC0jcY8nl;6X!!~uO+}LKd!B3Wz4sX0HhVi*podKf zbsjyE-K|xZ7eJh_(Y~5*A;0I_#28rbeu(u{F~jFOse`Gn#Qk;){my$WhsOt%_`@G{ z(6W3yY(3-0l774349W{Sg*~~WMU<&>pFD9YXW2mGZg_f1B`6m-aBAP0#LLS46BWMWok;@QSCgc%!Z0yjV$`ADe`mYfW8&FyR7bxAuGwx8)?j|hgx8+XEn^-sVjS6s*9Eb zQ(?I3f9!n257aN3EyUdV#tlDi$)*OzagXO|u}|b5`Dru{_EW}-Z@M*>X9d8CV}YFi za&z2gT?LE$0;N_zj4@Ka39f%w%VI0PV{7#+VPoQ8epHzfD$Smxz&+IR4X{$3zQf}d z*`Ii86ygKG+&_=ArfiBMOL?%<*~wOa{(+Irslxh!N&I4ISA0U;^y|rg*pLS%c)1`O ztWx_l-EMJ{5BXdy3@*}zla)FcJbon%O5977FzF%BE`vvX%cT#@Hi}-8WD0M4ZKMHi z`aJ@^Ih(RC&h1#>nIUZaQq6yUV}X}0mcYUAW~LU>ANM^ghyUcerF(95z$({3I5RVY z*V;)vJCb#9(KUlzpr1Y2GHBUu#%*$?j3Xx>usHUKIfohHlU<|X?3YGaFW1iax+b6U zIwWGhVJ6u6s|bb#)ivo-f48cCEOcVoik$iBtJec}c&D^^y|*a%6!FFt67ebJKm0!v zetu$iw)X*fRffKBYCf%y7;z&a)Sx$h39H)e{+~y)vk?S-wL4nB!Ow3qdVaCRKang2k-Pk86D;S_UdJ{gRPTq zg+WoG?8aI{gxpoIOm>z1C0wFSwjA0zY;+GlWrb>cNWa&i6W>(T6@L!}*#CPRJDDw& zPkeAwm~+Pt60-DguJbl98F_#mA21lt7t}!i4FkEvkq^Z|IiA#gDG|?aH^ubW^>FX| zBzC5VyskPcpw@f==W&8GT|cPPaOflU@>Dl$UqqT2t*)|zqyZjL`X4k(GTBRgCHXlP zE=1W6=lut0;xyYepx)yL``$)*;|4LX@>*whE5{UHo2-C0nz@|8psv)h>jU9^D%qu` zZrDUR>LIo2Qms9)qH=;RL=BLLjCRh(NuB$`np)Oaa{qRHMEb|}ZL|*brkf=LwPvFXl z&Ur$e%X>v`T$w)Rci0PkRJSpQ1zoWDRRZWgm52kC%yIW8>O@;wEYl|5|6*|r%r@D| zb%fY@SjB^Tz1OW?b`@pEkWI zRF3Qc9@BI&X-66a&Dy~6HrIohM~@1`N)I-XqtshbEomC4<6*&o{mK zJ!k%kP2wa-e%(wz;NRVX~dolVuBG<=rp|Oer;Ab z5_-CuvakJr|kPmXKho_*e6l>d=kB+W)vz)0BR*B~3^-3hyNFM#LS z60y3s1LckEr_9V_O-OTC5*9}p6gkWpDIV#)g}s7k8fRm69Rvz#=w}JcDC@ z#6U@oIfuC#xO?(6xGq-`ql2|km$dZ3curPA{Y`hD`@_cIB5uf51B~vv4<5ap&UPe9 z?Qgci&W6>E3r3M%Vtyt&F}Vi3;Dk zn=$PSC-Pz59=UALlzwuRlpTVP`!l|Jo*^2{UQOQKYs@N{uwv>wx^#A_hMXR1d2LgZBR1p8EUZ zv2&gZEc#bHdD3sk!2BswSSrouJ1vTCx&n zcX?94E#Z7vD%5|Y+>F^J@X$Mpna=u)f*yIAZVl&4CQ<%&Aobe3|H*b}nW4XHEbadq zY*mUWd4g7g+SOd{_vEg)i+a_~22?ToEN2`-cdKN7b*WKqj3}wmRpeL4QC?#8fSq8d zLOEbjO7c0KqXd)Q8~OLkY;Xzr&2!FuWzUZg7GxF+K@RaU%__nuB7zj1jAM(sqW+5U zFfJ&Il?74f0{Qq#Z(fq-`@IzhdnG{he-d$ij4dwDEQ7zE%`(HmD)N`U>x2_?_Vc}H z@49s*4ie;t+5ff8V`F3C`WsdE&$Rysbq=Nsgbw^Ecgo>EI}x7$_GedXol)9303tPe za`s*}*uA|TtRCKG8xK3+%8wPGR$&||{QPwVc$b}F zK}U?S|K2&^zfyEJ3a8FB?S+tRY|LvAZ#8g84MhLcl~uZX%O@?pB`no+g_vWy7|K!Z zXmbh6s#B9MZ=jabIqH0m4wTKZWFERiEprZ4mp66|7wjB-_>M2yMV;!&pgB+?4mL8yXDKTo|Gzfb zm|m6`okO#_ZZntvlYALb!(s9HU98`;zqsq$CLv*eI*-e`VqtO~gjFhuGndmYU6%`< zE8LoFtozAFh&yPP)`x-APc-;sD9matV=sv}`BM-C8+%nsXJ~B@5A9+6soN6q-qkKx z)0=}H#k$P9tR0;^>GQ4Y_?D*@IIn&;jJorVmDRdow;q*{y`WTTRHcM{Eds$>p3X-T z&n}SG@pFePHuws43YP~dI&)WfQ%-M!4{TKX#Cn}`!hnl@@Y(IEZ0;C!%v@Ihj-?Xu zjnoLWSTW?*);0aypo z<}k|{?`|T0dVVPPYl$v`#vW*B`@|MUI-qfR1stnLm9`HxLBITeyL9p!GhAsL2LS~Z z+=;^)nAmRyyvb7*6O)Z`@ccQTGyJy9-!tSw}a98Gxd(wBpq?51N3=l9bs1gb~%cUa@ zn`0|!#cf_I^BsLiTl;t={A`P7>eLI<*MvL~Tn%oko}tmUtM(#1oA!=d$jD?3?jid)GS*0m)bJ5do}A2VyMIH!_B285t|woAN(pzn{F~cKU2QQ+w+IY^Pslz|e-Q5x z4WmZgVB>nx+>i#t-s}YTd}qomO(uLJPMtU0u7{JBjs&m2Q`wRI!{o=gTSECYJD5C5 zA7AY(fKKP?nCsdBc=!>yV5Se?hR?k(E`0uPR)-dnr~Y;<^_op(S17CPU^2}jxj(nG zyB>bYn*w{?ud^|~olsAQycP4cWXrm^%MB}U3D>r!f+182)Y|gy;FQ5o4XO8_m*Q%U!un&*!SwaLJ)Z z#AluZz-pvKJT;rRwgs6G{oRIjuAxrM);Li2Ud**#GC;%XC9u)qHLD@4U|yp?c^X`0 zk`d$+IYIptxr_^L)5p8n`{DlC0=Dm22l=DzDZ+$sAKqb1XFS;_5nfbL?&x%LJd=^G z;1iS1P==doJeZHo=N8t{-gPDj#)@Z|^E@N`JdOI1Yngj*;>R_Y2SC?RM!YL!`(Nkx zz_WFoWqwC}TYcnBjVKAH-B``x9 z3#`TfI6876XZgqscl4M7N`J1g&>iFlifII%uQL7Z3PW zyqle&@1xbBP#Du|3;#5wD<-IJ1&tKD zA_TrERY@~l_X@8ny)42VW5RENd45rEw1%2 z#4T~&(9xku)-**8^B)(0J9*x-1{mXl{ySiSTYb~l2wn6m+yDbNZf1R+keA0a9(w&O zmC`OIuJSBaXrZ?}H$;z}vq8_(l`XY*!qPl{h*k>a_zWHND%}GIR<$xUTRZG>vK(GF zq)7KqF~+u*WbmB5nBDqihU$IdVNbp#=TxbIXD`o$0YV3H1N~cp@BKjA=ArEKL?;}5 zlkRa_3%TJh)vIIpZ2_ z%qd#{Yx0Yj#u0N==}x^}CP$z>ie678{Llb zTBXjI@^BaQ8q&-b4&`xcmrB?%6s7F8IbLm!2RPY*k05LrJ%uLgV4;qK6;Lv*1az3p??II_STLf!pCv?C22UwyuVN z$CzododxtRFkc82_v*RfvHEyZXDnD*r?Ib|pYd|%bm7AyPyW)vcETSL6`JR_v`0O6 z&xeXJC=0uyDOYoh6(WAr@sIKiv8%WaBLBO|*3g|UD=QRYXC}Hc${0y*rTb=Ib^fLaOS@8U_E&{dwtgw=eCDJP_Knt z<~7PuSuqtR_P)*@_i)5!+HYs5X~}f%lRip!CrHDySlfzroENrQ@W15Ak09Mw@1HTS zJgl8fn?w0vvGH(smnKVnLY?e3VPJ74kNcfKo$NM~AdstJsk0qXa-V!aFV&=Rd!t3o z*Z(l*^cEB1zIVZ~52M(-aet88Mk$3(Y8QlxG znztqx@+So5Ih|(*6Akgyu{n@c$lT3q9I=3KiPSDed}6aP{=8ZP?^N|9?S)Ms z1eCI6cU9#b2S*5o!#eRC`5BXb`GV?TH`e9;|9b%f0JjEkk4IUf`}NuIrt>{k-Nh6G z?Q5ZwTPn5DnLTjh(u8-bB#zN8+GxqzJs=W4l zp`g`8&hIRxT*_nRaNFS^Emn=3PT zy9zrLmu-fyywJvdrP?@PmOo`J7PG%u^epruOkjV5boQMRaqO(ey#FbQXgHxKzCCyr zBy$bf!2uoR@!sh|#jk_>YaG_1Un!ffAvLXGX|LU4;Gzh(Mw@)gqa zqECM9ZWd_MTmWiaj>&%Q(3GFjj1z{wILI&ar(E=gbztLilLZqt+kZwljMhkUKS%dy z>HPqhb4`t(*`kZP!^c3xvFU93IX$fHv>isgu4m)td`JJ72qFCGZ!Sl6TTC+>p}>&C zb1bn{nh1wdec7~U)C==5945yFaxGfq3m7>c#w~ov)+;&S;9P%buhW!WCG6q|aZIX1 za+t59MDEvrgV24|cwVhS6ARtqfb~`qpGVl>fn&*VL|>mBBaX~tSOoZsTR7L*q=Af@ z42Qqeu!U{*C>D^PVv(9O{N-vfWvm`tFe43vvKfZ<+ympDjb#Tj+Ho8CDV|m*@N=)& zVAI!JFt_=|oGCZ>`$_6sG)|NK>P)?m`y!y~LnD_)`3#TkCcy=-P0ap}J&yTBnNEop zrGM|d5OqKOo3Z2NmM9F_4_!Mo%l@oTmj7vr5wcRs`P>X$ocAUH9tJltmA+<}@hSpN zuItD5AI1PYn=I}5%Qz&GtYcG%nz-G_Mwj4q}%o4 z+xr7xtGh&8IE~JLUWP(1=lZ|^`z@nPB+54~8f}Vok^nH2^^gVXJ7BIE<+xIhkL?so zOnKb^YrOZePc{?Qqtl{uCU%YwhXcgjvarQXS_VKCSI z0-Hq{mAf`Agrn@F`w?FUY>W$l4LOFqoEc$>>jBtmq9;?*q^@Kk2T;C;>CWsZ-?cwf zIG3)*U*bq7zc3t@U-V#SZV|U~D*#eP1aO*^Wf5UK8}Qg2c0!4A^8JZV`MO$q@V*|# z>E`KMd9pbh)m>FSExAYt50mrr)?1^OX$2?^ z{l*IG`{ICOHN@lWm7eJIOXQ6L!SsC^znktpFVd1>-u$hsmhN!{Wf8Dy8fme%bivZ< z@gQFP#NHFXklSZ8?N<%5r$Z#Dv$7D@l15_Sd@J1bVn5tFC~tCFrHhT%6CgHt3-d3q z!2mPLzV1;at=lp}JbAoWfe-gI(MR9wvtZwq?(Fg>d(3|O|Ln~WPBmEv?>;GmUx97R zP>J+=PpTm)GhOO8zyvRJN{31H%bDdx4UAgq3$L%Jh*KsKu1NT;wC6+FT0;knqWAKY zzXhCqtUWe3A+$`5VEcM&%WL8bgsFRr_!6TbIM8Q5yq=xfcvf9W?s#LSFmT6q-p-u5 z{BfX#sy>~2s`48M9F zq+5D(5j(eu;dKtsX`V#XNi;#rgImEX!HpSF{=>WOYXpgq#v4teUexw5aMJz69En?B zv?>A?JeeUIY(x8l$3jpKsONeR27a<=91PVXj#YAz@?L@kzRj7p`S?p@_y6sv#-ve^ zlD4p7?M>OXx-Rl%39&+g=0SesAo5_&i-9#qDZ`EK&*`d3wM3yXZjf6`z^$6adM`*&JNperNP0CI_}$O zcO9%91$$>p_|1&GCy~D3=)aOhw%K8VJDr)39^AtNw7+dT43;Brvnx-X(dl|U+<4W4 z`yOyeoS`yMv9IoNAuqgZ2E^7_F(ukjP4$DIZ}VGb@x=r^`GqikxU1~@VLMErUE-Wn z#@(mft+Absz~b(EnL}a+`Ch#YK|OmSzjTut2B;=M&UuM=p@lMewr0bQ)ZH?@O@FW= zXr@rJcRfFpFxb~E5im0SA`2OBigV5`govnz6K zO!YB7KNr5Y?`6-n4a0*vRbahD;F7!3p3o~2bS`?buA(W94i1D7Qx|em=2~E#>TIZY zyu->b+u-243{3m1k+MtFlRm8&u7)SE*RAUE7RsV|=suZGoAq6M`gw|icPk+6&?w5p z-hBAC%$T^XWm5wcn1D?`ZJbs#3cd(?*(r_l*sUd4&<$A3&%IB&h`d6m`qfd?SMG~t z`3GR+?9c1 zY-ly>!Myg7AC2x@(-#MGReMM$UsDchrQg|slcc#atcJ+iG-;|H?S7I>!UTfYocO=^ z$zrzP>E4mQl%;{}_*_^vxudv>ytK~N0kE(Bf$Ys=J6vEz7-?YvcO}6Ji|m>p?0yh4 zzn~zgKIzD(yI6%WK7A!YD!VM=5EsdnrgJxe%!YCFGyzQg^*#gOf@g9Y!T+3OVu zE257`r`qliO-4OYV7V78yU|QO4QIycvj@4Fa+z7au;IoD{^D9EoT#-I9;|!EaxV|Y zoHgapKTsweL43_0Jz&mVZ4QrwtnM$_@+Gdgt>Yy~?9`V_ z&e|dxYB(x5I6rzujszBiZuwwV_fbVY$S*?J?2ycRm}z10VDiI;eqwWpBXh8h0$e;x zc8xp*ep!nkZ0%ug@^O94rN3jB$P6~>))}nP2^JoGa^iPA{w|jICBg7x2SdGXy?VR3UE??%}v!F%E${>)w0LfFyYM^TXcA=&*pJtJ|)7J>a!bw2W! zE^6)afvc*s*v^3yR^To4OWBu>?NG;TV2%Go}-x045LM#M7Tb50-+Y!TjQ7svkA>;u zc}XgyM7?1iYF3!oEd@5eNRbUAtzG_w)v(=N#<{pq7thsc;B_{K=@8}+O7qP(@Pf4H z=@W6q=tKqYrqaV4y>{;hubXdVi~shM?;2Gvd_Vq$A4|_~%FPt;?JsBRRym>T`c2SL z#n8Pyzzj9r)_|j%D*uT5mEY&jh0SMIvRj8}2k;>6LB}54k;jxt^|ledT))R$3LUYR zWj)+$?asZuUMCh>4pd}ZjBqkWm*@=0Z?Ix+qz6;`I$f}@0ZApNAL`t$$Les66Thq;N327 zH^GzlGXd;NWN$uF*2Jw<@SyS%8=pu#>6b-t^Y$tCCC#>YHjQ?n8wUK&1>NxR%d=3e z>?Ct=p#N9LJh(Qdj6GHviu-J;K*vXO(A%K4G+ixGPHPv!gkY!ioPPgP`D=x;H_ zoaa$6FsNNt$0&1k)MCh(n8#VVljn5k7%1<)kG*m@i%kw8LOs8j&m(>Za<8gE5 zKm0t-s|*t+XXNpNGU?v>y$m}0eP(+H_r?`r2Vn5Gz0%bN-$Zko374|cc&$6;nCX!O zF;ntb*busdx2y)c1-4vSx(0TgKM{TvwX#zmweY{dQSdCfUbeE63R-EX5JIX#i2C1E+*oSY#o0p{t zM{P6s*LD4|OSdvGd70dJL01?1STBRDbi6-Squ-W8m0Su{uAFm`Zs$u;+?V6 zy)$5|ZNN4tE6Wd`Nf&Yt9pr_+_Ne1k3RlvanO*H5+|pJKDw#4V(*C@yH46IwPGnwm zmK^CU`R%mjDjIdLWvVw++-+v(JqO~boA=?uUU%-!tUU3utD}NPD_LlSU##=NYfe9Q zhD+&Y=5j^k_rMT;#p`7P+OJL%*PP{yX{0Q&7;WEx(vm3_CZ;8JIkDu-! z->i>a=I#O)mnL>0sjK`Rmn}R31Afr<>tf!hk?@lI2ot<0S1lz8`c0V2e2B9X$!p{B zY$<0&`=Q5(1yFeH0bBpm3QaaIfDy|yWXF9Camlh$s9TfGc1-?;r!2{xD)Z!j93std z+D5p{I*2tqaYmC;;OuEVRzX;6c;9G9S(48kUQJo|Ni#sXrH(Zu*x>hj{xCO9RT@?w zCKk8;o4rod=e2rN83Z2~#~xIv%Qxkw3R#UgdJUep9s5o#^fs_u;%WbN*w|XHO#hr5&>QC%qGI?^p0> zlS7F!x_VV`O6dY&A?8>^den&nFS1dgBk*q#X{&17+}G3GTduPfy0obBzeeceWT*LX zx?3>g)2P2=2zAlsb?5$GpdRPD$HDm93pVmo4|G1ppzNF*ccQ3PG+X*__UaQx`g?j7 z*d*Gpwi7?FqI{;X<2uhb_BO;Hd0}vT9J%!0nP5%BVpy-;OE!Im4MvlWU42>;H?_bL z-=1VpbGMwO{rZLbYg2{O{yu!wVF`{;Pg3BwQG}Tf-Ioo$ly}P}Z~KF0s=mV6z*yeG zz!Zz#t%lR>mst*Z%I+mCQTRTh@7v%e@(uOKGT>$XoiWny9B{5qvP+BgQ7eOTEam&@ z|1ub35~}EY3Y-RcA>C)Mfo&s3vSoDFo8-O}O4S#0BhQ$lW|S|qt-i}_@?G%Vh>P%h zcY^feD>FRXZ#!^}N$gscvb^C|n6Pcf7(R6ESFxsLs)8>Yv7UCh{58;j?_U{zn))eJ zmnyt?<)m|#mW~C7&-+-F-$h)L9wnG-1@SiBweY~sBH*Yi=WLA$?rklEk^V!QS`&2e z>g9DXE54d_A8tk-glMqZQzzYm>&1yZ<`y)Bur=ro?55F#9Zk;|LW z-`CEk9AcZlustEv*W9xXK1?i=2D*I}n<4_CWlkEecg+Z|yxjnjIoa$X;ZEOW(XeEQ z9rrs#16^g4plQ!%R`XF4doCIUbGp{c25WS{Joh4S`79CD==ad~;lJJ3ZIO@s(8;U9 zhRD7kiKA@5u_?f<%4b^29%A^m?TYOE@5A*lp>QtD$|U@DlnvgXXCz(-;uD*G7v|>(vs-d` zd)NNN$?k_Cvr-zHt#tAGx8?A1-%hsepegD#FH!iT7uIeUox$EvPFk6DiSRLcK0hY7O`NwQ3BHd|6)n&i^Cp#p-i({F6>~euhgHN1 zcey(L>pnUgr#8T$vkzDr<%j#^uZ5pQsqS@aD6hb98O#jo%*T@-0fT+ui2Y2qB-09` zTdLt?;yLE}><9X|t{1vFci__oTo>CXj#S{izEaA4YEFccJ$+g2OEbLrY%L5LznrW1 zWq>b_`hmpe5sRljnxl2Ip?`y#%wUEg#vd$&e%0CR-qvrJdox;iHq48!+opxdg$b~r zNku&0V2PXBQegNZeRhd-4m#~?;c-X-XBn!EZBu5!uBnIE0X18E{DyLhOx2{Gb3(+# z-+Brkha}JhXV>h9aDxe~p`*Hdrfr&_tCP!5)we+9l+DyF{*!(GWQHqtC4=wHWZBk8 z%A|E&55q)}tLZ}-{zkK4#H`J1*f49{(lr3KXP%din)XoKAx{Ju^%~rKNj;dp6;KoL zR%UW{to&VzaX|F?`VXUMDKkQ2 zzbu&PWy9XznT&a=7+Da`>QE`Y1T66d;g64`s3C(|7rkq7-PW4cXCAUV`pLJGDlf?x;`%K zvJK3fD_F-BgK<=1H4JPOxWSvq&r-V<<{uixUOc4E*)PkeLvRUqtkxX2cbEtHq4!vQ zhn}bua~+1nrAYbb7C3%?30#g$W!Xx~@{Hne;rPoj{EuZ{#MYzJ6xy>HrKWiN26+an zlvw5sQw)8%3|@TO!tJCS_`#ihAi1iHy-+)gm+K>hJHMClv7L$6yH^BXD641Y2`Bt? zyBxe!eVWeK>EO%!7>K!2!#q>XFxGoL^zC>^x+Q6ySaw*h&M(r0>eF!1;@__^~cKX8>XCOK|`vDZV`ONXEM;mmAd>>U+; zbaH1j@biPZe99Xa$OG7M8K_=q1`a9rwIJXJRwk?&pRx*4>BYSBG(W zcDdrV%m46-o=O(DtGWcrj=Hlk9xC$nq)Ukw^2U)b}@#P2U&5AI2G zW$teYE9<`k9BUf6kVt)0_m~3rJhRxm2Pg4LdYBMd+Ko5-(<*LxoTSh;47=ipF(1nn zxN-NXYV!JmSmFGZTK-3rBl4$mh~IBx7hUP@tQAA|qcnHHl722&0iJU;_&7Tqw9Oh1 z4vQMs=TeJ>p1|n zsH#f8jtLTj`|2xZ^2y&exK*Vd79{wxk{1$rbI(*^$>nU`q1XVilro<`QMMj&g{uhD z`zj{Oey=dY^i45fdlk7B(jJfaH5-_B9_#nl62DOv@tMEpr0>_>7kB(hgl;m4_<52E zstm1w*w@Xn?iHQoa>p!TUkc+d_v?nC;U#dT<5RYA`f%KSy#h*I`?{YaOnBFs80a8V z=hX?1?Gn5kPPnXP4!jkvof!a~Zo6>5-`b>P}0Yhkv-Tu^0-2xZ6JIHQ3zVy^*% z6y7?E&jvX4dnTxEux5|J5L>fXL4<278=_8Ud-ZZ?(e5K#=VpaoBLiSv%~4L((j3jR zMChke!A`AJmdnRx3(b+!_(u;^utYZ*xHl5fo%l8L1Dhaw!cN)E@ojji*DS>xE`4i^ zSARx>*QG0LNG8qC(JP>#%Q^S6L%S~y;eJ6&zy^p6P6%Nqr8H`LnScDGnMtVrw-z)YlO=EWR6(-eF1le_f$ zG>U<@+mu<6iW%vvS3r2%R_<00ZSUbc zYN=c9Ojejtb!Quz(qlu2lu z3=`($vCs3(@I*ok82dPIMGG`==ZmROHwvQN%m4VU z$0VXxR9BqfHV68>c47W@R;b^H`h!-k1t`Tha3xOKc%g8dA`kiIw?63b zc5#h>4GCp%&3HFX&>(E?#tp_;!S?~kY2sY1P79?`&h$V zrcLwbQCcjdoDAXw;?7oSErR}^p0J}sE$~-8^(C2T$Qs=Z@XGUju=-Xm(|W5ZZ_mvY zGM)$WL!N6Qx{&5DLm~!eSYc{&27EhX#3sg5UrZ={W<2S@jkVDtVJ^Jid6+G3x4;X8 z>n`0Yksg__LOdOz5C6~DeA1b`4;A%r__r^65iXHO{Y({<7Ul3yd+1|XbSB&y`hoTD zNPc9!RFEG@k-gtQKa=;tRqGgcaY9$>*Y<@srj$MP$^y?5U;KRgIjPn4yJE=1B!FiU zF_L~i9|KFF#OI0ZV^$~mosn6>&j7}!pXKobb!|Uv?d?A1Hu+87$3j(ECw^8>Q|y<# z5^S%nV+EwaE{YC-mx(UijWwiA9dI1pxIbrsovOu=C4&^%6iZ9>aaL<4Xt`Ol!%x)Z z(M91x{kUnoYJWo<7(v)$>}M9NL+|L>^qD$+Wh;~{aiTyu5`&I%ei5elAVh@X!{zLJ zej8rcktW1m@ZoDasvujE3@s8>vHrU)mR>G`)tjqj@>fP^HfAlf{&$6SJx;h;a1fX+ zJMXTaW{F?AECkKN`ur~HUENf96Gk8GC5x;cCXeoaOL)G-1!6O(Q~pu`xYkrL?!W+C z+*}Ra%LMMxc_TKUPZGCakq$djW{TfiW8ihKu}q&ZpZXI)icZ+)MJAZ=!WVve-(mkn zx?sKEb=akmBE2*v3Rm>j5+-_I=kM*JoH6N6uvwSNmTc)D=if#P%5D?*8*e^}>GsnV ze&BusGe+017W7i|Bn8cgQ?WL-ij|1+@y-uK%n4gC3DtXdKX3$jyr z7wYus=a2&Ype^jxCNr$7jfJR4N~T?>f!FFOuc_)Avo6%f13RXHca~fhN8M+JM#WHW zqADJCB){R;YPgbdvMF@yczM9-yTZP4gW%9LU0l*L1Acs<9@|&}`^HtmwnKNNw@LYTl*kTvmVTjcd*1mo}~Z(w1Rs{`5T9(9RkUe4x$0^p`lBw6*$IP+nHE< z<~gW8zRK^iH^K$83CsEx%G4KimfxANN{}AW3m? zOO$L5fI3M&mqz={W|NbU9l4q%67IC^O^%SAlFKi(?~AKq%VGW5l*Y+d`^irZDG~NP zc*A$4j_D*W40PX?l2(eaBl0($a1f;pensLZ-{<_Xn-bA?jteRezYfU{%vcw}N3%j26vi-^p(kF{}ZmnOpNXV}o*V}&OhPzssUaFKT@0;u z&)DRF7MNh^4<^GkWMjJ}V1<*DuqO2eKUmoi=NayY<+nDouTM1PH!kH0TYD_x>-TG7 zuim8PNR)^_Hdx@viRtjJlOY>7f%+yU#liIWVy^p5ZLI4!A9Bw&u!BVws7Kxkx5X0a zs-k7$vRC>FPxP1kUUzMxDG^@n7EXQz*>V;=Re&(4C0 zhcjii#NCuP#6cx@oUqxhsB(QCbQrdkDV3Y!IP$q`YoC*@tiCOdos*>4rPo+Hpq8Bs zUT;)l=YOlqm;THWG?YX>D4av1GY=VltK$U_>sD;Kkk?Hkr-j<)qgX*ou1{$?jdk` z`2}}BTk?w?BJG@mKJRAM4fSqahY??0Ws|4r4yL0+u^Yj|%eOBPOJBI9P z*uS|QPh3y4P8>uec{6KU@`F4IfxzV}xUu9x?l^4md{W4AbOThS8#vbD0k&H7YAO$R9LMl z&H1_z$k~<8ZMsPw9IuIR_Cq;~NIH$b{G$c)rNO+pL1)zcTMU{fB;w_B#u$5W2h^VC znmius;MlM6u*&Zs^CVx=LGovP8`U6ARF{OqvsZ8^-CQzDJ~)*?oS1VYDYsr>KxCRoN&KtFE_>$02r ziO$Et)s0SE+!hUdm@*S)4EVv89Wcg*!E@o;`_nSXhF{{B5yimksfrVRn_@-y0SNeb zs_9CzkG$shT_N3d5M+JSMc)mXu-kS!yZDsHk~Ni}Cft>7lvipV=sM*aC(MOW0q1JiN*)EA(uevMzHZiqLM zv*GI1Q1<$`syygwsBlEo<_G;&!)58@(F>M{qw`HsQzHZxtG|+s{$q{~G34RhwvB7a zv&K)BXQ8>zdUkm=VKQ;qg3+67el+!x46&|+XSY%t2M_KqfAxN+FzUfuepmtNr2`|t zxAR`syE}EbzY77+K`33guTYGYyinjCS6(?|VBU4Gd}hW@c2JiuDJ&Fr^f<)}>nQIx zqy*f!XRN@YKmPZk8bo>}j}7WCZ?N7a{5@|4*J&?pS`-I%85}ln;Hq@OhJf|ctRaz^I7?;YM zj?%=j>taAx_XphrH5ql8G; z9{kkQccO1)GGt6u6_qk<@RD{pluy4d)9uwkUT|x@(8;@+UwG4ovYv9Fwe~X`N$-Vg zbK+sKIJFbty3Yw}|s>EZZsGvKtEAKR5+iS~Evq3-JymY#A!^wAovz@NJV z>54a}z^>4F?CDX;A=w*G-EHKrykLOuo-Kv?(&uasc@U0}KK8*74cVr?8?cQz2{tEg z@PAbd@bs&4%9q%}4#<_|`jb@kzP((B5Il&C}y?C7s_CNFM?bAVs=VXL+%rs zE8Kioz%QAohjw!V~PyQBb3;rJ{{$euIYlxz9YQ0Q4gAp`{2X2 zW)_^{j=i3g!ywn*?ss027pdz8D4V9i_ZVo37Cxb{@Ky|)ML1pnWuPS;?8eF8Tcd2p zdFVdx9qUna>3=L;hd)*S|3}$d_6nIrgf!iIUZ*}y+G$8Tq$GP)W@Tn36lJ7Eh?a5R z=XKL0Nl{ALI}J%C)$jei{r&+Du5(}K^?FV$TIJ7bWIW-oP_N+L-J1yadxmqx^ygg9 z$piI8qsd*65;AXtSlOPX%#id5EY=E#`D4D2r1A9Dn;QtOc8-F1r)g%FE9D>E>-l2y zjWEBn8H9f4$PM*&d_OseO_z3HM*J4TQ2d91Xsa2bMBPC!JW?TWP<9l$PAO&8_cte%C0NcD2nWP|@87T1NajUdfLSPmnStRMem$RB|=y(MSTJk@JA=8`*Fwmuk-6)Ulwi|#U2sZ`gebQJDprI4rc zLnu2xjGc7Mg^6$K<-~fHi#nuI=?wQ?7zb};hm$TH`kk!_g6xcg{AIn$$oyVR^Jpu` zlBERGX9tS*@EvNhxMSsEnA9W5oozG5S#9N@U+B`f^1CV?H`xtWkDVh(pLy~=j`qdW z@p@;5ae5CgG2$yFxv9f6vHR;P$b4l=5{fwd@#+8Pd4mROj5rNWiQkCsU1NN6ryRaW z6!YxAz2hc_dqJ6AGLz6u=lP5j`1~!G)YVe$#|zrGm2JtdsgTE})vLg|agY#my1(tF zz4lHw1<&9oH$SWpIuxY1rZL*6_NEE~UR`bsQW=33&(dMN#}V?u)EN)Nm&3*N_jos7 z@VJ1Qe>41ctu8K84}!o&Q;6I#%FECjjok3%&!+nMXDjMJ@$PU=R+;V?IyE81y zIa+#{sT2<@r)&~Tpc)BP)e!KuL&lOGajaL<1cDCn-ySH%lC37H%=DwP2 z(8k{nlc7grJ=xi;fop4h;l`_%=Xe^})@TvoTOCYW8U%wou95$!FI8p? z<-(eW^Sm{^xvlCNA`E2W8&mYiMA-g$GwDf|6n^SWV`JKL7~|7w7;-5C7BqYzL6md< zLNS)?##F)adS(2&hdx(I`DA?p^`$P^1k+dD;2Ev&;A(09)n#QV&Uu#!es2)K?<6rY zV)ZcL?PPW5$-L2p;mf;JopW?omP7=-Gd5%UX=6D#!Pqib=LOJ27 zExTCS1I27Rs){8S!{GhG&m=5f7bDAqfuxKVq}1r*xa>_}Yg*4g*=C4x(k-yi{T$hu z(2Ae81+XCjTPdymS!wjL%e9b7vR_u;z%*K$-N=ayVRe5oaPW7n!J{J_qs?G zu|%mG_i1i+3NJe+5Wf#7u@X^tnfkr72PC-+-X2ONA2S9~Nj#ig`N)MixaI@rw~?k3 z(EgDHkBo4Gdm=o)BTJ4_U4%D=z^c86_z4%3F@M%lc$s~g{8AHOlx+~J)9cLyXvpC2 zhQmUDOBrR7oaN>Wf!C{vfv8@r{{NF+B_?i2e!?#DEM_dIAtnDW|RZUUp4$XU^ zSwmsgZ#m!dUf?K^%p5CI!w-*X{>hC@vh{*I)|#!RIm|;ujpAA(N;X2r-4?;LzXP24 z@j~#S8N79x+8Dm)44m0~web(oE=adbSXxy?4oFVHKCyB*x3rUIY|P`lmKTdMIkhR) z6ixTilB%iXQ=Tr4-9~%Ey?yy5t5wke>%f?DN!t&MqR$BjN~s5UElEpJ&FmHUXxw3z z-lx5^4+?0HZ7lijH(dB2Kah1*Q(+E{qZ&)9(->qVx!7k^0|p_GGyI)kX)(>iiJ-In zVJ^RfYJGQ~y8=rbBZz^~0NMtnv$dPk83kQCoG(@hxe6)uGs0wrY273t9h{*O&`o zCK#hz2@@>(N%2T~JRwmH!Py)y-en|ONhZLPhZ*D;^${>bA)t|J#ZMDc!}+I{gG<#{ zVxwwEB)`+cmY1P$$VZt;*`k51jUJ%<)suWxrM`(Z z7ibPoJGtL78aJt50Ppvc_*b4cbJ+!RM3{zZHpS(5sqlQlM)G*_5dK)bjD6ZXgEDeK240Yt%f;~`J`uqr0|X~jkOxL zhOxgPhZfZT{y$7(vX4Gqd5{K{U0OuE>n}D1uVi=1#4{J@>@|254E?9ClQ-77xW0wz zqT`427TbDq-#2N9JbEruMqx!bf=d6f}9 z3l>21XfYC%EFmoVoyy)bs%L)HjKx%{-95eY3z0IIfMvH&z%K`MOe1l(0WNt{08e&} zB{vOZg!e*sumwf#jIEU_?w~r}@BN?28;UpjR)j)Ok&{52diR#q(9E}jdOiiIFkhtw zT20T9uNEyB_{*Pt`M{2mn(~J`$tFS0cdC`WJO(SqmBZipM6j?X(dfawiN;MK2oxPxCggW!~fGLI?>wu0oHiBpWspH50ieSab zS|V=#14}TB?RqZF?6oz(H*=}iDPjqEwt@0)Lt)V07Qkm7P+yGdTG+b&J`ry>$H?US zaOr02Nk&#g%D%@Qyok^WPla9%zJ{ zsh4e=iyWD_p7O{)!yxiN0beqk_VZS{(VeZ5WNsCpwQVT-Aao0(`Cba+-W>+rFOpng z$w<6bTmfTxT^jv{ISF%u&#~9bY0nPLQZwk-3rou`l6b}#KQpRYWAy-ihq{Epr;E;H z!fIXW<@W@g+1vPa6>2!mlRmf0r8#RO6Vx8f!2-Vnyq<51(JT2CXzJf#j%iRo3*Ei% zo5m3vDQV$2f7*ZAF@gzMC5bEPyS{y*B)7a%7kB7{K{NAS(49p!b;k7XqBzEI>gQTH z|0?_~h#h$4{3PM&$2eGYu%;_gD?rb?$)b)u%|l zuO2>-4~M*~O}zUC`P_W}SE4x_JJ$?z(>tN4TA!2-x(W}P_OsQgx>RRxjHdrp!mHn3 ziPUpD99Z~o4*ytSi1Pm>z`VN|M1PeYwtotP;P}z}8RjZDB54_5*B4?};fT3LAK-NI zEdC+YR4)8KOOcK)do<;7s*c07TP%^#l^6b*N_m_kd5l<$BL3GG2eTLaA&EZ?@o8!z zShV^I{3*|yK|3t0(}eu;kIJ}h#&WneHJz0C2(V-*jD71mhVec5nmaNzNwg0)zShTe zwCCma*LHzt$#`L}!+F+o^e<*kk2>lss?lCHi z%`y#4-LV!*pL&xio%4lb`=zIydp8FJRD&AjSP!2&?-Df|OT1=x0oKM&;_nE(&ZW

    %W{$A2E|@rn>~Q$sgthy&YvYtkr%#u(;r1UxD94sX(1Tw;ej{WRFpBMA=vkX3SP6DMZ6gOCBfc>8`p*c&J zEK3s;#tBxlmBxFR$geu+GcgRN-?%}hchLKV@-m;pBzbSOH*!{a|7Nv$rva{i-vCZW zHxNH*Y2n4m*=*k3d}d%!1y>hj!V=d$(sgVU_E8Pkl!*rfpN;>ZSllZ1)0k3b#XDte z@$`n2p@U@pZ;G*tdBcNC&Ad-3w>dk%f3rI1xH)c(xC$p^rO3;4abd`meQdp1Ju_>k zHEQ^shL8H6iH!UNj2U|ht_IsU`_sGICOaI8T;hoLJo=nRc*D@e(R|wyJ*sPJfsYU0 zll_6$a7wQqJBruCH!eKE$vaFIWxI{^GQ{b$zwhK(JCc$rBaHEmVtX!oFjfYt`0j2b zOmyob11VJNn-vbHiY5pad(yq7&>QwPH1G}S-OZcXLUWSo{v07LR2$4^w>zw7p060< zPQ)gO@aNHaqcLW8IhZadg2w~Hgq!Y!ur9|_8KVkKloQ0lefv)0K{4LFbLcY}((e4W zoxUsC%_1$wb6YD6`tS%GJRJpNJk)V)PciLEJ4ZBRe&N3EovaJhYM!9?PUfY(kb7+j zxj?^ip%Z3FEY4`n|zY+;T_O5rr0BhX+a#r>}%Da^J4(o|gF7vLa6hYc_iUe`TxSMO+{EO7XBrcc&C>h4Y`@0H3c<8)K-Z zYj9K!?Zr4s_Nz_ALDO<@t?l5oH%#G@UlohA9I3K&7hM$r%FlV^C-qaT~KryKxhSJH?Q1`nNFP zRVe#HCzP2`I~pHR?_}bs#QJb=8KKpvDE5KHIVO%~qqTkA1wKLLWE#zBbkV2TyuU8< z=vVawirHaJrkr2CE0_$XUF9$~p9?c+HoD8!cy&&%;EKssB11$3koVU2NDsi%gjL2hXdnW`_muX6DoUQs?{#$ei0k zS}2!fHG4BuI7{)g0@rgNH8o+!YDvzBzH9EpH^MU6jYNU=w9cu{V)Lc)nGm5e9zB@} zjX%DSF&7MxSG6DZ9?lX3QJv)AY9Cnk;}DV6ruSg)X4v(sh4-}l7UxMZ7CS8|u7qMi zrgN?Uk(VTm)cYUNoyt0R)G@mgP4G?oQHbq%PJ+B0@u2BR*raLgoJjXi^)r!h%P5}g zv(m+D(mt>-Yz$vwxdC#SZLqoQGx@vL3A2K_LF4UQ{=I9*Is0K#pe;j^v*|X(y=ujv z6=_d4y%ra4k_u+4RxM%b4^wSe(=Jdf?csQE+Dw?Sh%%1G7sT`QCgT zY%pzxcb&B)Z)-FDdJ)XNvU6ahJqEdrHUD;L*Az><*?$V|ZV(8>9EJ&>god)?E~PT_ z1e(~?9S6O6_sC~EI`^`6z^@N?oa=8I7xjgr-LBVm-|;8Fiw->G2!&}6zxC$AUfVA%Z}g>kF8 zV6Jfr&oajs9dngMn8ran9c-^Z0fEJ7xW)*%=ML`OpG&s3^7YR z8Jf?@5qr9O?4CyT)dh$7`;IB2h5AbPF|C^L@|A?MWg1zP+!|*3gW=eoa|Fx{q&Rb1 z%4aE7KvvG&M!T$e!bGl}o$ECf&d~X+Of?uTdJSZz#}7<}6>N_?z1iOda9Dm>#1*D+ zspoE@fsYEL%M?r$;fP$TVE-LM(jif;*i>3`-H zm>m}R1nYAxvAVe#97~@y(pQwQZb~OxUvCc^sb4ti$^p23r;HrtPsGkk6_mTb$4h@Y ziCdmmEb^+PQ*3IE?+zHJz>xFwzB5kq0TpR~{)X8qcxxJg9eL8+w=JVFM64CM9u@JP zbS}Wd8(+gUr#paRfBC#*^F`lW}H6C4?5u{pf~y;e>}yUx5c%B@~#*XbhsIVOy~|U6vPZ(vc!Cwa`;5>V1k$UuXuCsULZY?rxaSlS;Ht zP)(QHPPli?nqN*k>jQmO(SCsevS2v{5fH_9y%>7hv3W^ zbuE{Zx+b;&lA=Zw6o(CRiNpU z0Xl!phHnY|MC!6R9(tMq2`37imDlK_T+}X@KU0m7qCH9zuB-v)058&QISMCFx(s#g zj|rZ!!GRzS5(0sL^5IpE|7tEoEvGy1XNr5Q+y|%6ZzR)te_#w*!Ct>IlUdbHdEt;? zh;DdK7E$bC;x!)_vq({J!6FLN4XoJWxt+}7BtvX1A@FcT8M(MiQn;P!b{;2gWM32ENw z#xZ<->&z>$6#zn0&@;tTM{e+(pg0J|eh7xxDe&AoVgs zuycY6K24*!YC46a%YgQ=k}WV=ua!6R-c7FK8O@TVH|g*B7PyXWfu;vCM7`-R{*p{% zPvzD#@1M{NmOB+t6#S9+ymr7ky;IO6uy*$Q?jYQ9wvaWuY6jCz>Ef`nJ7LwUc+x_B zaGp!I!V94_Khty+ZpnB6>JNSq!CFUb9N!Jv8|U)hJuKs_3MPv*(*J20qS(b^Soy-9 zgnkth4xby$4md1f{!*{a?X(>*N3D;<(x1PD{`~C6lLW)*XZ}8OD@3Xg{(oy}S5A8? zTzq_32R2n3qUra)8tyRaL69JUuU=BOiYY#IEXd6D!y z`;OY?QS7pla?B9L?iyz%!XZ~TVvtBXdd3SD(eWpi0bN%C0Bus-x)G|c^CQ|$YAwMlb8uOjAle10sm1_oT-jJ z^0MjPsN&kVRBXQRjYC?467PzJ@{oml}UX`RESOyd)t^gv2WLFxm?vIPW0u6|m7RuKg z%pu0*gD9)w!8SdRXZFe~pvHwwpfgjPdwod0DZWDc1 z(syxN&eO)z0U&Hyai85k!4b|4*Fewpd7wG}I2rgo9!<3?;EQG_?}OVU&M%-u)J5`{ z@@`k?yMCPykZ{Ts{ye%B#uoTvS>_!a33ASFMz51FF)zSph{h|Jo;M8NP@p!Wp3RfKBf1q5C{kS%0 zSrbd<`ON61z|Mjg$8r1?dUR$Srh(!Qi%PUazf2Q}$(Fn4hoNjy4C*t{&8El%6WeAJRcD~V(<4W~Iv%W1w=bUv7t7?a_q z1L(bDC0l+Upu4V>1W`UQ^vPE0DU+t%%B#5%9-44#nk456Be8i+6U;cY zg?tT=5W4=C#Rlo+F<#cnc(F1YoWlEQHwyK(v}8fuqzplDoC@{lZi6_t!{o0P?emKF zh5KV~@lK1iaF0jQ8^=+KOV=_(x6Ed+b&w(AOMau*U)mG&Up+Hj(Fg~e%0RaGIdLen z#|0jzz^KaF`DL4fu<`L>HtVE0tfw3zcO{B;sq7|~U8wfH(-#~=ZTOBfYxk5wH%LwS zO)M_hqr%#5(1E%9fU`%rYa^zJ@DMACKVO3qm~7)fp5*>TVjawuomR<3i341x zRk8>V88yos`IY66k|GeSw;m?6p;;(~MQM!C#tQR&=&k*|pZu`VL*<##z^&+XPVCi1 z!`5w(xm$}7Z=iZ?k8T*Z&0b*BuZ~_;$D!Z8p6u(kz^RK*gM*bbKV|ozVAH(q{5|zU zf=~1_-}EN|7WyqED=AhZY>0+QU&HtxDK59y-V=UJ?jB zGxn@!*GwtoyCrPr{5r0P@M^Ia%Gh2(A zitBD@Jq_FE7xQE$Kjy;Pz2L#qL}vYVnjIIK0yjerkcG8BaOFr3_H%(eQ!rTpeLKA% zcbo+0-bOQ2HGM(%`)$GdnIE{*gNMO}k>bcJbBwro6Xs5Q(Ku2`1GhHk!>f!Fq*{C; zK8>z|m2bLuDt;5Wn}a1H4)GyFZ)dk?pwWM19MxL*7E{lfP7q)2p(5VY;zSsT`C=U|Ex5?LG=y@nzoyCL^k1>nE~vR;O$K9W^>eQFNYz+ z#QOgpNeKfyV%Tdn=NW8JquI!@kP<-iPw1?Us)~k1N3Qc0Jj>y>Wxf$%*9sD*XrSC8!_nBR!*Ruw3^8+>4mWpWv0ixw%-0w9{)R zQdW7W6}Bb$lBPRS!Z#f$ti#kiCRnJ56B`o1vQ>inuaM%Ljue-c^%Z=eda!oa7`U+N zD*t3F?aFLg4N4QT$k}C%sH{8ylf94g6Nf+H=4d60Fp$zpZS0G$fazE62#(T_{-myS z*1-8P(@gJ+M*SR`zxs`gaxg`OyP0t8UV*dkBRzb$F9s%Ss566Sb&xo0gJIo4*-+jYAngzGwgFIvY=@PfO>)+f?dZLNG$1>pIeQ$E? zz&9LU|LOY($+c989hLjFEzmo zg#yr&%@@2>a};`QDPs2re`Kchs-Q-UKRmy1gzR*s^Zb+_Y|ClmW#78at)g>#g^U!J zKV*f{b$8%>kRloUGD!cfeXQkB9kXDE8E*8dfM@ExWS@jRnocMOrztkhv+p|yyPb;I zsSOse^p!3Olw+WxbPq{ds*8i?{h-8uEI-%X7>yoxLsu7_+nems#GwaN%3Syz{8CPD z+!WD{oikq_XWb|Poe&2icUck7jot-iHU_G{-g6#5j(YtR{ptTgn{h2R#&`TjQ1Z@Ruy-NN0kA#^ z&gP9IP}&0hC?+s7&zT<|DMzAy?&jAWRUlvfYNNk-B6PD$$rySsXWfi}8<7!wA3qHo zrtb}t@*a`rL8CEo@mr|x+|Lu=?}cL~sjz$F?=sdgIyj~8G(@;(5pgRi;p*%ZR{PsV z=4s4xZb)YpJk^)v_EQc2fKdwU{v<~#p6KC{CoxcXvY79rMDHf5d0tssON#f%2|WrM z*|UK)O#5MRR17MDH>?zwwMYj?Hl7yg?)X0Qg&*Cz*!|STIO4Grn!m3CqnuAfKb%FR z@1RpEUwIoh`EiFru8MH%okdExHpv4bs!RxNU&1A{qr{-Jk|}+pinmXnh20guNrkN* z_H!SA|xeEVQ=l+*SW?c1jA zR43*i1K86i;3?2|G4+*LPAudrP~Y4YgI4&`7)^GbzJW%8JJ=l#5zKf6Q#|$Z6b!dY zsK4PfOnCa)PPXDx4KwkK8or2%gEPCTNassEJn|w2N;H~z0p2-Wd*NHrzU?^O44WrD zgBP^0_IL9o?0Ou?(g%(?Mt_IjO4Sgzub%{Fn&JLk6;OYtj^|Br)FfUK+>FR18NKxP zd>;cvT6X+vPZelR_)73^>?1qRTVwK;53u0)O#Xb01TH1&-;VuDo92ydYz3Kyt)$0Q zO8B=fg_W1dV@lGMFpugYemxw<9jEuQH@)v}uJIK_?x2|4`dIk$|$NKUF!$4oI}X|$D{CqehchA_KGZ+^Bs4+OJU~?DKH6@ zm$*a)S4f~d;P0c__@N>TLI$^x_qP;;KtKO_z9-XmQWHO@M#7c@pNJ&VdwlhF$f;2l z^ty#%#dj-KGpUm~cvT0PBm&<1juOw*ADCa9%2u_nVA542F?L%rtU4sg4LwuG>2m21 z?4e0!M>`5bZWgiK3^H*OXkW?V7%-}nHD@FI zTX-FkC;QXvI5FXV?QAwCFeY@<6 zg^8wJ&W?1adT}lQaJ~*>7dZ+~PI?B5&N>M?o@wCupmOlpNQh^I8TJoQo$w@Qe&~KF zVz@YtKe14j4Aa&@_0^Q$Y;Ys3^!xJREA^6C@8FM*)WD)2n_>Nv9^$#t3QN7-fy1&K z-V<&Uo=H++&s5!IER3~rw`?UG9G^uhs}+Q?!faOjsXw#&?NhFE`zo+hr}} z8VndJk)6-zTzW^lijI`~t zN?5jgH3Z3zB33SUamVva)_F}eQ>>(hqpzH&x$$D0s*65qcGQ4hXc;e)_mFdJ^8&*y ziA+$O8k&FK2d4RXUD{KhwfTkN| zyhkx}aDv!d(cD&DMDP7crQo-B50Nx zBi+aGjW;UbRDnD6IDI9CZllqDQ!jwZEdFKdJ)CKu6|~a1#~d}sfKMFw3s#Ykx5I@l zt5R9MOCEE#UlCu-O@;|qhjYzAI{0#XGQ>{ZCa9%YYff?;`24)i4@ZiPj9L$FSF%a{ z^lolSMlx*QO0hU^EBrjE3HA#=3Jld`g{fT`?Ab4unZe`gDE2u66!!I!3-3&Dj!rh* zI#B5Rk$!hfE2)>{xdwCajt>4-3xKw|Py(@|@Y(!ZP+0Sp+#KJJ;xSY|Y_G^Hwn1)R z>A$&s#}0PSmrYFNCv_ZsJQ6%-ej@#Je?Iy#0Lo6P2+qp| z;X}94?5y3LOc&J*=TB~i?1_~`qVp?uuS{jbTb47c=MTfS`~T*)%;ri21J-i9q`YNZ-fc}$58(AqZG1RW2)0Jv zq}}_@%Ut2a5|Tvx;}OmRpHJ<85(-}2+2!aad>9;ADFPaqVR+wrw+4bgJ`BS<^;JGIlI_J?&-{f`&0v?kPD;j21q*14jNk+2Mf|3IA2&pGr&g# z!|7mMrb)*fbJxFtihwDC?QaaRKKBCb-`7Hn>D>NrUljxw@%WVr^v0(+@Hn~UBt%jl zFO7(YLv1_xy7AOs*|`OhEuN72a#MW1;T0Ur&f>j0y8-3uR9Nd%cbO3pnizQVG%TRn zW52T!!iwNzcK7=A%(fkLqW7(WgJzOk?*RimR6srW_Z7(`J$y9l@RChm3M#gR<7^oRZ(7a8{Ks$DFs4j^*9ov(uOuE8SKo2O2&5;oh|Zp5WYv8 zn?`St>oaS?s;G=-?bF5W_~8ZPW+yV6YSeJvhIF{_AfGg!lo7I8;p`X>ea3Tv0_LUp z!pyAU+ymOLF@0$ulqq%!{#3u@+AEI0w#8E1W_t_NPq+&WXWlgyE?+2Q?Y^=-OJ~E) zofcL+Q)!)rQ>MR#mN|ErX*Se2C=LfGHn`+e9`k0I7Mk9wge}^A#PWZ+8K28xdcj4W zk(3T*1SZ2ayDYLxS|1}d;$di(JzwiT1>D7Wz_exkB(&8UudVqCvfVEH8DhJ+`+B2A z*!6Up0~6AM;P2x>+V05;L!M-@c?L(Ao(`JdwV3*n5+u1Ms>OYnoepA|A%a^EX|Gde zJa}0&^P4{?V}Kg%->lzHo~N|ojL(_u@eQ+>K%WQPb@Fdk9|<+V)9)JLJNHWP!bC=R zT|blM|GCUCQ%2y1x(ujo`#|KEk3y*v`(eY+!_J9R6LMcJ2$oF@Cvj8{>}GlyPV_w@ z&n9-@ACGW$S@;jWaUS7z*1L+lE%lNkaZhLg-0+SduBYk!+qnx~-2FoS(pzI$b`az) zQx%*z?~en!MzfDYI+lAjbs#h1;L6%Nqa|{nJlf;#ggm6pjkbRuf3N3 zPosN4^V%Qcx5FCedp`nQt+{-&;v<~z!l|N;zfttPFXnj^+Lk*K8OvX|je1V!on6Yv z(3!mZTMWG=2gubw=9uii4`edu39h`LdRjy3PubtZf4+Mp+9W-N>FiZfZ8t*r>{A09 zoRq-CU;oI({74q*t7W7{qK4TiSaP^t(Agj%3~r2Jmn&s4v*79)xOn#mFiGPHo;)|gorMi>@q8QMQ(Q4CwhBCF^Z4t$ zb#T&~6cB&3g506c#&?R(f7}0*bW~AnM6;KE4hMK2|ExnP1y#1E`!1ujM+?16s^P-7 zY_c~;Qpj9RWA{sLW>n`r=6doxM14|wp6O$!PC8suQ6jN+D!5U96F3XclY?(>quIu6 zHtAh5<9u<5i*_i6>r17$i4@c8v#*6NwMC7q{q6CldNo{4`A7zhoblxO3K)C;Gtbj= z3zvW6nrJtcrP$h+6~VCWuRZCW(~847GT0HPDw!5m4R;Ibp*m55Q_UHLMOP`sC0@;Q zFSy5@R`7-!hKbDUDm7e{N%I-H50amA70_;(A3UL6t$H5S^J@k}qS-yc*Zk+4^s6J# zwL*&1yJU`Ql{;a+`iDlFbPYT*a0I-@R+0pmpGRVVo^gFJMn@Fb7SluZfn?P(GL7@`ACd-zZaf|{T3AX&>8zR1aij~ z@%3nD;t0JS*gheNxW;lQrXR{SybWZ|M;YNhx&!|YyJ*W-!_4D*V9vQ368Y5_bxf1M z;bbQ-^G_CMV)+KmEi-WbG+|H@@f)zW+b`agPf?K^pW#R$j9 zR6w-vMc$4V+NkcA0^`1Ak?l?jc=5(+=-l&-xVG3KH}Dhc7A)eY7R7VL{L!La*Kdm% zzUZY@vw^FEV3H&n>zsVL&Up=7W$mgGhy)0~9bbYKfZ1ZzW7&^vh(nC;IY z7Wbrt(WL@5p)ZE%ZRp}A)A`xuA;od$E%4ysCTM8>C|Gx6m{7Vim2K6f-8lj32n({{ z<+M-adV~pXaNZ9xeutg=uF!s&PrQm6-y)50 zBdq2@<}R9lXfqOD4-|lsRwPkK8-Zu)B0*aCkt{Ny8rNv*H}p~yv;_KNU*%}_O<5cgs$2W?IOezq+VAI|RmDk>{4v*mRk;D_Lc~C!g4o8cu*1NS;oPuS#djV@G6-1m@>&;JR~_gV;>u4~W4)qmiQ7^aA@hz2=B z+;Hp^L_Db%R49rISJ}m|9oCslRgnhm(@cWQ^v7f#-HQ&$ghTW!edhRK3(P3{L^Jmo z!RsNOu>S0Kc3mO^FM38|5Yq@*dbi0@?>{JKmBi}Ssx#fFjZKlMFn!rdV&nS@Rqd9u zTCe6Yax z9~siw&TX3+$F@h@ZTZ#km1=Ge*6CxoRR%1+r$kbN{@~>sE7`5D_cBNPRB+TBFSw#} zku1q*Mz!4;th-zyqaQrTo!#ltsoj`pbiUK%0FpN7lk>=dW zaBzOGidSCL!3~%3hAqz%m`ktJkgt>lKdlSMY(rV$lD|9I`Ui%L{S$c{O4<&)Y9+ar z82WDY2?fLR_XRUOpK=S0ieUO$DXuk#<}WpM!kDBFjd7di2_=^Fv&*Vyg8{`H9-9}# zF}o_#Z!!+k7FEOezxR1sv+Ow>c~mrS_fIs$6Y>c#B;`VmkJ7`tzF`pN7Rg^|FO6g8 zpos6=G|vKS{@e$H?&G{kW&fe=&wuka+F1u@Z7+j$ReMR*gCCe_5YC>hRADSrhq%JG z|K@FW;Yf_+)9eV}zXGFZJ$xx14&Gym`3&75%hVpjo1;l&ftLW!eGOp?eFK?>2>QOB zPyrH)66()2I|=U%onuq4iNTU$>YcnrGkf3ElB{%NJpDciI{ohP>fU5>pZM=ZJFQZ) z86K4Bg*`@N$nQ0c^v()qeCu(Q6_$eh`;kmq+M)p!{EYyBLr>^ z{&XJNu*c^=V2IoZ%$?7Hx7kq=_d;B_?MFVFT)LIHxLOQtf>Yps`E^kKE0Mz>+cy)bs6Lo}0HM6>Av3V>%T#wk0D#`RB5fxrGS!MO8sLdt2fwFep*1!*;G zHQxzeo65*J>L0nfH5?9K=;Zy1Sv;4AH7 zyS>g4KY4$E>(iI>eRzf3rqQ(bfX?JYyYx|)c8cu@oJ>C4|AECWk*wQAH%8@=BJPQb zhvovBw?Jod{H!EMxj0j>VaT7MNm}0r$#2 zIiERAZ&iLIL@hC3Mh-K_g)*O^_8lXLI%JCCSDWCdZWqaAhESYMV%0O%nX^0o2o^;} z^G98jB(>YLF=h2WxIWjNs73w4M}JnZM&lPSOMj&-S>e9lH(*`gmc|jGW6{dC z3f{$iAmV-#QIai(F&}z)Rp-39p>x+onW8-E<9OyyGfa%f6D5;ow0V%pP7SSM0_)T; z+m!<|`i>C0Y=y~RZopJw9Z$XW4!76F8=^3QY1E>_=z^yv8o8!z}vWf1fy=@WD z>adeP=Z+-R79y11lIC(3n4|g6E_k=`1aI%}Y1laXod{?6rJ#+96=ksKmLG}dA5xu|q!=kG(ZjhmkuY;|3IFv`Elik3^X&~1h=H7n z(En-!YuI^_dFy6?PT}PsyL)f_=zcmg@d6utQykLIs-dw|BCHsDj!e_cPU*6xZb!-go}htsqpyY2@usj#Hluy5d@IFH{F9>cXh__q)L=^u?_%WuMz zzRg7WBGvAOWwFQJ6f%uh}xDqx)>%v^}Hu?&x zl%=y0DbtzY%DbGL*S|S@QNj%G6kLJl>}P>tF`egAGT306!!n~r6Mv1&1M{Ts?ETL=FQo7N7Yifky}6UDYNy@q5p8g(=`FFc6c=VE9%SdZ=rYNE_1w9a^I+I| z${%f{J>Y|da40I0Odlp8)ZP@tRz|I2epafX?Y$`2JO2y$R-%iyq$454QC)D=HxM`G zjAM;5dzge-`nY&sD_l3NCa=EV!p9jAY@H0B*?;j5_oD3IZmg$fg6-|4V7_ED`9G4* zJFe#U4dd;iMLX?5312gW&iUL=LMYiId#{XSYo{pfjH05bj8ueB=lR?pNs5S)j4~3k zN;Ik8^E>|a^787HbDrmZuKT*)S7)oT@FvHP^yzh+`(&q&UT=fItM5}<@7WKn?(c&? zyVONEe+Iwsq`s7KWOK*}C-*#r<_d4BIPoF6Kio~${r2UG?r7o}O~$U7Cd>EL7>KXO zv0h-i49VX7UPAZv0Mc(yAve!f3(L0n!LlD2^y+=a7#H?~-Nff2_b>_n->iSt=IF$(r#&!0MIT2TYT1DVG)b0j*qd;?+CLUC8|DZbOm5r!;LzNN)k#<4%%SmF`07wBAky8|Fc2nhA!xNkH{{ z1zla&f!D`{5fwKbPP>1Pq`oac?5C(q`#;df|2iUJV1)gO- zNru8}e$dG?>@HT~-~Akb^G#pFk9R){dvaz79k)73`7$?{XQ7J=dd`CL^(!=-y}M&g z^Wb{sOHt6_Vf@NT>D=G%ihP}?3BHIv3~TneQeggyXEzQ&X{@jK<`xA^x`6PgNSS}S zYyd`kyaG_XDB95Jg43&7pe+6+XS-V;i{mrk?9fAuHQ0eetbIwmfi{;H*TJXt-2|(` z6#3O&W;kk2IP|lSrA2qx8*QNv^mjQce)Lw4@o-+jm`8``s`;A2mzqM-dG;1pS7D5E z0ih;3h09c|z9fOo6fHMtIXG7Pe_6&@$!+*fe}0 z*}S1IXO*aiT+V7Zu&R?fDEx;@_H{$a+__@Qc7OimV>@ZCN|CR=$vP<4Y-0P?1RAu^P*?zO$Whl5+{#&%yvNBSP@2v% zr>)lL+5a9`KWLK3WXK8EBBF_Ljli9=(Zkq|6R>|!8+DI%#JS;Dz~y40V|IH#T%maY zmdE(fXNRW>Y6dz^_eL!O&wLx~vZ@6l+d=0n9F6ssui&`rBC+-O+kEqY8B&eH{ihM? zzDb5p4*O}{3D!?x?oF=QEaoz)7M>o@@;mpMsrh0fG|N2zRz|uKFXP>~IC~W7xAq;^ zP{e$UGs?l{eGa`lR94XYeUhjbcycvcyLsli0{5ee{Ew-u4|I73Joz-38k;K!_uua! z8LhFLq*fnYt_1_SRnm@~j0g4d08EM15LNbaQ8<{VnAR-x*lM^H^%1T1;O{TD#tlLvcM3C|X3+H4t(afqL#XuvZuTqIL0=vMOXRz0@l0c^Wu4$J2Tqcx&ty5= zYre4h;(hVsP*WV6)(Asg%BiTkfscKE1oYLF_^SVOa30&IY?+rQvAUxo++fUSyQ#_C zsC_1AeC{aJs5H@Yjsws+Fcy|oH#sh0->E*^{eS~A4uh@Hz`q5aIygz5zH<|9g!Oj% z>NgK!Co;BViUgMAR?uOW+ws!ZFk)J+!*w~z(3;vH@i|_FzPzZ9x#rPuW8f0{sG|*^ zhbBo_k@?l)Bk3V^h^Qls7`uHAI1yK=!c4@ec<$_F|_x8_we-EIO3R_ z!yW$K2hSM^kTOAuA92qX_q=-u$sY?u?G=xB`w{CwJo^xbtF_tx#c|lt{|r5E>3|#9 z`#SN_BJq5UUKk#?9a?uP@}8lLX}{42GJ;=8;%~j+|Ev8sCr4LVrEPrE?oBX0P?0Y`zSt@_k2*vaKpkd@WaSGeT*KU0UO9Ky4?v0wz zH>-d&j=#xWs%M^gwiEdf7JB=7q!wl}-&e>k#%W&@&3}9FRjNx&NVCAe2|vJCZ!jIB zrHw`Fu7a`XH`Tn(dVIEDf&89Ak;g4JAuq0y$ZmE4GLU%`!(&*+!v4IE>EOSEsHRIb}X5+U=la7 z>@mNk_6UqRp~SEH)*r2(mVxWD-;ycuEF*j}nv7i~aMot5`^@$jcs4ZC{X0iuG<);P zWL$G}+T0I^o%MzEQ~vZw%Vc2<(RC{I_JHx#mN>NLC2W8Bo2E}4gTWKuLfhk|;+9MK z{Is$eQjMZI$ruNkr^1kwX zv?;}y@puQhGS7jlQSah!yG6j^d_`X8jw$ZhbQXTk z97vsfQlV4bZBk+el26L#)df@qz`q*f*&T z`~$jalkb1He#}>RG;Y3l2qf~(8X|CEd?#|m07KPS_Ol<`0@VIS1wB79v~mG=x|asB zqC|KmFT=OU8DZP4!(evPSyH`_b-1kZhjnjC#h&B)W6s((IL_73j7!DnxR-gz`vTW@ z&Vot1(|e#8Ghe`axT#IN>qIOzS;Q zLv-N15zeUc2a&5e*XNrJPTtzZ@|Z4?wZDq-;rS49z~M31pun`jZ+AduY&G3WTJdge z7|{yW;XVv+msC@K@uI1UGd3d1oE($J59G=Y{NMh!pZvR<=l>#YThb+8Dz1y z+hzv??0gpk*84T+>Vy5TWt|^Lx{L8xM?4vx9L~M7ZRTH%OOxsqJ#PK6?ot`N z&)Za}^WQ)`c`zH+GL6ow_gJi7o&)2=KSfI(uHt{ME0t=ur3S&>s{&I{cMlp z=MQ0T{KamWvUtu?kj}$%0|%kU;7^cu?W(A1m^)5kRL$PA8n~KxUF?;Y3Dud0=sxXs z?33e9TzBYjubosdcc4EyiZMJZge=&f!D%qobhBq3T$h5_rDp1t@JbZ5_ zX$f4+Jxgc(%Zm?#ONk6`Q`rxrSci+UtiD9=>uyY0FrM^o{mdz5vUk>k2kUC+L z&wN4aU9E9{_eEHulP=j|EHA9x=|lSH*J5TtFnNL$!h8e!y0sR}sEbUi;&vXK+7BZ*eWyF zu~)7ksxfYMqG|*^#%5a4iU1gzIacfzu8X_F-of7@8GiO>#z8v8&gU8P#b#9}`1(;I zsmC}XSV_3__z0=^yM?>^Tpb4)9fsX`GJHZWb6m0{3ZAZal?+d0Z?vQUxVZ9xIB}s3 z<_G*F0Lt$#)jl>Ndli^8Qdvv^IXL|rpT?BcCVyP5tU;1LVQiI6}g`gB# z|K~TBFh*|VqvhOk*=M|o(sJpUoVHCLe=m=Px~m%0hVh;5vuxn-=VdhGj+U@yPAw@g zd(7ot`@#3fo`pNS65sn9>zZ$`f=SN13xi{9@b-pmc+9#%Uk)3My8UwCzGt)O%;}Z< zW`#0ow)$`;^C48SKEVhF>cIRM!`<#efq@ENH*qj}u6YKlZHq+kt&H#Y-+Jh-59J>E z>fko7lQ1R!EcNUejr`jjxHZB2nt~LAjk0$FAF)O{O8Lu*}Z?eZmsP{FypEiri?w$0hvI!l|l}km-G!W^Q%DIojEb zg{vgiuZ`rb6~0S#iLxbjNPEi?v(XN8(3z*0Sr$#4s;+WAQCgU^_Bz}<(@rP4Bd0-1DVmu&WODBuEX53^u~T%x;z= z9*z(0E0KdkSBRa{_wkm#gZ^n0QyANpuygp%BAPg^6Q6rUlDpZAeUYY&2mk(?ll7VI z-L8EC!utD594X_j@P35fh1|iqK5XvV4uhtiqSL->3bDOjkU^5l$%flyHyxKVKDn3# z!1mFBG}nEqAUGO2HFYhAgl-FbeDO8-`L)sOyGCNx!aBGYx>#(Qd7Y1Logvkevl+{4 z=9N@1`RPX;*>3&h$DL$U$YSncE%UDyguzu=IsQfn`+tvMIjN8OlI6qpV>}U&*zj-M z?#pI)B;WoJL->Pw7ptyduAlsbq_&*|c(6(68`yc~b)o*nDu z`3g_2%@b>GIL<#=B$DdM-Y0A@DvgJ`1v6;x+r5S2!?EPS)ID6Jq6X^jWc-RkSw8Nb z8K%2OL+MgCNm8K^?zbccKDY+oQ>_Q!_YD=PkePK!jA& z&@`qU+C>t#!_>VBk9x6iAK)d zjD2=nkyF{v^iupNx(rMBqdt7dk3s>|##MO6{a1-;W|KDqo+uRR{ zK_Eo@c_RUXNj*85NYJVm1e#1!qLGpL${7g67;v!vHqOR#c zx9xa}&JauHZoI~MF>ki<)_e$8@1p;$HO4iVjfjV2}%iSFX zY9o)*;up;G&sfv$4=uP6chzv&s?Ct%Cc`VP8iJvXisXUYGV$8iyLhYiK~n!)xVs_7 zDGPAU!h>4mwV}E=idfkuaJ63)@xjzcskS_4J!5BiuwamkzofWbP3R}@Pfn;aB(!%Q zY_8e?>lY=_eIBf*HCl#LUdR&X8Ic73nFk;Atgb*{5~WlA6*-xGyGR|BVQ1D8Rv$O1Dy zynz$poix&7IIdg!24*TR5nmse$3vXEbe2wH++fp{XF=(kKXozqgRYBrlVr;!T;@>? z^gJ2>qTWC07zHCV`oX$j+6*MKjCWz_W)TT?`o`6IFpaeQIV`!IPgz|a<~HplUk8oj z25bH14}SYMOZ%KKWc{0I5Wd5P?(&xv9*TX*hez?;7`EG5_d5nQO#euyH1)%iUjo6> zN=x)Rc_KgF&p^5dG@fUGcQmRXFm6Bf_9()p)q9Ch?8`lO)x`C#>G0MxuHKPUw4yxoyP9&aK`$p%c9lJMi{su2>Pt76X}i3<5P>n;n_Gmea(~`L9wTAdU>I#H0=9S3`E2P$!nXb;Xj%WjHZepIF`w{dp z)5(ougJ8Vuc=5uox>ykT2}0h>^Ff|W>-g0InOm2LyPS^k%U=A`Izq+l&qtTS`r8ZX zFMVYpuse#Jjo-l?9H4E#lZtJSIN~3aZP+-tWvYAgTk7 zuX#b2%q?f${%A63nH%@rv5p^g_n+2b>}7~^wXVR)VqOw*Kv8I)97(?Dq;S(4nXiU* zFIxK5(_xvGc;6x(4kR}_PBLX3Wah!}ZJ8A}P-P&lGn6ML+)T-e-IImW2UML*UeAMj z8yTO_r5pxlyrq4{R^Zh#FOoe$mMeMwUE*@oSG>_&o?dP>#Ul4p5Nx%Ds&w=g%*=hr z_>WsSK1&zd7qK4gF<+DO9&*P;*(< z+deCbELpvVtL=Qkd%RsP-3gvzTIKqbXgGO5js9>LCDdD-CGL9nxnFD^zEvLxifha1 zQ@vOC`pN~8?U}+=ern`%oX^7aGfKP#+t)`=cm`+dcNHeBV|R4FEKpN!pqJ|GQSkDD3_+{?fyLGxk!pyJ@mvcbVw~8tJQ!b@g{4(N=}u9Xb%}W>&*{?;_E!j-Fbldb{-4oekrYt9aEU^|!L){GC}8U(J1?V?u!pfspE_FN#P65j zlu3oCZl)c7h-m``S&ZeY(hvVkIs(G(88ngI@3rMYFlSkiSf`_tf1NJC?eoff?_0Jw zyz2|3wq6s}on3_2YI>8!ZtdK%zGfKDay=zA@$_Rwf6SBQKu_INafe$o|G~vms(a)o zvyO)FDA;vNp6+B?Sz_N{*tqAsSbc#pZV3JfioQqbu-E0-mKjYJO^@KFmK&hMoLq41 z6?S{g8WrKoiWt&sbSc+&tv2p$jt0X73Dxv+M5oY8p#EK6yiPlUw=VlG)uoS59Dpgm zWXRDAW2wyG$7mQAL);hSalY@^86I^Drl0sryBV+k)es5nhx?*F*^>pO>PnJ4X9|1= zZN`|2hLl;y=(rzBg7w{<#Qd8jXPl#k+E!a&$X^-0W|K8;Iw(U1Yt0j{J>$)XI<&%8c($9@+yM<&y~+V}avdH?2ZyLiT;F|2~gCwe5Udo=M|Ljt5R4ad-SG=8(s zgZ(=T9VasFYcUOi)15)|Wen^5+V&38T9}r8Y$#S0ynzahCE|A(SNO0>cj;W+{mBq_ z4L%3)a|5XQ$u2ymw3oaXx0HL|rH*@z1L0)UPx?ZO?I2WwVaInvNxu6I+>Ve$^6wUYh~fGRD!A`}$~>{tS9s`_S0m6raxC zMe?Ta=bp0MYgT+Ze6>;HuM}CLSSK64J7h}2wrSzOy&*7(UZ%_bTHx>zEW^H~QMB^# z6~4{-h_vhEmpi-DmA=D@L&lVJNKn1cP7=2}iCe3$hbLcW!>Oh(RBsp4VJ>CC6YD{a zeNzq4Y~T?{6e4Mf73*oe_65#`DDuJOgRtxOPsk;U#lx%Pd99v*n#R=8L-5nDQs&27 zM6Zle7UH+WkgKP5a<83wEefou7eDnZ4yS9>I zgC21}_)p2p?SW$U`=r;aO>jc=DOhK)g>LBSEo_+VM_Tr7 zmb3?Y8qSD92X901lYvCVy_MsrDQ>)02IACA>R$4YbzE*I^%pr#CAfmmU%Y}bkrer1 ztlx0>+*6=80t1a-o&SmNR{3~)KZtiyl9@hR8jZRp~ zXRd!B&4c6(G{Yw)p>WTGQ28Nh_;y?|>>aDZD^nX}lOJreC=&VXDdqzs*27r8P|i=J zi^C6{X1(F(>AZU#$f(jJKi7b3WZz$5xwmwF9?b6U+bhChkVcc_zpan>mZzyu9HPXB zC)i-8+&6eUNLI4Eo)ery+DNecR8Y?|!$;<~;ozeZYU^x`rMWq9erAQ+qv!#6Euj= zhoMRFbo-MZ{JS@v%$mX8n{3B)q2k{eJEO%2gDZc*6Gmk^S!W_tLLFK4poaTAq#r)b z$dfYjbq6U5L5@*m#HV8J(t=SK`0ff^f80nDg$dX=Hw#uwQxNY+KEmgJ`@waOP~z7d zu){%570J`hVtP_ij{S$m5{ox^oEMv`E3*qAw66>w@ZAdg>+&$GtyGlEX`_i|EckmI zr>zxgc*=PjynG|e54~cAg}yQ*w|TC3X5J2d`pm&n4f&#y73z+xfU2jP=-XCB!L0oh zS?QC(`CV5)WB%Xy=^r`-_nTdUgHF+s{US9Xuf(71zJc5$x4!uJ+ivI;kwT4sSYz;R zS)!48S?qhSgkRhi0b4&Q@ny*a@X@0x7&BOgj$b@W__4p0>^No(+qgcsXW&Vw9NJEG zHSKZx@vAWNT7hG7fxYnJT{>B6G7hGhnBjOyD1819O5?_u7nsR8<`1YS!4ISz03a`TU}$!B%+0FC6sd7>Q1MaJ<>Ge>3pn zmwHHURYQfLFAWP3aOl_r#9_ZbNAIbjTXZ^vH7oMH^(}C8?PWN@XGk{ajS=*R-yjwJ z6d;eCw@wM6u=GtfH9cvLZl+<-_2jci<8BV`wd07?lia}i1bfZ;1`pmC(XJ~6$g#du zNzW-R+sy(m)<~e`d=It%W`>^Yc*`qFjSF< zGUiBbUw0Co{!n!~q%NE!9vU|Ah{W{e}LQqsgymL(aa_7iT(rI=?q3rQ z=Rdumuc|BYz43W+{X`NMF}{HxoBZ#*Em2~5?TOW}Vg2sHU-PC5p?8|ekDOVs^r#s| zjL(9!9UtiI>%&m{aSlw)X%hLmEaCk>K9G8nUH+J2ebgHp{EMN;k*X^amyi7+P%>$hJYM*aZ?sL5>d7~CZBX;acQDqJlay?qCb-qhJE?ZhgCt{f4BJ`= zOaGKohm}^C?2!u-imOCD({1^XHJMV++b%yt#sQ9mz>PEMe_dUudvyV6F`Um$^!?5M zRlfr>*)FoR!xj&vHN%V7H$^Kp&%?EHs>HdmjhnsR1b0rj1+ur;yn3|LcdDBwEy-&2l6EO&v z#vQx8dy=A%d?}i=$Chx7_9Icn{VFK5HB!s_4)|C3611wxiys{i=a(BaNi~Y&FU|2u zQV)Dj8ch$^JV5@Nu3jKQ?m^dK;91tjjZz-7!}oc~BjRUN#ec zk7REjmpFK|_yoP_+)L0N>r33;+i>KQ8ftoYK}&%g|Dw6`!N z+tbX?xv}ISJlnaB_B#9+$4=ivGW!Q}hJ)p?QxpZ}X9xoW+lc2&YcP$| zME=z&2pZc-?UY#0%g7v0wCQbC`xrHNsy%>!2d0 zot8Wrh5IIdg=;12#38G*c~S3~u)<7{pWchyKI{cJ1yOBx<{qU%EuscHVoWSFRxho>>cB) z7tJSg)){bCeHjaDeKTZutMK~Eh9ac=h22Zmi1o(A@;xzPX-pjk7a6s5vFm*lqGHH=&lz0I z+Zz7X?MNu|WAE;>R%jG-2U2f5kyLMy6Q(yrlJPPr++=lq^xk~}3__dfJ~|rzq+Ni9 z<-J8;I&83?u`;o4nkN}i48k~5HK&f=^Fh>PiT(Fi!I`*EwBgxf+!VBz*gGh2PY(Z; z+F-Sxg9&$GV>$2EeX_n&+5&i-e4HNe{)@e;!${}}Q|^NASN__yEz&tTkomaQ4UdK&vGTO;%^y5A z&Vw*WB-b5aiuHfGfzLce4c@aXc1J0=Oi#M~>ASq39Ue_KYn5>LWd!mk^5FD@uQXsj z>sv9u1gdZ4#74Pc{J_0U(%oNw9drE5JQ(!u7@G696qlF8lI4T1aVCqk8LtfCM~)o7 z<+dHRc9p@{PtQbY(_Dq;jc*8Engu2f+Gv~@4^O-k==J9DsOOsv7d_UAufI^kUJl-n zy-%L+&oXhBd}WEspLt@hnV$URx_|TYOR&JIo0V{;WefcjT8_V2A5BO{5O@ENEP6Ue zu?{9h-h%OFuWmR6i+lqmC2x8OyjK8;q{vNeVBPDkzVNg-l^SY|!{@DfhF# zN6Y7Q5Mv=PCZHeVHG2 zaHh0ds)p$R3Emm-)F+UNmv*4vQXg{u+j8#qXLTeC4?^6CHu`qZFdUYd0CJimBrS@Y z@O`6*C{=ys@^6~sqNqktd{;~#>+sll--i$#F}GmiH~#R;Na^m+C1waZ$5MFR%ZX0w z))3?t#gO#YOzuRxHU=4ngWKH~wBYFgtc;EU=Rp>t_8k-W(%ptqjbhLOJ?!`SC8UiE zpgULe5gyu6vQH#%zjJ%zmIWEmHbjY^#5!}GE?k5UHfJSgm_OlV;b99qJ!tN4y>*$&^Tk~7<^)y zkUaAdx%_%2z&1VRr;UK%y-`$Ydn=oD=abl{`doup2YK&ixI0&cpS5BHp4=%%W?kMS z)~Sl->+guA9*m9O{==`DPa*j03OYXTFFHFPA%(&wZr59N%-GBLGwiJwFu)x5JUj+> zlIBXznv4`u!%mThl`UL3+m&zpCQH)RzoTa#7UR-2G3;IA#vP2U=AU1WWc+!yYZzyX zS2{}}%WU;Uo+Wc0m3p|H^>H72_mj?gGa9dtyae$pRYi_2zlIye7>tAM{b8@wH+oO6KelaCB1_Jn7b&TE;^`$rh;3LW z*W|(cmMo8-8<>psj>RqHsVImjz{sG?}wGtGMEAnPbEOF%AbMWzi87&PMCB(O% zCuUjYT&FG57TD*+ET)G3q>nJ?zw@MGW)ipR`di*l`!*yMW-CSA;;V>LUm@{BLhH#O#l zN6Mj4`|qrd3TGWU(P5xC>YK!@w1iI&`Zr6fhYi4a2`#XAvV!F8XU5)Hd z%xiqMMf<*O;Cr-C)G~DzYK>JTuTQse2EfkPW(n-;lR)Lh{XrY=aI#v}jFTJth3|iG zE11?R@-Lob=j<=b8t8p-p2%oJnn%}J*Q~Dk+xXLvW>4*lWv!C za)PP~+dHe><8<|`FuZR%G`@UJ8!{a*_sL}#aalneec>=)e5OgtPd;nH+$0}*;OeH) zbmqDe{2Luh_U7bqS3>Z8ExiUu(cQaP9`sS$1dIZc>x@Gap#&H^Lm&FIoR z1{bd+Qj?r+fz8x>`80? zlw+x6FVV~l=3;YXF=l;~G(&yRlCehHlR)uCkYs35FQFkmfNXh!T;O{xoV?s0>c^d> zZ|cWlRg4}{-C8QHxhL=r-i+h-R*By;+Zs2<)j;=0S*jn_2gg*Vz-rHK`mmQBmiNzs zkAL$Vxhw;8-g=O6mV&95yaDPjs)fOxt@Kd%Xso@`45rsMi-$eR;$yDQgibd_K7PDD zwvNky0;fQFW2u|)(E15Ewf7chcv1r$ri6g(<92Gia2T#NO9Z#T5t7SmHlqAH5s@wY z%2|Ik!_+UIL3>&;ow!Ux_#03_%C|M zp=Fqa6!q|2)sbG9lav9nj7zUKj`iADU1C1lvyz$YZf*JagoL^2gJE-DtUktiPw)!; z`1t}~_~QsnVgCR9ffkJ8@tt+78&eDUIYQ(Mb*Ig9?7^j*`62Zg-{A0H`r#nkxg5)a z?Dm07Y}eq@46@8mHF51= zJgwaW-WF@ceNIR5!f;NiUG!oz4*1mhw{t#TPs$<<5#R}Y`7WD z4^M+7z9!Uqi?ZN-(w}(gpW=pRo1o@7;!O#%YLnkDb5-2 z8nUUCVLQ6N^(7BwjJfO!vMf)rOR8^dax_J+&EXI`^1Ebgd@=uuroq*#O!sErYY&SS zu&9-n$TrLpN{rN<{QIqe8*41^@1-I*^|XTa-ZT(r8ZbWCvv;EWOl!W|_Pmt0nS8?l zI}~G}Wd9s`3BIP{G_UwcRDVK!u*pMbVD@KTeA=FfIV-Bqe&L}D9f zI@$zn<0y<+m_Soo+wk0qF!DZ@ZE<}*^GtirJ*uWp^2TD~TE>m3QxFf+I?PW9Zag-XWZ`Tcw#YIiWcv1g5FYt}qr-Kif$={EB!9MMMGqsJk$=OleO*#XD>%!a;( z>%`8=>bNI(52zAFesqvMCVkQ)Pi6LrlcLx2U*->y?(*W}7>gsn20Xv+pas__^3sPtKo6vH^lbvl?mF9TG% z1E^zvC86zh7#Ve7C%08lM~!`<(2r>;dpRRiJi|PO6TU|Kh5ldtu&vOm2 zEQfyOD9Fb((n&f4Fox+%Upy^E#BtB5Yvr)251xiEvVP{!oP zfT3C(J)hEnafM4rS&k7`UC{@}ziEcUQ&jlKPa`m}UXlFgzFiz>6v_V@#X;UWMPA&e zAAU_PgjK7j(t@3BsIe}bw8U)S(&nn7;pS*Ko2$sbUSW*gMMvTJve}ZwZLAWOk9S4q5jc#@y?4lGW_REF8BFUzTdsEJT(f0d{q=Grv&>C0 zB*8ye8JAVzQG&+*!?q%{9S5AsiYDW%x5W1Mtj9RboFqTQsisdVHKQg#2C7$;lJe zH*xd03!3N+0luP-m$*W*V8PnX}TjS|Z7a-5gnjT`Du4=0QlCd!eP_4?~=KUD|oCc4Z@i3`i7=0-Z;_)qb8|HqWa#$uPGr! zaoP*+U6>iVEGYu}5fyZVmMxB7TnIAd??nC+t@!M5=cT?2K7_FgOk==!!W??`PA4|; zONq=P5AM0y7yi-0B8d2{%oFC_;#&W}f^-yd9&UIxLX{khYvcaTXW60=6y7{NL4}+) zbUhSK2Bw*E=Q=;~<~z2*mS2pmq+o#s_KDE+LzVXOV*Tm4i^;JM;oPs==D2d45?Q|f zEPYf{jH4^!$?_S|oaN2_c)h(0uCGeEO-_gfgV)u>J68wFcCsGZDU4@mSWOSfkHzru zIp9eY#b>)h`5DKWrE~Ra@lZ5fs6~QCyVL#$X9yN*N$+Q@6R#Vlj{48`fe)M0 zyzY-gk5&3ae0ZODZJ)LL^aDerd&8I0O|VG(3_Ndcr5nxe;_*@5WT`^{mp!waf6_nt zpDsPn8n-fDqOWG8M0vZsFxk$BjM!Ab$*j=AGx>qA%p;x7-e1UvF+TRKA4>dAe=BT! zTnm?C6zGEUMVN~_NVw-2&P%@!x-jqAD#mer{HZ_wR?UJG%{)i_)_yotfBhxA4rlgYLm0*wXkF&W~6pE>XY8$C%9l8FwXq7JILmJUI`(H-czdoucqJH=MZN z-NjW~XyEnkLm-a+L$ylHaKqzBXb7^F)WokuUt2M`z2Yl3%#1M`KR1KIng?|B(7R|H z5JDQM3)eXIBj2+vN~%R~`8*QuO?UvOTHR>S88xBxQ7m~}Hy{GknSNU}$_`E6$dKY` zw$#$%E-DEj{Eu=c>Ie`DF}aI)vm1}=hS_NRZ1hWm_xP&U^Pe;LKYuXJ}wX8K5B#D~)aEIYW0 z7+VzLHHdyz8-1~DpA_$B&2j} zJH66e3BUGP;Pv8HQ0@GKdQTaNXW!R?!`qEw%SzVq+MWuVU3XH~x^9dfx{K^wu!c*V zW{itF!=W-qhQGSd4j1e7A*xQ-MDy7Fz9MS~DKP5fEak27{fPAYt!CgISfqFNhVTAl!$~}F-kH|R( z$1{}pAqfLez4$$}s00@72sTDe;R@_-{!IIy7=Y>HSpLHHi%9OyT>jVIa%tW~iS@sD z{tbuHzs_`cvph~JzXxAusqoGAcDVZbC-7SGL{!#!iyymlJ#2Ok;i6J?apABFpnNBn zo@N=G2eSSoagZ^$_k9ol+HSXWe%`}8z?v-6F}UrkWRZ-(I?2vT=jY6>{@A*RWi91Y zB-2?3);W{AF!yQ&m9U+A!s!CAiGM4y?y}$yt~)Q)oS*J6z#NE!1MTyu?A#8tcU?ww zc6o3sQa|y}ii%*TkqU2r(GGbBS+YLmuIR}8={P<|l?3>;akaBdu<+O&7-xEl&bDhs z@;97#d^Y9QDmCyrG20-W-GkA37O0zW5?(f`(JX^eg8Q^HWVPM{Ztg)#l-u2l#E!_M zHLm|7={y{P0#bakD{%mrQO@!Q$r=9k}^v}(+ZKa$#c&A4K0#} z_E6H$w33wH`91!GxA$>>?{nSP^|=hizk6Sj;Dc4d_5bYg>8vua+kCVz@TG>Rmvw}= zTUQA_JFM}-gLLqqPw2a4-q^=G5B4aiN_BhhWJBEQ<^DIzK;8p#-GCf%4WLRkqr@X) zEPN-GOTbC3Gya}+8)E!5Scsn+zq>tzI-S>&#eICl6wk+GQNU2no;JeiClABPL&s=B z=0D8(vyMD#v=MTHIkV{SW>_&tjkT0|V)zUb5-x6#o|!q1y*bkZy2hxo9B(_E;qV&z z$8Dr~2_@M54({`bD-Cs7wE>^xXw_dWt{Jz;RO>>_tbi1-B)!s@jHC_{%y^Jv8 zaX8p!XHcEYPGTc`AzQ~D6JivK*iwraNLE#6U7p(E3gtJ@FhG@x`PWfrKNG>V8)aJJK=U|~Xb~#RxulB&p6-TR)qm9RnKhQW z!~j&;%cQSnBkd$5`JP{dOE<0Y=C6*K{Pyz${Pi-HJR3Ac7-8{&o#r>M$DdT0!=v7K zcUKuq>m5L+UDFn~cq9<&mL+7L>x|=1#K5b#H}s}HzYA-{!?YY5iF8$O)XL8yC z|Ac+xoR&TGNB@UdoEc9tAW@iLu7)cYp9Wh$o|&>Tz;P$jAt>mW?7{#|G5cODQI_2m zhQ8w&Tbq5LJpK~3G$E)@&O*UKLus>j8uN(R3wIW(F_%&9*e^>6?UW9# zx>OJP8~NY$n4UP>Se-c3u9hC$zK1zi3iA6P?cWW57v6#VCzI*g@Fvbkj3z@@EfK~X z(8S4}adO>*Ni5N{-$B@_J5jbeT1Ompis#LDmI!10opF$dK3U$Ul}e5}VcKE^^7_j~ zsqfng7MU3%zZDkzutWcMymx;53mNI%in~&IZtK7?LE*O%wmT-n_MuJG-L4l}M(2RT z+D?+Ew(jWF+nAJFER`K;wMPrJ8dz|znRjb?BCLE3Lu{8wH;${9ow3>@9Tl!aQ}g%@ z#fN7)_#763{-WZ;^`vU&JmE_h&Slb#2K8_S_SwM|N8d6a7T%X7cBON$qNoSa{`_0e z%;esK*$?4VpIo|mg^1A}Yl){T2;rb(90o5i5z+tGAGh zmV?57{O)7Ud&EAJy{4rvpRgpybQthPja8~UV$V(QVeaFwBI}EG*xFJE3)7ovZlN7s z@z$XYSsPdt?f$q-|rhRnZJD!_$}V?><3uyRw3uqKlReIUehvDDRZAX(*s!lb znevV&!$T zD!h}TkN7G16j>2eE}Y^S*oFR`NEb;K{culToK*XgXq>GQnntaIt2-g)hsKfMb&( zW_7&-y$)-zQ4d|QOH>u~T>3_m&^&?rv>VCm!E<4(NoV{%BpKeSoS<(~z3@zP9+-7s zAhihYgyyd|L+8P2?9!DUsHb8=TuOqa^)Q>c-RmLGkKDF0N3$hWFmT)ox;*U$Y7Pz| z%WNWqbdOf{bX~06d#u!KhLRDdK+!)^_NPEeT&NmK@@k3%;gBJwYeYc*%+pkZX^2w- zzYt=6jQ7`HWo=_(K=qdz%h9mM#=sibw?my?4n~}{e=V`!eNq@G(Z{nH>5!PO%#Ie> z;q;0eST^K>Php4|4qg!jleh1pQT4{yE0_DyXS7qb*Y2pjuL06bmPyxl%3x8$#>+D! zea{=9?~>E-)hCS3S*syV`xHy^owo@Gy6WP@;d`L$eLLNA%?jVS#zMhr2iZl7>6jfL zB{^Nb2;(fQaer$QjGR$HAH?2A-OKUhc0`aMTkwvl)Wpa&=RH}y@ym@0Q1~{M>bx}K zOzBwI-d0Tyj?oz}-B{y!g;%n(Zgx+P}H* z+T2iTwlIa|;a)futj0pVIib3>61lL)h4x)oiHQSvcInSm!L=9ff1G<2Hr6)L>npmU zPhZYvckk|6HE{Qmj@di@ zb9YpEk_qK2mdo6aYl<1$Hj!OkDBQi<4KEJTA!W}R>B=1rXeTI;l&u$~J-?T;lJbsy zc>GW|Oz!;@#@c+8N!5R$*foaSzj0JZDdJo#y~CW{{gcjr-3t}+&%)gw+LBeKJ#de+ z3E4kynM^~`9tUc_hgBzj(TZz5akJGMn7n(5^z-;S*}{ptq<451U#uDLMo~$HEynBV z+&yjhTXzGwHgvwQY?C?KBt>&CnF2!M6{~behYj545O3gsFL%|#fnniAuY-86gv~YRvaOkFrgp=dmN{_X{YS}7 z-SJE%>8@e%NBpCYpsYqyWEs}lJTAsex1Qtmy>vVcfq$8sv*aG7Q`3@Xu&3kxLwMjkyciy~nsAxUg!qS^NSzD{7%)9x#eTUL0uZinxnJf!pP2O`1B|!%|1zOKm6g0*QI$6gU8Bw^|X=^(wCY)DUc`3|f($_#46SE<@6yDv8gSX zgy)3`v&XiuKi7E&D9;6Z+_ph==QH5nXP;~)?<+U4jfC}AGijyDOZ*##WYPHT0=;*c zDV&UfEf$==r|W_h-@o$QoDTJ#F5*b(2J)vMMX(9b$FY-6L)b$VRy36Rqdw-!bz=i_ zGfWz|N3KOIQZ>PW2R_3WJ4IGm?T+?Cn&I*C71HBnX)N&dc(6U9%I0xa_KMS2;KlxZ zG(SgO{KNUovcubiuLE_lxxA z&S-x%9_|dQq33y~W7=l?|rYgTHx~P1~4AIkIqcIgO)`xWNLk^ z@KI9*{aiC)Uzi$G8EcNKc3*%m2H7%=a#iufc(RINY zNXpie4i7rX##VLgy@MWh;|#HO*zD;@yI#19r9b1y^|@DtVNQmaAuWVUYAtjM=Vo+W zco9N}_w)&vHbP8a{*3hhHWgGk|G($Oqi|OB7>#w+5-056LQ>B46jsjG!hil9b9fZr z<$m>6AZt|TOWhQAvthwp&Pe7t+&?^@{;LeW#808!Dl71k%^K2c{cvIKQ+0g&IZp1u z*f-l9@0Xl`Osmy0TfWb0zt~KI-k~s=`-;D78xsHeHu}2t37R@*k@-7U3T}2~?7M9& z1ShMp+z+mJq3Ia}o&6*WXj2vEvSd=V_l%I=riXh^^EvENPZw47#Ogk0;o(Sai6HeB zCrUDiiZ~p8{cuHBUlUR{ZkfzG#0F!IzlHGgjdYPxf6Q0^3R%}TNI&z8t?9KC2q5d| z`RQ#~rMZa=y0k#3ZQy+n{(IqwqavHnITBIJOi9MqBFTX>({WQ(58|->w;;Chtn2Eh zkool-jdCo;o1-?9F}{AnpWN&0=C}VKRa9j+7IekFhMBNxvn|c+q$t*3+(vek9}*%Z zE|?y01Y}k}=*U?Q*^@o#5K+r-zC53@S+iEY1J5Ywg8H@R!E|~ZZS}E5FP@PvIsQ?y zXWLlzKDI)xMFjE8#nxGS!RWpp4Gd{#Q>NaOdzH`K;oa^B>j6WaNlv9+WQQ*=gpAh_ zg8l?++%~@eUOqsY#J!!ui6}CDw6hTVxRs6C*)fMlJ6YnmkugxVsa~e@w}6eDkt)xI zteEA9t{aue#{zBH#lRur^a-7Ooy%sywt{Z>Yx6zut9e1a)!eZ<=?+Z$uU_)wtQE^& zoh9cHox5y>^}tMTYRTScJDe%+x4H~%Klm8_4ri5B+Us|-K+xj2dRbo!^VlD z{hP_H6V9-Ne^b=-bD@t;HMQv98-K=~gZJZ9rO)zru$j>vGx@-?ZYXimBOyacQ z;^Vno9|j4$h~~e^i?@M?!C7*M3r5>Nh49^PB~3h!b71rda66Gg>pryLfaLW=FTzGx zcaVD*cZYzjl^Sc0>5056f_(qGO=_h(gEe<^mutcr`DVEH_+wD_T}hR9ASQhcCaVsH z2|mfc*o?;=b2y84%~$Nng~MjCvgK=x@Oi*am}!wsQ=<&TSFhSh_l7KC>Zwbtsb35j z=c+NE7-w9e_Dw#AS87vSQM{If&NwObP%^-Rv`kRt-iAZnY_Z%Z2PWB`_fd@Z7Jt0G zKuP65Z{u@r!t(G<{ zOJh|(JLdD4FJ18%UV-c*`>64JE%9SUBB?$SCTzCQ!=zh#VS1w?OaIO@LEm{d$~OmD z-y>6S$WSR!zF8;KEOEw6BNbx&-z$3Ja0Tv6j3?9oO%nvl)-qWcC6bVvZJmo-#v>Hs{flnp(M2TC%w_h4nQ=5jBb$w!`Z zscQm*i7`}h|1BKxC5DV_j1^8+DB;b(OxUoVYyO4`{~#Rt@lxnp@#afcEwohF|V?D+40!{H-9qzx1f^u!Axc~Ebp zBS|>lN9^sLL7D=G!{8k*_*u!692l}(*8P_i>il~Po5~ug!dQM2RQdvogMy{H&+BBJ z1NKP6JL}MW6zdbDUI+%lbuJ zZ31CF&!m)YqHx8&l@6$}!S80T>#?Ttiekz2)me=W=gUX^TZ6DeHvAdvd z@td_Zcg*T-eJ%Mrl(R?d8)bI2SJ=l(sW3E0jlF7g!S5f`$i*oJGH;#1;`-m6e8XdA zL$!?~p3`{@UG{K)$SlrBI(Y|98`VoH^1HHmKeObylJEStr>Am^d)wyG#DglL$-H&s z<2k<8a6i}&Qv z0YMM3B<3`!jXEXtxaWvRe>{d4A!&tegT{#lK`mrdnF}0T$otN!bD(w28~QrS6J7bN z-fp5Qt-ck`qH7!Ew>-ZI_E>>VK5 zl{AuoEpwpLA&3gJlK07i zS9yzyvoDi{!_;AHt0D5sGUqUyq54(2qUst2UpggQpi9oPovAUf_dfTdp5i&I``_XB zT^*X6TZDrq1ry72r-X@$`WWn=4M!>ej?Cblu!Hj9Me}8!_F3LyJI_I69v%uB1*SNi zvyc9+kD@X9N%-c+PICN0vEZ0%f)a)F+XESW#UA^CHf_MbTC$~C#!qfVf!!<4lMPhLt9nER znUpT<2sc9G;6yOtG`-<^C*%>8o|e2!0(-FmMnzB&_1 zcFrgfE*!T-@w)-(3T@P2@jcwOA%l$fUMf7(zsaK4#=^+`Y7Et!aq#Wu5ccDf?DPZ` zvD@>bO!~&bwWMtNZlg!RCy~~aW_)#Th1KMeS>M~aIta&H81+h`<}KDCFxQjCrKA)>qdaz z)OtFtpDR}8cOka(nIv@AWIXz>2MKilEo@w8k2kh_g=f!@R?bI^`x8RSwEYF^lZ-js znkV2e3Df?+F%qYAlrB0)EcjC)Y9d zwsYS5+naKKMY@g)`r0(Y#0k$OL^GfDe#;r2M43 z-6rqpwN_U=+jIwxTh>d|?^?1)d$Q&1xRmXjH&uKX2L75!6F(}6r$(Ka7PWcez6nYj8r29NoA79eF$#quT9Q>X%;dgEU~(%3|hvXqBDlw#al+}xu-%) z*!S)wyGB>bcjgk_Rk1$qDD>W}Ls#&(%n+?k#9>$_oww^g4(*;vyc$mlr+po<<-O9HKdi7SOpnZM8cw~Gboh<( zj{HvNeaIP~?0y0F*1eYu={riSENdivJ?6lb24g&|oeI4_rqgc6o3S!&1F;-xD~zjC z$33UFz=u9+Y=FKyTEtnABg@02Q>`bnarz$6d`p$R@iaw;hUcI*VlBOvT!fBSHhz_u11q=-dpiwuPjm9OZ<^|nLO&P4zrYv@X)v25V<#p=99&)x`G6V%vr4G%2;{11Y^ua{2mev-9p znE<++zg-w)iDB;xq5JAsirGryhK3l@w`#NS-ws`zoDvI8-<8?p@_zj8mIE`>hsZ1| z$Kr*ZQnF`No$!G3I`RyZi0h#2$DEP=ES$`mYXO%S{f!6^H$)VZ`D4ol2|jqe9Z4tcn+pqCxH@%JuVS2?agWXbz! zvfpi7dpUuuUz{iyZBfA2TwndacJZXd35Qzp-k)rl?C~{4(GOzCe{XLK2hk8q2JZ)p zhegyru^)EL%YhwV^`wbMjTa4rhDDOuDnC`d&^a!Jec>q zA4S--tex(>XN~_N7z7R(;A0YDgvp%_Ky%D~I%~2j9_-o(^+`O(H=k#kx*3oerQ4;( zH+L}Q?;!V1%;LB8?vdr7GkgktV}1|A@;8ypCjr8r3%na*S3FGO@2|hyXSF!@C=9tD zB#Tt!dD1VTWZ3Ky;niJR47Kb`;)~m<>yEp4Md>todU>g^%)695qOs6=PK}-BUe-QS z9)bJKw=$cZ%3?U@rg~@O2<^NZOZ(6;zt!q|`y>BWn$Wd073a#rWFZl`9OLa@}|c@1aB>>%q4B?xM#(hKP?JDESVGoduKIc<%B-0etan zpcDIAqvqYS;G|F|851;$jd^`f?rnQ_!xRTU;F;3`f7;UZ7mL-pCEtfFox9_-Re#{h z$!bYi&pbBc!$O$9Dnc0F&lZ>U6`@W47PUFnhFTl;ka;_t1@E{fwz8yS_DWed{OWKB z)<038t9oB#k6xrf+*EaD_SFTuOSH(8k?b%e`&;WL7w2{Ymf@7SRX%j;VKdEgAD}nJ{?c6E@1R6lQ=1 zTe`~;gEy;_#{1y{EeAixZ&qW zan-wKGH{eL_}IIl>hEh1;M_pnR(ayXO&8#Nxtg?#eHc6YrBSXS>lN}h-FiK;B!4)S zWOu@z|L#Cvu6t))@WOo0A21{Fx5U1|Pc+T`PU@_t!?I2$xGg6QYDS!FYxiS>yqCd6)Ft5^FRI`UGLSd8VwP5Utj1 zAkxWUg2U#YOk5KO!x`_nbF;vPz-(Ai94$MbA0Qeg-zRy>7O-)x5%$6;2;P`WFFtsH zE8inYbKNea@RxFmS1fdPRcG^b9PvkFJqR9p6vB(}Q1~WtVr#1Kqe%xFl(WH)caSC4 zTH(vJXW`0~3qFQ@0z_AKpHQXw;2da%eJ00%WuIs|VPzubyxvKM%`6tWRGFf`&M)}8 zL!E^V@xZpf?a=8%u=G@)lWe|OAQaqIWgk9sj_x2Ctn!SfkN^DT{P}27+IO9>RH}#l z&&NUZ6BV{%vK5|I*bfs~Qy62u2+`pJ&d&FV*YVw`#&h5u@`Z-Xk z?IY1{a%9UI%;EkLRW^gOQU_GE!{SqkboIQOI7B^>tlFC>oc{ceh5Bc~(=%$!@~0Ed zA72KeHZ$4z8U^ucMhrP*dq+4l+6eDCCqecHN)KM?kA;#vXel+2x*j{ktl~T7bCbIz z8fGexLj{g>LarfRZ@La4riv`X&k2=x+=0O3gMG@j8{w4cNsx2w0IkdHkL5jiXWxZ2 zQnS;_m^Z5trX_2z!}~4q#9sxndii{5+xBplGnB|#_r;oysB!-#)OjtYbFwP%Zbk@E zb{i{rT~o&B`|Z>Vn7b9tE}IL9&bc)y2zMp~UG#v9L~RiGP(0$k86Hbg-lh ziEx^{FJCGsjwxp9%5kvy2Je&~!o51y&!BMc2U*3mo9J1xhLp~Y5PX>))_R|S`@X-a zniJ2-Ch&Zsrk3QBG0&$z$tHC-M?+0d7j)qK`DdMiWf=pzqVDjI&?)&hCG)*7Z&E!h zXbX|*>wlFsc*RQREHt2RMwdm2;r8(uI?$b@wzUY$w5{=6%V(~2Q2uk(6KxVG`5SmZcr~_&RRqqL`;ez6 zxZ&;o6qGl6(XeOQ;*Q<12`gOy3(@Ws^R0VdacUQd3_49^@pCnoDM=&~|Qa+#aZkVAN zzc0U;Ih@vwZe;7BV?O`>=8DI6w!zMcZzZLZbJ@wdh0yL7Arzmo#W5MhP&(ocJ;;7z zRF6I6T&Mw|eUy=2)kNfkPw=50r+NiTFb6xPw?oLGOxv}gF z87Cg*UN8UI8=>DI-lwqSH59I`qib{do_x9j+-^5XN|el*cY3z`#y9Ax6<$$D0e7P% zv|U?Kyzp%;IS{{0=z8Q4yC5l*doBFe+T)Oo>SR+=xn!KH1ov;yCZ~&=g~30~Z~*_i z(2hMxmA{mrR{2VDW{A45F#Q=*I=2QW=Nb`ZYkcCC0x3#{^!X}Vy!^IXMGaQZ#?j5=GW=!@8pFW13 z_SHg_!DaIMUE<=NxcqD#T!?R!I4KSnj}$kN#wByWTWW%%)@HzxN161tQ#0O93L#?*cabIyFp9u#xsIn|0ORUx159JOnGSV~x-z}Ds z6E8jsVcV?GvqqUHetSXfb`_&(L_FD_Iz@<1e#|^b9Q^*L%04}Cz{cr!ATN6a?e+E_ z+FQhs%=sxoprR=b)Jujz1wUx>7;n_`%!NZQ2T4BH*|V*EE#$n588dCM^0*pN@J*&S zG;ZO#{s+j|!~=q|M;rS~vLHN!XYn|9MJcrcMvlKOJE*20`tn@o$H{ku=UfM9UY`n) ztL{;@t{=KZEv4s=;{epAh0!m@f1|?QC%n_9* zm4Uh45TDqGe&Q<5U~yhH19X-eVfl%JAaYhfLP0;&EX#vbv$ax>SBjXjrcv&rFlp|M zqOA!T(i9=Rtscf~0*PEJuBqlm#6y#&8vA(B z41>*&fq!O@Oyi51*kZGttZL!fQGfpb+Qg9fmH(mpt8Qa>-%KL=v`m=iDzdGnaq`_5 zj#{Blk1E(`@J_ZO`zB@{SWku*MG8|(^sq&C5<=h)T~W?^i>~v3XPK7dxrvuJZcGlD z<~9bF^WWH3X;;$h8Y}~U>;IQBK)OI zc_&)KvN~uCp>z-LSCVXsB)@Nt6PDgBWL7ul%e9EC;oSSZpMvLZFS;{cN1PWQPn7TG z3X6EB)uPJ>V9@hgntJ&ri(8!`zvWeDyWpXOzi@4OOwqHz8+bD@l1y1pE1cz?oDe+* z_t*TUU8gwXw0T7^aaNn;e$;UG=3J$mLG#+`DV_ z(-w9A9)`i673sD=Wlc-If~qj*DIlfhV~KHT^Xt z{Z~g{YmiYLuKfYQ_TdJ9c9w?iu!Z!?~SX7t@hG3gYbGbtElgnP9K*fW_@E zmEZLm2e@Es4;>PwRwXHQ8H7IED?a9OvjDt%dho8t(AqnT+Sc&AL-#erbdiQI{rwZR zUU{v2H?Aw{hAvx9LrAy@jrgr1UfsEs2&aw-zP9#weS*Nr*H2&qvb8$4{M<$9TgJFTE92R^@@wNHu!Y8DQVgp zNWCjHuwY}Ed^a9SdSG-NA*Xqb`ByF?o?C3p*w z#@Pu|dZ}V)<5sxhpvJZ-_rgWSF2wd+lyvBlF>Kvf54ope=r&6%&8!29MPc-MLkY(2 zk0f&oqJ>2Rzpxv;kFwJvRpuq>%sV|ZVAF`*vIw5*G%~0nUe7E+?|~t{AGsIi-OHmj z_p;fSV;%eOO#ZgI|Nc8Xb=RSu3ZP6P7$AuS(`a+YnQHof-$lbT181kHNQ{c9EA|i-jof&Uh>9H(cAN!Ri9taKDox z$(p!Py4>O@YkuCb56|?mz?$BSbCnY)__yHx^k@?IX{|8%n+^{9mH;UN_jBfS!6wy2 z_?_h>3$Yl6TFa#5R>o(+b&D%1NVW<4M|^$pV~s#7Z{Cfr^?M`{`+h zb~~@Z-KarS_ev{X?Xr*TRyZYmo75TGau0LQ$v0X!tq%s5<-jYmL6YGox-oqp3;8}g z$b7&rMb zId{Vp`v2nnT;>@taQOqee~UNnaLfZoHv{Rvll$4LM;-gHQ$%-sT4F##!v@iR$)m)? z)fT?rwFkqT7DN1d=q7x)tIX!FnaMPW^mSh zKxfipUOT;;ag*PRGs$zC<$|cf*c!Juxz{4rtSg!`moS6R z>KOkNu$TU&bzL1%X=e_2@6wd$$9swHzGumGn{hBV)&c)%S&>maH^_dT>57vUeFKlA zcAg{Xgsc_xb3%-JgVUf028RlDH+qF=NJ-*2mL z*pW^`nPlDc(fD+RJ9(JdB3$L!hkixhVOFt74Ttbt&xuIVK*tGbo&_w&Vu5@)wX2gDBF2%WdvXN7d6qb$`2aZGtEI&erEHn3V>f=g+z}-if55!!z9O-t z1P``ElK!Q&LV2n=?x?4r-`GOOSUcjE%xmDQ{715*WhlQ-ckIT&=S(qRX*^6#;qSGU zZ%pyaEts`TgG~-{MU^`W)?Wna^vo4PtvNpnS~p86y>(p=V8tsB}p zz68DXAL%Cd9@yAe1=lY8mDJXnvfbflmHaU^pESxyOJH-}11dp8=)MN5vb~1J?=ozcA zibN}XoRJ2~*NkX=e`PT(a0_ufd{nSp)eY74Ey!i#YqSy_@x_sM@Mc&}VL@;=oEv@x zZUlUx9=eVg&vQd99~7h~g>7urrWLUkM|>)3}=p1I;8&hW<> zKP9h&hltkZO{C6sHdym)qxPFj2*hkEmNueG{x*_OU@r_>s)9dxC)fXd#SWgmu-43# zgm2m-t%?a?1+zP5ufZ(-t@*=y)kj89lRXd7Lnn@WIh-U!?Wkh|T{~v)j2#xZ|5zTZ zSRO0uD{6=uFZL0yft7-mhY|iW*ase2=V+vQHk%tBE6;J5sk-3q*mih4#e`nf?1Y60 zXQ2L@8v9Sv0_(UY{5kA`&#t{AM8{JP$+dU$0soofz+}!^+!;sHmhVHt^%!Hu zM%XR!H;m?4gHiik@nN$9v8ml4oqjl(Rnb6j%jK-C1m3?qSp=_3iS)_t->7|lFDXb} zFI=CbgJ07U;MfmU_RhNt_O3~Q@vEF<0fUC(MLQ{}C7*?sx!tiM(}1vZ4Rp`}5hE-U zNL1gcLXUorSU`Bkyv;2(!vvlSPD=El+xWcwIAb3ZKcNTNT)hDGc!>Xhx2D7MPWNfrYcDL;KPUH23`$9020X*~e|^|w zy$hOZ8xXD81L-EG5n{^%3tyE|UnsZaUBhj+;anfy%NfM|RFfZq_pp&Z&GiFC^DU3b zgrkA5Zj%w-!AP9-Q{=Hdj1HdSLXJv+>Joec)<%VZ&( zv9`f_8%cVD!rUAS?95DvPp%@HGp-t4UohgrS&{V?GB#;h$8J2P#SX2dZ(*D8U3P2C z4czf@BiZ7%OVH(gSnVol@OE!It?6u!pX<*+0>|xDh7XRcL|}l564I z&t{tS$OAhctLKcb5b5Y{Z)CH>qvhU-8G*caxRmD{V>Zyfr93P8K8ny8TZK{Tybr}M z3f9E@rpq_D)Mw z#1Zw)|3Slqn4;MOyI`~pgT$&9+V;#IUnmuUx9J~=YO+6zop)cp18ed=ce~5+5S%lD zZkq6g`3}7e4|ZxWt0?}y?x#$?E%+?C_24vnUB3`+-q<0W^6ZAr{7u(5sgj;M*o4P! zM-xMR7hz@2H?}EZvwR0u3NpnrQxo96U9;?2TsFI9moDFdXF53JyE;8`ud}&q8P~M$ zWz|5N?hi_s8{V7z7*19El{9#pu$2C1!(@{8xjT#0V)J<|DQBiN!k5Ac+!vVy9p z_kd?MJM-L}e|J3nR)q}Jv7|>+9^ggW1Tt8c30Ij0=I5P(8=N%svm>mtOYq zJMJs446PtFxwByNeN&7(p9lx~#L^+{QJ8G7i_E-pUHDX?k3S}~f?KKviwSVT-L{IP z>(vd?f6j-Q|N4m_<-RiirKae}`;l*I#M9<~f6*%=p6DIeDvaOFXTDLQeD?lhruZa3 z5gZ>n$@T>L;`tyc>FmgN-4m`@8*fBfRy5P&?v7|WQGvYrT_kNztz@Ym;=sJK8VlO( zfs1NhLh$hEbnV(-oGZ1Dd-dAhy}-7u`{Q)rldM>cT!cyUE$ zBQdITgSkAL_P{+Ij>lKhxV~OIzjh8@+89c|?}=k>3NiA$bDXOK>I~2$>W}-;V;_c! zu@M%&Yw~@;d#VvC?kk7OS9rf+tP3V{FXhn5qkVE?jPOc*GF<3(gcjFv=GFZ5WTd-` zkjcB$HNBhU^LF|09+)!3gxtuEkiOOnVe74Z<$1al2^M%=?Wug;{u|72bJQAAv1O=` zFu9!#xs?Fn{ngk-WlPi_)`d)vDYKW&ukh1kBoU!Ig^xq7vGKAvsC=ZxB9iPe{P25l z+*U8^(GM|Pww8Q$ixAXR^wInR@7H^)z`m`r!<5H45H?;@lE}FPqP8OmcL~cG58>j~3S`NEd$g~91=cK$ zCI7-_3!`-}vwN==fG^K+6W$~Cys!cm|L~=rQ#<3=oH&^K<0ah}^Z+|&R*=)1WI}Fd zk=2bn4cFY%S-^T{oWZ#nR~q7rHlFN?0a-VoyR{;#-(`n=M|RBBi*|l&v8-dRu3KP^ z{>PKRtLr%WdDY4m6p3|?CW4GY^Ob4D7o?UiTb-m|wocs^7+4Q8xbN_)&` zL;L%|WJ>CC!6)c8GpsBHEfWoPF{V3SPBA9^oZd=o4ZX4NPi>O4wplO&?!R*9v)VtC zo>ZWC{QD|W?4T}O{_=oD1gw+qu^)C?VcF|1G<1R;PP~!>`?D3Kok$4V zap{+E+>ZONF5BR+k6p=#&NJxO)hg($S1zBi;*0L6Y5x;knp!07t9`}jxL>4O`5bV~ zH0F8s99Vojm%1KNLMnvH84=al!`P?6Jz;ybDm&ia67`NYz>%OxI=j6LpM8tr@uU4h z=!jaD&f?`-F6pn2Pd;YA;o@DgSGQEf^F}e`WBNT|(*&*?tc-=s+vn-%fl81LRA)|X@dHTDHPSk(TQn)@cM~(a;wKy;lEQ_`0>9)IKj2| z+9VU~eIpUBopO@pofmKn*APJSv(Rkkh^s>l$TwL%z5k|yo$M74{yo)L_e*~;^IAL^ z86S6MyK+-$sgLq(Gy>qoR!Z{ul|js9B<)xNftB@6wgNaF}!Xy#7_de%_l?n$Ef3E306yY?RNR zZ@%K^>KelO&w;0+5xPVkgCT2@sg3<_)H<`C2*xhLn#Ij*byyRWoX}w9yLw`-vITJ$ zcS~!}Z)CM$zH)s)>m2WmHFyS-%KxKHf8bjp}izPx?T9~sEgxd(Xhqt zFFj`LiksKDknW|t- z7s&5r%DsD_&-mMLCsslaN_e-FSsdB$Ia^TY{?%m*Pr|#9CVHouvMXF;)Zjec@2?#Y z-YAmwz2b|S0z2cVLhki4YNBgbd*JGZGRP@Zm(JWZn00%4U!H?Ad(Rn+6Oy5)-()J# zS{88ZHb}Q(tdqhK);OptA_Rh3^oA5^D?#Dg#M*C7oMcfv2iglW{W* z1R||t-)4u%chtZQmKaob7|MPq&>19y)ug6Ft)R}@2fN~&aATr~)-wM?e&UX8{98;m zfaXJc92)cyMsU8U%*7cKOdmtc!#2sD5+i1L{EVCn;b&}t*0a;0{r56zy6Z2#RM|{Q z$E*^*AHTuc-jza`ss@u1H@rUEgm~z^lQbCj!D|XSBzk1C5PRPeT@7Ets|z{QV6+Tz z(HfF_M_n+J-e#}^g9%=i-kju zgZMM!7x}x`2`2GQ6Q8eFVT|5a`Z>T3y*azjIbKov*>4l8zw=AZAKuS7pJST4lDRF@ z>G=N2xOYoATw0>RZY}PP4LS{=nbIm*$I&FWPW~eEV!3yB80TtUy9|eaT%ikim&Adq zJlpcdQ|SLy5tCAQ-|=EKrXM_%byM#N8R@*wh3i!FKQ@E8^)9;T-5pH37(?cy?HATv ze$VE9iieb6JX2=IJC~;xLAcXlnIxF=Z9HPgxpVgfPtK5ek{<^Jl8f}KUmELb+c8Vy z`nq7Rttw>sObc54yArh&63O~^Ojs~R9oOcFlR>3EacgWY4+AQ@sbW% zayo^s;yw`Kbw<9oxITBr;=pI{=+_PuU)_p;A3 zW8`^*3m%6l2MI^rAu$1s+R_Sw3Hh$%bX6P3_8u>GMC zR@$6^s_RF&Z>-<2N`h`6J8bUhYWW zb)>&(grFhS$5Z{YU~pe$W?*iE1xs?^zi16fews6;pK&F-c1OrsA`W6?}5z+27x3tGP6(g&qhIDKXz^ynT%S7xe+SMp;>$d54Ld2e03&b`eg zo!hC&lI}dq<4&$TdLq#oJQ$ry+{uE0Ekdq^Eo$#*hmiEUv}yfqbe|JTj?~N&rrkTw z8bTM!chn#HTt9qs3syYwp>usy#2lX(Vz@k0C{wY(fA0=MpnVMN0;M@SgmpK$w{7_?xDk4nPJrK7XqZ4W?s*8^ z_kCinZ6WaAJDyjq=6#nm8K(DFqM=Vx89qpdG5nT&K-m?qalL)zL0j307@iln@EHs@ zH_;DOE;#teb6EFQK^lC>ki{zG$lv}i2ASh2gA9n>x14s`{s${ZY$gtNtAxkYB#c2mZQE4n$0_j)jL zaT|KNr-oYmAL@*aF-ox(HhZZJG| z8F5ZwJ?xQjc>Gp3PU)){R6ICUH zom497VfVfw&K}ZjS&v3q9+=U`_B(sxyH=c?c2Z}JfutqJ8; z*3{CpxS@UZZKoM5IophGxy>VwB&CJ(jIyxzw@chf=@H;>pM_p$c9KYKX9&|PMU`Sa zUSFveb-6vHyE;rXggZA>@Y4%t$g-+$)K#w#`7q|&>pV-il+C*BlxhW&OIQa};YGBr zyp;@NtYd}3Qe9-d25Vw8K=5(>xI;f>D@2~@~2Nb5O_=bWqK?(}NHpNWjmW-Lx!Yn>o2Z~#deMeyIr zJQb8&IVxi5+zZi#>wVXe+U~fhyY~q8y}XaB*ro!h2jh{;Nilk|)CP{YIpW#g zPk5y-5a>O3#C1l!T=*PQI6qDTn=_tF%-A zP@Yfb-H{QlN6GkJM-k@`r^dAX6jb5;id@XTNiWRHN4|_#Q+LJ`idm1|<+!BswLJwJ17Vj(!R? zff+I4`0}dvyzHvew9PF5B~ClYtxGk7&a7q>aN`*}_>Ikmk>jx^>v=@#3 zEKLnA=)t1LndrH?1ZfS=p${JqX#y`VSi;SDn%L0WSkU_#3orTVdyH1yiGB^3!^|gN z5!u;GM%P+H`NkK>c9b|@?DGivx~@oc+v>Zl4fmesp}TK4k*C9j^v8rM(eCQWyt|gU zI@sdS2i_DtXE;Ai8N2ekxw{H1AGGQ}DOTavh9Yd*1{ym4xWGN2R+y+wIdjn{bWZTBQHn05YVrk%~b&@h}Jj zYxPK+Kbdkh>Iz_V_OED<72jY8u2aPDs(=6Sr%gzq#$gLZT5B)sI(Lh&K}%}WNXLmr zmYLdxKlUx;W){hUHS37Xv1fk!qxukBnT0&NM+)W?j)lt4Lz;lEL<88Box^KJg>n-G z_vqVOLo?Q~*aZ4Jnox}ET(a_X9SHOO!`}B|xKOL%&|H#*UP-WH?|sJ3T2hMSI^9_* zu?F3CN)LsqNYmnrjHA+`hWi2v$b-H{I9h%lk9?TV*(iRYM^p>ZAAt-tX8QRv(>9dX zS1)jWXabI*m(cv2c5>oMH2oPHFUtScN-{3)I5oV}!=0#}3e(=pTuV9FbHdG zWL!--`t^w=Y;}Brs@KnPf8m0KdyaMB2hZ1{=mqK!b|M#<6lW9qu?rS;vYyk;w%nA_ zUuge?ZX{kTM~7vMgUMHI@QM}3_@6fhQ6=q3q8k=vcY*8szoQVpU1Z@R0`cK{a8HF7 z*J#&6|K+iq8q-vl-_!?Y5=O_jY!ck?a1#zkWq5IdA~IpD_+dt-ShrPy{=D-Dj%EYi zVSku=ckVKE_>zdGv-gz8PYd|o*@=Q@4GPqT-G-I+JMa~sNN#81a8P|)goOFh^bTW0 z_-(z29QP^k+HR-7o_~k&ivxAs12ZkiIMjuTSy$I}9~T%L5XY%YBKapL-V<0>ALLhU zlp=94`tW4NZM1QF3|YTjQds{d0k1BN;12t#z_P0e$mlNL?A5@qZmg77~mvv9}Ig20mFE zEG=B(kSy{H*v!)bu_qZQzUDJocJ>B6)s&ACRb}a2_P)CpB#-k(rSxuGcwwIl76PH%f-e255t1M>@JRaz1&sKOEl6M`4|pSzO)9HkvuV z7WpU1(ecA9Vc07fYBVype)=vk979LTrA%e-pHJ%49NP7}jhR|;>9e18izb%)}u zzw$V%UOgb`w~(C0H|FIt1iQH<=%buCzsK=E8t(c>#8eNTVFH$B*7)H04MeqQfG$w1 zN6HK3=*mocSbzR6uE&L|L<|l8A=xb{2JB+!}8L?eoO(0n<3*)l&^i4kY0T|BiD@!x)EuXEM6MZtk}x zn#1YXN;KRsTad9~lJMNAC-{@D0rFy=%tbA!D0)*FaWgtaP4_X5y{Rl^<>D|sP7L>8 zO;WJ62DT+9WB(k&h1N>KkuOEa;EfD5+-eJd#qXm;??!hSA1o~Ne2mA3tV7df4dF#r zHky!`PF`4s!K9o>tSJjzU!gpBRs0qCX|oFq;ZeI7?o$utOZ`Zub1yDL(?2j@S)(re zoK=U;49_5iD)*S*CJ2wt^yZ9~Fw)+dfO znnFpNI-YU7heTO70#QAW#m#ndp@H|PS5p#N#*?8DPF8Rw`vpp=TTF!NHBdMr7^hE< z=B}R^4(kq`LeE`)kydFt#uzL@OLWHbT>ev|6Abl5Y#i~q#^88b9b4F3AnH##=$TE0 z$hlR9jvHeRizJ^TiTkyJxX;Yr$hfQ{%i74X!@t3v?7{-GI{w7Vhw0u6Lo-&c#S|v6 zzNag%5$RP@fgO7uAUEcz*vazaDZAPbH)o#vzRi<`51PN@Z3P?9unKi>Nk5BB*5;7I z!+(S3lNWgOX4iyh{2QKgf6sjVNFU02@;Gd^DM3JPB*8bSC>*q~j?)a*f~5w3kW07} zt$OJS`~9S`-Nk7B*_Bm-_rHf`tnj%WOr2kjI;4(}51D^qtzs+|%IxF*+ob}HI!Wm1 zE(yA`(*dqqkHu|M-}2sSy2Iz0PI%jtUM{+rd3eHxc30(DmC&*)5!=+QNFH6K*(74%EIMWgN3(L!+YNqX z_U;29FB^sXZf0>>;m@ho{#s;kRF1Cy%x>a2ve@(L4_=H-7S-klpo#qvTuZPsOrQT5 z9q|4^UVf~HdA_?@m#zlq?C_Qj6Wb@!WBY!YLYnqD6l9=4(v-94xB2HpnX<)VHn6`? zADas;1^3poH$~WYG=*hDmacb!y^M3^r>)3e@I-|!iY(%6!=$OIw-$(P%|~^swh;Fz zp29i%9^xZi)m%&DZR(pgG;e>gZt;v!`Z)CaCtmY#dzc!bj2|0xbNZc{V3XE{Duxx4 z!JN^Io%Iu4-5ANzFSS(lV5mqpxF4(s1&rgZnWjy)Td4>yS0v)Kc9%JeQ>-uVhZR1) zvxY3VV-NGH2GO!P^w#*D=CG-*3Q6Dra(jva1gVuEtvoS4njcJ+4*e1721lNmg31Pa zY#$OtjDPmg&QIPz?*sQ?dD$bZ*JW z7xdDzA+2B!+odmhvz*Vou^l zQ2bRAKl`FX9#o2hwO_Hwm-V{D3Vs;fM`yk?xF3z+g!ittV3#H9k+nR_2#cLY3Ww9l zF718LqZ5UXJr#0W6J+40VZUf!wK>ZCJdEG+*DREO!y%Er{Jl_=3mcW91#hdE=fpdm z_)WMA7Ma`dFzU@U9g~I~Fto3pY|?@AwOMGys*!^Dm80OHH;1Q~eB#V+nnFjcHXc8X z-8j-JS+*@1O|+4rD~rs*D!dh4v06e_h2Mi6f)IRL>n42%BTSpfOiM$V$&&v>K(NDXV1YC6-}d z`LYCEeY{nW;X6yXKJXEqd&>}IGR?En$`lWtSD-4!7wMskNus;|t|$x0_}PuF?GPt8 z-BW0htl(jise$UehrzbTB`CInbsSXd!V31CounnloBxw1+!tGkPp1T+GkJEfBy%kO z)EzHi9kw7X5rv&i>$sLQEwE-;C*sI%2Mb(5`k)M6bR~vw6j>>lXmUujqt2S65Bq8f zvdWGnF5~||nRF~xKfaf%iB^G-&}1aXx(>gvRJNv^J619I#Irau9(FHx!gDNoIR_a7 zcwHrdJI_2MzMq9mhfKtu*RJGtk1nFOb_a-VSl{z3z=2nbR26t+j+3PD_xfZ!YH|^` zOP*zyW}ZY24qwUDu~+E8#`9>@Oj-JhF*%>KDq{N+ndPPmYM?XvF8VfikZj9hKQsD` z==(!C{v@6|Ej!aBdi!Ix|3_Nnpy6wm6M4P8kf0ZZFPCOei4Buw&2>K8Kq#`L%~P zXk-fxrOMdJuA5u?ll`6+y+#Wa84HMg2lqYvg;p6I=KD3@qX%+AQIrGY8r8Xis&y?g zZFeEV7by#ECnRD0EtlD@%Wky}u6VEVQ{t2A2s@cp^J96%tz%cKV0L;W&Z)Y>ecEpd z(krTv?b3ddJjn)bxCl^Rj3U4AQV>;9=@ad%oi!$4AmNDJ_Xd*@!+U9Q`p_)BIbaQ( zUO!5A73Uv1s|OK10+jhsK+K*?2`@}b#UAh7xp7r}bZ=Rhh+AG_HUUN~or&K>p5-45 z7*E|^IE(THUd~#O^=$y@S{xxZr|trtnu_(;rgQ0@&**sD6f{9shW)>^0<-1y=+x;v z!CNIY(34I>auK(Q-OV(r{yPyBjFqLGCHnBaKoWoWPlrh4dkMY#^*jn}rlY~5V$gbG zXqH}=W?rdf^(gaoqxe7Ks*5``#i;W0YN-9ka-cJIaMzC9 zp|i&g%~gxXX5bBN=&J5gGILu6yzJh_a@J8?SI028`Yi`l&*>qF%%9`^t`N-~HXYLq8ZD5X4%YDEQg!2k7OO_q`b4KNdAZnJ@Z=? zeq78$|9xC72xy-nTva(VW4GT>2gyT2Z~rZ0i)njz6597uhPuo(gXFMoG@vO?y3SU@ zlyi}IgL5J`;i)o2*OZ`~7#W%WM6(^Wp{tf#%{Txj<;3vM&$2Yk$_^IVh+|*bL;MP}YC)ZEl*lJwWT^)ZQ`i~3 zDwb5u?}6AUu~;mBFLx_P1?IkG-iAmi+Q4@JvAOOz%JUO%kK|ZbvfT+^m+$3P%rXN$ zmB&wVTgmLXLa02Ognz27=JMzTS}q+Zx@YA`GqziJ9a8(h|B@hV+Nt$#OLXFJa9dJ&(P6BGAi;YLJ&zjf6+U zXrQJQ+-I4osGqWYujdnJrAD*J*Qy+&2hmG&P>c6+LhX0L6^khRATx{m`JkD8Xdl{F z?|!ug^8+gQ!qR@8%kgwtGbaG8z7fGXn9Lx_za1IJz9Abf-hsA=ZTQ6JVceLimsGB2 zpXkoDr(O^Kzc)PYwlx^v0?)&~W-OK9uFJ>&{w2OT$!!A4smxSZx|G>q+y|LgP_{?h>- zKC{4226}lf<*ng8QO1^%-Q3e@hM@BP8mvJ&zBRhKxGf95d8%N3W(Jtbbb*04Hq5UnmIx6HrH6dwMn z;4#j3Jj(u}2aXc~$?<-ZIZ@WI$(A4nyWqF9Y@t7v_K9}aA36GP*v<|+&)q_vnRU^h z_v%sXIyveU!aOP#5_m6Pn!m+g7j%{o^y-Iz)TW6Gw=nP1+H2!E-JV|R(>XM6w`~|l zQ)-<>JjNeWG~ra#0P=hpL)?qigdg6v;X7O3b4yP>rC%`ff0{7=zn3xi72HMc^Ropf z3*3dX%v$iiS$b%!hC1{mr=u1h0U4&8Mzg*R?W>8|_RyF$0*79(A?eMYLg)E<9y0%? zq0O_zz^}0wMKSMm;eI=q8r_8EDYUq!l)DQX#aEkm} zQVX-C_uyM0i#Uz>Qjn{A4D~W?@DAhH=kH^8s6uDved0qV6C`ZM4|1k|4PfB3CdLo{ zkotAiP@;4m=X>wqa_sNWyVH|JUaSsdHY+B#A?c(gBsR7J3R8md^ZqEV^z(3#U3CVP zZ~H?O4_ZR?gCexvVjS0r3&9r2uD0UxxBk)Mn*zo9LRicK7vvER##m>+}X1luQ*hv($s z+n9$UO@L0a0GBgwkXpbZ_qi2(Vf*kO_{7^lgs!W@jhO`~eq0{$vrrT6?oY=*I(@i` zq&8aZ+=GT!$kBO@PSCa0hTS_-`R*^*QHg1jMVi2C=1)LMo#;X1E>ch@CrsFM8z0-B z#)0~GI>6@b|2zYyTSmYl@pI^R|7t<*hUvoLR!z8t8Y1-sRrpwGikI{%(01EG8gGy+ znzze*7;li>;xo=k6U`kh(7YxEtK2`u&1+VI$DS8Ont;(8U3k2-6e%uI;PH>R3yaQF z;g^#(psS1RV6PVsudquIj5-qwF>+COOSRM!f7i~@S2~8IOXdqQ08+CB_~N!<*^QMdIg8m-hSmh4jm1*4msiD zAA7iw((K+5q=1zVw-E_hAy`(U+r&q?| z!%y?La8-R+vHA>ZQtTnaHkQx}Y{q8sWa*pL)-a8+Tld|`E+0HLQ@Cimo=1sS1UkD- z4HjzGqLn@3^htvqfJO__lvL*5w;NB-I5ms>0}EQ2-oCd0ZC42({`fywIWh|4m@ICR z{3B{*REI7xUQnIB4NMOkj*asE@s8J@p!1gmpwMFxTs^xNJiOe7v}0ZqiCq+Yes9I& zYgIU>cWspCzF(BpdQ42fe0c$i)mI{=7RTw_)^o^xyDSa$v4j0rEb!#lPJ(`>dr$NE zjdqu__uT;-Fx=UJ9(2j_YgQ`K8+-nL#xk!|p41K0Y8_5K21p7w2F76j-4R^8&K24t zRgG4P$x%}$CnyiH!4oY9d7)}dEACLn59GVKD<5S1*4mG_-)4);yC6fjqR-$ zaSZg=Tf$MpK~(fzoUfs1#NK*UsDJfcvT0-!eEqu(&r;RpCR_Hlzt+ySfVZO?5%2stLF&8- z!c0L6p0h*`wVr3(V4otyYic6ZC8;#PGD)NZ#04-e=)ed(qS1zENzD+}1nGG^5>7+H zL;W<`vIL!!k)>igZQwL)dEeqlU+-2GT;+_*^O8Bj0RgWuLqkbzn*nLa>a#GGLK zW}i3r>68S#OF4%Ac*;=E98K6=a0*rK8Yws>HXgni``|-jgWM`prso%E!erz>nehQ0F`m-zR@7gyn50j?1K$^hU`^K;F4}lF^o+|xmy`aI z6U$jIr(+>fZFl3TB`DB|Ui#?19^=fgY+9?FHnt5eCbME+Qr~q&C`eqEM!T3pTI5?a zBju4`#X=9E)~9Z)H{A|(rB^-0&>5{-o=V0 zVDi-fYwOG)4}9dnFZv;x7sdPo3z>#_^DVmR=5=rpZhuG9gR5dw)Shx(r@75$t)*R&gyjfR> z^Ko>@l;z9j*}<^M2;Y71jdx0G6yR(pEc>K~D~LCR@*E{x)AWiw2xeWS(ac|c{4U?c zH=m|>28!6@qa>Z+>zG!wa?q0~jOc+75{K*M&vAc#7{G>_bBNseOUg$T(fFt5(Z@-$ zRFAP?4Q>p>XE$V*yR&bTM2wzC>BI=M_L3SLiNBA;R!h=Zb8X

    |<2Seg<-t#?cYY z%_6p~`$9dilRb;xPh3eF!-8Pam?%6fIE#BZw~^-09GbUkDkE9eTL(X9UayPukJG-g z0JP~`1h>Z89Cqzsc`M_O#MVy$gQvIR#epiEpJyxeE!!{JX?wbj;M$M#=wOT@$@r5( zHI(y_T9_<_2pf1h!4e;s=`0v`zz}BE{ziYg2FO+Rjz}H-4Xr$?z;{hiprN)U+;8S5 zUn*?`E8sd>axaWLtCtX(^u%DZx(LpETPgi$J2Y?03+%ydF3a!308h%?9FB^q;QL)& z+{OpSu-&g070mE+E0q(r!~S`O*!*~VZCY|zxpR5>u)A-vA7NyiHlQV&?pdJ z(tzFsY4IE8Y^15f{)#fQSA&^Xq1*+}JiL?mX0o38nGHxGM2-r#Sb^azaonTMI^xq9 z7u2H;6;G-q^@hzbFewDfeADBacXrXGYr;i7*iUQ6LiD6LSRV@buxAwAa%m*G&G-Y4 zW*9^93q?Hh!3lENf0*#FTRYyP`JS_%(nPl~AN~kyrpt}B1?#jY=)Qfiz+;M!ux`OG zoYw7#K3eF5a$6pHmRLtVH6_#jkR*|JYgVfryj5X$ndOdTed$zT%mF=*pBdAT`20Rv z6I+4|7}v|s-v(9`GT(B*Q+KbWoG`Vj9luW4jKXWwz)phgpXZN}ZF!racSaQE4hp&3 zy8me8w|?~BUBZ7xZm%(vXT4G(^t z%{bNK5L0ywc}oEM)}YR)$M?X z4Ibr|6_nHNwq$niW}XUnBj6ot7wHK;?E-ko55@&kqqs3Fi=o)j$$Y9UK`DHgC(tOG6G-XhpigN41c z7wgZpM{{NvKw0>8r2pa#F;X{!jZMX9o~<%}^7q}eX!p<@{u*QicPK5vKphx80nzhLZ zCM7%K8Bf#rlXF+nLp76;{CjD7yxtJ@jO|5z&km4iMLD5X5WyKq8QiE1pJ_DP4^N$t zq2ElkVa@(hv^gzE&|fAkY+_wPxoyqd2}c#EQa8hYr4{K`>wH?eerUh_m2U>~>;Ivy zaB1@9PaTAgO~8A;rgQrK3h<6xL_I8DmNVZB{=^HA;TUz^3vAE6p_8#{dYWLPWfY9w zdl(-(UBk8Yt3vM+=2uxEM`zx%VBcK2seTcjFGb2 z^Cda^Dv#zg2Z}PVVwwuHC=57%O+~#uG3Qd z;RUJG=34;znH9mM?J;NEp%3WF%TJ_sTR8-O3&J)1D%||Q=ah90h;~|6B_ps1FF;GH z6iLI8BwJnVJ{3ju7e|`iX+r++Wr;6#M8P%w#PnJd6yRYg@q;*c-!` z*gB*s5TiWS&9uX%99UN>UN@Ycu#Zf-76pryqVS~LT(08H z7aDo40ky`!sGkxF>R-ZXOd`XhR!n{{}3$WURXCA_X^LPsPo z2ombNg$5bFu-kAaWdau%kaX6o#Vr=?9p z-UL_1MPb8LLN3gIkb2t>h%|)VEu$d)tO5Qt@)&>L#~A8v=quWFw`?2xTq+me7R&dAU$w++C1juE~YIg?BdWGwCxk3?P_m5tVrkjEG- z1FPJ1)HvY==9l&f4?+X^`Y`?I4fJl|WwJmhDQt~pZ(BQ#liJcmwHt@DS)Um#Fk|~u zylMxZdmOTyjyp9OwdYCG>+hHjlhch9tM`+7S_1}L0-k3b$c318&;#p_q2RqTR9lC2 zsC5a@@`^CQwEL36t0&^{o0U!6A{ix^w#W?UnJdzL!}F-~A;y3BEJGK$o5IccVt7uY zG+DT!0W4#Z@x)nK+^8k;FmHS*n)QL*0+h{QsRl(F4jMdVdt301n1ZuMrwf|O55gL? zNZh!vnlsuw0!p35acR07-I_EC;uTeJ!r4Ur+A$!o3XSHgzL6yZR}J9O-dd#Pm_iEu z8liv3fA~$-Qf_I#BKQR#M-D90y6KJ`L@%F)M~~^@c}h8gT7?symC?g}4>W+r$BMXL zmvx5vpQZZCHlQtXGIT?mIVjw0Ld8cW6Gv-lA+I$Pn@L>fzJ_Q+%C9rX;c_?0%*dx9 zo(0H{{rqd1+d;mpHkMp^zWkrOI$SyX5WQ#btcNUXyzWFhD*ZQtZ#B$~>g;?h+E=IS z)&)1ybEs?D++)+WVcH3BC>GR>8PCVi>pR(NlWU^8k|hB~7i_F1l>@1+>OjiFg_&FwLL& z#}>;{>0*2E4P?IGvttDpi5BFl{y-1Hddbqqwy;d|7gAJE=0EY2qt$ICA_jPQB)i3| zxq+rU4I{ZZ;=)`m7XMB?$Q}Q7fxbzoM%lyVsA8-=$W3#^WlJUa^@hf<$z26kzv|-B z*t?9dTmR^nl_a;x1r$RDk-d2=zhWoQQMo%s`alEc0IPNC(8?t)q*^E|9P=s($KAQa zDYqEIw(JSm&-xV!ur&j2gg7Qqa4R^!0k)SX<9O#vZp0Wv;4v@p@7ZFs{Q+YW88x8d zhnoC?PyWn8h2RDLALN=D(#;9PFs=MK8It^q|KlA~eR6dHWR zaQs6F{&dPXt1-3658bVn2;bJR?n zuEx_b>~)=;od3!_peVxQARhnrqRmsvJMx77j?l3LK+8&BLVA5RpH>TAc_ zM{GtW7uDc!V>VKHa)N}^u7j{8QCQhW$XQP9r9oK(hQy~7Gv`{Hg54BL95X{e z*57D$&A2ym-wd(pvl&G7gCv-{KN9H!fB#v+Y_A_^_x#oFUcNlx z9lKs^doT!<*|1q!QHEsk6{2@ULZ}}ThhIP8b0#b!~-KeU?okJ(p@>oA)+6Jj9pF zf3E;j3yz~4=H)XrwFcd&skq}`7w^Y*I~d#Gg!8udaLet?VHV?yMx6UXQY;@qtlD{e z&LNx|ot8^y1#A%Qt1BKbUQJ3f@>iWgwkSynZ>pcfWZ)X-$uj0!Qwq@RtAk{fSsv9{ zGPJK+G+6^rLK|PUJ73;ttq#2-o00DwS$c^5cdtdaqi1(U@XMCFQl*5)A}@h(jSkG- zdk*RDT}|{(t%W&U6nzr?f428Jj6Mjvh{^Hte5Pxxv`2apKSg9G1gAX)iv zvS9EZOcEZ!ZXYAKp5A<_e7IVa;fjeF1xs|s;vL82`QbW-!1qo3m=i}KuLI!udPv%d(MX1N0p}9J1nJuWCuR&KHI}@378R3E6Bpi6`5?3i@3vCtC zvFxu-vg?a6q&yeH$`WvEB)MumsM~Q6OG_`dIR$EX4&dCJ5Ud=jiAHrZuw51{|FcL+B{7d5Bt9OVVSL0`P1v{Xk5q8jHN8w zo0r8p9YQk6BA0p^uq{=zqqa0#!1I!)==#E9L6yWDVPD|TjNS3n1h(BPMa>_ckk0Ez z>F4$&WVTF}9u;Rh30A{DPuh|g3b|i*7>l@d0Lg!qqY9@Y86&_~#1r_Gq6_2Zy+qdj z`6Q}}z#H*Bcv0m7ZpQU~dSt_K5tGp7ngM)bnrA>5Ur@q4jV*J0u;i`*&ZE)*ehAI5 zfq^W&T*g{1u2VekRxG!c^`9HaZl(=~ z%gc&TT7U$VE--?*r%TYOdE!z*=?6_@(1Md?OV%|dK0*X-;V=rWn zwS<}vo#;hdo1mm(fv{wkvd6FS9_YdjmQP<%fqaBN$^IluxRQ7s{THsruei2_ng|lm z`kU;2%HD&sWR3AB^;yJzn*_w}e}tAFm7`x~+rrQ1J!rK{p!=eYy6`lt49ycGpeICcX{dZC%7=e3pl0gU6A_UunweI>Gk;=3?e7<~PaOfbM`3F5Tb5 zRd8l7TwDW}&ih8ru4#mYKk{+dw=iz8d=3>fZa@Rw($w;e6-*h~it?Y&BHrOOaCvet zp0MvICurA&)<}0g7U#FYEYc`7}+pSa*Z16 zfemU!9j?Rqsl_hTD(|t#%UbhI3sSe7Lm!n_li!zC0!(FIR;4U%T2%$@d08jQWCeQJ zLB(Qy9DQ1zuOOL77aD9p-p?Yqb1cW?dF?%#i95){tz*Edq!X!3isRqe{Fu(DJAh`W z%FtcnhR|VLjCK!GA$e{`D4*@6{nZ8>>h~^YfKb$z10HgDc$JR@L zf1}jH%KWke(p2VciHN!VFUAmRwhPeCvP0z3fk6nI7>jc(4sv~Vd30~#(EJo!aE8O3 zWAMOYdHz*neQ;xb2EFH9T+vYzNa>Nl&I2_hL30ee9Vd+|S10kSWd-!svR$G#ewr`) z^W@ecS1%WG?vS+bkVP_HeDD$%Vqy#Hw|nCK&fVmOp*1X?A%~+s*WS9vc$LpolJVX9 zcewkLG$8eS1*(qkCf|(hU~=+(#Hi~0U2E3T;<|p(Uiwhp2<(S(xHbO}(Z3!Jnc7i! z!IWHXt=n75pV^4yQst5FY2W}+PAkV$kRt?o`u?m{btw^;mZ5W0U)9k%!8qBVyyNC{a9L9?Uq zPE{cnE&N4&Y6nDlfh?o(@cyL@Hd=9-zietGU3YD0M?GP#50dV0kV8xXd7)3Bx@I@F zKe&L~HL;)Ch8-7ar!%7UVL^ByIupbbyj$x4Ve5SGrl-__LJiCFYt-TEzZabLAIEIU<8Ufj?Kat0J*e^4! zzJy=GbfmF7LDwJ=Ue-r7zoclV6Vt#aS>ca*gcMaZ(XIK#sMTGTPAs(q)fHXHqwba9 zdeSX;LwDk*T7_KtR#W(c9e;v44ulf3?(KAI`55!}Zq=k`1Yq5Wg`I3rBC@uKa#Y zBejpCrbNbnt94*GtcS=iKTfdyDkl^yd5lN48>0X8rJ?SW89u3|NN@f*Ma2|SP?MM} zeZ1KK^x4m6td|T?l)DRGXd+g9kij)3N`u1FQuKwfu+FTqg}iI^$mFpRZ-Jye#0Jg9 z6W-+t{>U7Fj1`A*!QFe@Y<(q=$rs1@m*v=eFn~ob#jw%!2!2S&4Z)m>A?>s~PzO?` z)S)Qr6f*W)72F=X4SSPC+#^XgSN%_jZdGZ!9YL^b0q&EQ;=kH&2|rbwSzl)lr+>-> zI^#94_CGdPP3ytd^*mPm7slE7X4CcZ8%6%BGRE`ia%)8`8M7E0vl@zRgYl^GN7=hi z7vk3yqU~N{bmO&UkUS|0OOFrbq#{o@t960p{4crx@DsFc0 zL#7{HxHN*F{#25_k1JuCI?KqX83Sq&qJi`%(#K=DjN3=>`_KsP$&6g;RaTAOw9C?U zj~zk$aU5g2G_U?;sCGRLuo?){RA0{vvD!c_K#O?ry1)f5S) z%`t><$5QlUPYaQ$UJS@C3Lg)1;T}dt(-@g#QPy==kOBA^so_9VTXJR;V@2M+h^mn+ zO?znpItSa3(StVkfYlR)(=6X(gT!ETV5~Z%{XUDH|IH*m9~Z;tf}Z9`70^T^BHPr!3(BHsQdgga5# zOE3Nzdi$GcvK_U%1m%|@LEQ*zn0?#_`)?iK7A`Y@+xx9?Ta5z!sCAj5eM7TUb3DsA zMt(i4|#wIpd~*L`usvL(PFO9R!zmDE7}9)x#>b;_ieQ5 z%SUpEy=Bh76QI^l+I)q(>*-B}M0CE9?R8dWpv*a88Dl@9+dN1QK6)hbT(wgN$Xq6l zCEo_S>+jWvsg$6txQt9y{{vyoNAPl=3EatTcWD8;vHtIkuNys=&Oa~(eYqt~gP&-F z3S);_xkM24&3C{hjOC1mv-v6gipB&SN8&{?wBv*|Bps_qyyPPSRX4scymV-OzWO5p z0bkAV{)vh-rR5~8G)NJ7tCVLt!NaQ~u**~}aTY23o4-;zWfrfsO1omw#j#8|?%d&T=2w@9p4= z#X=muP>O%;uNjz`J7Y1g9&RS{6J~GH#J8<}kUYQp@Z?$nz91FBRaRxu|F&#I*ZxV< z_y3tg^_*5TGiVl3n94eC{Qtw+bK|&ob|c{ZzZ^u}f092Re8Gslq5d~NFU&qg1C1`A z>&Ikid8`F2_SM5dYYWS@n})$%yT^#UlcgRxPGG$B3rabt!w*n)riNuLBJH$8ToZn8 z%138QR+ERXd|`?&d*gpN$)ybn=w++>=yxdd9R6{HGb7FMGCZ7r^5RkI6}JI3J&52! z`;1}n)$gdWs*|i`e07~;UC7BPf#3b|A#HLALwd}k{>@nz4j309vHMCyaZ)4=R?KI8 zOfob+)DC1E$6|%~Sn#nk5h{K~;fZlA+yZ}XDD)dZgGmz9$JYkN*!LqYa|FMzOM=dH zzbLv%#jsqA^KBuLTo6UJAMJ(4=p(pIErN@S$fi5rRU=RK_Z`v8x}PN7*^O9e_5S>=AAujg@ z;MdML%*`(3Ml5gyHdQDt z|C_7geatKJTLnj|v+n6S)(N=g3EFb9nN%87LQ+%^c0I1e-P!+%s^ksLRo|r(;OMMP z_)jb08!s@YE{k16n(Bmk#;~VZ3%~9>LxPQ~sfEcgG=H58ozrFvLa}FPSx1pzCd(Bz zYh6Hz!Um!zSOD|coIf?&h1(x^nA&M1i*f|L!&weutTFb|A4gVef1&DQN|8K!6Ww6H zrygltpB8*Qr^A^t0Z&wNY5<0dRlqKhYOQ2T?|s z9MwMP0zYQj;3NLod>m2ky15*t5X%}E{YrvIEz zh&0uNb^2iS>>^5AhXobt7Lb?kgI6ya;EputLPMZ6{y&n=Jgmm84dacwNkxU`c}{~O z8R~u43XwS?L^6gGDMe*0DnlvF6d5aJNE6b2*Rv6gM5Txjk;>Sh41Md{`#;yY4(D8# z-Ls!{KllB+zhuZ0jYkEfkLF>uOL)Zpwjq=y^rB3e?c9O?Dq!iADBN0*%tk7Xf+EX8 z6m8EV*WYTu&}f>UdhY0A<2}Hg%h5rNiPGdkwGnK*XOD+IRdWU6Pe_~2b>Uncl||q6 z`}Zb;hE(YD77} zH@4bgyX|YZ{l9;cbR+5qramj{g_f{%wis4Q+~GX4N)wEdI8@MZizqt+tnCiJ?ds;(auQ%Q+lgGcE5eht-6IpwsitRWg3%7d2 z@epOmWK$1}gvwZ~pn8h=syhZ?LJeAXJCXBtzfYN;fp|=X7yI-R59W1>=I0&84)*4) z!Mil&nOPAA5I5Zphs_#bFK8G;nzc5r)Ewk~of;wN;&RkVNJI&KEi zpWD%D?7>ZNxer$F0`aQcMp5 ztmn=TdcsQI7(BNzlQmPgORT2UqA`B5#5=?qGRK(U>765)P2Y}@J7>2FHBuXT(>#a2 zBJ&a7xh#JNik|F6p4umvW|ewU<|~??TkqHdKd}le+HcG~tBxc#;yI|V;{X0hYv7wW zB+d``F+H zBWUTC!_U)hk^1-k;KG0wv38(N$A>ZmHNGSn?zeuL{a% zGZ=HYv3n_Qoh(MS(OqczK1JLr`>gEq5nkpDWWXfqzyR zx1JuwJbkGL6+tb?VQmw4V7CA++z7y*o5!&Kia(L7ZzECW4jwUBIt5ll`{P1!!i-;G zL{i-Bg*mKuG!J{+UIVZ7xy*H?J|zDwOF=y`JTjHO>qozMfzCx-;|KSSfe{*c$SeCX z*PZJLu{JUIfww)Y|DEcYl#%s+z4Wam-DgJVW7O)zZLa!ELh0LPHv+J!r)|4hwmG+dgIi=t}Ia@V^(L6d$j?4!H8(byrL95S z{`Af}+X{1cmUI1zgJk2n2BAh;^qg`q8i$ePsQ_o2pR}WMH$ls`-R9=@_krE5W@3Yj~X>i@L~LOq0c|)>mMS{7~^jX70Be8bRrd=gobI3OfB6C1fD9m zC}S+QyLXNtE|naxWO}%!$Df*;TCPEglRhOJE}+OGXe!*g`u8+a8`_#>C#@S6n{Mh%3@O z`+r(+_Esa3+kA@Kvqu0cO@nY&wilaMA`N0<>1c&4kEGtSqngPEoGPWr+@ZYI3@a&cm!W7uHcyJ2=-I#X;P-?k1R&f{=s9`Fyg`&^yc+Sj*Ah% z^@%~)D*HJ5Va`Yx*1Ck)v%Or*uSGz-V(`J2A?&i~QzUwWXfIt$y{7!#M)-?rarsYe zML0*frbjKQub5_G)Sq>s(GS&`41H_j8Q3iB@-7t9go%@Gpi5!?9B+6L40zLARZ%7z z;d7guIW2nE_kOa0_EvNJX^a}P>%dVWKKVa1vn!I#FVKfM-+EDRct5vdmp#1S)Q6&q zPcX}OJ|;oe4x%;G$FlT{0~AKpqMq}n+^dp<A&G68Jiga(9zVp|tZa%9^RdXysB*A)Tv#sW0NwHtJDPtw8r@9p&2B ziwo{3C1K_4qpa+UQ{aQ;44)}dxY(|1*`tSv#10-CiptL;-fj# zuUv_>lqJcW`R1S$t&GRFG?s0AIY$sky+er~=An1LRAEJEHBx)@mpi%00orWepaabY zjAq7a^08DjSEEv?@2GbL&i|RpS!4#oV){Lf-<@Z7Ml}-^`Ff#O>O-;}oJtu(Ialh; zwJgdUSVI9FA6|18t`Ye0J^&xQH-@!;-9dJZJ|vv0f5lv2&67|ZQBujMt+M|WtPUmpndhU^|P|;qR9%l+$ayn4gky5_mdw^hxo!D*LRd(TfJ=iez7V>F* z%`F(Y05;HDhpEADnLM;h{v4NSy8v85VzBRJYL75!CoLm}(Jl!&GAp0z zJi9G%#*}l6y4gPB_ENN?CMIe^MoABH+)}_9e|`)X^y2YBm7Q!5^MjmANkbQx(B8ly z4QL7~K%;hH{#7+SSOSYMU-vJowr>pZbuI7{nh$z6=_=WZlhHXklbMTpAbGhDmBei4 z+|27CoZhA(nR~k?t&DVTyFoVWz;#k}|$oUe_0FL=oqk`Of96~%n z$=K6ap>95#r*@Z2`~FMFTA4RA6}Em~jAdePGZ`D^5RWNtLhaO^G9tXR!hnms9p#=Vt`BMeOYnn0rVL^}Q{vrb&##rB7 zflMt(C5SQx|F4}+p`9tGK8?l7Q*^jts`rLD7NVMQGNdim9Ma!5pnq45ToeWt3!Gl{ zVh3Ivx=Qa~-ShnL#gm16$=f?XX9msL1y`}lzDhyWLV<5YyU@k3CdjY!7I| zuOK_T(rkd0l+yroXlv^3@n?DrFJ_TDjmb zCs8y6g>{s#xG9=-w@4#%HdYFAtok#o;JYTmpE8vh6>Sw*r=yJ3ANH|6wA=j*?bo>c zw~0$!<^XdR$m2U>QyItk#pI#F9(10*i?_JZjNXiAXxAf0PUqq;sLVWpr@qf;v#wi! zZ`vAcr@wLv{}{m0xp$FoMmyK0KL_kk4DK|vXQ!+^NV1YeJM9iXs{LkI;_&3@+-Zpq zni~w^h4yUr275Xpb7k6fsJw$zfj0{hhFxS(T zkt-phJ+{+L5B{Y);*qe4vuTZi9-8GGH;~PmOa3G^w;P1FDuqlFaKz%+Eiur!i*m(v zt|_?smqekrZ*@VVtO~uY5O7PXodSf1bxoOuq%X6Inzh0&~2N;5g+D4M--TZ}} zgV!nBJo0)Ql1iG#g{5;aF>ELP@$WdhbNNUxT9t#o-T1}*b8?4*fEXNE7{ZP&PbLR* zMf>fd9836+Wq}>y%gQI1$ivSI&xLoZ*zdM*aqa+`_gIgqce5m(Gh2kZK~aYZum=En zQE%Jg$?ou({+Zb+ne3|KLZTsEhyG^BlEclE*Z0H%|Db*$XNPDquTZq#7N;4&Waba5 za{bHg{BI&ehz%o`-Xx}_t(trq6@ly!<`p;j;uJ_cS$64ZL_F!%QP zFX+-u!1DW|Sy#7Y@?m?WP-{(5wS|)6SvbIaG_zElvUw*f3$@lO;nY8KS^?jed(Pd9 zH-RiCalBqUmYI64kjRJc5$?3gD{Otz&_)zvj-ArPlV-0eA82o z_|so+T`(GVO1>_WHgywR-lpYhad;leSxCL^yPlu}SH;QKwKi}x@-_A0=re{tSCD?6 zVPQ}A9V@E&C;8$fUK!l)5`PH5G1%$GdG<2@DOny`kL;-zTKljKNIg);Wqz7W(?seK zb^L_%RNiy*z7QB=9fIFo)L?6T+DUQxA@u76%?h2F3`L<~)H_fUN!A^B z^me(;+Ma#Te1I61BqFIG8KPcl0`p3Zv2(dI7eDVkd1iYPO}HsTp3-b`Q_VMY`SDlh zYsYoqDE%H+x{=RWTf0N4Uktvq1=!1PUz3xO!)Uj@9O(}kE3k|m<7zQAj@`(G5tscd z(JDpy9&|T^4@+n+pzbcWS4~FnyR{tGM`p3yt*_+TH<4D*v{)VH<`p1=rI@b~panO$ zMYyB$4|}4Wdb*BU;50i0GWzKiA{CR21k~R?@sTzxDWiOnMccTtnmQ=)Ou(iev)JAj ziZEWh7`6POJ%Hzp;hZ!<9)+`9_)k7?!-l%ZivELd<@7$XWh%a;+sN5_Rgj7w*O7&v z4B2+Y1juU%JY(WlenRFGSj{A1Gg8IAU9JmFCN;>UV~|t(Z3{8%W3=j?F;jJRF^N8t zfIfH79x)3Iuu8JWY}i^(>{AqM(TKrH9og)8<{RnKZA5$M&ze7dBiy+!j{9+tv&oAY zf;s6UT>Z91qxbu?Asi}EQX+6qn(9C%EeMb7HeeSj6_Zq}L7|?I-{k`Tom!3OrwACw zpEJmcLN^pob(qsMgQGH55ijnI=i(DQODOS2>( zwJBYA=V~^j%wE5}xO=4*qY_5>TA6mZNNj+e_f8u^XXxTH$9~gHYYQmTd8NR?E$95T`S5fs?VC1_Wz~0&gi*#<(D?5|T;HOZFhJjB{wX1B z$ihTYBFIDk#mf+}z2>lE$O6x+EGvg}S%7-cu6y~r6&SDSMWwfOm``&oh%5gUsK^arqxkXPX1`NDd?0he^z9i7IksQiM=XxO>$K!fk2ymYor2(h^JB!n1#<<;_us|EhqzuM*AMHYpR@q1J#j;wEu?6KTPXx(uu~@h)o~Yz1=t zTX93-2*M^?!Xl5cIQr3>vc60;XmfgozD|)O4?D(zqxvx2w zL_UZW1Y;#b4R-R$x1{pfArzm=BR$t0;QXO5{JXu9ksKIHJS`oB{wtkxdhq#-A+~;d zom*E|P6`ZCg?g;rPwGFH_==W>mGhTJ=z>;j8EV?}j{CC96>{k9X}!8VJJCCgWYW2c zXcoYOdUyhZ^>F^?NnHNtHj=vWCOUFThV0yA1{T#{(UJvUoM)`nhRxecTj&Z?cZNW;R220ff=;nT)GYLi92%k!@ zn;(x?ga)x5D&6F*cRKnL%p+;@#z6D@o9JjX=0|Cb0lUsc_-*|k>hV?v*K!LiYpFmk z{Jl)@-DH%%okxZ3)l7T9(k&JLpWEbQoU$K3J?2~_3@+S>tN!jBwUWF z*rInja4o-(P<6U=RTeF)C0#$dTS z+3W_x9#T1>QFzb#zRMIGbfqzx9_k!FgaxX)BV3QwMj^LjT2Ozs3U!(YxJhH4z^IU2 zSd%qoE6)@VST`v2T&-R_4gRk2!PUC=n7l5^NY4`Ov6hrA_Hc?44*Q+J-7tOz1)^D%IgtYK&o|l^TxfQ0Lxl!h!|CTCNM*jFHFkArktj5T)45kbkuM7<)9M^OsCq zYP%K+RCfNt1tBNUr!G54_uGw)vpK$c#|BtJ_0M4KD)y}0Fd0mvJirE7a&NR9ST3S- zH7AP+4lLxW?LQ&(xGE{>LXc%Uidt}i+qFsnTK0Rf*qSx$y?k+ScRYn2&E^qv#qlsJ zbvK@{K%KD|R)dFk?6B?cepW?77p^}wz@zqv5wqJ(5TXQFXGS8sdasvAW~E$0rqm&3p05d7pB^i1D^>Yfnx`anEc_%jbl zWXh22ZFTS*%D7HAW5qv>hf@xY*l3C#bN_E7S?A@CN~I35+i2cd zobIuLkYR4~#;NcukB3{oXE236kH|no1iIkGBR_Ui2FTG$)aP%=eOkAJWQ61jxdF#< zBsBU*;YT~4vgh}x!H)ydxQ4zXUWXaLkiIzHq@%`!lnroWWo`<0S}#o<$fLP11&uiF z;h}0+E)$4n&hup@@=p+-+m+}R)gLa@+rhvc`tz8j#q9sC06`wg`1;;HHp!K8jBlvo zDe~>yc3V9NPWgwT(vC7IgV)LDu06v0*BMD;*qzge0@R(joO&t2-k+IxXl^;XE64)2 zbopbkM~Y;_TXXo-G#0CQzAbAjQG=W1jY#>t6e-$l1+V6`p;8Zh=Jl9mM_Ykzp%ezjpbVb%{jUoE(eRPpdyd9?)aM%%p zofYia@^vA^^|MGTh>+HTQM>f{u#=Ekh4*kAogT{K^E} zvL=g_bCHJ=>2#;1o|YevY3BO4X!dR~eZ}?d)J4tI@3b|{jPhpPabENXjs(++Esq<* z``3JP+Htc>0;~7-@C!b$0#Ex9uJdOy$R|__{IArYr>%orU$_-0eXm9J&PEKgV-9(D zKLPD;173`;(^baL&?1 zf;z7euAZ$?sKQkf+El91lSKl~VOAxm-`RodChD_)9Ig@j3xg<(dh(xco(!#3KDcV> zJ!aWzmc+`>67IA%oHk5rRl+iRPja1kPr&4B4*s?_ntHvSl6ybXP#nz*++0ZcQF)EX zdnk_o!flbj-t#w3l5;|Sb2`X;2@|YvNP$>JpCH#+(d>0QUunV% z8l=y-O^YD*8~la$vcj$OPT}_p?MnT{6%|c}g}>-7s+q}rI$lAdu8U@`9M1ycX+Jw& zX~Y#L{6}04<_Z~E>6gdD-2ay1LK$Cv6R6NXUmB}@pse*{bT(4*HU zV}fxgcap9CUIvYUJG zaA-9nc0`T5c5@JR!CaK0nco02eDYlpxAyHF^36RJjSZ)Bro$9Ao&JHS#e?rCW(=!) z@1w6Dy19u5U8y(tI1UszvYl)&36Mxax3|iWcXy1TeXbSmdorDqt7;`j_#&M)pL(sM z=v#>&{=<2by@%l2a(UOLpYdosWrC^SyiL23uX0Zgxxn&>7!2cqy+5XbEc+{(y+#{V z1iz-KyRP4Pf)y9vK}@q(qW|~61{D}Udxr#G9wy+9-LHVOka#@XCx~^6?j*B{)6u^p zJR%W8?-Xg(D5PW+|JE@T_$TIp^Z0*Q_2v<k-% zL>dPIId|oU(48NTm!_O$_gKlpw|B+JhWe5AAGd-odK;bSyVPYcwwbH)7wx^_56$4G z{(SuCT_@)-k|VE<-$1j&WJt2PF1)-bjsxwx`6snCA(~f zJDrcU8iD$73mWiv!kPc~5b|H|zbwkrM#S)4E^LTPzIlz-%n8BR+ZK(aIrHkj-1%gtm-}p>MJnBC| zyQtzrvGD@JzxZPnv@N9^lE;S0r1R_g5WcGrs*JhNoyx$}}FanP&xq7sK!lUk%1odL*p* zCYqnKx^!V#qZy8ol_ox63FPtqZNf~J=VL=aK3`E)&kFA3y}RJ7AC7&M;@Pg=k&yoQ zI_eoMPR#eYzSV}=helyZ`rMtJl z3S46Tprae<`{kYyX?i8vSJjdXAneyYRQ)!BvyGbq%cv%>-zAgfi|3GNzdE7!wd%4x zOvs;xRZbf-av2B6ylei#`xoC-9gYPIq8}>;In4kkXib*E$>%Z|&nNdu=jRACliqXH zy3OIj8_IIIV9c!>>qpL1=OT{2F)v&g2YWP@;0xPU^Zz_K01xD2aO2qqw$^MESQ+r> z=RuCh|3}~Q^5VF$E96zx)c>g}HD?D;~m}xq-O(K|FhNv@ukS4!{pTD3Q+FtAIBl2K!vw z&mR9}3EjVS@CC8YWleZATn&1OvRf!S@uD5{4}V7CZsyF&_lt?uelhg_PVK}<8_KxY zk4s~2aDM%(z?S-&Iv1X27qnCm5POOyhRYJY72{#^TO+)5*qB*y%M8}1_M?|l-?>eW zj_}v-2QuB0!i2WGB+(v+g$#j|%<&*7kHlp^pE2?CMiRVQw8wrps0UismiTo_DW~+a zgk+3Q6*8|fzZ=7u#l0wQnDDzh<_n~f7{chcx2e5Ss^^o>{9B}vU>y+)x>kNps64o7nbk;9Y$=e57)3$hC3U90}Z zBV|Qx%9Y|HuQvr;Y}F)qlM#cXDT2WeYRNt=F-$18v*-O*@)LUtch|m39XJ~=fzM@{bQ>z0E0fh4M@kr$13;8K){+36sa#m!o2KY zL&|gH13oT46dJfs!MZ~4>*nWWL`>p_u#51doE4-ED&ofR;+*4?xq=1r)m@LzTYxlZ zAF)%^6ZGrjU(WoF0}PqBq6-o>%%c!j5;N)~vieKEPiGoIkMmsYX>^b)ZP*LOW-)Y@ zX0rzF@5zQwjY5yXLi&BQFjfJ7ofhE?guZQq8_}Oz)tu~=VbDy?z-NBVXFD~ri6%EF z^uErJW+3awHXJtN3A5t(6oT|;3GZBfD>Omv+(=v|oy5Jisv}Jc(}jEK{aOQPJkf$o z9TND9pSKb(SreSFT7d*MEeB(U=8^TLvZc<)i20gip^s}<9qrM0rHW0=)Vb;XKggB* zA_SD5u*Ay-9{l$iN!QxDyuUVA@axVHZZM5U_`MbU4LX3ES|0GnYOa7FdZYh;CTp)x zFWI6diDUoC5*cnH?OUb+~`&9TH!8o||vm4C|LA;NIB> z*w4TIP@csp^m-|e{Jdrf1seNtm!vjxeUBo9{;|W7kNeqwK6;QmXo-_IQ?EcDZNbY95VE^wQxDrY`Z4>XK^%{{} zXrUu~ijKjPCT6l_!xu@>hB|a`l`Js|r+z2O@m?lx!aQx z;YPm@klNu0^mHL*0@&-pu*5x7zek(fKYtx@ewB+nlVphHLJM%NUW`xnuHv`1?*%to znit4#U}cvp!}vu!Tse{E6E&^CQ$`8zTW84F%6{b{NP#eWRbr$LjtMpBb!aTN$-5Fv zb3<^>nf2_8MbTs|Qzh&i^a`iji_|*YG}fGXs=$NYwaQqfu#auOr4P+%WAMk84o-*O z+BVT&UktdwERoG4U90z@_t`X~RBa5;l3pPrD;I9--~-U59Pj9Ycy?l%KAe;ez;P8y zq_BB8#8S`F+Zls}Z!T4k?A}802 zp?gizMuRV7CVukJ;g?x!*fzO|5!@WVo%K=MaxSXv#4|8+iN%9<64Oq_!-FVI0V z#kH^C06Mq+9{<{yhv4@p3hO*BXU{L!hjm2{g!`vK z!4(*JK-|^&dJemI^cHfzhC?F4A{M`MM%`K*n26L~qg5cyoD zpS?>~F!!1mz8U+^S<&<%to#s#QyWJhe?|*}A~;kTev@;i+$vsb437IpSU>$Lf-S|c z4gHx?KjB9*oxFwn=Vv`b(0wI?&0H%vqa(Tkz2+W#s^B5(RMbu;dz?Z`sJ5(1{V=BA z8<6YJMt;;ZdC+q7z}pl5u&a%E;5)+-zj06?(<{yp-QX1To_elURcgSBJ~1qx8p?@T z+=HR8lX$JdIW{4m2S+cKARAK|BDKQ|rV8p%+U%t+n}Z*7*XjOg9x6?aQl_!m`xV$x z`WMGG-6r~{ZlF)D)Mw~r0UK5;;V)anxsi=?1i4-su9cw+QHr=WY?5g}iCto({fs?i zh`&OS+iVyCW{AA^uxTt@eyfZJbQ3wHyejDRy@I`TVptvR8loGQj*LI^$hNmM2bBE+ z9Vk!W53Xn?Lrx}GB1nNm-1US}bk09|HHCd+bA${;B@6Qf3P$?y%32*C4b zpNr7(1u`VVh<>k`x1%X?)-G|!&ER9letf(CK7WP!Qb?q}`o*c0?3j{o4_ecIhf1ct{WnAElvw(rh11tEctx^zs}cTVu$3Rn|=;=^7~mR zq%%{+2GgqtiT92pMXR<8{a0bx`cQuRJ2Hv)=Emt(z_oKxc)9W^w#R7{R9&Mwa4gL- z-;E-NbMnxQVVWxmvW9*oXS{a!arp(gcyN6iga1u!XXnX?!<8S+D9c2am{eQB`MqNJ zWt%axs9m3Q<-QPRuUwn;U}MDtq*fBi)jgtF7&<>Cbu-xx`SZjfunwJ{Crcu&#=~uG zgbz+IXZqX22>x#yvd}%mX4$L5iI2mm#ci0|`eKwIedkL&=jc9GN}Eb_QzFsMH9WGm z-UL=#)}o<}#@v=utBKz~(f&ES${KF9dE;{nHu2kfLLq^2=Jk&@un&9`!EHGYpVW~f zrr#~0y;vE)FfwLLLVCC@mu?C@uIF+!p~vAV4csTLO?nx*oQ4&a+=i5<3EF-t2?!m_#$e0uXs)^~;hEYALcTr#`4&tCL?s@*4? zr4s4QWcBc2bfbnx$|G{AyeRJaRbwHW-!+0vKO)*cpQf6?@_iHVtAhgW&cY(vpOuP| zs0XZ1&J1KdeV;PAQvWsUp7IYs3{MzFZ6!>Jth_vp=J zZ&(r>ev|{l8;?WZyK^ffPtbc@H2$8M&sOekBx_SdRZp{iC@ryLkR?ZUtdUhkM_`gjOtDw2|IOuCFz<<=bM5Ysc`lq3k$tb zvm}okpgxoJFJ$nY@s(V?gNi`=_e<=1@fMrBww+iVK85mb@rbhBIQXZ~i1tft;)|V= zgBcS%@Y5rI*kk3=5J-2?csB)N;C_Y#{+EL44)I99MRmFlh~WbZcXOQqJn9iDLCscl z{+pSBb-ieQijS}6+%Jmu&#$x_%d%}H4(O-eo77TraY&?{-knK%BIYXN9(@V!nLcG1 zMO33(mIK^!>K&Rs= zlk5LAp;LLZyOU;w4Ui(vkBxM0+HVMlQ5%YgYTydeA3)wP4*(VlRWV!l~&}Ze| z$iVdB-MFHxnVHcsfh4V+CCsJ!=p@aoM6beosXPZT^O-Ahb_H>vOsi=fzv`imN;upWBRWbxHxv~-LNdB1})H0Bv& zBY`=0bOq&O=M|y6U-W(5WCC-Zwf%9q>I+KaAP`fy_$8{l_E0&Y*g z%r00piuR`$qXP|6MB3>P@i>!*ro5p%zzO4Ekhox{oAu>31F`U^B?c!9y<-np4HM5f zEojzcx+gESgc+1$Fko%Uv}WiL*8Qc>HzjdL2RaNM2zSmN>i&yrDb zb;xU$ERniy13mi@&h;~A*6rU#&L(X`*G3;=B@U@W${TUK%wL@BTQvbv+~shr(phHz zRF2$O6)C(iu|Z~_FuNYT-(|*WRxBrk3^Hv)YO+h?SAD=AfM0{ggEXlXv>Md*)%-0*Hxb={n4)t^tCo`@ks$_l=0 z=K*`^TgG1LJloMzPA0Bt9v63YjU+mEvacOeO(*SbL zOu+Zn3Ak3H0X$Ra<2<0aaS=Ay>^FFSA z;RP6bMBH`j(Hu5SZ7or|mW1}C%8Jct*;Bw z*_Se8N3A8qjFrSntHfQFuAeRN+oa%{VwHgA(%*Y$^h4yvyUiVx83(GT=@r>MC?B#83B#(az4QKKQ zeqaHIDQDPs`X>I@BjRwN$P&lUcc}iIQzZUfiZHJ_PK#<6A7%0I#6#SF#!~Q~QK@iF zS|2rs)vFp%RQO7lS0)d+-*S5B5Pc&&EU<*PHNJT5!C`JUQ%wHi0<=1c?o@78V0%v$ z7c20%C(~8o4&~+A>HOlHGVMU;-)l5J!j{1rlgLXa(QY}BX9`QtuEdE+N4dstJK%sL zWj?58v*h4Q(t4G$;)^Nc?wt|HtyRQQMmv3uicvq^w`(cuBll%H%GS4bsoZ1^eS2t+d37EC`l9);KO_dX z1yr)JCn?ABfF!=EB}Zb-viRdHk22k6Jjz(shY3~#=*Es4+^B~#f{K*8c-^y0Y#-N8 zUOhOC^!M?|EiVVCn0x~7cyGhJm*T;XS>y4STm7ufQ+msz-BnZ0$rD}0V??@ZJ5r+e zg;#I&;QO3@WazYpTOr>F**_Dpe_IaQAUg^k>6RiR+6DhxDT0(xZPQFohRmw606qFw zHB0@ z5`BDnn43j4oX06K*jgf!t+37@Q_|~DsFN%y{$vfCpSt4Tb1az@&7EZ8-EGK0@eu3# zLLDx>qMe>IC5g)$Qy7jB!{hi#%$=xmVsSPSjSZl=l`=CBd-x2QOtIj$jPxWtvn#?k zyL*cb&9803Ydd!EM@k05efs|GoYBA@yDSIMXGJ>aOjjEi_8fy%R$4JN_dap@vkQec z`d75e>G7^6bQ}`7PAPy3MM0F`wT9hsaW8ojS0(IH37a|%#Kc1J$l*zh!p~uHOk<=_ z=iJt)5AAbw@SKou+>M2fuzHpbK4W!-89H)_luOVrhG?osNf^N6^KIyoJ;NR50pyhg z;WIVytQF;oOKshbUyV~DEjIHZ*oSuB&E3x?`dETTmMQ-Jp|5P%Z6pM^zDAb4^iHa8 z2_190(a&Y(Oxv5e8!Kkdpt0Hh#!pNJisT>ijfxFNH^B>5bmo zf$oI4kNAT$)A}d123Z;Oa#g3!LRYl7>$V*^?1siwM58nbb;QsN;}Go&duoqs4$bBM z6dr*I%5-O5pU*D1Uq=o~7op-t8FF3U4E|6iVams0XUzyV!IiTLt}&Am(1O$2P;2@S zJ*ByIOIynG$)?#o0byS(;fVQqG5r7R|Jwu~!i-!c)I8g!>O)Yv0&cXZu`OJ81-G=B;kt-g!!r9czPpSrb=)3(%i&Fs<7&99m>fX;>32^!h*Us zr25I0*{bM33_MQ???h{k7=pgTN^CXxDEH`>Klspm$AimReuO_W*MH(2Ini~zm`JeUJ&T;8v`D)RgxqHcE*#0dPyH0OmBtvXT z+}l~gEY;sTdJub9moh@nalWk&NbFS6{FL-FhTm^GP{{mrK7VZ$dB0Jlb6&M{hb-#( z?7cmOWky7jWZ4uX=|Fu=v?F7mw-pYiyxcP@I*D6HF;YmTf4`p$A+O>+I)B>QMZyRR zLM{y8yGgOgmvV|`w8!CFsW16IHoJrS-Wcq#ypq+f`atF#mBcdi9pO4cT~PdCjBAlm z8mmxqj_>3j%WSii<0@#6{HeeFXtC}M&eBUpFlrPZCw;!mZZGL2hgCC>Ac04w?2&|f z9^>)i%zkzs(SUb6JDf5oPuyo5A>RhK3$;!6zuI8L^`aYbtGU3vwcs~99=C*FWPA6I zguNcOP~bWqnKkPG85FyUl<1qt^t&nC)n~BHqx$ll4ujx1)=uhuCi;HQ+Gy)jw92CK8v*$OVWL-h)0hnu5y{syjWk;L;Z?Bqv-% zbJCEqh2y6CG#Y}IdIRT^dBORY%TRC#U-=L$8jp_DE2OuK{I=~F25 zh&G-b3$;BB$UgEU*SL!ViD^5rp|&rJXb8GiwHiH|Nq4ISPH;YcH&%+9#NeO5NyFrk z!uPnF3;iCKFvOC916-r-M3_kZX*#-jjK9o9l6Pyr@SYy{h`zIUJ!sB)caEYk;PJPe zSaC@LYv!o}qinYecgve@?qI)>-p*|Hvnrn~;ZKGI&K^Bf7W_;Jg0H+rnj_?h75#1+ zT|{rq+BQt@kUPl@7DxXmbE8Rm3WUg{;m9-f-1Y_Tuz4%Z&bORnuZ_4xphUE1UfOC0 zZ${hV(P6gCkU|`6U%VTejBRDpHqkqHi8y|&`G*tloB&Qr|IoAI3}#%%)crYS8}2Ke-P(&wvKiHkYoU-_e2IWZ&f^p+A2w^|C%`cEsCN7jXviN8qwp3^tpY z&o22?OKN@>qTYKl#A<^j+kn)0G`UXe%W zG?IA1BazW&P<^uzWfH1wj&CEbevX(te8Fzc_)F9!t?;=B1#(Y5jX1p*X`9O`^ z5m+lenp+z$0ee=I3hzPLw=Ll1{$})Tt&htMPd?{0Ll3=dmnLtuEI=#O4=4U7Nj6Qr zL1ZHfg!lCMkImrZMK!!Ik;mnm&JZj*rsewepa(j?MioZStVfR=|8nOgtifUEHCjqP z!@GNINXr`0&dDD#2BXfkc+bB$PN1*_?$fNeOe$g5i6K*p9^y{m)h zG!&z*H8SMtSeiqb-h<*A99)tkSV5cCFKm|+iy}6$a8v9Yww*V?Zwj3W8FZHBI90M! zSH2@<4<&J^og8seY=$>yT5!12N;Zwt0CegH8d;OiwbfKX@}Cp6d|e z=x5l-a29ObosD<8&1K%pi$g{Dc>MlqKRYsFEcE%=VYP7zB5)i zLrAV=9apis9&TSw!he`t_Ctyi%zjXcp4Uo~T@_*E-OhYrx0K2+3n=?I10PUoDUVBz zf_o>TaiGf^_N`(+ne$Whet$x}^c$OH@UO$x%iH=_cY3*bJ~q5ICVWcg{T={WTvY2Hd)>!nz5S}o4^y5Mr2)M!F@@cL(Zx2A$ z{VkwPeLEjy8d&+C(lD}HG-D^4*#ekoVc28GWRrGI;)ZA!{qk}Qlul|wX_FGUn2JDR zWmb(=Bg($pI}vowhT?=tPE5v+0g}61^kzR%X$JemE%5AKF;c95o~S(AFT4|d9AyYH zMjhzC>C?Ha*?dTM3C2ekB(Q5oDZ_*9+wpT*B{IcxCTv?DgT2M~v)<|EQ2W#ZkG38v zn?FMlx;sU)v}U~(tXuOF&F&q?RCmlGC`25+k>U~CB~DP`ate#bH*i@SWr@N={y-t6hf{914vB2S8DY5zApX!7~VZf#~+$ z&wI}KEc*4=H*rtB2fEDZpvmJih1-VrA^CE=?9O?M&%*`eBVxfNJ(&R7vefs$>J=*kD6zD!&ldLFt z7Lr4XGsXgbm+$GD6RfbckusloQ^W|2Lr)v-arVq7=dy2s+t9NzES)}~H}3tZ$a>^< z`2TlHQWj^VEtx(kiN+5%;hzupMc%t4`tf~jOK~ELKLX^OQwf+SE3lV8)uCX_L{OeJ zMb>qaxZVVhbkb%fQ!7M+1yz_mI)}YU;8?o!F(enJQ)RCCY4qTlhr!h}1m{R|*7EMc zAAQ+lp`J82w84T9N49^z7JQkL3N}O1WIKEP6*KH&qr?23CW=-w6|nphpE;QtxE{8_ z&)aLM+RLc{u9X+W^?~x8ed2e{14b`q(LC>N%!vXBO+F>l<T6 zD*7+0LC=LK>++kl1R-zT0ea~>=Zm?vBs8Fv#zbaGZ@44$J1F1ff6rwI{F%4d>q`dY zM1i00UfHc9uN!|CS39udkDWzz{bq=?IY$j5xxZ4vPsGF4%Sd z3o~}RvB!toNyUinxUbHYxh>>AxIb|)H(8FW{u|73C;X$2tir@)!S~SOaVncO-~?GV zunTrgy+}iI)gUK$6+EuYm*q=GEwIJ-;e*(XF^?}deEI?|J?mte&)O)i6aJyVbaz_` zb8L*D+q-&M_UV>WX1Mc21-)}JQM|^r4Ks_kvSDrq$&EuP;9`4^z8|Fy&p1csq&J$4 zvi24nycU4xI)1a|{E^!(Bm7aX!B$uE9=!>Q)GgboSITBKWMCqS&)Y8Jma znRL0Pg;__Iu*dp3U^<_nz-Lsb-$2L|N7U@+!X)1mO7AX8!-&rbY!dfeg@YCj^LfT^ z#Tszm-2wa0{YJGTodnO&!LaR~d|sWV(I0<|JH$TMHi$!aFgz5U$eb@{6Pp32;Xm6d znSSYBUw1U{QoQqa3`NQBp*f^1Cj|QH?2+9<3kxlA)=A2& z)Tf9Rk76*JXAl0=$tQlTBJ)5+SaZ!!gB}}D`dD11 zb{`dI291vZSjEO2InKT9!%GR&@WT<*VE zZHM`>-)O~ipMX$B0nHB|XPYt=#F;e#_$-ENPCDHp%{}UYyzj(1dh_qa!Us4asE#Ej zP9`y5GNj6vQS-~6K~ram~q z#(y3myzBD=+!EZF{nB=_q_rC=e{p3^v$ddLMJxooji5KVc2v19?>A}e#42@{h!$Bl z@lIM2)1Q8nyfD(ijV%}HZ;nO97ng$gR*s*~KRaVv{wUV#(yPmfMM>DvJB_jZKgm1p z^F6b^jO;%l0$E<*#7Yx?0gdjpo$ zsX+KW<{YGql4B`Mvcd1=b@bkAClR6;gq)IN=}VrYJ91AXGtAv2bq%GR~G3zIvZia9Q4WqnfbJ9z)^qUZFxU%FT`yi3{6^`%VI zC?IDl!@zL)9hw=U4lj8>S6X`{v)}A3ytMoTxqEeGnbJ*sw|!4-SbgAMacpxH7M}*T zu3#kjwmS=+nQxSF@yUF~Zol=Bey|S`>-|b`%HGxNNpLc;U89bY?eg6p^aSjDl52+j zqe-)pE8gDMmpvJ%TI#xX558?pU`OLm5plF8p5OY6YVmxJPCWZ1azYz@@X1M7R5=iq z8YT2@Z8>f<~mf9d^Z0hE|}yg z)73wj?tsot!CT3p! zMOaWj7Aotf$awkH{#IBQ+MO9T*NfY{s?h61F7pZ6Nk(@(g3)Rjv`C$IVDVf*mD+kb zWZ5F=!KamQYos@8NvJ2E*SA7&up^rotpzJPlAv*A8nwNw3YW@FaQA*4Hp6C%nAZ9i z5{H(^?xhavt}yOU(Ld+wctYNRQ$;G81uYh$pqfH zb6EMbjC=Bmw#Kl%Jy;uPh!N)c|L@DA%MCig#tNRJ8~U0~&-D`26nX=cB-1oyHSnKl zhrilZvJ2-Ah)W`-qS9#2?{FUZPwZXTA6Y}=v(-UK%Nhqba@>Bg-G7_sc5I$EhYkPn zn3ObGV`BVQy3_KNXceMY_T>H*c0p+)d9`^P47U4Cw>(vc1@>GQJ$D0hKF}bq_oy%}X!Q#`GCT6Xi4NeeThyQE8*)TKxi?6#ejs?+JGBx}xa$hxdc;=HKz} zH_6YLH4vkq%&N_~-n-chKm1i>`Fl#l+t;t+?TFp1V(ohJ&hb6GY0scFS*kFA`(YDe zPw-6j5yA}i753%2F^~1_|~P4rmE+V-Zk3z%j*)=z0SMBJ=Wlo;6@f7e2WY;4Tlp>1+pCJgITVaxPAh={Qmvr zFku%OyxYq(RezG7JwCv+19j9rfZt?hnV{i|4(k58m!LY^01n-3knQ+;uNdQC?RzwS zZzAsy=e-ie+u8jw*~C(9Crn*+Po@j?c;|##PGgx{v5&B?_iXq(DS|4^j3pHc1~_}T zCYzzG0aXip(6P~gJvdq*T%CIs&Mu6V@lCI_EwG7u*qff(@ibe1sH@1O+-(Yf=DA>r z$wqc7DNf2ZOvQCvr+xK!73o;7fRm=GG4)Xz;Faozy)O1$ z_QZF~U(ifU7qt&R#Bkb1{Dd3J6Y$BkHOwo%fiyMp9@VT)?E2Y%Vo^wsvdNjx7!2G(3R3QX?eGK{-!%U3 z3aq7#Z1GkP@~-)-sJPEl=Et}1%JT$H4`Tsi>&099{)11J`(=03E%QzAu970#a_g4# zbXQB1?5Uxi+d9PPoE7*sppg|tB$4#!q0ldM4?S^K4UYZfT?|);u?Z9Ai^?aXv4i_- zu9WAI89`;hUdZ{Tj&*kEr=!J!$EXL)GTni~qhO}eQbUgNzuncf_o!K*C?@ede>?R= zb}LLIL-!XzkNa|sDBCz0qq#5J?D0Qgnny7BwaV`Rx!hxA(#e3Ct!ogibIZBU=mayE zw1brRRKb*)88nnh^11fY$bW zv22dH%q!Y|(xCl@7_w!h>SCwK`e+&4Kvx`BhW;0M z#+v?nnl{!)7+-A$`!6O_Xj28Z$&Of_8_mKm9uiYxC*eWvvse{#j07g#f~UpuJ3ud< z^*2a=E~}kZM>dYP!EY+xshRy7anOdo*zDLw{dErs&lD1&%V0Tv8i!fJm_8-kU>Gv!!PsK3+6+{1FFZzjnmZ($P4 zl+B;1HvTxJw2%c{7$dA4^bt0r8!K4VP8MkDU^;VSo0e+9d4o;RbDA7KFVddqkk&yz zI);fWcVEXJOH$b0ZpX=*TrG?{e2I>1QG-p7mtoHMMm90v7BLT-2TIcmWd6;u+Ro_b zIgvGN{cw5kqeQfeNM<)}622!CeqNK~=T2qb8*3lUX4Ulf2~PV_)HQbErQ zkcv0w>*5-NMD}U6NH(hE!l>7BPRcodAkOc;mZk4}Ba|Brhq#ThbaVZCu`nTg7Ml6I_bA6_`Tzq3`6R9`B>AHA)7U~!-5;~`)bH}6MV`uI&6FG6mRWp2iqGZwAN1z_I2Q3 zXkX=tVcXj%>v>2Rb1@b+Jo-(C^ZQBigA>@mb-xqXbTXsV4D!XHGOpicg&AHN(uY01 zS18)2^P6__0a?z8LA^Dm_W4P-4*E~pKjJ!`zZB1cOv{LCLLu0tShMh+S}?o*1nya{ zC|OogL~fdd!`ebQ4y&5>#*-7>nBfOc(Za3{k~Gg#vWw#|e|O9+QD9fT(|}gBZMgl8 zAG3CTL~7kVFo$!L|L^bn_xm2)aa5LRr93f7n(w|> zK+yc9vJ8`phMee({eeZA`X|XPhvt|D=F#T0{``_m)!)~o;zY^A6*t2 z;4Q4q)C0R~PsoY+s-SzeCzk0wpqjp0#a=(Aa(#XkGa2!PJergUP0jaYc_wPR+;QIL znQVLL0AV7X0=7vJG-*gI*}bY8W|g(t4Oyl}$7EBQ6_}B7@>KB0(3QVU4k=va{=xs}Q5QDa;`cgjR@b5tuxjNt^otE)dk58$ zAJ+_U`{lcI=CV>zPnTy-<|i`I4ak&^9H@J!!2aJuU3y^vj#6LCj3VC%!J~&kwVfP$ zOW*fKt#D&DuurpSar`zeQO{+cLw1l4yhl4~M+Q|<;=0OZmKfw$PsOJTq&{a5=3Vh- z+p(T(aA|^pxsJ?jix&J6#$iwXe~w)wA&Obs;6%9`d-HgfNU)Y6yWOx`?AG1}xn(6Z zhIgL+K?l6r*h1r`g$F!Q`HyEf%CR?|-#2PMu3-unw81HT6prQd=O+cO!9JP|4(X?9 z>VIl5Xcp%U$Mj&IdTWRkC-w0^rRTK#sv5klc0_D^M{k_*7IfDbK*d=(_MZFah#6Y( zY|Vrmv8{k>l6kII#Q0<6<(w-ZzN(RV@Js&L|tyj(JAE!cUW2kyA$KGCw zz3`iY2gm$kagy?RaNn9v^_|tghj%{qi1_0e%CpCL-*l_}G4$eEksC*f z$gR40a2e!$7PGQIO@8N0nd&J4HLux%1;hH1+fth{s=!ZHrc#`CZH_yc} zb;oVekmMjW=sT+djR6v2djijB}uwW|zQ7sps)msRfU zRkRw6U7QAvr{y#44a;7bwyd2FJsm90G_S&8ExXy9>AB=?QahB+iD0>IIGW*!XUq{;vA&Axa;>k!L=SxKFo+FVHBdO+#|UGclvr2G-=c0eznFwdKT z{!<#6=X4KJ6WuJXdo9OI+g=WM&Sx5{F8nBl+Gj!H@%?lV&t1`T=lg8Wu1v}Qxm5eQ z3Hm;+rIspOOF3=^dQWO((Ib+`*`t22hkF2TWT}CLjsq5tnZ~|+j}pz2m*Y(Cd0DkQ zk35`p5i)s}-TyOA4O^{HV{2!&YP4p+p4LPZJ3?6OxLV>rS0A&cm(%MRrDADc4P0N5 z$cFd=Y1(-h*gvkx=be4_j|V~A{;4t^Dr6YXY8U&oML)#)N)?uzM&QI6J^To~dA@`M7&vHP^J@09eqL1*+ zL=QHVq|kmR`R?iFiMi#wSo4On;^3GO_>}wFJiLw(ZhHbx{aP6wZc?(t37xH2+2}NX zN4t2`u?yq*lXawGp#_d>Zl`(Puf;uWuIO6aM$K*?6rQ)N1((mi>2XaBxbb5=`cBSg z$4$BuBO@a?-#1XE+jr(&x`&-T*xcA+aYX4^s6Q*m!!J^63^3@RgKiv`{`EczCtq2! z7C{Ss1|P;L+?S!Sw}^aSI~#7jkk6mNT)*13)q~YN=_@XK^AHAy%kl8^9!H$0q0EA# z2LcOBtfb?G;WZ_rJM9Hh*i@hpY$9z6fB zQIluRTos$vzkqiiGwCjo=VcuW!Nk}Htk1`2;r%*Qynjf(?~i}J8a8V!lif?-SMV&^ zN_Ey)yh@x~sfLXyrL>0*_r{)>2p7&4&=>qOx8(Phem&>0i6j4BE{TpuYnL?UaQp{3 zaJ>=C*VW53rLL2lQPYcOYb*~Cprs4YHBV%Fz2R+r)ZAA=#nc4xJNLE>Wb%CSzVw?EG3eHk8g;{}T;5X0M_}yYME1zJio^~60`DEv z*`q=YXbpEl!wL56+B88ZHGd$6sTRxj`n{tpFz#|Yedw4Yl0OyL<;*S?svAQl3qc?; zxJyqh;{DwZ>Or?pS6LtQQ3L*-b??h6d^Eu;a}Vgh+(@;H`1d7|_w2;C(HprV#Xi69 zWAu$AHp)4V{B~@GM!N`B{iicH@3+TcM*_I+SF03l2MZKB$$Xth92{{izY*OF%qIPZAA-n>Rdm;2b+Gy2jF0jMu&I?2 zVQY{PzR^`?<s4JdKs?j1r@2m!KivbLURWBa{6~z$K%YZf)ZE`8E#R z)2GMwP0$S(l#zhBV@9#rycg$Yr6~rVZlDPfx5c-K1+ejs8>>6Nh8)s32$sJUSaUt+ zH`{&j?a;Ms?BF*-vCaT^{bi~w=lKE8`RPvW*sCvoShAm)`^FZywP5Kb7!y@aDAncsgnyoyL89*Q!l%T%|Gh zK7Hfu(im!0x+&I5jMh z)i%YD(W^3GL+)vrjx>0jEm{^@vq8=JV#D8Vm|WgWV|rGmkvzW zl|qBo@y=WyH_YF?o86sUELPnL#CSdvx|ts%o(nHS?yy=J7r*0yE%vszVd+-;{ZHk_ zqOc;2&E}d|y}aJ|w(K8$7}_ejHCEsW%Oo~`s~Jk_Bv-m4FKE{_OtAM#B^;FjC0PSN4bA_byg7WwtB!C zr$!6M%m9o^OqkETT9RO@jD{C@ZUgsL^vqZRny$-a^I_v3W9;av&dyk_6qBM=(eqrX zYzJR$I2Mjn6;S7MYHQKj+Bk577Bf%cGvREm2@f@8tDMdXww8IIY#s>EpLfOb z9@T*+!|`MAai(~0rSPj0?^Fuv%9g)wBPD%%VNL&jY|bKWupQB(Oz*CNE z2J3H<>F_5%bVh&vnOl9BBffll53e>PvHp5_#LxH*xTZwN{7QZ2*rVSP%1n24EOT~)K%q&7pH)2j=*lz&cCgG-__)Ov20W3^ik%Hd;DS>R*?7fnFm#PA zhH$@wrEfMdo|_5!rB(EmJNKyGbiy0l?=WidK;gx;1U%0(SF-}&6XRkdyvjSNM|V|( z7l}5QoT13aklJUP|3UyW_0g_i3QUcX9Zbb=bi1c~Z-9vO3ipM3Cd^ z>~I&%__L7x>KZQ&+qW2Pd=uH&pgeNQ?K}j}D3&@NJf2Ssd~x&`Ij#=)#-J)|s?6_s zO=5#1vaHy@PM^gNliM(KcqTpV%5lDdbMzxy=+39Bq@$OehBkX2w)b;A`Fi{TbgGfx zIkocwv5IH@_Zc7|s_p{a6)hop_exZc7%HctGsG?jwv$=dhw>?{2Asc+QdMw|}Kx%KpNq1Wj-pltNG1 ztAX~5LHL6EG7f3+*)s4VoEcXu%XX%E4*2$!15=-#>Az7g247zcV^I(4$liZ^KJ4;` zmhXBmJ|24yhwG)VB@YA0rlfFqw(Ad79H0TtuSa6>e+BGtR|C>(n;wjq7bxT6KmO~9 zJv%&@QMYqq*Of(3^(&nYwN-;l$^5o_M3Hr|&z0WTIlOE`Wmm~k)ex$`JOl2JvSIzB zv>@3w9ZzwcM$zgb(i9O2#hz)jXrvmvDz?QQR~Sp^Hb~t0o=~ zBGGW6c_UQN)#5TOF;j;%tAb&NaUpHx_k4R>FD#9TWHAwHQZxU}s3fGZRWpB(<}Y{Uh8v3v3?j7| zYoK~frEHJLe&&hkmXR#oVw{k^eFSWOvV^Kc#gKUlS~#abi-Sqe6BP>zxI{CPY64>tB}qLDo{;BPw5ATm^7uk1X9C2c-%$D@;sqo2&5rE~mQ@^;SV zJ%$IM@_H2w>#YvPE4Y@)bPJnY@rif&8KISyI?Jq50`(PE_-(5q+x0C|n7;v_*Y-pj zrlAIlLYClvqN3!p=SVVeO0~FF(My)wO#ZrJ&+jXlG3f*~b!o7#`vK~HgL@$}d8gIN z?rh?O*HV|?lCt*w#uC5H<7sR&_k&NUqQ|m-h=<-U#!r_NCCN3%N$6x(xORIF)jOsJ zCz5%uy8jBMnXy$2{S}5!IbL0M$s=x-XJF||IhPbzX@iwD`fP?q*MR36f1t^tYs~jt zAgx|yh6Sn5Y0uI3#D05^K+g|c?{|6)aWmWptHvp^S6q+X!`U0B>PNGJhz~+-rau&F zOp|#+7pT}HmN_yV!{1`6>vd4ro=HP{tARp^4bG1JNbf6ckVZtdKwq2nOmn3H{Tz53 z`ug`_OOI&5Zm9&zId}QoT|!b5Ho-04wK3#@Drm1W#>-}A?4m-N_-w*k7#MbuZp`6( zbf^uAy+6{ZQOg3t4U$Dm3k#a?PXz|H>tU*E6kAMmAWl<)1zb-ae>;YRZcl^$YG>&D z?R-|}9lIa4IkK>qM&gf?Y1q=7z{aSYBTYG7@I#N6^clY^{wcM`pRr%*uycNbC)fJB zXQj}Ui`4jg$qQRt(pl$qW#VoA^PljaAEbPYv`;t>-_mMjnRtf$o%==N#>{#g@lX1- z3H_Vrv2JJU$^ZAM<@5j1v70`McU4u&vK~vB-ssh&Y3p3*efkewI79>H@{TRr=LM|E z-GHPY(&ZZHKpB@*deRiP4fbW$LwV=Rj6&GaFN5axSA&;Zt+0Fa7!^sBFcc zZj#sGA$0ilG2`xj)y+`_Nh`-4X(oO8*RRX7X-lHAzW_CONyYB?M(sHB5AUUe>W z$K_6ISp$w2?&bt>eP#rmcq@hkSZQFFW-aDZq5&#?hGnWzY7)(d2T0@2<4|%Sj!xp4 z80FKgF;nt^_RIGb@2oU|;~RJfag!RnD3D;o!sASAERc?Nl;GjyL^evHie%ch!0SYH z_DiY(?(yz8yJuhKD;X~Q8Gc7J?R}0&6IJ2V86(W)8AqWp$HXTeZsNpVyVu$oun#ShvT)kFOEZrG53b7Dk2vPf5YsxO)?#nQ;8+Ed{JN@9J~beY2Ki|wG&;-vk18S*x?rO zailxf7wt+UTORCz&*OMz<8xKGz;)mYj0~At-dpLPHa+}TT}}JY-{P~3F#O0dy!6g- z@~T%KaC#)ai+-Bxg0ucbvJUSZ;$Mx~n8Nq&9D_WvbzTu1cv4KwOZY4|*bbH5d$4PE z`T>!7ZFo238XJBrkdEMe5c}6R)9lJhv0q{qTzkd$rrm4E_(iE;I$2Sc?=;Q89T)3H zF~x=N1l1g07(Q#7OjByf`^YBSJ2F3oU*e*#SAY~{(o-gCpu%r@ohn-C-fq#-x|xlT z=CPhtha1ps)2@Mk|2_9paN+7IZtGdCofPV&#kV?6;B*)Yu4U%k}5)N@Iwh z_8zFPljCitqCMF5F@artSxj1b=wRr)m(-p6&A$}d;R^Uh^&|WR+@SJvi|5Ku4N6s>B95#v;C(HFvFoS9rXF2R`J;? z5ETfww87|8gBd-2 zOMK*>50dF}Tuq%~iLF$L-QAxnEgz7=`*m#C`h8kZc_#(EG8H8aql-xT-_g)%j(lEy zzt$1+%tx@1At9n$@oi|+FQIucJX80d4Qg{g__eD;17_`y!ONcm*cZhbvbcIPcK@d* zF>sqHK3K)GvR5Ur?UC0>#kC7?DNkAEd&+9)jW!kftRU^a_)z^m9xKgZ!B)v6#-JWn zf6k&UUsd7Y$IY19Q(y9=?2PcD=NVw#Ol32wrT7!hO?GD^bG2Y`_5%3WA)ispfqT9j zbeZDXP2%rDS~horiRAA!7kdAM687FJ$5Q3AK_J={%6KA`JSSY-Ig+&~t4U|yUWXIM zq_Gs+A7tXOhtSKfL3TTBed&ZV-ax6@IJp_k%)I`W1(jJ)BD>yNBqPwd7E%U%wK>cJ6oQ(O#j>!XI7{%Nt1 zXEorYV)wFR!D^Du>kg3b-&uE;J^tf>_%xE$>{6_6Yt)o1qJHRwuNHZ#S`r1_ejC5{SKI)=*l+ewv#3^ zo_|97v7;8+FfFrNnM19iBz^Q@lAX2_)w^!or7i<_vY%*`4cV8^*Ak!$u2|*jOADu!UXC{6v%s zdt%~hZ8qpW@2=JBk1v%BS^dTH!m;zE@aMJsrn+*)9JIKuDADUZlALL-5Z_05(b8%a zXsF@0luK)vqKyiurp`oHr$nZ=DUnzy?Sb1ot5dz2^GYo?sF!5Ob_Tzbc79CDCa*P- zEDoDM-zay-5k9r_@t42ixQID;=ZYLlN2)r4{U7;F;3Drd{OYobecQiH{0lR&?~p{+ z^>;2=S#=Wr_BbcceY(hX@*zFg-~Rdmfod^$V#{dul+O$!ZTS8Y|Aju<{X{e@%HSSX zH#R3dlHj!zc$ucivWK49#Zo#6Abz--~9*G zzJikR7irBB&KqXg;iQ~zv@R_&z{Fp-D0B(9!=V)9UjGO19V{Z#Qt0(n#i6= zW60hO$?%A0tNvf()IH4(lY-sY_Hr{(C`!R?KN6Vv^zvopyFW4X8*1wCOO~0VU{~fIG_a^%)%g4f4Pi@dSq{mBkOe7rDE4>r*AZ+3}p0sElGOE;G797IOM&4ZZU_v!w- z>W~`K2ZtoDV>eDs5Qfbj0Q(0<&@PK&$ejKvxY9yfHkV%JohdrU)g(>l50GIEMLO+VOQ%+}O{KKJuzotiorE%w8)>rODJIVpY7w?FpSl*oo3c|aWE zpTX%%^11Yjx+iK+@@LK6#tI)&uZcA+avsWcpfOIa_)FEa^F>MQO)Tt{!UoNX;~riY z5O~J^|FN{&a*Bo>1*}KUXd&U&4S18+m07g5k;p5CXq?}Vxs2C_JvX<5MW!4-brMW4 zs-c7K>OWqzuDpSD4tAb5R zFNANxITnfRoNE!OF=>NIxlOX16QAK8DB0GHB`zHb%Dm+w_j4>KX-u$^P>Rt1qnm<)w@Kq=LJ8~l%af*K?Q$n#P z&(r7>o=74Sl3;W60hzuu;fy1`o@34$dwiEx4b#Uct9q)kOaa>FO~k$xijp+xaiZdE z19*Va-wN-8Z{G5*ig~-mMI%BnjBC_a*X5FXoAZG6J16tzyFB0-Wmim@ZIDsG z(&HO(pYj+cReVg+`R&C$>m7am@R9hgEEQh1y0MqxYsjPBJHY2S*FXDe!09YcaJe!~ z##Q~i+Y2A|bYj=SIS&01;b~wNEuO%2tv#%9TmbJC-M2}4-|`_$aM-|vC_`#?=@QJh z>m$q1JDa!)x;&QOQ8T-nqsLHt<~<-=9Jl#7e0g?}K1x!9|Lpj^;#(VCK6_1of=8VA zus}Y4?w+K9asE;4E#E;Jn@fgeqs*Jw=Se&- zLT40Anf;eu-=qPzy_chP-$rIIo00>Z!&v=jDBb6;0$IF+Y4yLMY%{-U@9UZa)wksM zX<%c5={AZi^KOoG$>^=1_QZzmyr>1If|lckA&u)_jR(<$fJPW$PxX&)KcQ?s{dO18c6}Ypx zpap+aCgWuOu2&sBj0{zp4X0->m)%rpcu#!MMVGy^+9bZvP{8TmFViD>>TrCiKU_aj zNKYxM!>#=eIHH=rPZc$#&4ZWYxan!^+4JwD@=65^I^RGGC#%D(F>bgi+?v^J4;J*e z4s1#0GntlY%SwG*E@`0IvAe``alEs&O^&O&nzKM}*nR3$!}F$`9Z=FYiW&czC|oY0 zV5GT}K7|f;7UJ*)%ABKni@w6+~afu%-u;(@TjH;cf z1KoLl-)CEOIDFg(clFCP-8F2G|X7$Izevw)6W~ z;ndqJ;Q#Cs=hqb4~WyY3ei_}_K-tt;<{ii*A)GVj(FRR0uY5wSw zQplE7M+>D|SK&x)S7vYcf8SYmbo|zjtzW4PGdi|%&5-<#s$^k`A#I8*V$megXYzGC zZk@s`cI1)bB{$$+Y6SCX=?vvdm*c^OjjVcDC0X5%dkVTtVtWsPx$;;~LLjZ;5nh(g3R7Gm=sIsI`bB;?9*HTZ!$ zI&7KBRQHDpi%)OFMKiXrwAG)8V!ILkcc=?HzE1^ z&egVPt6;{;&wP`9&DO^yE>G!7JtgSdYZU4~Qk0CoaGcb+SiqU^y>vu7?=_gubyF{* z*}iAH#ewT5;2oaX`>iIIjOly=daXVu%h@A`ZSnehQ`RxUD4@&QXzc4UmSuC#;~d^$ zRJ`jw9Tia{p1-{d{1x0~xZ2)jE4WoDGS>+jFd!rkP2xExvMYi-PIH4ln$u~Rg(~zs zY>tPP^kL_P-{OvYmtj;?7M(tg=Sy$meMv>XC~b(9HgDt^R*yC?vqy$>tMPd#ncqj2 zAJu4{hb6I!k{yjDMB95AOnooEuX+tJMQwElHmo*Ve3bMIp5NiK>r|e-`GjY;Hnr1p z8fyc(#cUKa)>}{yBUR}BfqUO}N3o5rIxstM2kg*2!~46r?#r(izWeOL29GuskKNgY zg}fhU`<7xd@PG!6j(15JQ%hVuhU{BoJ zPm!6GV!11$SM1XbJ}2NEJ>rP{4?3ZGb7+r{R=iq?+n-`)8uPS>4jI)jo25g5hqH@(fCsyt6!E% zEG|8SNyiS-EPXY2)DepwhBlJ&X}5$sla7JYI#Xuu!+Vm(yaS_VcNX-lLUn3hpnezu{Vwe)%+$s>A&w zBQaw4Ri68OM+zrAu$A9Y-8MZS=Y4A7NGA>E%712IjXPF+qioXai9(t`ih2*^chm;| z-q`E1I&)XJAU1v+QMPgz=Ui56(_y2npxvvS_Nh>Z!PE!)g%>if=x9NBBSOUUuFR%W zJDGQ*8+xkvvMKYm;jGIR_;E{)tD2X4p>K#f(|k7je>8pfLyiCYe?xntL|Qbprx&U7 zyq`xIh3t`$T_RGbq$zDOQlcWF(m

    53O& zuj@5@JuzBw9b}|Gk+VXsN7@yJ-rJSzr`B@RZ|8Zuv2w&MYzkdH;=ei{EJk2x$Gze2 z-P!#lGyI&k84)K+Nr8qRol#X!uN_li_wGH1$9`VhXI>VhsF^7`) ze|3H`_e5mmC*hM-B=IzEr|X?Yqv~@5Q?$~6weo*;{>mN$j9gHR;75$;UgA6HQHgk! zvYiCWXhVF`f3^Me>t$F|6%1uRh5FJ*%i%j*h>HG$=)Y$=Si*e@2M(TQG5kC0Izxzw z5ev^K5 zItk^jg#x|G7G!N1sCP!lJ-*WyL27&?{^l03j9cqy|I&lhH+!`}+NjMHVD`q_?3C1gV}cUuy| zN`wMc%^oPY57Jw(d>q2Ojj`}*BtnW-vzZ;PNIzDHOG_xR&W@*f6OPd|Usq;NwPC^Q z`Ad%>?B{iDbWhv_wJ%NN)IvvuR=DA-nI^M5;D%}HYmjDILNd-9Az(lxg7$dTtx7XQ z#ik@U=G`RaQt`B?@hCmMyC2)BWq`=mBEG|VD`?s;MdjW{(Y?jlOn$K=)cI%Wf4eKn z7e2%B-M@GSn-TqV%>ila;^6Pl%%ZmQn&6s*{qJ`Oy40<3^)KhR1xirc5dxIeq+(ZM z2`g4JfLC)7>J^rg$dSM4aL%+^6!4IJdTI}$y9>hGz6cWiLg_P|q`vIOb1Td-QIgl* z&ROi{Zd>fzpA7eyYJTgKfu!j&xUo)Vv{3_NZX{rY!ZvnqswSRH7osz*NcXnNMXKj03DcdmT6(jiUxJTh4BCHrUj6SDkfxCPvR&y;Ye~T!GkqRu{M z7adICnjD2Ety9?L1WUy8S+!P>LYxeRwC>e0+JAx$GaaIg^D9!YLCsinxD2RVvIPwr zzLT2ePMBflhE4n~Y4gGc!~XifGTxemE|x>Rrw-nIYiA|-#^|(IhX*FxMAA2GvDP~q zQ|phA?cPcls~d?oGuzn;M`f7groc(7NB59VGhXhPt9P}wg&uHrfW!(HIF`SvFTCr8 z2+4K0$Uc!{<}0xIS_qVeSF%xUD-hC{fUpVE$vypPbl^WrYAW-M`Mwh%+n#ghZ@RHw z;WErtaIRj5&tvP@;8z+5 z=N>d2{RV+*mJFR_nobQUN zEuJVke1{z#AB0^}LYViD7re3PK}hC6y_L7dBAL&vN1`HO^kOwz=wtz%Tj?lmQzei4 zchMVC(r`Rc&nmc&Mr}R!b@qs{eD_6oCfJ0-Ip>J?a0jlCf9Z`N@T3%VlaHht z_p(^!94C129{9zK7SX-g?HIB8CG>x5)5-vAoa4748{6xwt;iZ*cz$(>*iONr1}jML zyKSPp1WlJGULGV|W|e|C@8z8xpWgtw`7D>P1=?A&LG^Ysua1D(Fzm!+`h# zMvw3w{sP{Z%p-KjD<{ZzF zn%Jfk?yZOy`x)FUKVUMj2 z{+NC!o@FNR+QWTq|KHX4&F1+D19)cQtPY<0s*icC33xM1lFf-SfHdFHEqGQ-p56$d zyX}urExCy-f$t(x4i|G>u7V&T&Y9-CbEO}69drH6Gi2g@kXNqAK3(yH!ot)(?o#o5 z4U`RcL!3nmbLnq_jDg9x*^(!EWY$K9@f+)%O+n9VqgGaS*8!tT{LvMAL1eMhAFuYL;_|%~(#11@wYVq3c;9(8jQ8*b=Y){& zKTg-Vt(ATmDG8H<)kJrjGFCMt_tp7w5zk}HE5^`scI5I0N33yk!L!l3*)=P!&%Lt- zITuEe{LCIIAsWDED4xlAeJQlZuS0y@WOg~+1>UFf@GC8oM72v{f3GbxT)Nrv9m?E` zmkg73Baz-LC&U-JApWwDji|Im;%px*@v|o1Psl-cyEZn8xEL$O1e2bx!Ih}{E$3{Y2W_m0>qv9>?D_G=Q(eD2Mr8w~Af4SnG*&o5@{BX&ZojJE z@3{&WhH;Kw+-H&yV}ZkKLeOYd$+oVt!dqX?pmCl-oQ>t^jq8?lLdG{HuNY757agWI z?-q%^471=F6kIQtw3!4bhSDkX&eCJoG+6cQ*I01=E#wQX2%N>*ajE<{K8@(0R!2E= zf%6-So227=)=cvCVp#2>ct5r^|*i=bpO|Oqr^;tz;SX z=nSF#xz6CQi!>XV@f!OT-oZRkf~q;_aNUhDUfDM@`^4qwPzr*tJFoKv)^L$agyF-% zboMwqT*}VE``){3ZFn>t@#X-1@w2~R0r&eDE%T+vPFJvzMQW(7;9lb_OZH(v5E`pP za6zSkjB|CvmK>h(vi~l#SZRrO@uBGWvO!SAd-#(V`|EA_r3OnO-y`w8=)5guY*67+ z+_;v=)I<6`S)rW zx)ftjxFCdW|Hkv!HPbODQ7UUpFFOD`sG-vm%x~Ze`QAw!&)q z7wr3`&Q`2<#vb!jXa=_sr(DSj|618aDJ?8(k4M9ULS2Wqm+84_lBiNWL}-&L z&M4=icW?o#kavY#xEu0!brFLGe(#&%gRCo6tltV}{K}4jilP*Gqx^{~NKC-e5s#Qx z8~@o$60p?Vo2li^yDKBJJ`|DOK@;F-;3UrVD>FbFp_5l z^ybwP=ip>|{QNokecwzrjrX3OjzxX<)`1P4G-IzhZ`su> zh-*-b@L7Y^reMYV9{;TaWb|$d<5rGrYlUa-V17yD)qo*S)PW4Nq@yO-B+MeR6 zf@;fTjI1&e=}VoZcO#_mWNHMtY3+n^EoZz45i)TndqjBnplO8-DOZ_}mVfjkH4w*JDUspG6u@O{XRD zR&+%9cV;1;O6kK>^kCU$(d_ZzG<3mPx=LM>*|K=VafarKEslaX+Ky36df^k>PEQAN zy%x{H5*e*y3u~P)I*sp9=d33kF289={S1^$yU&;y=k3mlN1F0b=Ap&!^$Jt;657n@ zVD2X#XOYe`%)8ll-+0Jr^DKz_6{Pv44rdh_L0+|)XXdX!+Jr#JNh{QQk90&*dNQh; zhS8U&Y!PLViL0f}?2@7u+`Qvaa)JqFT1=+*z5M!ato6gy(ep4DdtO>F(|fV_@FWiR zBd?Msfh!*F55&#e{2q!`_`53+X1RrewbNVid`^G8+)6cs=Pbci?q3e8D`R86EXC46 zSy(twK%f~;@A@63YbIJSF9}sdSmvOA#}CojIg2p+ja%@BP)pGMe90JlxPKcbnDthGAN{5K}u71QM=22tLtYZ_0r&un94RChq|r z&kAHR)oz$2n~!Vm0#f=$42^t8oTqY+)rWGvq)RfYe8t%1Lj*JJOHkZ#fgI#>>wwFS z2vAUG{ZiLKpZ8QxYIYH`%S-XujNe1YdDS(}H9^2U&Su(hi~O3ck4Uap(M)e*H^!JC z`$;j>tv?D3UrAH%#cQdqXBI2I>4@&bPJO#~=S!jRT`GiB%nf48_cxnAt>^gzt&C1} z!gs|K4BJvIm@!~ER9B>8)A})V{-jh|`~DOiKI5)vhtE=s^)AMil@_G)emJ$cd6s76 z+pxi>)*!fS4N4acBM#>}sB23vZ8Uh!V)*T2s4$rOPv)?;Zd>&GCq%Qbim01RM!;-S z{8Q^>pSNVvki895cEaKM26l}G&X|Ztb3)0~Pilyf$i<7Fb!=Ro8|2;jduXC5dA4sR z%%~z3tZ8FnuUh&1`w1tL)!DS+uJABP#qmL{WRjaY=FIcQjhn4(;UO)UUgrLd%0k@% z;@7BNo+JvUA0`hPd5-ZT&X(eJ{*j#!?}Wg6k&qfN ziDdMCqRZBfha7vzY#%PcRnK@FHDAT9M;pK{Y6F5yQ^+*OP&$-n0$cr3WM8R;rxxW{!vG=4m^;4Kj z4c}4E;rhTNCGOGV*?V6zP;O95{-tQ5HQ5E@BwE-5YfsL0%tz483Q>lrlV)T|V(j=3 zvf^S2jr(^_!8ZOkrH;oc6B>TvteAJRUz4#gj^q9=PxpPX7NNg%7l?r?kzHz=fb%jiR{vC zzMr)8fy`GMqH$t6suZ-K?byz2+LmI__Hf<{ZWTrDGsD`pBn%l(`ccY8-KO(W`o;D}nqT6^p~UzsTxQmLQ@)_^jE^ zJm2;p@Z4~{*9&V&TIo!xGs>DOJN{&=AL(P^tyC;t>dBHg1I4SX48>c^$o!G*bd<+j z#D3V$(%s@AU$GvWH#i7lbK60G_aNX;8&!Y8cPY1mF}-yyE1dZZ(|d;NP0kxgn|F88 za~%LY&}kV7{WFVv_$u|GR!)CiIja@z&*R^s7>r#E_};C#g1lny+#Y$6xZ{d z4kobGk)dbvR?^ld+gK>~uSMDC_T5{@Hu0Htygw*8Lt5ILk(cHV&EvONIRCrM85IKy z^&ElUq*h!}@25AgO%-C+oUdw~i1f2tnc^*;QT8>9*G)pqf45ROqbV5p-~>~u@}{Ow zj!~O_(?s?A7Gct~MVzN~i;dzr&$rHd;=Fi8{juGv@aL-#4UYy;^N(gIbYF+%>D$>Y`O3^t#7XMyO)=?IbuY z5M!Y{KXz*TCJbG8ff%fGL|KCaF27S_tKNI!e!oz}EiNI0o-c*Mv2fTB&$=PmrZAt9 z#J%dbiN!g4%uwQfx>@ZkKF|cqhZbW~(g(qZoig-FOax8P&ti=lPTafai1T0Wh=j}5 zz<_7siMno*tb;2sO?fq_)kUUWWC^ha>!Gl!Lhv(WIXcVvZFJ@s`X!wEChn#nWLzmb zId&~ARyamglGY2xz3!kVI(fe5m3nq^$7*>xMn z_^rRf58q-r+x;=`*W&ndSWu`NJf3?#eo3P9>|vs!tA^P#a$w_<&;I;%#REH61SNNo zIlF9d;wirg`R!oFlbq2a9ffU%lSobLCpuYSJbr{dWV`(gA+{|ZReM*ln~qC3cYXu3 zPp6RH8xwJIgBxe7+++TMYM9S`l;Lg)qU&e;@l@O&TZIO6REh({`}shSw4Tk%vf`f5 zU|9TeC!x2e;z=)s-L7_~$n!0QoY!FBB*7kYJ;}o4bi|t-A`M)Vsd`BW%eD?Co?w7K zU-)-cUrBJ$(1IFjET@rOYuNiSw#aSZS)!lkvv+xsII}+!qEm;+134|YA8_VO-n(r5 zI%A}%C7|g=XlYRk~xE!;Z--)-g z8Pz<`Tss-rF7o7l`Am8@&ywma`N0lkQ%L0`!NkLbDa*BBZoQ12=TupG-KUdYdNG%0 zC0DYV*!B3u_1j8=?FC}T+fkhH6j$upsB*_DjOV#1MLfIsU9A@aLeucFG?6Tr&`JNS z8-ZgwB6erAHi{m^axdo)<~X4RmyXEjz1w0!3+fi)(3vzCnRYX^h$Lt!B=R|KCwarO zl*i2H`nNL+|v`)fyb8|M{fnsyYM$Y*vCH8yWuzsyeU$%fM&vv*I_z_ErJ_?Q+ zwjt}o2aG;77-N^&Lu#84d4r?b%$Y0jmupcHH*&rn*O2S)8G~=nj<6w26-M?+Xc;8N z(lEinLioIcYF~_rRkc=~KG-Vp92VPD2%hnK&}V*2s#-UO&i!MD!TE)V*QjBaS1-o- zgXtL81EP7ZjY@aOW9F07tTcn?4)R%@wGAY>>$>Pz?`L$G^K&*?WQQltp@5(8d_k}DA!*g7tU=U&yZ zvXyVZdS7t9PAf5WorTcM1&}-6%5@-?STHpJm*&@s@_A-JbWAovu019;;Tm|Y?8`Go zTiJ+iZG`TLh2fk+-FDNP)a9TgR?8hB!YXxSdS>J1%zUQwItGc;Bk^JVS0bI{2=B$K zFm3cMc2UU<6H}s~?kq(<4*Nfm8orkP7)EKYD;`?^*qet6g^^F2NUzksRsYzkq zE>|p?eUJScrGdI#*{C<<`unzG?*ik*I8smaNOE{14L;~AoWsCaMU`W|`lFIsN zi0AoPb^83?H^T@%G!EUK60H8O9ZHWCpmC6hY`&(r$^|Jg=v6=-2&6`$vm@3MnghB!JS7P7Z9 zMeiJWj_gfIgr5v0zj7Ai_1QGsEvRQF%mgUDScqZU#E9PZIk31hvv2plV!titSMxmU zGYz8mYlE{_!zh+*ew6jR?&dnJY4%ma-*~Nx9Jj3usA222}ha{E1pjVyygFJu22F*3Y z^)F%g@m!Y4YCFM9B@=)5Y#Wnp>H8rzn4vkB|fVEQ}}MXwD-KX09-hY}@WJSdEa z3Y~G{kv){|Ca`gvogn{f6;!6%lA3}U@X69Z`;|79Ct-@4`$BQ(^%ha1p({2|&&G(h zW905{RUDYL2JKvzt5BeZ?yrf+3x1*-%9&R0__E;}hlTby#`QBT1~Z9q{7mZKvx46H{*84ja8_oSw4St+3{4%v zKW~6vUxrL-<{O;Odx43cE(wfO+p)m^F;cl!S25NSvc3LTx-^{iU*ZALuvDDcmq6q) z+Nsp~VQ>^b!))$q!+2aQ(u#+$#VcB%%Gq|+HT!~`6y3n`fMw!;a;9UPxuYg){3Q=`r#A5NoZU;MJlU2aD~_QzXzL{Fx?An zZ{slfOrAh{XDbc{{=>biDmbEG#JvXGPyM`zNFTh#HuJx&Xd2f-gWj zoIMM*!gr)%nM9r7M6n#zP;{b!XU;N(mFsA9;1PP$AY0V5Sr7B3Z9;=?8QJvP9o3pH zkY9G2Dfz5{@~3!wiB1qyMz&$cy7#EC7>wV$&G0lU950IlSW~kX9_`LUmK`CNp53Ko ztHxl{kfY4om-BJj6A^sypXhX?5xzbv<2uW$WWgHl?`yQjC@*z3!fzE$kPtj+;#!&& zruh3Y6!vdC>H<^jklUVy1e-3BSfLMt1IbvYd6re504~O7q2R((!K@)u=!@Wpz8mY< z2YkoL_YQg!n?=PjPFUEv3Sw@jNTaDI7G=fa!kSi=Ys#~an&SZ3?Sh%7mt$8?5)O|V zO&5+dz>jaqSbML8dFblGkEUY)1KHd720bUZe(Q4*F$`{}VwI0*?uw^u=Qb-mpBR8g zQ)aX0^R3}!6NAm(+ex?FRIHiFxwm&a*hJ1fpSv%nueM(tbDM7N;df7A7@6Fn2|IDl zoqSNoeK&6q@ADj&vs#GHz}c8SU;$1vx3ZMUmXNaZL$udHk>k=;Xl~d5eRPsQElr#d z`oL^TE4y_>2UouG&!1YT8-45+wJGL0z|bSab-f1nLvg0w(0ul#cNMlgaL07ThotDV z9sKLvan^nZYnb%Vq-6QSPD>>-yny#6>oed%lh*@T|gB-t1w94V;JP@toEi zvhafj(rGq^EmROK*}NJ@?0qn6o&j}Dw!{4pcPMR&V%N`DLHwsb2G+TfSOq!s91%e6 z9cSU`7-0$D^Z&XsfqC#c;C(J1b4}{W$S@TQs7}DYRUIr=(~JJ;bfKpQ@SF#pFO+TS zg`LY3+4+rbcy)0dpHH@t;)&YG=Y4PXqPwhjh!K)MM05R3rbxVOG4`M58oZh_EJ&5| zOvNH}tM(&@2g##p)J!}b(aJLX`R#0wI|dwX5LxUA!Upbx8)e!;lsUU|B;QMa5IfIq zTk)HYMGS^nj@F$vJ)M3JIZxe&w}}kbo8rOkEx37hCE2FMIpAXU=y|e>)ol%e-t0(( zPaRL(1@~y~!Y?%MFTaVLG($vhD9mbQnGyE_9M#AK8J$L!-;#ytTwY(eKX)U~oJdtk zM5m>pXh&QVom?%6cUQy6Bo#gj|FGkp!vtn>$OWgfyz#)pj@UQPz~pRo+*sPiw!1CE z)_q|(HEf$`?rc{aACU#icSlL4B_hoGE)zSk4o=L$`9qqiiwyG10s z%LReuyjG{asyF%Mhy#bYCT3C(DG~Ugg!isr6%R4|ae(g?t_S!$ll*a?P2De8&;dt( zu=uGdG*JHtow;R`NNC-Ho&qVor-!8JtdEi~+U1K++j#C`#T$Gc_`FZk-l1s)yK(*) zt`yE(oE*`=zYzUaN0RoUR=Ub?2%1t)u|O9cM1P6K37aA8U3Lp}IjgR5;8I$cri3{o z(lBgpH@i318`F1k?(eG{($ldR!K(}~+~5vd(P0I{^SrmnQmCI$;Ep?7!zQ<31huKN zNAUJEJiB_E&HtD{qjv14K?ep1o>j@v1yb&`;rSM}>4%WETV0|NVTGb|gSh_7#}}s0 z&X72D7yKOIjgRMUFopi!nA)=*uJ!qXnwA!xlldE~y|_1KhcVuMkHt2ZGA7G4Q7dK@ zAm7E9Y|&|@nOf4w4?oH#oz}p>+gXSU_#v8Tu8Y!EEv|XK#bWN-Lvg(aa_TGU#}a4G zv{{4iVn0d7oaL~-$g@rOF8z{>6<$m5zT)dCLA9M6_xU-{*J%x`caA#N`XzFn#4`5l zsRyEX7HV}M2m9`R2KNW=;8*cM@T=U7G^-tu>IgRBzH$r{o1>*1M3R4*es99;Sdv#G5*(F5v zp(+w4Z-y6(|EteI`|L5SBn_|9x=8gVZOnNU1<%mq?867HvwfCp$lyWX|en)8`btw?V8JWm|^<$~r5_V}4lC)L~?Pac|7Y*46U&sTY&QGs|V zPa1@?oHe!u#bf%Vjgo*RPPkr~gQ3-fdAsi{80?Bi{ewb5=nR-uW#e@wn9~j!D7n$T z_R)QDd`k+vrzPTgi7Z=Q+Q>IfzRyb)ABi44Z7`1N(tjG5>_B_Wr8%9`rmf6HPZ`eF zjj{RP7GZ5py8VZA4j%+c$91XW8j}^UdQv32b9W~0mM=q>f(qeM6^pZN;glQg#x#ek z(hPeda*s8N2`W~2|1ba*GY&{M>(t_G?KbS6W5R-NjSJ*ibLm#cw zO^L4MiC5&YrRFf3q^FCuEh}(zLXr4Y9El~Z#6Pru!@3gdZ^un9-2Amo`1EnWUdm>b zRt#dt^c%Un#&4c}@tnB%mvnK#i{Zc8SFG6Phz~g{(c60kQ(Te38;LvoOjRNbC(nfZ z#Q)drF}5T^UlD?`P*bim-U0I0J+M+OL2S5hg=Gf=;k(0?ZI2#>y36DlP-_KHjxbZG7pqc@U@R!-PA^Z|ddU@sbSW>d=`HK_ zkR!Z~vWk8R@$%kWIwR|F=6e@b>^cs|*cco++aLt7$CuGg{nOhs(y5O_(fLn0vI-km zmsU$W(~iN&;!C1ak`XLU#KZ8WtnU6gYg{L8YPWw!a_NHv{+#NV&50_h8hI*P$CX0= zqAx3zx+1KTJuV&JAv$l1K(Eya2DRc%Dx0C+=tD&@K-FZHR`s7(-BUyhs|JM!duyb;XSago` zHf^4y6|-hR?qgy9i0<%{n#4MF3mlU~AtAd=YE7D%9rm<8>a(Afk>96NRs^cPQJ&Oi z%Az7pPUpvubWwPoD_hfkd75Brn`kaKzySx(zp8XDaYp(zFRI~B*r4~;7_SqEYo43L zgmca~_$mbhOI4VKpBkTBV9BqK{wZR*>p*fa4u$uv#Nn;_@V%CYxN*zafi-Vn==uz* z8!t(gwpqb`SOA)zhYRHqZumPt4Zn9MvftrNd~-`TSVW%`wN9j?i%!7rAY#MbXu$Ie zL-fFmxznG?2y)57qk>j3l7BGbzU3i|>@2Ka2RL^IP3PkYJag}O$zL-tg zW|tnae72=A=2Ru1U%#`W+|>cXYHKZ4Kj@amY8zx%9(wpYZq3O5(e2F4(4 zT?leFonsn@U5T;hgGUKBMa#1gOo&X!?W;u+ot{m2H}4k=cTT~MDr3Z2B|`Sfda>To z5qU-{;CRT04by7m|Mnk>fjNgof7O{t8jz1GyS__DpV!5izr=$cTqBgM9dL#+6N9gm zRgT+4_4rBzvg3ZRTV4yGW*v#LOQqsdqa_yF)1I;C2}$P!C4MEticjoaA&#`<@NNHG z;A8J>kX}u;KzURdyc4%FYl$b`_&VXSQjIXPjKOe^CAg8FBALIT38(enV1Qd!IA5HP z8KL2r^EyausBy#Mm^}1eGK+nB+{|Bm?~kejM}_?c$~PwsSY-7d>5-SD8(dd}rI#+U ziaBmLLB8wq66(FL`D2zxC?s>%v!FHeu&`$sX2p3{>8j>8ni zV{{)kfCtT9S}dPQx)mz%i+{qn&4*ke?d*nF1ABa_tdnlKl7RP1QlW2D$G&+wz-dGX zG!iLqMaK&k$1|`mez!zxrZXc^_+2m;?hlvYJvU+3qdMc& z0Gi|Xe;^X>hLb)b5R=%8pPZ-&sn{R^~Q( zBu-@+p~|F1X!+^m!f%@42SiG}?CW{qUwMqZ9m%HBtUB9?w2KjLEKObwcE{B5X=kHY z+iVAU!-XB$Nz1R(4$vYCXPa)bbyKu4dyy|bdo+lvO{sk3p}qX^sjG8*>u+(T)zo`i z9AV4PXd?blChR8XipOJ?pwlSQ0FC*|#!)@D?dySlpSB7#I-__8`93TLv)$y8+4%Yw zf48~UWHIy>rq9+Q| zIB)b_N%Nwyn^-WhXlB#>v+UR{vG|=4rliE7^;51?qlh^6!!nW3xry~Voydn#e$YFM zAJU99<`{mh1QEVH+5T>nWh_R+^L~TqZtj5CTdvqW^o&%+)D>fEY3|3*vle2ok9`nL z@7+t{`#@uu?TtgX4YImfr)=?|ZW*$jNAd2Cl*QR83!ST03EPQ!B>PzfrLXqPkEgn@hT|l4Z@rhI-9|ZqeUabX~B7FD%`3JrB2%}@}E_dBd!p|ZY29)R%aJj4a*QK{&B?eTsO*QwPelG zv5@ON9g0njVnJ78({>HRXi2Gb1G9zP(hRJdxR)J#H3O6B`AsWq6tTrxI8WJv-Bvu( z?H6&8-z=5K6`3>a{(Lt~?PG`80d19`$0+mE!3$T7p0f8nV_-v?*jMo$M~HYbEQVT8c|oRpm!$Th+Af8;<8pIBrBW6(ojF-JRqH@MghC}N0;swNoHIRSIJo)uXQ_Sm3JnX0b0B|F@Q@gBdN zxSd?FP+h8tiQ1VM*vU}ztMkS?XJ=TiIn0VGd@yHa5Jni(i}ND`pt75IYhPAK3ZFfp zc}!P5Z^}hEp=*k3u8FXh6blc3SDb5G3B3eUR_&k6x2PWF-~QT&N%OT)_An2do_?1a z21sz<_WyPM;T=aL2fHKJVN+%OddeCe7XeZFgDv`H4o#JCWHgkBBO~q6uRIg0Z&ygh zkD?@Yb$dQ{pAZYjYoTZw@%i7+6MpIQP^G;A*{Nl$YK1%cQO#_=e?!zye2LVN@31KC zqvRTEg2T*L(B9ewwTsQMpY&SyF9nH1&)wj*G#7WyX|v(Q&Ae|#KLi&a5u3+qVe;fu z95(wS-5+X*!!2t%{HN&)++o;-^lJBKi1qW5$g`D7nx!3#Yt2VrxlruV^{n_kk+^Ww zV?0%EVOIT#FQ*p=M~!2m8}acbETPPls&$$YuMtAT&m$uB@NEZbcm03T_Q1_)5tHa9}V4-qavWU54!Gh!s(Kq62BA8e6Q7At~TwFFrG*G@?HG# z=;Bz><9#4-C<|@12blG`kr;PoE>?FT{vI)vi%L^5%OX;0)~S)JDJj6XB#N~!TTI?% z!F31!mHHY5Q$Cv)K3G|?9=p_lasRLR!L~N2CEw*k$pNYV^M$xio@moMcUiw{+PGTk zgVHGtV(3DeAGa+>m%M*<$M$L9H$3IhoP30J8Ml~!pCb6^z89tUed7V1iDz@sO+5= zabwqCj7H7XIXJ(oNqlTJK|oGCR@KRguy>@zeM=r0g9EJcR}|lHeJ|f6J4l$E(!;*b z#K&_OFIhIipHJ%V%CCOP5LXYmk`~VsOFn3dyW#F|T^0c=X$dR-qC?C)2VAARKOMRY zzdt~A=3cJ!d#*7$k0&iww?;NLB$*F>c9_eN*Kff+1MGBIO?{ONTfclf?rQ$O<~ut% z!hI1vhaP97zdnZI>FhM{9`)?!D=%2lzVg4^jh~ZDpiRv4|9be3#+0G+G!NgGD|3?r z9Q}`G!Q}z%M#m7-_4+DokR=VwY#+GHcS3&rzhWEJ9IeIh5IvlG zmyI{?a@p|BLy*_i53|yYO16YKed&arp(AnQ_Fa(|st^BbDfscLw~&9;fW+PMdfh_i@~x5K{KNaBe6Y5h z$baCA&JUbXz=-JTfbb&@^5>x=Ib zgK%zLy*Sr16bmX-vF_X&iRHT|NQ>>FXR>WJ?R(6K6Ou@bp<*#T!5MyAm&2#gh}n!z z=H&+ubMs5qLauo-9#MKt?&derape*y_-aABqFUSvbtK&ZJp+r&DnA+p;-b!C9DFIm zv)nA;IyxLFb4$gpfz*f4?z`RWq@-Y~GEci@Nx3T2+Y=M=&_UWUY?vp$e7A<_sWK=f zZ)3}Xys?Nh4Nhlj#BZZmY-&ryLA4Z#hT;>PEcu4LefwZwiUl-G!r`J8EWAfr!f7z& zIBcHCdiyu?oh7n3w*9d1U#kVldeShT`Yj!n=LUX<*spu1i+xQ=NTzf9;MaC`qR#?i zRfQtn%d6t3gEsn!J7HC(%(OQaMLglfxD#a=`07h9}mL5TUSJ~yA}RMM#9jkL{gb+iNAKKuxsqg zALYzJSu(vxtd@&maz?l}gFHb^Mr^re8s9nfJg+Ks76BuDDBs=*=L3F9)N5M#pSSn< z!m&@qua^$Uh@rXq=y4*cAOOD$DXSuTKYK%U{w?OBpuAapsW-+&#|)(Ii<6$vY~mvd z6i}EG&GLLFWA&>H^dDU=hT0L=!Osb|`sQS20H_ejfNFRu8YkrjdB0Y(DLk7l`=ZNxj zKgcGzV6)3T_K0RL^G>>A!OJaT>i{Q29uLNeut99o^Y45^*ZxQ=xGz*c7-Mw*IP6;E zCCo}(u+nPD%d>Kud%yY0Vze(&NKU#KV98C4(#Kc-N_*pJR)7=9sVO9#i zSbBu3Ul}TLrc;JvRwllF7%F*fAIPt5apf9UGR2lE(tgaReawuBBJHFHrs)!EopQ|m zV`jsa=H@0#Z;1e^!v~6D;IKVcYI@oPCBM?)ZPCb9`egEi^i#Z{MMmr)9ZT}))kyP| zVf{XiC;#y%VntGKpX7v}-Ca9o@5^pCWBS>bsCg#gA4@$kVRI_p_o^2@`%Q3pdMv#1 zWpy7-vO#@qE*_p8!MpTN<+0I6_{o@yQhB<2j<;Hcj5`i2=b1YW{Yy1*{|<4U?)nuT z;YjU0fVHf8!~gXD2W^4mS6aLP9w8yGG81G=kzHC&%!mO$Ar#z9M z#TMwYIuxBAmP+@PJ%#6~K6+!CXYvF7Gx6wGC^S491#k@w}TMa-=z!d+#W-(w>6j*%|l~)+}1MFL1^Y z2eR{7r#1-=i~$-~(aia$Ei!ld;rPLEl{;mLyYoB~W0uHroHE7m#c`xpI3pGxcErJu z0xUJTEoo{U#+9-h_*MD!;&Iv(B$5ZMbef^K7Z8Bc!Ugi3kFmq`zDP}@zgOQ9KaK}N z>0Kh-{Z>epDiS}I{65~@DMy!l5KB)}zobwsDuOJbPJYJWH+5M)WpF$$t>Cx!xC+(9 zQ!x2-1}5`2(iLMF;%RU4FsoWvk>=Lms4F5gHdXp<@TYnfPaMxqyvxXi*r$+%S7#3j zi$PAv-jRu24W}iMVM_d|j5(hjcS4LKAV{X}-Xu`4V_ zX?Ez?wbW)JrFRN64Sq|*^XuXEd4!%Zv*tVAc%o{p9R}BEi4WSz(4+Ua;+Gxl!F~(e zzD{#b@+e(j>H}TbeBz8eX8C)Z&`#M*+5K*b?*92a$KpKiae0*F)$0*F=Ex%M-JT<| zzq#SSC2JHeuaypx#=>TE0_yT_uyHrNVL@7Fw}x9{(iY0H>lJ~zwhgrV2*z=h6?jml z%v;NiG0!|5>tC-E?H`Sil9Z2%3S$<$D~&e(wC|&yi{HR zbFW6TPUI2Gj-jlj>E+_?`k2D33hyGg`MH^ug_7u1(?pUOU7SQre~6cbVgx*Lw7|>&~2lCg95Hk#JtxAX>eh zp-bGugqkzb53((IYySdwT_yaG#0QokI! zMgbrBQrzvbS~y2pW6#GD^k3!AY}a`}uE`pscI*%ZrGYqGPWfROec2$bx7_#FAO2q! z>iVBnNI4ybv4$gr%O)ojk!LWsC7o4|90|*=7P#=>ws?1MCQeOH#`r1&X~^2Eyx2`1 z|9O;#9`MHdGj<)Efz^FnP}$!Ve|uRm9f>N`K27PU=XO0w8!$K$+xKmfUOHh(ysl)7 zp1PC$P}WAnlu#^^5bM}Q8(SYI<8|yq-2+3e@m#4q#wVX;yGq=N>uE*xJ)?bkuXt7fx7tIUXr4qnX+`b-r@G1s@;UE;iGh-GTHdeJ(nSIr;{8 zG%Xw6k8;^P$0+XZdXz`zYKoBxQ3%)Z!+u{=$&ai^Vz5LZsar7r^2!$ezv#|$G+Zpo zb;t7o$yjO-&(bv#oI=c|-Xf>b5a-QuFuvj_OYf1z*G69EUHgv} zd#3u~E6q>OZ_j5seHezlWvKmCBks*4?!CJo3VV#NoMP&WO*P~x*xZ|M(J{jh+gQvm zJR@p|{k7>X<>!{%lgO1Sa{piU9d+LCViu2Gc7<>2TO=Kp?T6ejM<{2YovUPAFa2}prjDza?^+N6o<&buxd@frFYs=|| z;ipOWpmA5MlAVgGaT!Rt_*y#a9>az2(~-ZqT3lG_gwZ*~k{e%ES)xvw@F5Wx_Mx3+ z(EH-|rw~NkC=u&Je4yAVk2LY;CG9_l^Z2)B{MwM?Lan6-3HXs$Zzx|nJI26drt5jFR-;?bYoI za!He{!=%OC@biuaY9sH8mm{>XbXhWT-F{1DZqy_3qmo{cpA~l)6o&5MURb*k;tXX) z=B!DEe$#dqKhgreiHopA>RFN3lXU*6#Cy?dWiy_Wj^c4XX-jIv12=oDCEiHSuU{os z3rF!E^`RZJn)4a%7=OzOFT87|rFyjAvkOAy?K8~qn-5;gM`N#2z1TwDzy}ctaJscw zBF@@iR%|MaugLPX8HV^`mV)oKYlPJ6qA12&F_S0D)GVERd$eDY{K4ajmPZ?O z*td?zh(YnEJU9$|%6`Aq!BKZFY;2?5;zMF)#HC@&rD9##6Sw&n;^7CB9%DnJvUp1u z(opTFk;?V*htVYmTxz+)tVttxFVqDa)3=K41>RU?9?_v=KeC%xIzIh6bnIugn!)|Q z@AuJ5Y_GP)ipFfj-O6D>x0P`8u_GGB-4WM&O+&`m4Cuy;lx8(0qE#yxgAdN*F$&Ja z{B$BePMnz0#fjK20q~gV!6I_U;y}4hN6kNc!JIOp6A+RvFS0e}<6UY7+OO|tOA@qD zc_p!<=2ys1!-kO=SY4P!nB5)^gBkM!= zgC{f_S~~QWI8M3AuVf<;8A18iC+8#LU-BleYG(Z{m-2u6o#d;NWW@3$ON3b!<9K2Z zHlT3=9>|PDlVgK0Y;wjuOJ{iHoRK;?Iw5sP0AjC5*)C&iLdLhee-9vAIR+{Hnu(j+y)w&H1=%nSo*M z-olvr?FXl_kbfqZReKGCYm7Jc?Ykq+or}SDWq@K8VdNzbT5f({o&L z8QU?F?;-Vo!Q16fw74&6xuVFGx7+a-nd?O5ld1T1IUUmu8i=#%ei&3_55GZ&*?wma zWZ!bfR;wFyzYB#k{cO_2)spUa8|iua1Q!`%Ex(+HsEx$rAwJS#{R_soPW%z5Ujy8vSuj$CPsTL)TPN=bTf@#CX%1&ioNO&BE_|$f$ zwab$7?iL}&r9}9W%gb7D&q{J?FMSarnej_+Rg( zw^+M^y_fBdo>MeB`gxNiZFDC;m;8=j(wq@iICrHOUH9K)--;GeZlDX4J$1$2-KqHP zl#0rzU97^Ayv#jTY zSMovWre48#cOny?2eq;W`Pm4T^TNlvdZBj12zAZmYyP=TH$9-0FH%)N?>EO-*?b*1 zODJc`pip=^(2lgs5iM>CBNLk)ZqJloZ$HjEgwG5Gb{u{{eY;)|$NbNn<1!Gl+qhT>oWTbdezZ!}c zStTrua^m`2B<9rJIx*?830f6ND`K7_O(VXA-|c*?Sn-U#`4Y`lrtjiiZ@!WCS}TEy zQyvBm`X=cOb(9+`!)8*0xKFIVArmR*;M-Yg?oB5sfAzzRL@DcHV~Ho}3sL2NPTZ%g zM(y0Fj^6&Hz6Ivk6PxAKP%e#1;eO=@_}hcTF3_^VjYI1Z*y_!mr_vo(Y6(7Phj?(9 zvMiE=u);@{8QZ?+zxMy;|FLDBzp*7APZ;`YD~qmXHb^+J1eaedX8J0lQ0QO|OS9V| zW5g`DOd;;!Gy|#O$eUc{m^|!SVwmKW2ewYNM3|MnX6&z`pJ-0 zZxl*BERn3S5WYbr($19QcAUI9w{GrW_eoc_-ER@rUu_U_t4YIFw-~c8KhS;KeuJ;v zAP+~~b8OsY%GdtK3ej3^mDcl#_4O$peXjh&hvwShZ); zYA6EIpeZi0J^P>5yhUiFrpqYynisOUf9S7ZT$zo-W?X5$m8tsb1@cW z^cL4&&BeDK+35ZA2z$I@1}>eYU9-b&aq@Kl?rwAFn91i2=U8hcfq8k2sCZ+C@%Ow? zU!Yd`D9HyJIVsrGyB8m+XO8-WSX{YsR>;faaz?$CCjooQ>J*%U)PbrMxcO1)kdzrFyAZg4FOqqtsqpC&0R~OVh zr~7qnS*51D2U@a&vGC$IR`bJ>?q_ti+Bb*+iPrckU5qI;MUw#|4`( z3;tM)sjg;Xek;v4)Qd5A?k1*4n*9C5Sgap;Q#=^{2HT&v;i|(&NxNYaEN4H)RxKG! zo@t3_?}d0VGf<2p{l+EYq@4Jw?5; zjTU@eu?IFiw?L1t(?p0;Dok%Bql)?sg*+R)9TkeY<31IK*9M_`Wj<;TKV!>lOfXn0 z6&C7eM2W5qYR0ZWO|K7Bg`FXSexiZ7(2SQZhF6GOJK(%3P?dDX`qy=KwF&kz@i5|L>a zDlM+L%S*n?<6wL&yVE6$A5A>ZFS>LQ_~Q-3uGZMS)rd(ZOrX7$8U~S$?pLNAj@WwQ z)TMpWe1#D7F{Ym_t(E2K&w<(n50q}L7kk_0;$p~RtWsI4TXga+uemKxe6izf66WCP z>uh{ZFBIw)0Vw)lhew<4uw3%xD=curM7gb^aGeXDZYJ$c_CWUUoIm`vfow-@w+*Mg zHhBZ*O$!wUW1KMgWiGt;<+E-#M?lhr7ANQl>NSo&fa7R)-$ zu3m`e(`t5ebH{;V()8&#|2++pj}MWk%?{?rG@W?b{!9@$+YPHXJK_F7%Z~9eV-O$L@l({J_csmDLl!bKQj2U}3#0$G_S>WQR z9pYcpH?WF$i4`bdr>5NIFONRq?v!s>`oJEo8sS*kYozeGJBl(7=XcceZo6lpo-`;C zP5RO<_0_z#P9DF@V%gFU9;i9D0PFftJx`Ct=@iOit`208GUE`UI2jehK=Tq-*dMtN zL4!-BmlCY8^iv}GC+%QP19V`%jB-j!8idST9sGQmggwh1==M2V&HG%ChotQst6b@c zWA+wUuKTjGaC8tX?EP?J+FKSj%aJtB#IRG_Bmy6};ov{<9o(?g_2YShtZ7G%s!x~^ zO_eods|wNc_$sz(r6Qbec;cke9Wf?_INZVuYDFfJZjU1nPcw%ll$ASa zw*$h4(Oh6ygxG0hi;qSjsOi3t#m;Tvs}^;FSb0>83Y!Zvqa>7k?IpsKO>qBeHj*Qc zG237*boS0bsNQW61``s`ivKjITjTQav#dojW{eWw?qtgkc&-x{Tce3fd5B-XoGIO2?T@X) z>>$x3FG(j4jP-DVLD4m_T|N@+HtYE8)Scn_IJ#I!!L0A5kC7#LkFe0533 z=$3)qZnIcPQV-Ny{J)-GmY+_UpJ^Cz>lNKSIhOo06>3>GMcQWaX37#{w0l|QXm@u^ z9TNm|xvy+4aof5~3Py2oiBS7YdZdgbWX2qkcoGjM=pSRgt>;l;c6k;|SQ6R>nu&Xp zNaIOoLcRA*F*M)}j0#`kZ}kVs#;(oy8}bO>G-Xg?YlZaRL3Hi|g*s*NtO!pz%758*is#a@)yB$ zFW$g3imfn$vNHdh&wQ&3!``SujBS3!-kKYu)2=1t53LkVn-=phjlI0wuAk(eoum1q zLBYJ#K3DWp@WSg_3usl=N_#5$!`a0fibE=y;yK!D*Awq6rA};I?2oAyskH0bC7BZK zfrm#j;dMriUw&YO?}|$hvSy7Krmz6lifFg>#*}G|N#_c7QeLvgUOdqbf|8>>;=F%J zBB$Qx?Q3rHq)|^qVYnmyA&WZ9aLoJfZ>w^e9Kr^7dtG6b`frAenkaGJ6{N2zhXQ-S;lmiD;%BSx$V zaD_VE-#<w&_dP zdDrrFx8#wm6UROm5?}w?0-W!jA{*4FZ>(F&M=@$Uj_@0fjBZj=DC+uEr6bFOc(ECgbQhi3VDbFYH9urOZ)5l+h%mibM z*_niGcbvqF&2~`Tu^b0v*06uf)A{1@m3&;Yw$RFnM%q+Q%EU63{L+aao^vpU<@)o_ zw8trp^1w~GFtKBgHM-RYVWLw2+xD)WOP;p#K3e7C@wvHZdYAzFRlUT}O~jO#kp;Dz zN0{=2nW!QjPPg8-ML~T4jPq=Gw816Q=iXN^*uM@|%4ud2;z0acAQ#<=6lK+ zA$y6>U!liBMmF)F_Wtl+yiXh=zF44A8iE~PNxy{xJ%gs8e$!16z1tPB%N$^?Q&!nc z5NGvi01VfCVRBa1*cldtQB@m6OlMadKA8p?zY58ksu4WJ*O;3=Jt{UIOymA)2f2Yp zf%Gitay8g`e3aY7*5>%Yaf2n69=Rdp%-`Tr!*j?zdM~LkXoif^LloTUgtjy*%GV0S z$Ho9*f7b~XQK?W>o6J&`TX=r=p7@dQRPD$9Y=(MO- zu|vAma@>FUUQ%v7maCr*<^%iZiJDt5+qUShZUxMG5W9~`b+ z5i@8;yR7#j$~N9030mig#8Aqqc`V0+z8fJYAPEEitQK-JoX{q_3LmO%Sk31~KD}`m zDy|<8j&q_R^V$Oses*R(e?H>-rFVJO@#i9pxXNMUeR1H4s+c&6xDC0nFv{M_QhtoV ztsg+r3F7z8nhX2s2~d9#BGr@_Bk$8vB>%e0cJ$N5P|a){mOCM)-w%WTD;Lb`X~oK4 zPr#60svSN2GMe)p@u%-wvrk%~6$*p$3?QVHxxS<`8}AOqS@mLc>T-VF_ZV-ozdh$3 zWmE-yB}SagR9=%6$8EYE=67bDmR68gy6C$t^!MIj3fo*TvVc5Vm77Jc95=k(LhNXj zLCo^o9o~EF7cNtMR@}TzzGK@6jG5&r5(0@YdpZw>{}iyj8Oo%aru@|Yts?x+bjTP{ z4qAw^^w0Vb(j_?|@eSj}q}R5k`@;AWG2-<2XGmK0j%KYd*}JtWxOsFYzC9&v|IGR1 zMUKEgzd=GJ+5tUEvQc)8_SBQKAxJmXr-b~ZXQtx?`8QQCL~^iqC|`HXv19k@O*72w zm$q1bWrFBI37BfGg>g8FV&IHOo6q;}@G=oW#by}8oXR=T@vUW%SG?=g?2 zSx_f^`vui<@$iEIN~`m6A--Kwe0L&(!j!OhM1#EdDdluH(Z{Wf`g_JoGZ9Omk}=w0&HFr>)n;GGaMTApPYT9w|{yYsUO*_c1o76AaX> z@whYqF*^c8PttZCe3pW>uQb{2{Vn{uUk~^x9}piCW@Fvm1Z;lOE`1R~c_r(I=;@xC z&!aCb#FKmPB|lVE__uNYuk)IuG1%t10Eh3p`^yz6QNFN! zaYbBx7=rfI=_oq7S2FNVAk-G+Ao1EzUVo6d`f21{y}w#y_i`qF^GdjFvSHS;EqwE2 zMa2rDkjel1*fGJ!-Ek(wb6CRJ?8kr6$i%I;n0!I;%l2dlDoJ8 z_xm#YQLWr&%zK{vLMmL_=A-MnFnm4lA!NzJ`$RPZy*@2vmyV6ZjEA;3L-|unbhL18 zc`D3wm8IW$#i5*h;{RoN^j_%=rF>^7Zd)u)_jkfs6%Q<*;llQ=RE1xH7B=o{5atmJ z&}Uu*COjV`QZ~+l;=361O=uKLMrz?F-3|No8X`Fo63X*(9r%N3ONGWN^7kyVLw>Eg z@Q9+h!LBgaA1q@NCNQ)qTf*jktr%TBpO_(G_;MykI@He&&%H8Xeen)+OwfVr@mSQp zJt(5w=Az&yim`_{+NVK~0aABE+z>;-X&FO}TmeQd6Zi6d<>Ts06zNK0-J+V1-JQI(4EGt8ue-0S(Fj zh-2eXFiis|hLZ+T&IVmN(R&Id(xmUiWc5vkwZXqE^z>|;Sr>@)N9x5b33(`uR%7q} zE|Qd;^?b-Hc}&eY&rUz|!HvJ>9UiE+PyO+m@)%OGU$P5Z9C6*p9RVjdinMB)Aryo| z?w2xax;}viX&LdaCqIkPR>q(N4)h!8C@vG<%rcEKWwx(jhb?1>xw@Y}-l;B%Peq~H z#uYDn8c9H!+snu49c1Ur4Pzals_l*(k1&y6Zv)R;0l3}Z&khzfbIpyvxa*}uLgH-< zVHb}9OL~cs-%W9`dMTF7Jj(9BPUdSi9p%4kxzA;DuHL*_ zyd0y2`TD6aGSC;=)d3i{%nDz153#@|Pt00H`>Bc7gxK{0Sv7AFlhv0|Fbh@;dWCNL zC!p(J3rwzx#QwDPqP?_yLtqtNb>8cbH5{S8ZM51_LIM4f{$6tOd7hP0lL#{Xu zr;eD20bPM7?b+bh3P}^?kG2#`Y|yM0L`Fh$v_JaJj*zVWOEaZocVT+|AH3{igJ0kM zDGwk()J3_I);JB?o>SSL8_oQ|!)}9qL# z+7_qf3($MfTSj>y1%~&bXR>f^lbOydCF>Z`Uu1 zHxI%viFSF#N&6%kDS`N)o{jA0AzZGH31!kHAZYPw(WQaj!;UNPJk*+bwIuU1E01!? zgayLdF##H0p4eL4m3c3J%rEHP=1(Qh#LFrNC@gWsqjRH0^=4wkZHz+Ww=HbN8x>sI z#?e50m8liRc(Wl6aVnwGu3wE2(UJkTK6lukxeR_ovM}uWanWg4Bsv>YJ=|%ISu0LA9K_U2*cU- zf#U6HI;%4?(9O1-6`7EBta}W+(I^hz)Pni<6g1sdkPJ4B;xXRN{P2=&p=wS(yL~n= z>8UOb{aFm7$W)Yh?q#Q+kj5;^qNC1lUto@*??cdJ*Ka2+apVuQg-2-qc*6%J3GRL4tUVaFb%4k)0zBNs_liQm_Yt$ z-|2=J(=!bt)#p(rAn_%t`GsCe6QEl5Clo<^)v5O`>%k zdE%n25p>iS@278&>QRQs;1!FZU$C2HlgDIwc>v9D>czk7ow4c0a`Mh~lFTh^;I85F z9ew-9?!mZ4-WY@L?<))5`{VNySB$^*f}OtNh*f`F@xoxExFzq3uj*ltS*^_OgiPSq zy$rdQ)+Z6Zzy!08#K8}aqOQ>aIqe0=k6O)QR8#ruFGu;}5!1w&p9`_@wKak*ndBL1 zU^`L08j|YA?;oLjADS%=xDqN93T$!i7x|tl{aMzQ7QT?O)AZX8iFxmg5v3akd&6F$ z?>$rWxR8k?(<5wfVjSrN4sg4p14Ik4V53IZVA!x_?95X=v_$FPj%tngTjhj3#5cfV zwaSgByx=j9@~>UH@!(cptRPSH_rhBu*4&*v4y`K*^}!Rj=z zA3y1dA6o-p{l)@YmzA@jS;XOXBmIqWoiJ1+uKemWVEzWluC0wQp70Xq8pb2*+X8fM z4a2R`>%^Ibme}t?8QhvP*|3kj5UV>APyXH!XK0U*l9qxgp#eZX^E@?AwIQ!y??PvCp+2FzoKgu007G94W;bBj^i6zG*9{rR!>#4{4ZlH7i z!vMaIQnACzTI3h&p;_fp&Ot4S~XNmj@~o(r~$CDhqb*g~4wppwGcOA|z5DLms9eR8dBZ>)nVgm*w^P z8qecymEI^`IuAeAOcOJ&lmGOsBT|1ZXWQs`x6urM^9Iif8<|D8N;;51woh1YPg9I7 zj>qKbr^U(kG(NX-FF(IvfJElHD!2V-VaKfI&^vG3pd9o~mujRJG~>`SY!Tw^E;HB7 zKB(y(h=SOgqR2WFEx%LId~A=zeozqFs0Q{c9>R5;O>pg89AXEp7FIgeu%sQ_L{&5P zdO|#Zx%2@4c+OaC{t|`E-_9snBg0Y(9&yUR;dWo1h?+#|Hx5vpA2LQLEpsD}EO8?x zo7vNsD!50PCDkQOLUpe(lG`Zb=6HzIZ8K$2nPs30vC-~DrttYckMORcU#0E~1F+;2 zF+_whyPq%-OJ!7Wvb90%>Q1>N+OBvobf47axC`{ohoZmgWy)HT;GoL?>wH18F`P%m z;cwL%UC-{;IHj70GriRL%h?R$jxWXU0|i2N_99&CV~Yod_t;YtIt;_p#Kio0y zcyDmdI&050=Wmj4movB50*+0#!mD`= z{GO#HZU#{o&(3^tiGe>(mMur$Q7_r6MaED$lL^txYCe*>9EV;xD6ChXBAPdI7P@UF z5f7n>d`Di;k+H{_b}rsh?N6-5AUK}7$bOy;!u1iUJ^K9T&z7iDi0sklACW&~!>m7xq3>f$l z#V%sV_@uCVr~M%MZi-2|OL+ZHf2>M#!RsydO!1f!G^pQVU~@C~`Aa#AOaAcYo5b_x zhvJ|p7xAGdn9oh(u#w*>@}DLivA`2?Q&$sHxUc9(jUSc`GDDxX=hgSgAGm-rDi%T~ zvj}&=k@2J@DVOn*JjxTV4TjyZNi0=khCop>p=!cgUh&-+8RrtwIM|ubSx+9cAo3sD zm#`fYQ(+%LH`?DkCZs)!*MY>HgHtR`n|4d`Nc}Z_`y`#*8ZpS%TMsJK(zV2Bp4rDlE zA1h|%(z?VXR>y`DwfyTgS4^|^=-J_oh++QdPy{Az?<07u2|&|Y>VNTQL=pEF+mrPH@ zssHvy{dJ~;OjU`(E~O2817%dtx@P0Mw>H~tAb}F+1!yD|ecG1A zg43?U!YBu6vCd{)jESCwI@{Y^gKq0d$Lvub_HT6&dE-^y`k~M1Pb~7Q9e9;LayM+` z$4P5yB>!{wr9+}L!zn_aZb8tMJi^@_^f77nQj8Vb@ROx__?4UwnSsTuS2XPx#+LZL z{x(l&O~fwBZ?0BP68$}V7frTp81D2}xJO!0OqL(^o)6&a`rdd-_ptx=`Hq?)xWtrD z6VcAi67?`0u2_8NbrOmxBDe~X#m>3}CJ z5KF_ntM1c&dt>5q?7u-;?k^MM{7Hh7;aNWHlN*|Lu0mL^Pojds3c{vM!NP=f1w2L1 z55=oYVH;5=o>mZqnWS$=jICnb^gGy*O7EPwYdkD37@}9H=zP7Kva!KX>yv|eTS?*3 zJ7b(Wk%;sMYxpqgFiKKig<~&mn5F*^%wGXib>HXP_C-+U&K7R+zeWDWZGvRfZ9&uj z9zXlZ9T#_dA~jWx?-qGM;Z_v(By3}DPvx~%;KR*+e zX>F{2c8;*?(i!27`(LqLDCvg-$Ws(#%r<7I;N1XOSiWrLODKP8yw?@qA6JO8{Ylfh zO&Kxc>#T670L9C$m{8uxzdWMuxvh!x{wmQ<@U%zQ_X14Xs4ToSAgw4a2Uq$P@s6@E zWOrHPe0n<@(e8=JBHGiIZsTE-BQWz~B${qaWa^2%;oCg~T7w_*Y4SFB<{t&aZ9e=W zc~ursXLs$CY{pY$AX-a)Yoj(^cy=L97B0bs`BLIi){55M=MXDhAzZxU1?ONp@{%U; zVf4Q-nLL;C*1EE&Av2($qeg7gX5P|lg^Jn;>dhI=E3a7L-yP{#cD9`5p3%ffk2s9@ z(99*TEyRJ$CFJds6!~Su38yoigkKkP`O1Di_(#JY8seF}RyhuDHoS;TIi=z)}xJ7h|*J z%o8S})V+z%F7?DY@|;($7mI7Z1!L&!P+Tb^mUUzh2L4XMOoayS5^D?jglOUnj?ljT z*#V2Ymch1bf>3r$9~o&G*wU|5WrnrpxD9fQt$ru{_Te*Uj0klbj z*b`$a*70r?#y=g0nW3pH)7Kxzq)m}Be+lm*&xQDj8@60its~HOW5%= z0M!YU;n8_nZO~3WtZK?7&g^0@&bq>|gE(kKWxV%&Vv}gnzuPg9MeR`*4EyN`b$>qa z_6QS9Takc68=biRVGq=uS%tEH*0VtsQ}K1bJDkk!@hr74d{(kXij_zd?MuudyAb?M z2^JdsTo9P!3eDCC9;fS!=T$*;`v_+Gmj}Xb$RtdTxz9UxQFrHtc#K**n4ev40_mNZ zc;#`FJ!{dxVq)El=-tYD+r~pfpB0da(1l#|7gEAzE(lX2kMO^g>8_#o$j&u3 zeBfjoD6|y!@PTgxhohPJ<8NKbqq08^pX&p#QX@|E{YVQe>RS=N?XRFY&>pF(exxe~ z@)sE{_?DTB3cH!?z>OARd;fk=2`}dr5A=~*n$e@-l-@Uh%#Z?_AD~9ZM zMNaww@o3rseKrOmx#J?+94Sy&wF^pxMxOH96h{{%;*5KVcKBo$*bZ5Nt!1->>qm2h zErZVpue`5_YtzFat!CZhpBxeF1#9v%efQYL?e+vic?Zoh4@q`g=mU+LLwYy{{b&x) zT1amyD=)rys10T%rb8(>lUTdcVRXR;g9fzmP`L`Rgq}|A^^PW1Y4oN!ywQTP&@%auz!QJ7#2bz3Dq>U9KE(jssm zW-CiL1vrkhz@GGa{_HsI*!1rPT_;8vX@L=+$lJWDn=ZtwMh+X(j4=Eq_1DK-voV3UR3WT zjW*ia85X&nY&YHRwM8@^_m*+Lud$eLfjS_hX0eMZvjnB3`a;3_&phC(3EsxU;}V?s z=~7!f$jhT%hm|ZMbsA(8-4Wq@kN1lUgYPR#?CI7P#gZrGL^=7)4u=TteSB zNZ!p{FiDY^y|Y8uj1hxy%y1&Y2H)owtxd6@BOXtrhw#F2^fvrKH>2|7>|u^3l<6k7 zTHM0>-bz4aKWEB#uV#_s_25Bw|0V9VJUP}Khljc&|Dr7Goa=`y`>)EIBB__?;X|&(}@x~eGgn= zA2f&J5M^2~_HXA!hKtCjmxkmiFT}UD>A|^cCX&dnK5(KBswgk_WG?Y1KZO(5hu#tu zf0-qDgs#2|=4ZW0V>Y~UE{X>DO%_E(4 z=Y%1LirHiGkjN*bL%SlmYFthz%&2?u?%WQRbju9><%vD|{IiqPUvPN^CPcpzy-<-C zM)maXq9g!ki$(Go8!RxhW&pzMm(uw@RpJ5w5oz>UV zJGW{nto=s|gE!Lb4Nt_1X)7;hU$4tiG z7d}s`75Z!4=c8`AAd5INhg@a&w2hSCl^`~<<91f!p@8MrwDJ1+9WL2qiiWfVT=j_* z>n?DB_M!r;>(#~fOw~c-1=5W(Pw{)Di{V2|)y5f4Z0Rc%40$WlGw1mVcf6E$heq2$ z@vIZ{nO#S>lld3fZVv%RrCo5byMb4d|KdA!Py9FMZ|<0 z*+zl7DoBe9Q@qdKlMbAnPQKNsZTz=O2o}8w#_Ge8?3QOANFDnBoS$rHg#zU;99ZJX zOTN%dlOq2A-Ar~tZ8}=E{D00j*et@Le(6ZOFh#7nyA?})IQg{8g^nodL$v+>oKHUc zntE+sL$Tl$3(T8A{eAOj9yReCCwqD`MI&t0SpIT=HB_%I#`jU>Og>8s@rJP&d9az= z8ZW~1uW2}NYMkiq{77Ni1FIfB{CD!%-K(V@%?KsF;6x-YZ3;(M$W|7oql0Dh%wc6w z&v)#y!J%2H*bJ=wdYa#PeAkNG5RCyWX8>+#sE3=2om{%jaM&0|)!^5ii$#PMS-d~u0B9w?;Y++!ng z!-aO?OD{f3DTm;4q8ZL4F69ZE{9s&RhbcNXO!>1iw#F*q$BbtF^N#}tPx2*p z$tH2%s&G`@$wuzn6Rgh@5q_vqR`5h4uQ&5S#kW;3N$M-A)wafssYTE{t0lY|AAo5u z=(aTAc{Ljy1l3MQYP+kVH~@yBli2c;vxKXadV-wSXTJK4 z1*Rn@A$g@MUs>sdQ_Tg~e!Q41{yhy$o8ITY+xTLeaEx7K33CaNNKM`q_cWZbqfZ2H zoI{@5{6P5FhOooogJ8C00=8ak=QDgQaJoJbHCrXPHvLx2SIx$|xD#xgk`^RRWc09W z_B4bc@tOt3R~ND|(t3!9Ux3G_Z*%oPcQhopB3MqL`uBVKr#;XWA1+OJ7*XIc_BlcFZ!v~0wQ0jo% zsWLj2^9mFAF!to<9bA%pf??|vP{nNUzA6mPp6hwVh)zUJ9ik&@z088P4Ta1s zHGJ7~k88YJ1fyPQh;Mo>R+iMqY{{AU^8FT{NSef{i}W7XE~~ydE)WMt`lB@RD--ED z;0*OpUcOz*P40H$+UMRnH;hH>NAy%dDvk+rbdT`Bp@#S{UQ(6YzbN zGSeM$PbgU07w5#~+(D0KyTuZG(donIH5nkKR~{xyone*X0Z^W2429%*T#A^5GU1N6 zA5+XOJaR_3LI7-veX1_c49D)AZ0zsoUYoiW>G8}TNDhRZqa#!UE7=G}9!mpHB&@l{t;=IDPdNi)a?3^Glz|oI zEJeBIXkm|y1)f(YB1L%}|9Zs|-{=;Ts-?$%eUU&@GQ+xs_j$j&5wKfti39z9ivHYv zDyVcf3U(KtaHV0?aU(+!9mHd=M8a&%wNiTI|0peMBc}W_PPR-oD)|D8IPM8^A zAC+zIQCHt?)+bM!kKk0A~v+P^4|xiUN(apUEMVLO%z*P{*# zA176do$p6dmx2}kNxsj9e)Gn3DeIm&uV9YfVJ2}- zBsbF=;Bper&Fcn}eF^>hFWIK+ia77A+OyA3Ep&v~J{sMF$MJVRY_PO56{kGP*=^Dg zqIX1Nv{5tnJgkn0Lh8O*HBRK)KSl_-V=YWq%;vvulXgve=LtC_-c5P9xjyM=b*4M) zUCJo(+J+IyBi3^t5h)(HX@1$t{2TPW{Smwh6iFylrJ(SUtj~jxZw6de=H;4#dJLf1Qtg^d(#N*KZi)8Sd)R5 zi^mHiGmP+4VhL7FEatb>sY8wOv$$f*9;60h(=j9L_1wju9u3Btr;e!nI*?U-{wjPQ z{YkJ~_L%R#=Y+8-zOeS2#I1MOlP4_#=6>;P@K1S^jWvYS?iRkaR3EEcQ(@fONPKO| z1K}X$p^j*zF$K9`ILK00F)mV%*A6zjY}icOnOL_~5hjnC_(|I5+cs0r(8rD9 zn++Z~FGF50rG0F207EXl!4La2^2t$jH`uofi+6Nu_m-zTW51QiJFh9Y(>&SeYJ@4) z&#RkBFLCVUh%b~WlZ+vr`5)r!hi&0yi-J(LJ{BEWvaI5)ydV>_5@_%+;4S?w5 zU#7W}Jn8Bh~q*Ka2VTUHvr$6Xi2SI7#BlBw%Nvy?|wspE&{VtU(x7t5w#@*^jh z{HbEGE#VMOyTbf>J&)1r#)cIyU}-yysdwE)Me<{$A5 zIa{2+R)qcbCHmfSLz>pv4;>1>P($WjEiSJl*AH3c0{-GmQTUCfVD8Kpji9b|wF0vaRfYsy)C<$%gI&tQhDkd($%5~cEx;CgC z@&7sBY?CjP7MvCgysnBLABuwOT1zw*-DmBTJ3P45656-6@}=jyakBO~9!G9qPJ12* zb@tDN#oy0z9d{cnB5hjD+LO0V^hU4LY}Ec!$X@T4g+N(IE7Ml)o1+2Nor+<_Q^fB7 zwo!)WEF`4L1*imT#Rt*w^h%af7Z(f%WW+w=c&Xq zen+CKBm~EZk9}~bE(~s%LQ|)nZz#9H%+6rEo1QOLrg!a&l(2M?Pe}@ zO!m9P*GUjRIX|q2Y0!I&H?lOSk2_IHnEuBIiY;k9`@HKB3rx2wM2e9e^|A%w+yob|qjy@4ZY-LBL-6t(oZD$RjGuaixRU_3f{O|jyclbEsGwajTE?BC37Sauma6e)n{ppN> z)4sucnXxOflMArxP&FIptBp+CCAds|g`4HV5k;Md_s15pA8GoiSDugIjkmd`uP2P$ zTzb4WRw2|sTk4O5w7={V`A>syP!>M7j$b3cN+{a7%YQUTF5h35Z#J#psH+?VVo}28o zP#@~Jw1oVlE!7dT>9f2z5&2~Ugl1w2r78KKwsIr&l2cxIXBZ6a4~kZJO%!XFp|2&-!5E5wEJHqa*S0R2DwI>|g`s zY@l&92{P?so{&V{dHLD6;`CH>;=6)yAl^sF7?H=lNq2ItFu?Q7T5%!e3vbP(_i9}w zQ!ytt(rog`_P@?W^j$c=KLrVGdqw%ZJz=#W5ktNY6B10VP)eqO$4=|`ac4IK$`!&- z--2z`8HTWE5rSsi=QnpmL4T$tmOuI_(wFKK9!zKy-Vc7t4;RyJztIt6e@pYN(w&f~ ze2eEJrVHmOlW3%@iMF@R+|CH0 z^-b|%ff4J_o{g9b(~wTNdzUOXyj$T2eNlyY--|e$nX&|4s;%rzFCC2ZcLcN=c;9>r zI4q6BYlRZ+ptm+~o0p9VLGr@MV0FCunhfut9NyItM~p8U%oiT9)owo6wTI^asBQcc z>xS%$E^PR@p6yj{7s3Oc3AW-he9i+KI7@{fZ@VXNBL2;Q`V365%3%vH%TnjI6?V>{ z`=HV?;YaErAz+VdwVQMsv~N^FZrgsLjJ&AM7ied*kLS8IzWBJ0`o1l^*scI249J+< zqv5#Bv_Y3sFrvyv@!tC!ah=|PW6Te-IByZAL`NZ{oAO@^G>|EgiWxHFL}TirgqC)5 z;rOvkUXknvU1_TxFTLV#e^f9}s5ow5Q&se!(QSffqw4w80vnV{1>sdro_OI)KbRNh zpzi4tHaUnm^Jb~I9&(Crr}y_?Y3hsTeOUg!Ik?Y* zib?9}huXc_30H`hlx=v9mt6ag%@~S>D#NwklNX}!4Y35*NeROhjqy=?F^-w9;!plM zW5(lR@?3bZ;*ub|p!e-5rCmJYQZjbr_#(@9BrD?Ig~sp?JzD*}kCffW_QjUO$=vpc zEk^hSW4~cElYFRvUiSJJ-M57YoHM|QMad`%G!)+&Oa7KsIXE}*3EN8S+xr&{5O*z| zYYmFV8sbez6}htQ8&sgVYzDsmZsM-hPS~jGMZMCS#LEVHW6t=bo}5(2RRNDSlMbNN z$gew@qW)((b}78jeo;l7*n@@W+Nv&OQV(zce~jSt@J03Ze&m z*ekt-U!eC+)g9iwa(D(mjQomKdwMJ`LeqO`1xuzGkqX~ z?jO$R2yf$iQX=uKlJ0Ay;h3pB$I^^O%&Wd5C@!Ks=b}BL&xG+&1G*sl{S8u#Ke4k1 z?+Y6PKlRM~;SJ_^_AVMvvIq06a?W@xn}@G`s+jo@%K4I)<1qDNuL+KX=YBKf|0!g4 zZ}lN$rcLCk_{9;*CRt zNcx40kZEWpcSh)4g7`o*-`DS% z`CD2;@Q5;T?@doL`$TVCxknxMl~?%k>Uij?60hcVxoCWtD|Ww#hOB~wp!muHcABwR zbZ!k_veE+z`Gs%{vt%dNv{`!=AFF zKn?6RPr^u_3Z8K@98N|iP}pk3T(svP{=!s@rJUy4JMQo@CQhYcg;?V>_3Y8@+4`R= zYyo*$%fcOc_I&9rW~i}`g!Sn)+Pyy7!LcO^$GE(3BtioULJ~HN&f(rkF~ldgK+?ne zY}{I399O5D=HPAI>O6hMU(;?hcods=kN*G4Jrp#~oa85|`)R|YK+Hbl!P^EBZ}MF_ zwwGoziAQqqeqsTWpDnz^m+s3N6~fI`PSwj_wIN>e42JY4YJTA7pm9lqbCrL2UFUzTChW zGAmaRXH7+PK#N$UqfLdf*k#=M0da5#TB4~~nHN+BAS!_Rq%1eE9mn<1INSs)AJuUm z@zVnb zW_}o!MZW(BV)6SiNmwaE`-jtvz0gPF znRKqQEC$Oxh~25?#%w>Sz>4$(1M-f3R&>Vhe>~BBVWZfaK7%DMm*GXqF*bfR<@Mfq z_ssc)onmMjD*0GYxtP^8gMg8!m9_2KY1QQT|CsQ^!hln%L>8;I~%$e-{7TRqtIy(gysLN z6g`{P0?$4VaA=4;{7(}@l6vyqk1OH6x}GpKTSmThEym-9!_##x)XLhp#vomU7B7X* z=Xc`ynw0;YqKIp!Z}HMPKg9pEKz4pvb$)gX(ymYjVN5TfgtXqyN)O!gFXi*evp=#W z6G3SgMLv;J1+(!Qf}hht9>R$s^M-OaH!bKgnwIMe5D?Vi+>6a)Lc+6ORSYWf!yGd9rE4=q2KH2EdRzZVm->i@?;yg zpv&4&4yJ397YLsTxu- z%1Ih&PUmtjyWl6+jf#sh!mpQ#R!bAEvXF5^iWrU4jk9 zIqX!FJjPG9z{kri{LS)QL1Wr6p|r`nI`UR4{xqM$rq6qY%rswI*=C0RQSn@Y?s|IU zk?tMs#U^}IrZ?tnJXq7jugrA7HWEMQ-u{O_uXTawOIpvI4|EeyH1+>;epLTug3kGJ zq4u4HcBE9ikWgyT(-r7PJzb`mmUy{+CU=qbhrFXJK3^zd3GVusU~7!z<~pvHV2h8W zeVrbYCoZPDgUt0zWEOR>3(dyZmY$4R(@t?If8w(ZS%uGf{aEL|x!5Eg+oR`bO(9QN zml^I(5sTwT`=Q&~1?dB;nJCu<#V2BbdkWAA-csx5Dc;k9heRXFM720k5kQ z_($5uOnwL9abOJF??HQlnI37;E&Oqg5e{@DqBh!4+%U?BzK@w0{O}>m^bSGxa(z@; zE#Y%ygK#_B3KG&b%spmS4?|;PX%oLn{?bX)s8i}~skm!k6ta?+VMoj{);n4U+g-i! z4vqX=nK8C&BxBdiXWADvNZWWrJ`F=bc&r`_=QVn;Kh#w{R4WX_=h^kl`Exa1n5E)~ zhwf!OCBYf?jsNv{NwPGqD)`#!^z8FkWrb6xDeHaJiSKP9A7Z~8RBa}P#_Q=Q)o{X{ zx>i2+NGx*v%~2{6MB%#6@nBmW;uD*NvzI(zt4;6y_Hh2`hAVEUc|rAj0DHB!O~9#c zp(*zOS1qSKA~zEMd>h1%mT5wkG!6H<2F~T9uqD_8;thpt?07@O-%&*YaloF*co9?A z0UoaM)nd}RGKtlbHvKpCv%8?%G#umKpQoH4bupNe$0q%z$iz%aa6h0cT&iBhU%o9A z5=$xty#YnyGp}OtvBVtivL~3!*eFcd>xjs)^}MVh8Y^k;ES<1Y)H%Eb`F`!N^p}Iq z8avA6QJ;=f32%__0&k{U2G?R*Q$`^6`5ZJKXyd_~@`df0Cj>bSMX~HwLpWdtB6Du> z{7J;J=p^3X@-5Y=lsj1bGz=o0KEmY~@`E(dZ!PgH7wJY~7p(q z&OFEm95cod+hlY+vgG?mxuKaDj~Zs1S=xeNq^;7U4*D8?q&N(}mQa@dX@IENpbPN1 z57*iKak-mrCWh_^N%7~e2D##2`aX`EJcE5R9*zqyWN~0!8~^r-7?K;4F;TiVpZMMl z^D2umcR&q`unvam9z8tiKaaoH4#RmhJ6H@}%}VHAY4yt!-!;9eJe<9-y_52yyX%-8 z<%wP%$|1&F9sfhD63LrcNdEm)q!T?;_>|x)bXDi`#(}|@5v+%mhik>x>Oyg>!4?yq zRI=48Bd8mS_MVnHUZa$OLDkFfJ%T^y|=e{YT^&0V=HJdqP%@J`S9KQyHiuXMaq+4VWv8_KcK3NOFGD(>9h<5nl zk@VY3*)8%|)*hIHKF6i7@=6nrF89C`IeUCpt`G+r1z|j0r zokp54<-y!c*J{6dX^pw!rC1s}T`;iI!rss%dUxk=-KqqHP|j!7yAI|w#~=3}nBz|V zHZCPlM+9{vrHe*rHtacZoddsKkZe z(!y7-)P?eo44gVCBUaekhAPuaRA%oJ_D1<*`*;h~_$2ZbNBm(y4B7wq!%rP%;_nUO zYdvq`b{51}uk=URnUQ?y;}9I2k_S;v6-(7-%oRpCA1+QmAdOye?7z2}Ot*FE5U zVIr42;s{yVmuw|t+1!naI1F8U-Eo&E(T%q~Bmqsg48&1E#%OxLqoiOZP;JYjh8<@?@#-PiIL)!&unsJ zp_}K3b^BU*pG*1JUJ-y#=bc1>^PaI zDlTN30t_+q^;`_py3MsrypU*Mk5BLAs_zhIa{X@~DD~(&~8g6c@ak zlnR|?HKKoPr36o39pTB$Rs6_N$_m}hAl{h~pVFQLTPG`=Hmzg^Em3&X>45&z>bW+t zwhq1yg3{t5QS7C=n7p$My~|`FTV;E9%p=?Q zQSnlNecLA(+?Ns`9&3aX%M_?{?G|tB_Cr7N)-Kw;g$@#d7*I`Kj`R=g72TO1PIM<- zpp<&3gOPtB6)b76I7-q745o_zr4^ese!G<~SoY%nidG{JF*_7YvCH!>eco7IkhoRGnlo zES@}6J}$@|nS;V{61<%J#`?Q6k@MpuTaZTmR`UATKU9DMt+Ly^bwD=!VWR zPaG`us*2v}fwNIjSYdseos6+UIO!%=P0w&Ux*JZGT?z%`hobgh%EB~DZ{hRRJl-}k z9Gj91aN}r$*p==h3XOIMj6K7)zw|`WD?94BxX2gWPQ)bo+s%tC7hR!S|BrR#d;2_C zIFWCSt(xQsxwD3UpJRhZgXrBva^%v5BVaI zLmdY@dwD^FSTO%-^(pn_JNj z9@{>!u@VO8n7kCZ2aa?3BiYCkQ~q;@Co71V3;&fxMplV-w}dSSW`QQ<>B6Erde~){K`fp^KD9In zk^L=^lJ$sXW&|K{y%~OP+{X3n$y?pwjKQK&EZ};7=(P`k;pB(>6?Io7pYX$iEAG7N zkta&#{(t7{>`=gs(`L}kY~jAH)X}y&1Mcr+#Mdjj=$3L0HAjyMiT(X?R*gFU$X7q( zOCWwYkoWkO7h_*2uW2$1*{)68(A5qzhmro0HjayMppc%Nn_o ziaX8@UWK-pS)z)r1YtTe7iJ`9^PLuc*kx>j5o;CsfG~e-raM#Hw{@&6g!}+|=}nhW z$LG&;z~&SFh-l6ed-tY0$g>w$1+9|JcR`-yYL;7BrF#00@`O*Q0Qvz`3)==#iPGNW? znG18`VgH?BiiG`%Ff%CPS#Mp@-MWnWa4U|6h!8+muRGJDAbn4rY~A1#yiwe6 z#s|rAvBW~(%j^#5BK?Rb?!BYzjI9|m#w8=cx>I}q7YEF%Da4aXO(CmyG_E=tp=8*b zYV~=M2z^Js^DA9!D`f{)P=Ct9LYn#G197=92r_!pSVgw7@b}$9A!X%Dp8mlV$7l}N z#22wQQgWDg-T_+it$g~{c-)_528(h*6d&1&-FwdA>((p6L}f3^q1r;BE}So1;f4vs zr#Sw}pEcJ?!0YW;EH-ZEcbP9XKc%k5h_O67#|x78h(R%4%no`3dzPi*lPl#GRim)3 z+z??+1;j5kgv^AwFc^26->~<>=O$asj*zQ9AW3~7l(&%>@rMQP42OLy&H0V>yw{8X zd|iz|C_wy;j@eDz5nq9=}Z1hoNoq>K&40)7I3M|K2;mw^&mPWU{Qw!`7VphlJ zIVU5Tbc&s8ibWCXE$~>|iXA?(q*vLaZ>k?mT-WhdSr?>vC8OMN0gDnpzw3aNxsoy79txXtgV)d}tOpU*jj3>r}GuZkP7FXv% zT_;``@!h+s@qs&n-iBj%^G)WlJrsqs+dH4D=arOO5yg$=px-Ku_cxN7; zw=)#Vk9B+4m0o-3KKz(?za7==!_`QfA#Tf|Rm3KZ>BjxHZ}8{vbY`*8111*Kq0=}- zxcz~AcI0#0(!82Wl=xu#%D#P6i($W1r9S3U;vsiCs?D@0+A83y~q(+?#YLVpCjt~!c8UV?0 z%X@CJujrn>XvJ!b+kT4|1!m#QU{_)?yD>fBrw`uPF_{8uJ0fA$q{&&f3$>$B+6=-TCdL1cXmt z4$WO_*Jc4?B{FWe8S4Lc$*a_n$VmuX&2-y$)p^-qD`KY zKCb9x=FLtOt3d6LO3$4CKFR@ajs4&_WfYIgh{rCvi8!~NXS!Q~N#ygmDr)4TwvkV^ zWEJ|C%oer2iV$Y0=?izRWpG8(=O4Kl<6M#=KeRjmmuEQ!+l=4hkICdYxfpkreOu{;c0Vtaw_oHH?;O$hi$9`14AtIC_w*5cb1>gX zM(CYshR218m{3;4Z+vsZ%Y7?hQ0K-L-Ob0ALSlb>ILB+gMdGnE?W-FGvD-WE3txyS z-{1`Wg$=X7wV-5#8+K`%zjB7hk>$7&tt}i;49C`Ux;U`*MfE4w z2<$&;-NQyWPcybV&!%U$f4e4*Sfp{--(Qi{%~uxo+AiqvULJbo2c3-O8^(vH zcO%=n8$Zu|VaX;#;T#-T z&_;Zo``OUeY8CyHFirTWt|R<@w2Ch-*T)>nP^8-%@@I6DKN9UqH@=JP*q0DIJZ*t} z7i##v=0x=J3&NX)t3(%5TA*yxf=Rt)p+Xu(#%(`L8&Se@gWRxFH3h?#E@XV;NF)xT zjK`cdo_b-WpzTm8xGqu=r=6gCDg9oret45#q})*G2@~u%xTU)25OshuXZYv5XC=F+ zLuauomTH&sw)9TOBz#7v)goqlaEdVIkE&pLavwMULw%Yj;_+gG1z$1Q77NYtp#F9Z zn@zfR;W{AT%ynKE6Ap_PR`A*3FDhEr1>3Q$2pZ52x|ApV@zWJ=lLEMlzZ3Lh0x%J> zEURqH-8i<$Fy>hMt9x^01T zKZ@Aqmmc)@A&!+X^#&%mpmA3aa^GHK9dg$22?WvxKOC{}@KtU%xEqh!U*n%UGHhgy2kv|e z!}5$Fg4t1PTpJvL)GMpG%%*2}{&|Rw|KfT!Qy7Wyx*Cu=dynU(#$#=n3Hh>qiKfqa zB#fGNMHoHs9tV9Uf8C%g>KJLh(INwd3o@{y?@_kOOc{?u7f?o&{3LX%Nk32T&FK+h z-%BA_K6WKWCx2v}i>Jzbsc55Bqp6fszr?L2k4cfZyE|^9Al3tzUQF^2gC1ML~ zEH30;@>%pdO`L^iZ`gr*{&=HFxt_eO{P3hudWX@CWY=hRXYK%0j30ohbq~1odh#*l z_+fm82al)U=nc|280fQ-vMMw1nfUKo5-mJp3-Kank0faNtNF z@!U+IRFKFItcb><3?B?t31+M8R4_tK1@$i*`OL-k_^;nxw0R^~;l!x+%)y?TGn5ww zUSx$JW?mx?*yDxNA;mD%oFkGt?=Li|YY89TC2(Kz-n_qOgf-_C`S-FwbZ>CP0sj)# z7-5JTP4qi7rjFlKazIj`4;Eg@6)#&(x$oxe9`9xQH#4N`Bw%&(Nv?5$_^ZS#4n5X~ z$w$w_yWXRr8r8@P@&n_fAB^AyR8!!B|hQD z_!4d512KYrXHbXDWTB(l6eF(1K`Le?KTCY4L&T20v&x4xjE%u(TLUb9y_cW&ONGe_ zSFGAGoRvCt2)>PVf^yzf9%AW=tmV#_d3HQMN5B8&D~K;PDvr(dQijna;GW)H?%!<+ zh2HT!KAb(L$cuC~8{3_pu?pgbIn%SwSTddWxfM!UkU2u?ZJ1N)95m?5VvTMS518VP zn*ZKejT^<$t-fFnqTpG(hpB|?A;zBc{J{-;?L-T#E+gMF?e-G##KT*d|38w>!lBA- z3*y+V2!e`A*eHSmVjyRK11Q~{(%l`BqNE*I*n-^+oNb_@peRTg*oc8*x4w1H`vcy6 z-Ycwc?O8LwL7eFv0eRsVx=~-!Kk{)o=s!J2{jC=+yW7CfXA7^6>%^L(H#m{G ziw$;D6UJ%l2xc9xIDcS`6V9P{R_eglNBN+ncOJY$SF`W>6Hz1W0I!cNd|g>G5_2ij zct~HQXLXPANn-S#c2&6W#0!Hcm$%|a7(eOWiKB6E;Cl88GpM1QY11$i)4RL!iUZ`H zL}7B|06uwvKF)njf{aHKU%xFLQgcnN@#~1&Bol}`_MBgJR20tWiiDny%lZ3D3-J6j{eGqy@toyLXb*LTShk9# zMubwIvjx-_6K5m86X^;MarZ($rd!;Cx2;VmOB;umqaAV0*$2D7tmSIk|MP_=qIiT3 zOM4@YxY6o3b)uCEVGD4}C>^ES--|828>4IYc+y2{d6Y8o34R*m-k&X%+D<_TGIYjt z?+;9uvN&2JTv2>?1J_s?gHbedigYfD`b<+4cIavf9tGsv%(H^EV=~-LZ2631E;zZU z5Iye}v&xE4Y*7Y%XK(Pf*a-9#tZ~21U$lO83kDWnhsM;e!ghDk=Qp~b{I(x&BY!t7 zcCej1jyV}iwmCB`gYO_h;R08odufDFUEt7XW9McP&DWO36C_nvsoBY zJS_2J{z|5i<%zRrh?73ZtK4OT8x%?cF{+}P{Vuh|0FQ7?`FD zT*&haH{zvz3N8-sFHC3+z>^YV)Ou{^Py2@=f&5@os$|&RH@y)+cbEbD+xP$@Cln?6 zNOT+XMhCPJ8|TQ24E9l075|h?QMkRC&-^_fePb3u$xubyJ*xwI6DpxydrUAUF3PJg z6Y?u3a1HG!1ci8_=aK++)KeW@(rPGw(7>x>DSx+(G6|(axj!mn^`+$ zv8PlS!o94H->7!Pg=NJ1JDMwY)(F9iA&b#c`IM=5nnPh(94dyAr|8jhn3N6G|5KRD zEY@jZk%|oL`!?`!$_m|mL2unYT)c1|brO-cCU0RSTMtj<_i)4C#TWQaw5Gr^ujKZUOnbmf=2A!Bb?PzK8NivZGlVf&Sk!Tn zJ?YZN7{w&;=}kONJrP64nLyaRjP*?=_SAKC@@L%SZ#8{kH;np~$YVK){J@ckUZ`@D z5_I#NvBTFFt&b{r?qvFIZeC136HTICr<4VmY9_=yU%}@cr?=yaMF?BBfY0-fMiqS{ zHP0Sp->H}8^miL9+fc_des|*bpa)PW?#Jd#Zowz1M)Dz3pG=Aqa;W!YlGsoELo zXZ?8H6Uw}v^ue*cW7(c#(rEjvg8YxIyl15)wx3RrWU2NKb3=V-AtpS#%<_MR;aHN>hrw0rw0x` zUW}vr+C|0lr%``_yFmUeUVoPK7=f71)HBt7I2MnnTdPsEf*m#^AJ!ORS2fk~F0D=s z6~Ce$a1|CB=8EB7q&0l%Eqpp{i&gYa`)a?MS1xr%xMmjawHvSn+lS(u%N(TKyU#OD zr(g-ae?C9^CvyDqR!~`1E2tMg=N{9&QKMxAlhevP`gR1asS{_4vQ&zz)llt7-rYY9 z-1M;x%r6IHu~MkG`EVd2mgi&4noic!l>XlKq~T5E2`)b{1A`+haq_+`!yGL{?Ny-O zpu2q3M9Rv&v&LhegW@&q0o3{61HSeuJNbD5nwqR6GykpF3GTC^pp;UqSDEL9s|HJ; zeqf4FZEb?Od&HX1FXEvkIWXDa2%Wo~Y{4VS7xy%V?yBv)Kk?r@&pV>fekePl-UrQz zJ<)2~#($C5y-UX%18hBb;2$MO2K)1q1)2T>0-oOv)xnNGUkHlBMxvwX* z1|-t&^&vL8uOWKo1xaT9k5=jmZ_0-4EM-xK={>>S;;3-Y^cA<5LEn^NG~Y{9`9P~+ zJfKdRt2ygg%UWZ|>lorha~%&YqpVMz7rM^midSfdz;JXn?DQd7Y zr5}s6P5kL3GxVc;NU79(@tty4lujzZ$hq&>dL9ioW`L0)S$s(~^^tA0z+_E(*5W$@ z*7alYj951V*14nnsuQ^1MzPc{nuS-XbFJ@bcCThWQmTkYaPJO(kZ*;4^!-Zy_d>7j zsWUo%=i%SKIYLCre;wU)FQ|E4`O+i`a<466@#6&xX{9c$+15xowS}Xg6K)r0KDTnOQD&fUL>eR5Yf_-Wj-!;+?e*bm+EDm8C2M)%WVgH}`{e7s5>R||S zZ}#QA4VDzs^ zq=v^Hw}}OL^c+MwQH?A{tV3 zlTgg5<2pK>m@uFNvVschKHCkyNTV=$+gp&TvPHx+>My&piYKMJO^GMxJKZ9m=-A?^!8kr#DI5D%rxRcAI4j$$ zhO9qY(7M~e8?M{I$vPC#AHu}7ugIrC^Ves=3ugD&7%3O%@A}9I-f|!fS&z*zq|k=- ziPVDBVg-ztc$Y7n?t@2Lte}*BK>Xn#y$O_)aqi|l7F|w0;i=@Y(Yno>KZat)u*K+} zv`6ncy+@zj&A}dnDZ<7GW89ve2Iu%fUh0=g9n@9`9nsDdW&}awgAqRO-_E_HLa>c? z;uTp#*+HQX-74O~{n z84V(Di6>_VF;Oy4#^KkA11ztPA!M|IQ2n!>r>wNV{3g1^4^t9F^u8zfHy#!?yLRwN zlLHY@Iv-nysq**7!_b?)d2+Kiu)DX6@mSgb_dVX8Pba*0oL@xVaxdX9G)tf#ug758S)egC4N);@wO`Ip%=d(v zZy|QPY=G_I46> zme@j7w}rn9%0@CV8s6+P5tYi{LsRm3$j_(}-m6j`bR4m7`i1cU#(wyDf!>5KgW0{m z_l4z^&xAmw{d`-LE%emMZ@Rw^cUa>Lc0L`R`6t+(NrpJkGXWdcHFC8+aR?!pl(pV{Ve4oNnAy7zHXJ2~BV!>NAj90nG`?(uYXHE(h zuIm&Zr8}5$Fy)OG*75}M)E7N7f@r|jN>9q*ZdyqlPVyhvRojK=)cYRjWqd%s1%`>E5qHFbZ&Y%JcK-rYXB4wk*D!SD5~GCn{2R(K zctg3BtyY1e*m%RURo=^c86-hR(h{Up5}^YVT0scamZ`+g`IyQ^S|>^<(A zK;P%?aTr)H#n0C{BkOA}`j5H50?UY5wOWLJ=QR0>&Im-&dqZ>8N_OBIbpRDRW9w|s z@@l_8=oCc4@7Nu7c~LOF-6Tz>s)oCXsE?&C1wIEJh{Q+Lg{~29g5~U7eq13MIwUdu zH}eyssWW*Jap3FEvs%hDD4n(=Z`f6S*sBwLircaMwlX`gnsigj*0z=Q7G~4TPc8_8 z&&*ZSCqfLrTUk)+wSYaDBTIgk**I_bfS-G`2#HN52(^=9x!d0hQlD#t8P{L%q-lZh zyFj}A`*FNfIsiV&o|rzMg#EfU4Xfp}@c4ZLUoNtPT=yV+XbcfoybM79sl?20dd<{H zKj`Sc2wTlg@TgxIXcL(uE5?>BHP?nl;7G}y-*UkR^Y>F1)ZhK$L+ku0)9ir*qpR4p zYetZ{Wr4XpZ}UJ`>QVPwjND75dTWXIdr&_IS-w+*15-_L%WM(Kw-xe9GTFr1CC1d( zmuyJCcpM0_M)iTceB8!3)L!vGKVdj~I-@VXZ0><~QEmK+xhvk^B-U7vC*MH5Cv#dT z^lbiV=%J}T~k%TILWpVeQ&5$D|l}~A?aGN|EGri1kx+Rs@>`uek z=l&QzIGW{u)xeIQsxVtm-K@kDTQBR4A(=z@29JdpBOQ;F_XpX#q4QCg5`eh;dOlH^ z{GXWxh$@^Svfp`6Fp~NI%wO^?2>P^}{&}IwrB%|`8(MY3lrSd(8m(`T{|(s z8NW0=Q93YJ+^hP(n`{geXWgamLLidea{=!f&P?r~xBUMzKW6SssGCZo+r$Q*m=Xjz z@AOpa46My^J3}ZAS5TR-)K0`a#D9feT{G@{g zW|7{qh)KF-zr7%Dvx*7U8rm=q6HRRMP=VIT27YKZ`C2Ih^`EvgvPU4^rG&%qa2fL% zZ3L$YuK2k94nP0T2E{@=%+)1zh{*Z&@dE1kp7m6wG|9be2VwSb&Y7;o7{EZpVpc$gB*mhY!tpzDu? z-HZ0}64GNs5l9`7eYmo`E0!HkNB==5*^D0ab73DZne$IBWMi+kH9S_YW$G=|_d@-_ zX)ZUpWoQ827SS7z?z24&67iipe4fwy2?^Vsp>d3u%a70VPmzw0>I$LXy^EsipUOhF zZu2A>{+JA7>^qQ*K4<20g9S0vFDf9V^$45o7>mgpEwQxj7N7Yt6zdi{5RWBS=3;vZDvm=XgAbz}xU0fW7GnVr(wy>Hj^@_pg6nfi|_i}nv zD>QFb!M@vPq4pZ_p1T}~W#-4T#yjKU4Eh<8R$=;`4~5O+KM6kSd$@=)USY(oP5b*# zJg`5#9WLd9xnE$@4@6?^9T5U5w0QO9G#rd2Zl3%`cIc-!=Kpa)L4sGgWqAVXcBSFf z^)~jim^7!TB}lu{z<1KmXFd7owB+82UXPh3c&%{~ri3oxH;F^wbAn0qoC4Bw##8s@ zf8NU$(krfb+QC5k8lS!-8l!&&;o8t$qVbKSyZ-jZ8oS=YSJHO2Sw`Yu$2z{7zBR9@ z!*th7BeuUy79Ym`f6n(9yO-ACnv&iAVSqhGms9@7FjU;B8I5LEgjH^z*+t6z+}n|iZiA0=E4gfR zn`TKp84gTqAN9f?9)Zd?4SeKCVzmWZN;nC3qOuW@L%Pz~HdZ`@yxZmGIJdEm_c-B% zpCames92|Wm9#yJ$|QW~RlxP$CnAb62ohfXp-2o|WQrR(ySa5lEJB$Zx@6^9#k#(D zGr9+!dyt0X>w?+7q_>y5^J~OI`_2LYM@ToX8%Lq->>wWVGaeDV9A!M7fc<}a3 zc<~|*vs;6O_3jbKr#VZT3)l8c#(2^`9F43olKF@>P@# zpBYHMk0%Z>`R(%|P2aFu>w12U_O9t$Q;6-ZAliE3zR*>ENci=rgAZOB423R3Tx(F} zbK^qMjW_~QY3o^8y9qp!sbY6*9Y49(8T$n4M(S89UZdxUziss2`e_3*jSIr%yGvoA zTEmCTbimiv#ker>yJ*hjnUKK{+{muy!Q>e{KiUw_H&=+4$b{f;jIG3nlS2GtQl%k3 zg!5m+7UE`|uVl8LCLiMivk3I>BP$f?T0?(jG#vIU=bLvrqIX3OzCE^PiKMZ8{j7)X zmV3Cfbu21oSV%a=gXFuRb4-V1pEv49o)hv9{dbc+RZhR7%d=3>TENC`nTF>d=0TnM zq)zvO*;-ZR>Xa$QScX!4ScAl>?Ki5^yMOXq>4cPrnzE!7($Qy-w(OE% z(nYM=a!c}jNANMz6VcU1Ec=pF_U*%9>SZ2^W%>8HTrWFZ-RqAtefsd2#l)yAO~VC&rK_ziy+^d_HVdJbFym zhwYVP?CyDD7g4_BV9Ir_xFrnz%IzhyeN*2yXjR>%jOuvQ-1o+jJprh7*u?+rrQWD$ z;>!J0V`WCeaI}Y-#BZtJ(}cP^lAxX6DJ~+WO2b`c^i`_mar1+*?VKT;YPM9mCez#E zlpUOFyVyn(FO2DQl=$i!q$03`-V(|)&x;OKD+=m$YC_nzQtrLN4v}H;INHyaCwP%Y z9caG5HGexg1}Wry{m*ZCd08uZY`lznfu97AgPu_KrhYhIKR!Fl z1yy4xlb)->-UQ2%CZ~*ld+za%@}zOPCE?GL9(<8T5VF>fcOruQNO8L#Fc;)o`H zb36mgj`%_%e_ZoR#g-U*KzZ+gRq+?Xh z6H)bebwShDNhsaBgs=Zh@5&2$NK3vgZkmvY_;70+SY5$vs^YLn+8utXl#y?Z$Kv&& z;0b#~=HyLEw4mPki@k(qWqaZZ2B2`rDy~jB$irq?u=QKOCTb1C8uM8at$sxmY2Ml< zcvL3Eg5GxtTGML;mr3osnQlsJCR#v#q6*(I)*sgNHkf>VGg~)79kop}kmcXNw>sKG znLNkZPea6o^!|PIyZ{!Yt;Ievfx?kw#2Fsvs;8(QtdabJ{j6A6t~TC@MnGq61GmWX zLrJs+&h9)Qen@O*ljGi)>s-x_6U!xbuQ_xp>$v{=NcgYJ#wO2Fz58v?vF$=n{l5DT z2;)i5JEoF^(3|-@wObOdjxogFK}DLu*fWq+gI{-}U;^PTL(> z+a7Y;FV1+m+ye_oxO3sJ1E!I`ymx0R%lDg#{SCyjsA=Lm3XHL$UlPn6l*P99HlrVT zYt`0-3VTX|@sD;XLzQ^mFDMviT5Zs`mj_E5HyugWC&S@aJ>P6W{_Y=MnA}Z<|8n-i zz$tN(9X@&Md@KH?B?W73B_`M#aMK)ETaS+ZH@J z3(u@Ri@XNw!0-KFr2VMpx6X&+kKcSe+94*EYy_-V+T+}C&XDg7m936Yk-NbEP!4O- zYT}Jhmg?J5H%z3P#J+nnLS`Uw{-ueRG<`XLILa2kx@Td_1~WG1S`_Z~(}VlGJv_&W zI(MqfP`;}VYb$>w4CdDaQ(WeQ&v@bm{kweZHiFMP6ou%_=_R?6tcBCM$`aj1 zMt>pHW9{)wYomBlT?Qtf%EDd0vusu$WB5&ThDU#z^G*&Jb0HqLN;~wXs=DF9s-+lv zVYXn99f|7x^C;W$vNF~@2@8oGeB{wQ#&KM`_dUkFaE2l=L>cDQ-X578fc^VlQt_?5W~cl55aryCZa z>uD?^iPfJvI}W!h8CG>GV9URfU#w;dUYg(JP7QvzW=dJ4r16!1y9Xffu`9wJ|7CT= zHrY&UAO{68&l~*`+T#!}JuA8lBreiyetj>mvPSDf8O%z;~L`P_SM7`utG z@sl)J-GN~ss+wenkA7={qu&!HJG|lxGh7*_3{4sG)q98H?MS+*@RCZkq2UNBwZrBE zAJ|V~wBMGaeWh>%@4hq>^$x^X@T(RT_g5Bdzp4r2%gVTRVKAz)mqO}Y0RKJO2B`s= z=rdwDduAE|8+l!cR@3?|6W)KE5Vs&sbTgzC9-}V7BK@Oq!`d4GL5^5!AHZEaUExnZ z_hB1U*q|S>aCxI7ne+X~=W~U!pq*uZ#fJ24ue-Dyb^$dkyetx5C(Xm2OPXABUKDOm zF+uZ)m8|_N`IegqZ++&{^&JUPw(9E)EhErZyj$Y&h!q_%69}j7JYZo z6y$ol34hG<_`k)ZSvJli9?os?!IMeYqffpr?MhZb9p7cut{8Etj+fbx=1*QP&GtQ_ z%^n^|TI40!;TMuG_t1NPEcmdJdm2)wMsX%~cFboVB8TCii4KnH-{%)A(us3rgs3@E ztSsz4N+X1$p*}&Tqb2&Ej5pGna?qJeq9g2iVN8D@R^WO8!nmi8XbPv=x&Co zeGZ8IKZoJHw--#qs#)_?>dWgvxzPpGp+kG)sJj8U@Mw)*ztR`DT+&1TjLZR{i2O3i zzZ0l)cPA^sK##IyCMmr+ugClZv?xk){nTR-LSRgA=jDY z4z=N)IP%$pf0U+9SodJqK1gGpd(`l)em>G#ns|v8-L|UY;ks8zyj+Ty(3Jhp?xQdC zdPi^7XhZbXCqLw%1e8S)&-`d0i&U6_j`fo;`B6Q8v&#z=r0-pRC(AYI@8N?Gjje45 znA~OZ7aj1$xVv}w4RZ@n;VG`|93|?sejq$7KOnqk9sH?7C@KyZNI1s5>|^lst|R>4 zY-D|@GkQcV!@Jg7JhI6JvI|KAJ+f51V2uYx)r8~6zB??SpAF8Aj0Dp?#aC%N;iJ}K z9C!RK+G(MKNQJ?$Bwor#x`oatGLZ1ngD}1nWxFa^&T;MscJ&57C z5Rc9b)D!!=BP*A@^-pC4waKJ0&x^!PmF4_nupKm?XX3_hGiEcE@~K~S5!#2kWeekQ z#?B1qUiD!+PCpi=%(^DTXI|!muKA)!k66JU6}Z)Ztl)nh7`!Tym8PjyBHg>S(vDkFuh#70nfQ3Ah+UmI1*ZzE(3a55#ajyTtJDRjmpO>~A8y6b zKPQp1;-X;O*B>4O%-}2^#!p3%Cu)})Zubdgn$<(#RwIo|2KRa3ILb=y_a**9Z*D=E z^1n{ht+|V{Q{;0SUK@kziH&@8&SKQ|vA`JJwQP#DIhH?G#g9QZxzCh9WWG1Y^PLka zM_)?=tBb^x@dJfHl;3ovj8B%dn0v&x|LP;{D7pCIbtBaza{}ct|T~maX_j~y5 zqc+fKjl|K#mOOW%Ev|q%%AJ<8qXiMT(lrM)+pD=*cs6{WQ6|wQLG<=tD^d+EVvFxb zp(cxRF51-ZdCr#)+2DmIYNXGXOkk-2!!XT2Ns^i6^LNN9JqmZGkD`B1a>?RiJ8wc!Dz04l_#-p~7^5On< zJZ@$@98U-0P}eR|_}GQmN;k*LNE4E)U-pm%*3tc%3{WcSU z8TYw~cLr{brM*E@imm_mQ79UHU5IdO=Wl`n;Z3}zr}ATYs*^wLDu|h%wTWFnMj1F2 z>UlS5;FDE}i&f(Xuc8pK66Nw_!;ZhTPUloUc z4oc!fvYA-4WC50r5rl)rq3FudCr)@AA5fo&i;2{ux-*FN+dTvGhbzK zl=qu8gu9!NA16H;GdCS%I?Iiq^TS6n^Nlp=%~YL)S1%Mq%H7(8Q@0KX&i=3X;EE88 zxdHNJs`4Hq6L4=gc`q6_v+P(iTzw@%@xEI;kN(*iD_wDZ?^5yUxt>sH3`1ka9hPTg zgXZJmIC}OZSM5gmeuqrr?0*uS+M|Oomq8K@XJwyI#P-#P`L_!3!fjFbPRxzYcbv_; z>W^6^l&cE7#D%X5VLmWmLQ{+Qt^WZfp>zs#C|;^mMenKgDj74|hkc0~Ckf=A+ER zaq7}i+;x)@xs*2{<##vzywnrI)}hfjykai?<-e?S*prO>k(R`gdd+@br*1ytiAip< z9Rav{$Qe^>6j-!)tniYL6^u%oc*`{hjK1rOCo1-Q-ijEAc|JOtidp29Dd>5D_+9#> z2M$e#<2FOIUx(=8iB`%kpFn!Ai^BUxfAqFD#RiQq9@#I1yjR4AdmPIAG^KGwOBxT9 z?{lq8>KV`VMY~)du0?P6-Zz%OHj*>VXd_HYh?Z~?rmRZE@+11V?X!$Ioic}(lqz-+ z%W+dZ-GVgDu=C0I%FB~dh^ZNZUPt>0GUb%Rt)!VhjdMkM|3352#*4~Uk(h3>5$dyq zPS+wHo@S0+tEt<_Z~>o89q4t`ucO&Z)%v2yw^ug&YE?N$|D^&5yp_R9&n_|bcIG8+oBVKdT zoP3yy)CW<+`%jI8V(fhUa@$sUTP7OCv+eO~-e+be@wNO<#h^Ljt%K&HS=s>9|s{jQxE|H;PBIacf~UH=3M|-VHX` zWf3X5G@%2%JZiCNpAL!h4RR;@@(bT%@!==&fEH-6`eVZ|BT-RulU;N>5F7R^ zhR=vWe2foqEEg@uH?>;kUPm5m_qmjn(&T%IyQn+O7-u%DWG`3wV^o+EZVmP>Pc`wy z5;I?jy>C#z2HnB?_(8^y-r!2%(A&2ZgLAt?<-XGe=VcBOJ!cr*1P00IqS^emc%|AB zWIQ82Y}|F0pdN~W=$jMtE&MXOQ zYL9c#w?#NmWq|d|Em*HHI%sv4m+bjVuKB~!$W(HZE&LMzr;E;TE4;)kj+kJ~F%$Sc zxW#i$xMGD&Fcd$o)7zx@0=LI>*Vm}sC$#38!6rCCqTBzPnuuy+hL}gK?C`d5oKrJI z@ai30lpcenNe(dlC(9IS?h8fKLdc|!@hP$%m`L4$LtlCDmSk6qYz)Eg|hV3qQ=j z(4P~jKdynlv2ev>D_4x4JcK{!7l3WVqziU9!Zdam5xcWhb;nH>@`8M@=V>P|ILUYRazIVLOboj4Nz^1ii#)#r@j14h?}!P*<2yj< zic0ZT&lm(#zp!(~1@=QO5NZxi5;jio6HkOYdf>G4K)uliyfLRf0$oOOf^NJW=A=cy zXT@?JOIly`gnUe~a%FcMW6(o$F0Ovr%}xx{@ze z?Xp8=`bZwPx)YI|Z^%a_C3G2TVCbSbFeFxzd^|A%OCmAf&RATsa3R*}6MtaLTb4gO z8Ykw>fu3F(7mKJnV!ai%XSuUJQZu1CTM-ZUH1G{0ykSTFfr^hC#Es++9CsrMvpyYU z6BbZ5q8o9~|JCuP9YOHcpl#+Zu-YBoDlxfEu!b9IoR*_vJ#3*&^eD- zdHa8`l>vdcwtzCdAzS$Lb-}p3m$IC)qgm2l6~XtBvY_(jF0YGlfX5?mv`g9X+|qWK z5ACjh{PqwbD|RXhDZ3Rpvzgb{7Qx7!I;& z4S4 zcO~CxsU-Y9pd|zhFW};bmZYC0VeNS%?x{e&$|7C3)*fa(J!8?4W(2#(HM}e)25(81 zD>;@Yl8tY{suS1odl}8^b#53S?TRg**6`aZ?y&nBgmZq=*{iKkMAfo$6)}l&!%WWGhdRola-6xGs zJ{>!}uZSY^#|XdAOcZ`h-^J&K+ak#>T;jJh^!I?C%o6O)U(22mN4oUiEc~>urh8Bd zD!!QG2@esyQtN=~=No7?mV%`^@rK*2(fP)Q7c>Q99QD&Y*PY59O_oE%y)hDxeX~8y z`Pgjy5e?)6Px!z|KM(SEF0(xf(U50zu+B%5w^ZihW4JOp0w-ctV@I_wQ8D60hin$wd5WT8Xm#_B5_?2VQM z4i>~qc6$fwb@)bpGOy*)?8QkP>YS9r(RmGAPd^0Vr18!PJ0yPdClI$3oiN$z5?gcK z6m0?YeXJt>c10v6B~d4u<1W4DGtH4_7>5%X`TW03(&J&KINYs+iI)}P<|u*; z4@OYOq7}M7mu6c>Jr~-d8-y8Ur}>a?v}0IMRxaL+AAjPC=ZK>-ZztdQAz(s#Jdd~>jm^|IFnN_X^E{=A)f*<@ z#mRcE-p?IJNl$<7M+eTF0K6`aK~>&i)_TDhnG=Ws5pjo?1yKjt(s=MoBSmMl+61%o zeG;v{vYI#?FBw9*tMa%5)Z<-cgFhoSutMVclv?XSNWR4tr&2~kiTV%DEEUI-|J zAI3*&neQ!IT#ygLsVyh@@J8wh(Irm)-cKUS+*$DWI{;(+>-nX*VVGhlps}SwyeKyY zzZcu$>w*hRLvtY>k0QNh$UwbR>ZVaR7l9|I<%Djg_QV4Tm(26R@s3!tDFe59o3n=M z7%ZMaxs3YVJkK*88RW^U)at`TnNJ0eO;r+o{^nzU6rCoI-8}_??u?OuDzLeddY;5MqP&`y{MM%#uwp4m3+6MoBo~wpA zqQ=o1`3HJ)-4G90lfKNMgW>k=rFF%MA+N7*}-7>tyeFX@(5+(O^pUsjMhvQ)JFd<)JMRwG1D z5pSv6;#H0dPARPAhD)5FlkNjcX*H%(Adfj4CS$iwD<3h-3YQ&-WpnnuxSm;{ZN+H( zo>jxM>796Yi9WhJZLMssjfMYKJ0xa&VSPI(@A!*uVQV+=Pp9J$V^3WvV=F|eii*OQ zDgU4C6M8%2)VpYiMYeoTF}+9kXCl1+N;as9ycy4RpxUpRFN&gDVY~(G?ZZSO%?`XO zypE~2{|R|(y|Ap#3i8E1Tv4SH$*r%jX}}@YenAe0z36AG`#nC+$N@h0Bal!d#g{)M zWG!iD%MvhL0x>*6(kNv0c4Wl&njcJX>dpZgXT+3}XAtk#x&`+)j7oOuNUMJ#(?Jh<5J!-fU0XJz<*lF`?zyO>VU+2m?MEOLq9*q9APQbU?v} zO>Cpz3>>Gs?0>U8a19z4rt@_i@z_;_{8-}3j?IGityO%JCqCA;q&iQ>z^(WD)`wJHMP zlP!^wEzJyOJQw~Bs2ARDo*DQ@mA5cf-dVO5^(#S3M zQlX>jC2*_=>z@tqbOkPh5YdXi%y|13% zQT3!w9@1uwrMddlR^0yd6y6Qvgm)E)ceoH4Cvskkh_4THZC$8$w3 z^ZOWx89y>n{^<&@IY2wZmJD1f|147OIU8eL|3BwPYed0xggz!Ga`7&?I0#<0(C@s! zf{**cd5#V8tHr#%Kl#~Wh`s)xzn;fUAGjY4qxZ%z;UZ~4MOQ*G>CQ5~xh)2#-przI zo84SDDFZn%me}e!kmYIhz>q0VC7G$SU;I&KVMlK*1%Bd+F9r=+h%_n%-KaPn-D+pS zUv!s$o#TKD%EW_OWF+?K5r7tpJS-XWfnC0vh&6|FC4I7H{m7R)f|#PW+?nm=nZUl$ z$Upm7?~!4-We z{fe^Vg3v+lj!&~NI{Ibh{i&<5TNH)?=6wa<1wqKsG^Ri67Cy==5W6ex&*&B@yTTH?EtZNVe`O;ZW8ykK9GHl#iCyB*W8|}{8U<^`8oqN~1blA_ z5`F%0Of(KDSfkAUBfC4>5BE>nP?yREZaps^lSscVdR8t9Jx=7>k_nO>zVvqx*s?4v zeB{j!QN|?bZw98HUcqFAD0IG`i31(ixEI}&9Br(zxim_oY}tY7bE@I2`cH^CERt~tbTSUIwSVOhoi`d~D_i-GXF*t+k%ffe19{>R7aaVTiGZZ@>~l;Z zoJrdc7cBUUH@Vn)&<%m-x3k$1#0mLnjioo;%VpEUFmGcZtb%T{Z6BSm$lV)HJ5O_u zKnLj2yQA=ZqiBT2Od-F*k-j;(+~7|%Ipk&`@xd+em4;}{4KqNQ%PD3{Io*D{?XmIK zO>Xi%9w&SF;H>RVQCtb#Fq^$mwzQw{OVJtC1@w;1UCGltX}3}f!@HHU*~$CzNUhPN zp1FH`%fwVnoFPI>`w!8(oK_+I+7V&aoLVk248hk|)O8p(mdlHSF!zCj+8u5EMHXx}*5>p_r$Rliru%s3dwrZ&xhP&myHiD}HJX$zunes#^j(Wlasso9uNj{Zvqj-EUWp^k)@cer$+q``` zrVN;cU2=E%sbo9oN3y z{h1bw=>HGW6ORk$ZpM-yc9!HOd(}M?{eN5F`Kfp8^3Y(sOEki9r7isCNXi{IoQBZAa;G;BLp*-3L@-7ZseuOjL?~Fi*+7dS3bs93e{eR|1yW~NUzSB-M z79tb-`*`y62n53mLh$oY1UxmNKBGv!;c^sq9C5>{f=D*JaVRmR2Vnv6(icS1%ry6s z_;57MJqcAdRYymcvGF)kKAZs=gRd7b#VYBb6-0Bh%y%t|>P znb&P_V?Zr8-9a2_9on7VZWrx88%P>BY4m6M2?sY&20XzFF19OqxVAlloI)`2^eiT8 zGaR)tnz;1&eF)0CR6sxh6%$bby9)ywkvRro z0RjeCm|!4wV%+`B{dNCcKatt9&)RD}tA+P{NbkWrCeYt2#Xb*tEX;B(74|Hv=NWrL zQU7ut7CaxzW8V|^uNSd8{kO5j_L?Z5J;toIk*g4M^kfa?XAmOJi1)-4@?m^-zt0XX zw#6oT2ab_CMZCBiWDOwy z6>%t|o9VVCySau`EDWhPWk}%=hDZIes_l>PpATpIE%JbDbi}j)Zv5+KFU)unh);4E zto{XcaO(q?YVYt+(h}#~`!9#ABn}$02yc(iLjM+h;b9u}#6DnHP?gAy#zi2!mh=J> zH@1&h5es&z;9OxN*X-eg#ljOQzVi-xG_5HSh#8J5VA4 z=6Yj9-Ar1Aww?Qg7u(yp-25o)*(O59u&I1}KpMI^I-x*j8&mvefkFEWVEC$*D_!$I zhngc~?Q+DA`g%Yw#Sc2gH<=!Bc%HdMpw99v&t2?*)`ck;w%~*4;t}c@xYHLSWE%M( z>O{@zB!+$$7Y`Voh*9*Jdgy$KZ8=5x+>bV>esz)m^Yp^AGft=!_cMAt!wnI%7y7*% zD4g#~AT2rvpXTl6S|dF$ST&P+BdnRK(<*$W-t@u%F}GQjhBtKEIJmqYOB~)4`Dsst zOUIt_<)T0&Y_pc|a1K|IKe5vtW0u9Sdt){5ll)*$I-2<6J$A(64MzB)+2R$XEek2R zNFDl-O^J(x>Pc;s^-AM8#M9RJXNq2aZtO~}4xT%Y#uQ@5-Iejj(w&wxPYcCAzSA9l za~NhEILuxUbJ~^uj?2H+@&EF?Q4LEVHT0j+gzopSSJXxP>*IobSsYfjYt!#)dxd3L zBK%j*#`dZgY~Z{Q#2C%RqMMuf)NJY%-%Gpk9%VLU&;(&$ppr1E+g;LZoiU`l7uYyE z{+4b%#|xq$tDM7@ma9sDk4sLXi&uzAKEM=nOQQMGi80X1aD~&< zC?+x-3Mu^o@Q%IDOCP!7fuRrTe)Q%GZxH|4hTdQ+OR3w)6rQ)~{!TaOM zH*%PwtQB;=kC*KB%E4jSD>Gl>y_tMA47uwapyl|FIehb=E_mWjZYkr_Keyxl$xck& zYswl;RfKngX9~U^dEA=(u6PiQjTI(5GoNYoDh6*qA)OgFQ4yZ5BvMUI55|oXONzGq;N6zI;~}=+vq-Xb0$s%*6=TO zi!mz53|D$Zh_r=(2n_Qdjb70$ zJj}`g(QinzAit%Ey6XB?r^DBb#o<_vp38y ztmO_-PIy6Y)mPW`+5W1LxZ^_o*XLSz!8Fe5&Y*~i+M&zR%=Egp+)59|Jp>XWp#EoM@aaTlnb>bleS%<*Y!tgwdo2O0D^`ESl2TpkCP<`3+(ndczHMS=u6~lxaWlbc=Z`?o??e)J9#7~3ta=vaFM>NZg0HBE1bO{MZ577 z%?YA-^3_j$yi52H|C}#MkHVM;BmBp-v{%Z&H9cqCaox^71ru}ZtUmb&Yxyqfb_riW z-re9FvD?`c`u|@HciT3$%Y?jef0x2-7~M5Q)T1~#2fRp%-7waN!tB1dGNq9p?iP#w zAq>kbx%jklB0P=}YpDJrJCIM=!}}gk+jEm^m`0<2bRgbdlr?fpbce2m54g@CVR|X$ zKsN_r+TN91A%wcawq(+6!-jd^iO01dZHN}`;S1j`!QP|vMz}nPrP%jGk!`DFw;w{D z*=6)+73IkBZqyy4|H2jeQ)1cUjT&f7)ke-4$`l{6$Jh-)5?{T}o+vEoorkdTKbYCL zcB#)H0jr{Ice=sRa#E&i#2TUR6Iq7|;PwZe{ zNsCKVu}0tHb^L%*6yzy0c;LcsBbn4@EK%>mwXEYpror2E!?bN+ahicmUGL8#i+#5Yq$zx1RBaXoDLfXVI9JljQD z)&Su{wi;|R$fHttmtStl!I9hZ5SL;qlFzx1-uFsK7Z3|k&ts^|#hiBQcwYEn5wwo_ zB3L$sO${E3=pY#w{b=DYeB4Ms_l9v@Z~n;87d_k)@vitJtEcZTN4o2nm^SfsvGG{1 zsEr=_xhzZG3OnmmaIyLZ&;AvPpL6G;rFneCmi=Lv+1nl$lKwJ zD-#(N(Ct`OMY7M|zHf)cA+o>`HhHjGk(uuT2fl{F#c95tPH! z2o;@pd7m;D=kV36Q#jX)IN{%@Z(~9L-_@FgXQ#;r6RXM27mUQRSMqSoXyKoU{XdHO zWp=*n61Q^7Q#Yhx_NX%Et(1Um+q5zNws>^_)ElUrW@HwW5VD4_E@PGsZZ3PKs$qJrtg~9F^Q*CnSbq?!7rkRT#^~ z7lNS^WP{8dMeL%?Oaz>shHa&d{QVSnsQmMWa&egWX{sO6&Lv^bq{mF>G`$%&=3?`u zYF2Jph!8yZJ{z7zhs531MIeVepl)_0vyQVsOE2OQ z#?+e=^d9YB#)$q*@<4P`G@Qvqzh{sY5gDVA@N*fT@gx?}UuI(6*+y3WYc)Jo zeX(>p=Vmf-#Lu@t{?Q>U$3TX-EWd@sm5+Ea?MTB9I^fzUH%_I|SffDQ<&##kQQ7L0 z=N2$D?+&*fPx@!?NIdzhAU;Gl!J@fFC`d6BHaf>*!%>E}%}Ko9#t6(>I3L#Su556H z7A9>Q2hG`ye0hQ=@*ExD|8^j^&PhXhUM3a}tYBfo>FqLs=6w7u{+e<(hOr3}U%in1 zM0h%WuSBbNpA?P8jfRprznQ$@QsjGN>$bD}fyDLst0$TB37@GC(AFMGV{^nc^zU4t z>5H(Io2<3N6>H1GiQjdWCyofheWh%4{OQJIj_c!WK_7{RlVlYGm&Hb~G!%H`?Bt>t7Jh)K&%PA01?ru>3vxB`*GDqMfD=ZJK z;HvTRP1;73psSLRfP1c2r!%GDl+L!mAnhATawhEVY;@NjlH`d@bRvQ_OnAimf z+O?fuBBru`8+A8sQD*1%st6{{qXo@N#6!O2Of$wE1!5cimomcFS1m!1sDRbISHqK4 z)W2qUmxt@;V(7cMa9Cn0a=L#XdmkRg4P&vOEguGjF6vt$UVY4fcqquYLNzy+a3bgg8`@6V;k!`uoYKT+(0BAVcWpfBzl;@n zS>Z+VIIu-G_^Zj(r$pJ>QuPTHS?9xurEQDci+`Bo8!y1f0ayQ)am8z-J)g)zugF%> zrN=5l@0l7x#?2M{Db0E1Uy<1CYr<6uXaq!lou9vPH z(Wl&IxF%epY|CgoIp_x&;=&xU*vMbhyFzP_r)0O^kRXR)A16rW{IwN!C_NvCNmcK~ znR~2o!`z|O0tJSvZvmI}Er$}M7B=v}_-nFeK5YIxsiX&6^O z7i#B2L{}}_F|+m(P7di3_Im`Pq`?APEB*N%1wUjgp!@6BaqPj%k@z%Go_Zr%_yPrc zO!5psj#ZcV`lvRXTh-Gz`}Kb|i3CX1YDxMBg~73?7$HK)id9Td3qbK@bA+C9D>wQQ zfcQVIi0rIkKJ(o%ZKjeJi+D4Lg>U`XyE@fKz32`{lnpS(&oC(RN& zFPcEdwT_$4@4ydwZ>Hoch@2=-QP?*|qT$S0XN^8uQP@9lInTNji|>0h@Ps%*TZmsb zYu79cxw)P9l1ZT6Kyz%JIFva)l|gLAFTpSH5x@4^8+UXZFiy&y8=me!iOhQhbV&<) zTs5%so(N}E@9-h#Eb-wVb!^EhihBoU;a;@}LG;gfWotg>QU>O&{staa7m0Jy^CUAr z>%2C~v&Kqh{^f;U7@KffUc*TW2y4Xne#3TwLS!N94OZ>4@A9WQ%q z+?gX*4-CeK1)=oseVg@IPE7cQFzSpx%ePC1fIDU5;(95Te_kJh4)uoqo(8@-Fbm0B2WvY1zTCByYBFlLNBQ~IKdaU)Tzhy9T^cq!=wxhAtAl{vn`Gdmn{uWclK;_oATQK981;amRt8inN7 zF?bPQFZ!M|QE0xUDNJ0vl0VO|#-HuvM?Yx7cU6=FG_WUCk0#M~Zy1eapR%S2?MM-kVde_XA zqV4fe!ylD5euR3G3WMBWuI_>3o6hj9KVu;OEff0vIz_tPdV*9BI|=JdT0a4Om1g4l zr#kWSld(8uYJ{CRCt1nC6ogb;(H*gtf1KQjMvo@gT##q|7saBte*l*14ivtBrOYe! zSypMT;Td+0*miI^FlzTy;X+yX~xsKBK`^Q*fEME>;)ai4*RDOG84%?|OJ5F)#w#PTXZq zIuUrTn2VG>HT>GrbZq&mhqp6KS;rN9C{7-XTZbCCZc!){=NKb&+#zu|F|sDEw#O#z zDmI#Q$oP-OSZQ3xyS%;deiZeZ#}pWiZSg^$&=^>}94pA#Q0IwvByzef=V6uc1&!X1_}>56FCn(L@WzFoDfUOQ zaR9o1%wV}2H1Ob(5oKm?^Uu!KIIkW7(^5t8c!j07)XJb&0AU-wvj$MEe_3K87wN~q zcfh#hf*7FJE zWoocX!0Jb1M6a5j2vWUv3#u>M_?*pgu-Ih?sRh%x{shVw2AE;dl}&8$H7h()(8cqK zwLI0v3jx<{@GUi4>`J~A#e82pSzpKArcypko%%$-o#lTI`Quqs#i$VP%gw-{P+|-0t6|N>$>=rG4cB6B@~^eTbDKvD+3v%PHth<; zrWb)2Hb++YV&{Yt#{wuXwvyM=E$(uE;`v-RV>NW2sko_$qToHepHn)dKFuaiRA08k zP8#yg4<&p4G5cUF;>1u@kmFX42^2sxyn$g6slV|S%vEu@i=7`TP zBi*uoITC05VC6lNprJ5RlBF78NIIyqAz~+6u}4OFI3OB@sL)1kOuz!H!5-LcE1UaGyx{N=w?T`-Uzc0 zZ2s8DuO}y9)L#u8t;}JqO4cZuJQm|sZt%Cd;b_$`ftmUE3ZZ8tj4sih) zqm+T%e1X?0#-PrR^oaBIq8sZc2y?fo3sdy-csJ?=YqW{LV09DTbUBUmE%L$sq1yp@ zy6$)BV|0BbH&tDMN$zwnQ7shRdrP++L*n>r7Vs$xy{Q9=xM%fhY&dE2DO<;*xw)BJ zt_Z@(wM#I6W_PabX^mYYMv~{}I=@X>w$Q@{IDBwR#nkjoc})3)x>!9c}*A%#gCh(Q7nuBSDj&K9PYtR`XDBdIQ@x zi+X?BOcCMhRz6835H_05NUf`8UOU{8)#{Ff?`L?TC;>4yvoOx>gXo)*p72d%BQ!70 z;g9LvZQo5(vfGdLNkEyD2v2&PX1aetbgI8ncv;L$#ht~~4LUbedpH zM36@f`_;_~PZN!iM_!|s{okS7>KzWdD~MEy_t-5X8N2Ey3N!E6qHj@@gp;7u5sy)Y z|DW?8LSnGzy#e&(cJT7z|8DxG=kVEw($5yNFSzjDH66It z?;YkwNeePJG%#?V5ssa{%|FFcFXc4q(o<0ucT3ELdF*Wb^O-BSghu216a%0wj*p+3 zjIP1NKP>fSgWPl=KK1`OA99x1GX3o#Q#^>5WyRob4f!=^onVL8n&Y^ZEA9~!L%hj{ zI!rU5+?P0xWfKZeT6X zu=hsZ92;EQpDk8N_QQ4+Urc&c$KK>pSD||VrvE+34-cSTl*LORli!VIFAmJpq_s_;Y8&?<)tz*?Q!|=D!0^4t2#?s^F{$!y?H*4Y#qUCw*_JCP-iS!70Zk+&%{K^CxkgQ@te+$xY^$iy0#|bpScle zlg@$b=ufPvIFXnz8WP?9`S^HTrCa%0FDv%&SaN zVFl^N9oyLx1q(EiZ|V#A2GxjL+f)=2as4u#>g(acdaL8zE0FVS;+h-Xte-xYWDY`F)0 z*8FLQ?+`CxXRfQ`d&WF?cHQAs6VmapQwL4Y3`Nfq?nCL*esl$05G=dG@MbH(V#Bx# z?d&1H?Qo?aoL$o%jx!qlC7c9VPdA(xPCx4oX>RkN89t|8V#SUrLUywS7MKP@k=Pgc zWf^d_(uee)mCW?HHB>h$Bh`U!sbNuA7(E-7G7~Gl4v9c)f)(}D|7K;>%elJ1Ny5hY zN}8u4y~l?hx+VIeIzgEAT}|T2nUQOQft0l?A7a9Nm&d|my&77N9b^N`qaig!AD_x9 zdGyN_c>C559l3>~OWKd%TW|@(aur|@>w^*2wv>%o&&PVb!}YGWn5TV?eSIkp^I`v= z`4=YHL2-U0_Al=cTWQhU+Au<*=LC<5L5rI{_Rii?VNgR^wrt7~Z|WhuctrWN{pPst zQN)#drI643KM&t|(fN%^!tMQvf|2|VuBGCL-c7z3qGiepPCdb<{6Bc=IYjtHx5TiE zYLc0MQF9gg%ei2fO{Qq6>?_(4#B}5NDfGD>2zO#bgpBdy?%Mvi^xPhUr;KB}BjxaA z*(k&-w(yR#4)F8w#fqq3;*~eTv0-yI1cNGeCpZz^JT%~>q{)p{(~!8!81EkBvuTTh z5fDSHq89h^qTEn;TqEw}hih#484v6UB~F*YS)R~I`s??F@Nj7tb@tR3u3WR0cyjvD z?yIDJ_xe3|u< z=UPSJaUCQxf5ceguaM7nfK4$|_s~XH*klaXCQXJIV^tL{I9?JY7RR{4$}tcVk2SDG z>6CXLmWvPdS9$u+W%xF2HnMV^Y3>?^ot#N1R~LU_i|pfn|S_rW*~Y) zBh#M{i>e9w*nN9DFC(u`)k8CgP7PzOvj*b%w(mkj$|G(m=Y!+)*>L;j!heUqL(jT5 zF!<9`0Mo?hhFP$9LLGv1qv^OBfzV;fVqc@Bm?Ib=;kqDfK^*ax^d;TmPd9AD_Y(=w zZCS>ubajy%sf6bKja)=I*Q*^iSgAaS@B0vj-o&{b*!Ku~eba(?cg|?esps=M{P5)R zVzjRuFFNw@Au)ot3aR8>DYJ}0;B-BdUY^YNeo2DqzXdofRmhf>SmTnNHgyi(%kFWw|B4tQ^B%IpcmCr;`a$l}32yeAy3NfpaQ0xAD41AKwI$NzacbaK zyCq>(wjmzuzbLldAQ_WcW>13pw(m>JQJ$#>G4l$w4k?k;;b#IY|wCsIh z!qq3d>vsSqwoq@`-VuB)d6)|;oM1OHjwKH!ou*O)RzDhf;ach$D5XE^rm@&9m-vFB zJiNF4%|2+RP#2OW^yL@x6E%rAt|Td5l+J$J^etu}nDl^aGL zqb`9%OW68Zq!|~{owVc*ZyvTBTj>5PM``~)Lmy!E%>BrWxFE<H1^m{N_$P2W@8`^z$kfu87 zUNSUpYT$ZjE;~Hl2Cug(;b-3)e6e=~C`ybeQ^r>eNsY$HAJ%v&{>So&Nq$So0nhea z;E#7_V938T%u{?Q>Xtf5xI0Z<=zl$rvkSHe9#1Uba1(y%Cvo*`)!;Jw5R;u7gW3st zxVEQ~TOZ0p-fH49e<-AnSUa3=T%`;-aW6xBiMv2=&sFQWp8Y#;^EZ^^KFbyeqjB6q z1xHsj^JnMnz!8DnLWg*)i4E>A9gf(f>->#%EWPXXz;~5_H!5dz8EZQ zQKP;U>ToeOuI74oQepW+K>UY5(e2l-peL@tl}|r~?pi?zCGGUTJwKOjOo<~MaHV4$ z-D~7fa*WI|CCxlq#|cv2zHl+_5=YF7#QltH>^N4%w){*)?4lYt&vUcjmvFTFh*PRwOpEIaO5^`O z^TUXPs=iGf3VrLvW%ksmPIKUa#%0!O7mGC^b09uk#qVmQqT2-G>bmX{%^OR53+-c_ zp9Ttjh=V&Sf_Ax4)5wz!L?S#MSXXpdoT?d* zn2B~+IJ=rP5nu6yf`Gp3YWXrtUl`hZ;_RIQBjK|T60^cFXNIy6cGVu3Qg5v4DQc`%Ir$v*TUm`kdhCYN z$N#?G2>n#bd|h6~zE$aB#dSr=%vBVY$x7^DLU2U*$w-&M1iE~2vjC3n2 ztP08&*E}S4ri%~F&w6Gtz!}#|eDG-A34ZxnFxD=i?wjVnA~myFu)5n5nr01r*FVa1 zd+H)pxF9arPr0!~6U-lRp8ebyg8p<{EO8O@J*7c7HqHTt2W5teLwp#xtY&}s;aZXTSGCQ zp%M(id_Im9j^uTo#00qHfS;8ytY(uI)_@+>N`yTbF&T+t( zsO_xJa!Y()NS$l6+n?zli%m_bNTkD87QIOydBx+-b2Y(W3Nh5rsw1}7tBR(7iPRf5 z3$hoVFtwIw{HZslUWcvxp=A^%q*_90i9FMnnIbf2juz5&$yZ5zSdRr~$*tC8vOCs( z3n13h61J7}!0yF!FnRVJeq44X`k$JM(KD<>KL&22>9kVj_SX`Ac62wVUF#gZ zZPm}HLN_s+NyXY==}ATOzj2*Uni+|;hXpJ#8DBA@i1;d$N4PPpn~=G~m;6E2Ffb_N zAC|qt;MP|V<(jfDp_7F6RyB!+b7V>|7EjHDT7n~g9uyIFDB8{s7ExA`5i5ZFIfu6rXM*l(Z!a%rjg-+D z`H?bj7S%j3ZxxP_58?I44AH+UEifB@9KHLz7UZ`QONV%}p$h|ekBLDL?Xt&hbrse} zRUTs}{(sKr4W*94ecm{z`b+%h7;zNWlD6(c-DiWSo3ANl{s5{Lku1$yc=cO3OzljR#^aYcPmcn+G z9Bw>63Cwo}(u(TDG5_M|POXQ=)hAeVw?&BPWrnL$Z}R5gXv9YmXV1J?6l4>JQMbJi z`%p$uTIG%{dd?WpzM7}^altfVI;{87Ve_I!Bm2vAt3zwOCosT=dRGj<3G%MUli${$1^79wM7+8>79$o?7VABEa@JU* z{653XY`Q^czr%@DuZV>;TC{)|5`Rl0B>CC$HTH<4o0F9T-Dl4yQ1(p?*;0+Hgt$9v zR19&+c{k5Ex(K@K&0uOO%lecJgtOT<$$d6AiTb9Q4bnZ`_?Y2-sM<~)Lgs0#TdgL< zR}3(JZ4)0p-wyXjh2hjQ((1b}!SXx$P>m1?vZ2W+G9U(2w}rg7Yc|TuobYsI3_I9K zxtvpq=%k-RV_g7N1lpnQ+F)M1ITLQm={R9q!K}MkLQB;Nxeaw(G&~f)XJx@dd$On_ z?YW>ad57@Ws-536PR7QI22eUZoyQDI!1%`5m>jTyIhWdC^8vcoEWgQn(#>MEr6nGj zWQ&DNx)nzf(_~v6(<2S1cab+X^g6)s zmG;Crzi*G-bQka$Va$pLWMH0!7OoCD$k!My!iGPFxa``C+4g7^l;uwfI@;&C*U?b; z4_N@uo1^$KzfklZ<0#qZPiku;E>vAI=cSvRpzxUd>eHl_vI{IY+P%>KFb-vE@3$MxJK^LBN|V3SzxuoR`J5eG^5VhWAo1K%w(b! z91btQb&XoC;vI&|6XIbV^T|lJ$Q>R$4wZk@gl+lB$o;1V-B)cDjmjxl7c@(<&;P23 zfODq^UTT|p(EVsAx>-V}|7dn^%0$8I+DKvh^9DYYwE8!+=e<~D!#x{4p{Gooh1#WT z!~{)TxjP##$K2uT>~qjTZ-m9_b4By!K0xlLJvg8Ct`P(ts@qm zPB3e_{#-B{eoHuYc`yGK?18vd)OkVs`~~t<-+oUX^wTF9e`P-ed}77M_wmFLwSiKCl(2*O`9Emx;>blzWZ&!`7b-!AGO{5*|)x zRTO&lrrdaCsmMi3S#bM4S~xUxJ3n{D6_4KdVz!Mr_oW_b^~9x+wJKsA^W%vdF%6rh zSMz`4a}eFI0L540L@TbpLeiJ>7!>kDc>Q08>U`?m{^rO3{3RV}pa(JYr?N~gkEH!0 z=zFD^f4=Vo$2Kp?oIiTr9gZ*Ju;}z@Hh5w(MxRt8-i;=I(h);EJ#9?Z%VTAfQR?cu z0H0pCm;1a8#D)*HnE1AmU1;~f<37&#k$IX2k>dXy zj_c@mhIIQKXQ+4VI`!_wXftWYF=(uqF465T_sd3QxB>1x=*Gg;y9B?%7lg3!FZpO< z2knhyIM!n<{e9_A@Ck7VG8H8I{5aWQjJ#!wV?IN;WvVaUnYf`icn|wyVTD1&tkI~h|jhM!-tx3S3IunTxCt{c_G z?q0@>1|%SocD&BT)%=Tc2uzdh@Mfos(Z+xjd>kEvKE(<`cUc!S7kR8C*uIx+2jaBMc;kA!j1#E>W`M^H6O=3ee9tc`BM}>2lXZW9Ubkkf;cS&hEZaj$Y z)R$aPq?XLuk7;A>z8UZ)j!^MrV$ARN#1%zjagz{;$-7e}b6(~+b=xjd!;7Is0BeVs4CYIbWA>nN@^ggNL-@&$usY?=3H&PET#(U2xSu*zn6_Wjg!!R_D}!9THuj|rrC(9aPMN80enSM6|m(usm|eTBoVny?`c zOxKhVgo!4rKRJEH!sG}k`XjGmgUsOvjPI8I#rQ`BEo|EGbw_e@5)wJLrr%3*5s_dYfG z|8qX!UM!k+0j9YVE1svv;A<@1EtdXeA3g`cD9Dz&s4wt%+5@v^g`s&sooM>6$wIe* zYQpBsJpPVY%~y;=pwVi~hmK4}orfw)9v)^@Lz6II32}t3*6q$U+*8#a_iBT2yyqM7 zn4h+|88J+9pUuA*56c>2a8no6%ElDb&zy(!U!RzQa|jMEAqKDdCVqp5p|;rpJ_bic z^9_^*?RI(L$?9#~hd9dTxi9n{nDcz6Xr$j?f)470GTTmBq>ob(^R0>>Okaa3wvLGJ zn{8ET50{1_d&xZ9QE)HUj|;); z%Xa9Dsb-_xh?Uaj49gd1_|QM?DE>+wFOe6+dIKT|v<*ZiS-O0VTIe!~-c)@TklZ-7+iLyI=H{U2cSB z?QR>d@%DY{EV(I8&GKOz%2gPn?g7J(u9X`KhAH zuEn&jhwf+%Zs2}l@vzs@hRnVT;$O#Nv3jh4 zJ+@`cIye;bgOXaTH zGmvsdgzkHs*q|2%U|)w}(1Ql^WQ#S ztg)E7!?LK?p}S~A&&QMp|A_TfM}-cVMKB#l-y=g`RorpUL|8q8Q^9MNx1AUQ3#i}l z?iT)YbsSX07I1qonoaI8QBYq#TzKqti{JX{fiWW;5ct-bzZSp7kCE^3*qZKQ5i_B@ z*aYXhQ!ej)E-vI7!lYoHsASm#m|fb18^?5oCl2g&K>HeLzH<+Cui2+V`;VCA%h;edF^1MYY~c6wGSKsh2At2XU@x!P z(!G8Rau;9c{U4Jbe=u;ha$<$)s#qkxFqia|G||uJ!v*RY-(1c+Gn4RSEAhu)-V*6+ zPZq)lPM6$dN0hrD-yj0R8s~Bioke&fQiDSA5jH3_87;bc*c5b?*IrErPE)7D$K|5o zaqU>SamcUH!jm7HEB=z!+I`y`7}8xns38)6FDyXQykaif5st)Q2gv3f z6c>j6AVsnanjBU6>+ANWhQoxGO@qP3t8kK$_4zIf=_pk@!+jT|9*1M>$oZ(*7QkaloA2v60DO-0$ zl4d$M=Z`oK>*1Y+cAgOe|G}a8r|iA~y5qWNkQ)UCA1)!cbK`7slG|STKKHh>>*D&7TSQ@ssz*GUV~3w_|6M0|~H zYx%Bal%r4e!2Z88S%skjLTre&O1jOW)*Sqnn}zXO-C64N-$IWs=Os7Uy^2V&0_p3al*cCdziG5E_?<|fJYpC)<`>l9OEF_=cBJLLSZ%KG+w`B@jqRVlOBOj zKTq(v1#9td?R=O_@MX$AhDblqU$W14G{%6e7zm$NBL2_Em`-!-jrJ9G?xqdp2n_M4 z<|fyP&qT$VWEA=wFp57Ah=}*JBW@TgY#vK}O7vdtT$Ib5D^?+Y2fdfmKd@m#6Yz@m z#m;ZrxqDF#F}EDBY=Hthy>1ZvSAP=vmOtdL$s<;Ig7%#8uH4Eb0Bv&a64qrfxPc6JKlYfcU^*xU5wa`_p?zv_=mjzcbSfw=8*1Mr-5w!ztXCI5yeeMfl#D&$4^jVOuv1JnVUsN3HY6{1|gADasai zT2dZlts5$hYgvc28=h5pqS@~RZzyg@+=gE;JCVXtdl_N0N_WX_KdCt$wVGOpNV_1e zBwevkMTBoU=h(ycRQS@*RQJFQF6!_{7Ue;%8uT@4qq}@}kuNrUlNH9dyCRA*dMa!3 zxUs(zs{4f?Y^pK4-n0;z$EKsoYY)Hc^ak^iOCWV3nU&P^Mn>EnLF>^IZWl-1-LyHl z_;DnUk;V`C)cz0_5$Vu{mui=;}Wm zUrwd+yVda+G*Juk2hG{HNwaWb^e}j?Z{R;FL*O7weO@J-#J$ymF~7tL*AHxE*UW4X zw`?A~jB0tpkhkcn>cpDmQ6lH>K{RU@QrD)oU^;9eeomc^Ra1l{OE{8tPioonjQ*F=h0XprDm|emQfChF7M%Mdyt7Fl_E8 zy!%B=yz|CLd~lmb|Ja1hf(^7bdWz19AJ9It6Vq3n7y5UL!?A8m!ZGd`91VZ>1!$ii z$d=}hL~DL;G%dN$6RJHi+4sNxT4}ESD+Q0=q*1>tXEO0N_`TH^x04(A*gjcs>reWg z!%FtSz>c_%qv0NSo%_=*Qegr^(Y*;37uy!$Javn>e(NC=>?U4Qh6h&Oui>#xN$55^ z99qe@MD~f3g^`NWBuwLAzgUc=nR#ciJ0B3Z5TE_%=d-yw6TP8BIYe#PH%TTHvi!rtSIIzzghc4&yc~wbB*9phI07LeCg#tGAQln{N27dOsHRiP140ok-fywbI`Sh^7EZe0EW47n5Od?{mJzPWi_4co@q#HVO}DbKzr#^Y zGk=MaM|l8?Asx;MN3Pvq(%ZaIMxLPyPfzp2b*=~^pZdq!w?tE$4TVY@bHUv>hpWd@ zAHf(^JnDN({B!CmWL&3QW%5n-#6BJyC|8@aqLL3(U4)-UY$*%BU1XsY0jW{;c%Ro> zSU-~d-g)GCARbx-bH%XZ9*D2jV$r7*sIz4%x}Rz0>z-^v|1s9M)^{i?&3z^uf45f{ zLLE1M{NgcVCPV7CaXjW|Dt3RTw_?st_Gz9TrpS&*-!%<9i82&sl*JCo2^1Snpzj*$ z+lU)-p9Oy+|G@Kb{7pW|=S)n;z(Hzo_%eqTzz7!W`yqQ$Bi~27z|srk1GG9QZX&(K zl{~-=GS}GV(RS$5HVc~HZ*m#Mg)m$|w^8v_x3mdn@O zT?vBx!RgyOHsmewg8t2vag6Okav}XKj3S5eXT&#FO#SLeJg_ zyrLr(<64X`N8W`^>}`Or6G!7mdIPshC!e9BIm|)_@&Tu#Fi-Hq$Jr%pz-Mb@4YI>y z%{snvek3f&dwE%5vgp*Qm%^a$TO_)D$B#HH_ZN{KzMkzcx5Lq2Gcf1)4Ss{VT@G28 zA=Eot9FY}_HHxGgF0W(jsjI4ao`*!ksVDZS^qx!!Cn0^I5q_pfN#?w(X9E1l%RVOL zf>>!t9QGVD!nMM4Y=~AG{Y-3;X>o%;?xgJPKMPDL?q?*mAQH|SeK1XSxR6O+b+>j; z*!r#H7j`?N@)G?UuQq1mzNTXN{pmR1wU-}1oP}o6pAXseV+jFIgaZo4gd&SFzI+tkUE0E_bqjG`ZyF9RZL2snFOIxq8pz7J z&svT}WBP6KVtH@od%e?P_P~yA#ABI@=QyG8eJI zQrVkqMfTn!glK3W8XB5PTf_6IG$a+JrCrkAd;hNQ^ZT#Ao?b6J*L~gRI_G^1{y*pM z&hr8CsjK(ZT>gkY|08{Vozeh7NYlfC7l8b>b{@pmAkt+vG73FKch=v*`nZkc+dnD{ zF^fWZiU};G!+65NC>WVq77EkPlHN;Il(SIAR5GQ=^%>!&+y(50_8H@Ao&3p~r@=h!e;qwQThB(_YDE3Oj z>p|m%4}Fu7rR|Nm9!-2h0(G|;g<+0etLRNHHQ{NBx*#Je%Jb4_sf0I{rIUXnh{EB`!8umI6gS}QX{H45595_m-*;U0IWxZh9#|JIj zXY!5tvGBT@19|TX=5r<A)j>5PV;7#_TC?BZ@IvA;t?KV znt%k~B)p7#Df*;hBpAH55~P(E@t%Jvr;vpRJ?oDRw}4V% z6OX7!z$@R`X!=+wTDLe1TXgIt8qPM#(UyO3#LrDj`TEBmbTcI0^bS21ra2xR@6?f0 zKsRxXJhae0*(>dz=&I5KVK3Vx^h>tL|DmO^H_s!s&EfIQO?@jhoDH z{YHO@hI1!13jL1}FK)UvA1tZS#Rjhpyzka@JbysBo{_^? zN$n7b4!sk)ZNJO+G=^a28Ol{=d-6xcbmN-rh8*=&Hgkvpde#}>g%ouxUWuh#Y7X^H zPZiHPo(p$7Jt&)rgkE-u@U5PTz{&C4xsbjuHwCmU@@99#jN#xn7KfbL_-pD|jMbV+ z-YRJxs2Yt;eFEs6Yd7;bXOD_72Nc>|=0jDYalS1Jk22Lov#Os8xeb-VwY^>3LNx&& z^K_9rK%HM6AB*GOrkFITlzq)5mg>vND4$C`5q*Pj{;v(rO67@94-Lk~nQn;Pe~~G+ zdm>NQ3+^TRcyG$rO!}Au6X%{xf0rUsX5A4sN$=;*)$u5#+hI?o6JqNpq>-L5!p}P5x;NCbxwM0+MMvY-5EFces^sY_vQWI4 zG)!4#c1}x4Q0_Na*uC=tpZjqh1{D6ssKe>E8z_b36Fi zJHE&Zbi~N@z4^OKSupFJjq%NmEM|`bKAs~6vO*hgpO+4~TbfWAR={?8Q4d|OvG^F% z%u^{79ZwlR(f5fB{l}FZjq{XF$!X%kB&sqIB5cwiklzq@*?~=#kSHpOeEWgReEq9{6IDhPW(T4FMC`*TPqsipeQ`r zK1#4%ypE5ZOIe5A9(Xg$np>=*`%B>>j5xHG{ZUT9#P_P0U~`tAIG6_O8HSW8@E85i zc>%@RgK&-dA}s6~0j+D6$fytGielOyUe1-|svelj;ls^g5!CoZgr!9<#Kn9I9C7hH-clEZr8Ar)+{>+$ zH8bq*h?3HS{Ix<1o=|R3ss5?x$!arU$n=>);Q2iMq$myhW@w_|(-m=^6ulp5PQ{&n z`&jOk6bx}RryNTY_b^<7TP&FR^Y)6qk=G)LI4zx_{RPKUfp8(tTCU{^o=bn9yB&N< z&z#0~{v40>>(t@Zev2yy7o&*op&2XsFmv7^OsiQhoN_$N2aZX=oZTXf$WrEOW9glU zyiXM~t61IhX^3SpcHYkzcNE4VhB(I6 zy{HqC&q8JUAl_9UgpuD|p%A@=J)dZgBXoOyRB(x#bc-iXMGl@1*Ao4F_f*Kfu~tY; z>Efq`B*1Q(4koQu;~ig!hn7h1n6+zJ!6io|eV>GpeJ}E;_tarW{Fb=Md1CWXbPMKg z5>C!?2hv)Mydg~*n!CPW{tC0eGE$Z-7;bLv?c$i%_ zmE3BVN@dXZzz!?goB8#T3y`5_i)HarX4%6QV8>2(2{U2mUQev7AhzSWA|5VsLr?7> z()0zU`aK;^y)~gdeJi)me2M5M+cBV9B8!sgj}4!$O7gQ6ZejQ}2Uxv&B=<;|hS`={ zh@x!Wi^1L)PP_fl;TGaEuD%F66OMJis4u=G6>9>itGgnNH*6-pCcOim(r{(jIi^@V zXed1C9`V_pzEk7OQQD_moH;xiJMJ0;+?_ZDlh$^y*9W6<@sAPq8C3Eq0m;O*qbyvb9CP}o zB;>aY65_`+^NmfuPIq%xfHukrMo=SH;1C-Z6FBd3w%mj87_s>!kIf zbGCO7`e7Ynn(BqWbRXYhNuI0nFkaOjjnqw6Xy_KqGRKa=GQ~d7tnc8-=KlCc?{zW# z`tYk8Q(^0$f^Ai#+q*cT`|o+^L7nM|%^CPyO3&HF1uQLxW{LC|+#cJ^`_x6F&rgE4 z<|sE9Zp_2OMZ_bzA|-g!{d%!53%3i7^200Q5#}6(j?xxU)n7HCPEAed7*og(qF7A7f$Pg_SvT)gjP0*4+3mwVXCP1861SEXi1bcBL$#L}=|>eXs%QZc zD{OHjY8AI@2|&vU>Xj_iWIYGUV~_cGXm7m9-#u``^C~}di|Z1P^QVr*y1}r{ZRRc4 z6JUH!2Sa98HP|(!qs-a@Z*o4d<3$Up^VVFl+eetkB2La3yzf4d&MZa2s(Pf5({mj+ z*Yw0S%AK7Kv*vN3l<`Rm!N8>j?7cemls2m1`rR{p!;hN?DXs)L^+f5zI&kUoHq3k9 zDd@UIp;svNgHX?SOgHMgRCa_`sw!*Dl|#c=(g|nY;&;hUzPy+^UnoDTl%I%?8jH|n zdY;MtOT$KQ4ea`;%dHzTVW~%VyN}D6iDe|*7F%MNhxhTlQjy3Bv&V{2O>B36KRi-% zkm&Y*@?!AEA)5SzPero^n+dV=tc5A>bNQ)f>9F~!fnRG|#liPu@QQZ4?ko4OqA{sZ zmHCoDBjMt|sRB`32Z|eLt`N`w}A;tb1@F=nTj4K8uQ*;z)CIj^UYg9&e=ar0P> z+1Z-;bej&A%z2$5u4rxZ$I0LM-2dPr6!=cTbD9suT1ohJQb)o`Sbj8ve)i^={6U7< zofryDrMD7Jf<8SjO4kry{=7T?PIGelI#<{_r?F}BhG@0W$BOG$c_lp?Zyu+6%m_KL z`OO0C)i%UuV+%oR6WtAa>0+yOJpZt1F}@YfMbn}v)^V78*>lH0rLv7%CI=(vyfro- zm*yqZt600pMdHI*`Ivmil!?;+d5Mo3@C>K3K9RqqT4X)AOUOJ`Av6!};ypSOV39Kg zWk=Px+t?&D(w%x!;3{St??j=qNzfX0k(-fUz4U_(4h?Te$&dRz3^h73PM~h*`!z~&~xkg*hDs!{7X+_ zG$p&e*ELTpHgpFeAjIQLJg~kt2%VZY*d41(e6G|$V?!pdo=^xQ@+7EA2e6MXOfkxV z`dKMEuxRW;%I*mG9a|pYjHuw!g&Du~LFxIo*!NGXzy%3DbTk4?rzFzq*q9 zaH)uF?7WbP<@FstoYH;nN9ow=NOz<{Qt~9 zPxHGt(gwe)>UrIdSS*7--4U8a`ft^RFE1tvv-}JB_17-=Ol-Z;I|N?veHnH|37EE> zyn=MQ40h2$Ny%AW&^-_4(`F%i%u>wO3J{nKFz#W57F4xSL{76KtwT>h|)mtkO`>vVd zZozAowk-k~n<&3bTK%S(aj?v#?i{myqQ41>!p9RMBpS|y$DUBKqAqPeYkn@%3*sTf zNp~+~A8EIr+cJTAQqS-N%J)rr&+u$xq-faSJ1BGC1{Kezf}L$7Ua48YcXuHFo)rOy z)VUao3GB(R@n|cT!CsGB+%JQ&s88I`&FH&$<-bI{$jZUG$LHAo{4}_pRg>_I-8U4V z#@zywlGZZiyAg=IWR74ruj31dLA@fv5%;b(v*5nLD0Og#?Y$#>@CWiTUCqFgo}WZ- z-k1r2oil`YgYx(ppFB)HAi^_&v-%&Y)OR6BbejW##rXP{_VuB4qKv~a#GP`)wjuq6 zdDIPBKEobS!ArU9z&H3}@)AbdPO0nHuBdbVc+sZQ~8pm0CeOn#Rw;V!7F_aHm^E zwL&eQb7ck6?t|V>{MePz4B0RHO6Ix7zCme zL#9Z4l?&-6KHO4-4?~9#7i%cCU3@LM!!Dm1g0!L52q5{5KZUx@Y3CVs~~g%~ zk6!AA!A_J<*}>Sq4H@X(sfJIlw{SV)S54?modl2jvdC@yarhF!5I;WT7v6@WWv4*d z!cn~Yrx*;rXOB_W*n*fr>*F~N~-3^hal9fKwFyu~~c@?t=9K!rGwIF{cg+auviHJd%w3C=X@ znrm9P_M5K zxb$i*_YF(N=WjMBd?L$^+b9dYq@{%?CKtH+bzdwTI2R`t&*h%usI!9Jl^)(&$%>^6 z5C^((&!av~UGfqHXdds+n}f^uGEu8>hA9qqqMI7|fel-E)RGM1*Qr6HaWPwa z%o+V_N73E4nTODRc=??nrc70CSn(%~I)-eqZF>))GiE+|U!+^}nR+hm8b^AAAEHg0 zMcs2Xgm(M?&-SlPE*MXm!j*Q$&*m=2>?4f$r)OB&z%-n>uM11FCO-36F{URv!|Ky& z(fv!eG1aFIg;Pc%q&^g`r>L93W)+XEBi>iE6H?2x*urn}xc80vKKyR-tY8-y4Ez6V zFAzJ!{hT!L@&X^VEfI1jwQ;0>Rm0sQ>1YoZuzBJ~cHw3?w8{mP^(*5iyd!b&%p3$w zs1?2Iry$t*4imzg*7C+LUMOyJL&Pp?zMYu5i5I9_VfaSYn{sef?aH`ad4?BM=b>t+ z8F{0_MVTu)pmKIA^i4Yjn+H))9%zAr{2=alIuhmM=3?La2`uH@cz7GiNVFQ}>V<9w zZg6+}E*|KffceL>@b<L=Wm^M|a79r_wA z<;#Y=!O#uQQQz$p+w84?iEAg~9X+RR&&$Kkw^P7g{1FXOz9SSYsuX4zo#EpO;-Hma zgu2O!JbqOc`K0XNGj9`XTugIbK@oLy4_YwOA1Z-%xM>#j9&*(wul;Q{lkdk+w4yIo-*4lKKS!aF8^G?>cCqiONKEc#PMyCE%t_iA zd;3pApUEv;&XnFuCOe>W*$OjFzxhz>6G+`c^1_|To@kQ^g43%4KEk#bd*qBEKJt=f zeN4jaT~j1Ge6PVvA)DrkA`fNuqq_`oVqZ)2`O7Opu%@3i?oM&%!PAJXan=P9g=tK? z*bu4X^oS92l`FcqV!N~-POgv@fBjGbm)WMM|7au3PDsU+I9=>=PUJfe$HMU@JqH6_ zndq(wUXLFQt3hr2zD5Xk?VW*+Ez*2p=6ocLb3yFQElh*nrTYJ#1Ea~8cs>2DHV=bg3UqggQ+-Q5m2P|a+L zoe=3myTrm4F4g%4XD*Yz5Jy2cVre+`O2pkY27>p0dXB?H3F|EXRy^D%PePB;9jxGK z63pkDpk>*5{`7td>h{}Uy{8;|yM2OSW-2Xo&<%0b0zV8=nuEaLxxBI_5LYkxKxIfS zJD6&K<^VG+9)FELoRN(@Jq;{4YAk9r&xNszG5VW$3vqD?s9a%$USGrcE33u$l1EI% z37Kq``B((l^}<`<4u0gaKWgUB#q=S>LpT+K+Tw-q?|zs~eCUM3)bmng-paF!O7Y~4 zfGeLXnKF3^4Zn?)?C{GiVv(<5h(=502L34>ueEI9bD@VYyJwlfUjK zv00X#6?s}|3hGZ)h1~o?{_K|rwoVU_`05WITn1NNGlT^+ve&z)=lPG0Wadl9mmrw@ z5Y+#xv$Gy7>HK(neLX?QAR$veHU`#aWT5rOf`8O$E8;b)IT zK_z((dA4gszQqc{h&CC?%umhm!M{t?^)Szde@*J548l8H&mAPZQcgtsUL{POeukf< z9s!%*W{@NQm18-vM$5J!c*hf=fIO#hQVdcT{P>HzLeFs8F^01cpZ8p@T|O~@(~j}Cs1MtA?XFOFZ>>=A;b0_@i%Hud93wtR{y zyfUaeIjEJ-92$d_)O#pZJd9r@4^sOiNA#%O%!XWdq+a0JSbmN8@YH9~TJskFR&NkZ zd)6szC|@mDdOYEeC@bW>Z8D03)%k;mG5EYrAD$DIvpvV1F`$;_;o4^IIx+-r9@Fo_ zJXgHq?R;dEJHqQ-r&v)yn{Rn-tSCQzZ>#Te1t}Ukwq|y3Iq* zUHbgiBCbL|pYq4^@cxE~L4*8M<5VH)+{~Z)ZN>?j|DB;4Ojq`yps{+JkTvNrKS{SU zDFu;)d-G^PIL=$m#K`LrEHK&_{@&_jwz=;W|fPjw#Q(Wn4YI@)oc~L zC*F%8wv28I_j*X&E%Pqq)h-mxYl%dtF=c_A4TZ$f8HgCHim@xY8h$6_!<+JE{=MF^ z=HNKwoidPUH7i|GQF_oC6((}bTWPY;^Hp6Dm);E|t#ar~k^x<>Tnv*ZHs=B6he9^1jbzjVg2CDiA&yp?a1TZWf| zO{j;fjHwrsr$c5WECx06yHknr=wT?~-mKl40%4*xUN&?SF7Jqk@*I1ZD4phkwF@!- zp9@yko)+PZhH$`EMVL}sz#n&d;n#@(^y#wTv#nNO4&BmLk2=e|Kc>NlcESsP&hygT zb@)^ohULF%L_R$_pf_p{cIS*h7BOmie6f;vZ(3!;khhZhu!wIt^S1(?wvR(^hnu`b z-4&7T-uP1fRQ$Kx1tx4DR<&N>2WU@op^QVx*s2C`JbABL44|g)oLL1&V97iY3YM+m zcivGqk>VVz{Z%VUHBb~}V`K!+&ujVR25(~My1;y(HTP|KhOa;0Lgw}$q4q{1)_zyS zzMwPw=k$DBzG))a?bQ}_U{%m&tm^SZI6?i?>WWOlz1dR`0YwvHlwDI|!=vQkbbScK z>bLlAeQz94aKX^+-^6`)C!owO1KkccGUq#)7-29G#~r3}pGaarotuQ#g-ck#TGITL z1WA6XX~9q_R02(dlshO%V=EVUkqHmM4Nc&wFVx4%a>vZ6k! zux-06-c_3p|7aaaU&%vL3CYYjsYA z*EQOW3pVnEQ$?`!p995+@ht6|45lZ%5FSU|rXuyPFd{K z-f4JuLkBmS+xQq_l2tkSz-XkbIH9@#J2G`pr~#q%Vj51L(?;`;1n$453jM#%$EuV< z#@3ml?$ihjuxaIHgZMIH#U$LP`)1B2w(PzW-afOXT*)P_YVaJHGH>D5 zutBtW>6Wl9$`uFgT7d3N4w9K)OWLQQEOl*u+Q+9y)2=c)mORPdMY5!yE^ECaT$kR%HFqUJ zrG~mA_a7I3pv?F|SACpNJI}%Thnc?Q&ksNjrSXpHQ!@iNs{Jk-DZ&bsI=WTracW-?6c7{WRAl9W^uz77L z%unBA*RN-iR-}S{ztg$t_)SQV^TWTcT=JigR#z-7nfd1eqhTLF9&+Uhu_x*I-@cH? z&twPN5#@|R%D8Q$JObBwi|VhPDAZjj+I43>p3@vD3D6N@$7UidRs}mhcQw4K%qNbH zF^c!SVacQomT6DJ2XkWJD5oR&fHmr0$+2DkOa=2!d75Wp3HXIDk5y)INa%Z zlfR~Xbif?S)n9)qcIf8{?}P!wCAq+tZco9LzLTk+x2i#Fa}i{&&&CVep2Cl>QLq?D z{TI|xrLiCeABWAx*~_(}o;3=>&KE<3^RFxT&|yA!Ncz&L-81;grW6$VX3^hb1>>(0 z@vK<^2EESk;>I$ZI^h64)qGLiF=CC*+XS_(j|B(WNW5EVhWsCXJndTs%nrEXXZ|EM z{qK^mW!SDv zIm5x~!uHj)7tfrH;a5ud=^1ZuXhbK9z**>BMZ7<(BANNB=6P619_fN#zeLNsJrJg~ zuN73;Io>p$`g{)>VB{|aep53BDwG@gQd7pPXyy;uIUbibxAOkvlQr?4jU7orVy*UM zRI5Z`?$b_ISL%+lCw(yP(QdwYT?tb58RGDJH`Yf@z`+H*v6WbhPm&Vg`^^B~<93NT zy?YLQAV_Yqhp9^;!;ofv+C@G%HUau`edzgBY4%$?8JCF})nchG#7uO@ck-INHpu5~ z_j3??N*z+kx7oKB$w*r?3F(W;do!*CGc)bs)Hm25ttj>$}j#6!=f6>>N*eR9~aEWfEr>wh&D5!!U;pYZ1MC& z3t##x16T9OlQctHH0bwT;jr;i;crFeRc|%x!%aqIQ`To~7rD4P+zGWKA~?{mabpv=6pzqW|OgUjFZaJ67j-qtok&XyhIR zs9nD-WNYr>>Gb)k^!fksaCTY6 zcFSWSKzWK<((ya zzK60m9$xdspvl+Sz?e+zn?FI)IlHE@2plitguR1j%|$=2`WG3g_B>N@h8Lrsg|FO z4`MsM_CDo27Ep4CdhsRiAWse2ys?Ru_Sk!|w%?=(wnd|-wZSibtFaB;j&5CKB_>;PmRiAJ{ ztGx$W?qA{i-B+Mwj0x^-t6)#}k@m1>P~a0zN3`d zjY#xNvcc;GCwTs_aP0GRf^O3((a&F6!hCrZiJr6Vln1)ar=4oOz@_Y0V8I|0D4U;Q zTb88b@6pM)nsJ_A(aOi5)6;M3S@{C@vPFw%;`_d#Yz^YG`{ zUy`s~k^0TwtFdcA3aH*a7~x}X@v}qedH&W(qV4Q-h(MWb41H&gvwgIaT-!bYA(^`T z*`XqgnoK*-`?ai5IR1&s6k^+QsmmY>Di2lgqJPnvNwujU_Yx-=qvwj?W92Qx?4fG9pZtgh&Fa+qX!;ak|uj#H@{n00$-Zp;=itpksmGVQcrZh)yi*$ z&~063Dq5{}i1W6R?mAF}k24!s_sPT>x;quO0x$BAUg4x``oV9Mf?$#FjoI?P@EKLW zH5wNoeUlpb?>m@JYdW61orDmVYQE;^OQ`hQjbghzR{wAq;+8!VzO1^-FVQVYQ^67& z$B_5NIvl0pj*`smuO=hN5QFRLrZ)cgp9hN4y(PMR$BQM%{-+DuSC+!FEvcyY(}MD@ zINl*mT~5@&_urha-)4sGk;5gs{i^Gf_u6KK>vhCN_!f!>HuktPZVMYk{G0!Ls>}Da z@Q3$b!6WG{3dU87xfDJ1tk-o)m$0Stne0c!_!W`QmP!6U-OZ@fDOSmy?UeewXheK}r$Z4qcMW z`JGDt<(f4moCI0f62vFWL5^n|%l4xl^%_%j>)F89helxJT`R;Kkuodt565g3N9ei^ z5x(U6LE}8-Lw^@>sZW$im-fan9}x>*o`qvZ6QI3!3qMP{(`VxS8mP&!JAO}u7`Gb9 zoWETk1sx?*^dCHm|DGO+K`UnqSgulZgnr)W(NV2E<$62}{2S;$F+WF>c>H zoVni4rqcWJi3Q5IaW9Sc9+m;U3zM+OW-c4Gj-h7K|L1(OP9&Dod%}_zYs9)8 z3pUH@3tPG>9u>rzQ@^v8yR@fcldl!Fq{^{*olJNwtsoqcdch0s1i?1e7B&yifVHq5#%WuGQTaivy0YZ-(EVZlA?Nu8o;551iM{oZl&sv~7DC!iGlOyOpG>nW10|J|dE9ZH z`w_olYrO;ZOPvx;=rc)J(PM(dZ@D7W9r4+oc+e=~&o3{>z8}+&pw!6xCuTtL<|N6S zXXI%q46#Hny%JGdNeA9t-U-c`;b`m%#o{*>)LB)^S52n7(kxXCpJ<4a_5p~V&iUZ(D~9|vfEotN&z2Fxuk~5hSs`8n7>EBR`u^JjqY5+1Y!y` zt>Fb-@sJ-o8v!%+inesf3p2C_390(!JZ_^ecD*KTmNK({cD;u1@h#+L4-wjaC81v* zdHDZm(HKljZJ;dW0V=Bo~jSbAhy<8uh$<|}bC?_z( zn*0EC-_+Vj42B<$ICuA(*smxUODRkE;M+kaeJB(2?8$T9Lzmmj)L<6f&zc4uWmfbY z|0^#bdceHnZ&znvqni^}9cyLxRI{<{B<%#1&3w_0Sn6X9hU0)oqPpegf>)%aWVhdJ zmj%&tWjtSWMSS>I5n4zKJraI~1(l}Z&)I3He{q)EzsZ1!=?rKZtrHEfc#hXcPf^xB zOX#yH2onTbBcIXzj+%6e{6`_C29Ssg92!4cXp87mM_Eh`Sk4 zZl+EIohC7pUgSzIHoCYeN1T>s%2=IlY3|=>lm>1rx^1B&+t{X-yl2#rb6^gl$<|s0j=HJZJ3^4_5+QfNExzz?3jBgJ;J;0c%l@SI@#i`cJ!ivTSG1Q; zghmee=w^l?=bkzBF64>D>XBG$>PSn$CDtJmfDH0F{HN#mr9|S>XkzZDeiv;wRRr^E z5&r(I<=z$95Pj2zoanUp``~1}f1roOGwWI5>S#QPHG%E+6I_06B+MeMh>0=4EINyN zXSO-OyL5<<6%c^=#QO@_y@da{?t`KQ^YCUU*xa{S_!_P(VH)?TE{Cq^TQX;MpfZBgqn3yJT5ay0y@MfT|FF{v(g1?xDe!vmm6| z@vZc4L((yiHsrASuhXC#ZG@r1RsOZJ0%bB5*mc=c)b_amMW2l@(A!_gPK(F58M>I# zE0q7Fn?)JDAC^S;vvrQLC{OGTrEwiRb8H|!CEB1{V^99^dI)+Od*IR6oovcw>SOVC z!|%u|yvOB5$d#EWVdIDsh!OZ%Ml$oC4o|>2>Vo-iw?DXp_WYY>xU%Lu3yaRgnG#2g z$vMw^m4~D0wmpt^J0)6JK1nzfqAZ#DJzluOHrWG)i$y$(W`1>vA;ugy%`BobaO{K@ zT-kY^+iL@!ehtROTQ#EAO&!SDx&z~9568vag(!GL-><8s{Gv-3zTTOO;!9dA=bRD( zr&0e$`wjm3n>&O84}6^aRD9ds4NYVE!))CJe(@-=Qad$}>Rip* zJC;fv)8ogZ_-!L!**zPoC~esU1q5 zsj~&{ikOo#NTTPMdi$bG=l?T5HkEP>%9%Jd_&oEK&BC1kB?;5GFd_@texyg8Tgv8B zuSBNF?Ahx~6cK(_V^YgRG6L6U8ieu>Z7l@(p4=CGZE-c$`E*#vS z%SSe6L0VA8z^hlp*5A_ca)B0(NgZGV_oO4hcpCOvo#TCXWMFQ^biAyt678~mjz9h< zQInHJnGxb@pPh+$^(DOVcmUG8U2wfYpLG@~WAZm;-2Hcx-``h)8?h8WiyEPV7z3@{bxq4*o^J@>xn9g*m=cNx-xaiT_VQqQFS}-|hh6@= z#M2MO;sSl{u-FDRop`RMxw>%s+01)B49C1N#OQmv%It(@ERvrFB6x|iAp6n_0mS+F zFFzZ@vdKH9jE64QS)gqi##w8k>FEYuYqSBfmLd2sQ;)??9uDa*Ple0Yce(j0>eXB` z9X9tpdHnGR=-zR_v_t7kd!I43A14MrY53=RdZJ~OC$4mk6KC8gfo1blEEzq6kejL4 zbU{PXQMLX@7HphMP>|-!On;bR;QV38|9pjaKN^aLKyx_QOLM>0NHkq>#F_^+EP9O# zj{LDf7xj84(5@v~mWhS)CW&_4x+{GBP$WEldy9ANNQLJnb&1Em=Yn`7|C)l^mzS}s zVmBB*QkBenP2DhfCj-B0bH#Tl@HdsIcvr42$BVbFX>2!Tx@V zob*JPeSNb~>3W#YF-(O1A`$x7kLBamMdQv%D-2o@$rh-Z!Ss`gWY6zca-^?fOco+Gn73R}pp-u`2a z_;L^GHfs04P}e=IagHm@yG$i}e(|;x>aPrif#VmmRHI1zLIeiZPZe|$v+?tp5|(*C zZ*U#71O^Evs5JY;EDVStW37wha+Umt7jejXTVm-iS+;bKwJ?4JY29ugxlC0MGAY;g zpFc;LZmjod&o;l9!^-Cv;o;J0DE`pKcX}+Po~x;t*fmqMHn;#Cj|{Q>y|3^`HW82Y zDX&5K*^06_l%|{F{zreduTmELS~oOz-R2F&!Q_*f39k#ixXadHjNj#o-%EF}8wcF5 z<(ezzR$bwx{Z}Kuzyv1wRczud>M7HZf%BCM{2Sfi-jY6f{(@3NepMn2+C*r2|C5z! z5~uLK!~ggEJ}Efw=?U|kX3^{2lLb|0Wr?2ipKhe(;(<+4j2oO@0k8RnxVoZ|4I$n5 zU4kZjPoCqS$~MBYIs|p2w~Kr%J1|afJAUmNhP|XW8pfDos&gr?CI49GmD!leHCd{u zGBHF)OZNOwQ%{t;d*H{Tr(&0#Zdh*Dk9rp_@X4f?{(Yg2%TucwmO0S#af2mJZurN3 z4v)i&(WZDVQ_f586F)41o`cJ4Me%J4!sAiWl083imoJtNcR-T=3_giG=Wj>8hD`Bb zVSRVXW6qS5%>3qvavaH+jr!y~(ac|WaA(VUtl9QRcin!5pkVMZZzvGARQyg*f#CP%Qtzl5uA4<8`BP_dHHa0mZ;m&nkzUtK`jNIgj zj6(-m_d~?Dur!9Ys>kta{|Nk{Y{+l7)67LP1kJ7VJ2gGX)5&A7s>>gdd+&>)l+1-S z^eFs~hxVR21o{>z;lST3;&GPgxN}$ozg6}#=TjMIs5iv6&F6TSX*zDIQl7=LQnct) z9`+3K!t>R`g!@B6u;S=Ui6`@@Tp*Usc7{o+K6|4z0Wyn}F>O3)QzmOsHX0~$8N$A& zcM3)p6~e_AO6 z^C3@tb4JN+OlOW4zJz(8(QG&O-nJAOi*+S?{*^0Ac;nO|cyHLt`^KhVMBP*g)4ups z0>(Rgo6WG?dXLE)J4We&_Y(NTq1C~7CkD`qYyTqyA*28=t5GV^#$ z-y&jo5HIW3W7d>Myif0GX6IsfM$ z%Ln%@#NHH3^o$ED}2$Ya0t9{{4qF){;Hn zc=;R1+Pp$t#YWL|qkBTwxFW%TvdotD>6o3Uj+#hy9@{e$ua+91X7Fm3)R%gS2B_lC zf@XdvFAQEj0{W!oir?l(!0ysqSPX4p!{+&;2W8woTh;Nbq-gkDjlkyo@1k6q$NG*J z1=C-9cw$^CoTjPa+REeN6XfN%S)h%lOAa!<;w%g}UOC@nq^% zZy@H0Rn&DhYZP^4geysA{$<-mxn)=?1WhdZgODrslrwR4vveB=<61s&xZy30v z1iLBAW@q?~%^?ool=nI?DXrvRo$2S}Yl&mO_#xDu!8r(uH3IX1H-1NAdCa3bs+ zzb#vcb8{_GueMC2KK%}gPjAD}&%;o^eIaoR=yx-+l$TM);jW_>=9f=n=c(6Z)6Y@V z{dt3*|Lh0DlzC8)eJyTnb;Adbz9=@h!1em2L8DR)7cN&ewEI(jff*s9$4B;deJq{@ z5J$zYjNhf(#LI8QK<-~F$_!Qzv>FBoH{8qk`D5e(udtWgZOhs+@S}GcLeEvO0&B{V zGg$=HH}b72OK?@o7(?Y^MV_Z#V4&+Z+?@PQI8I){OE0G3tEV5IoJuU9HMWo$pvIc) zlrVd~v}Di!@y#EY98>zog{i#Ufl%-HrZZ148 z%;U3DvaxQ5qJ)R$V3L8y!!&SU{(k05_bjLT2KZHbju+|{BRk&(QpyZi{HR*c#9BICyz3p zCSrHf+fLb$vW^SI9}5@ZzfZGp!hp0LGjHhCdq})GFTSk6#5@zp%$GOOz!sBM$;`h% zyWgcD#<-VLDefrGLe|U4czNmya~tVF-LS^gX+^iEd8FsOB&N;z)iy6DgrNUK`W$8` z38`DXutLiN)%&yg?iDNX(bN=OD_=1)on%x6=tw%MjQ?a{SEeP7P9MsC+#QbYLpuZq zgM0jNO*jsou!XeoT<#(pf}U%p;9YY(GgPp~8*U)ccJ|%zLbxN%*;5MQwe;stUTA`{ z_({SKy;SVkr;BHoV|braMfe%)inixTOqFhiLk`H`l5!KDOP)7pa{(Fi2l9ilOQ6wz zIwD+lu}N8T(DU^q$)11mco#aZzQmf*TSOk2uZ4T*t0g?NiN#A{e{eL0F4y4!@0#1{?{JJG@oQ>R{K?|g_!LN``!dw`$X6^;Vx z?O4+IS!8{kc93KBf=_WZA5C04rMl5LJn*zwSv8j4D~2e!c$m%6ih?J3mALO|ewnha z|1EJq`rrXJgPuj;9OW!Ljtvp6&`fIIi7;m zYf(1Jv`uj6ejoNT^1cu*TPDQpI=~A*MWJ@e1USdb@zqz?!-M{ATXvSPwjLsw&)3Am zq-Jj9LcdeQZ5X;z5MNOB!%fn9&W*jzHV0%Ny^!>&+*Gcp_X?lXH{<+pF&jzTEVKE2 zv9qCx&vS~znu+5fY$*}n=pxolvjdtxmaz?vbFi9jn&$Lo{Lz_#_RvV`yZmD_ya(-0 zDe-t%XDwXN%Ycs^ao0D!sO{I3fwaR0n0WRHt1^y9ySFh^$om(zqYw`Ivyt=6fL#ro zC~SGAD(G6j;bqc`(0I%dS6tn=jLu?=`87+T=bKwv!r(c1j7cYSYHX#>)*SdP-zduX zoR8ZkO6Qb7endI zvdT%spXYWWcTy1!?ot#c38@&GK%f7#i~QipP!u-^l6}50mi%(ZeWCu)hMCUMgk`>* zM8k2E_QKVXb6~IXRJ@Yzhl^H8{D;k7w**;s z7U(~_gpb^qM!Z|fDcc_rHOi<7(zE&t=d;)G1lq@XIlE%kgo*sj>r|M}O`_Scf&Ds` zh$0sSoZ5DtU)!6EoDdz9jqn!Le`$l}hD|t?{6P5qo^Gjm76|O}<*V-`;z+17G8;#; z!=>s-+cyC1|J~+#)xHRmb3^IdFJh@4;W#f2g3aI)OvWP}MT|b@`KDZVVH)No>p_MW zGEGhyJzooyz4ACEL%x+kXXr4q_Z+hgUxb;mlj*L1n8!;m!4}G>%p-=A`s*5k17!3F-{%5q%maL4|Zy&}~gOQE4N zRnj@@TM>k=UrtzCxROu07=x{43y4{7%Lb3o!gdXH%(#A=n^Tr{kORZ8!9y6geI~>_ zS}z#is^^t&;_%+k7*9^C@Vg(Epf2A6;nbO)pDx0d6k_YSHF3vBfyi9vDDmW&6)lFM z_iQ+~H8Z{WUKkcR2d1fex$cAwxOT$^KPv*+kK^k2HuR40^iMUE1Xtl6zx6!?V+;k1 zUonSo;h}VQor=HyiA?FS71C@B5TisI@(J=7a!-l({)fssI9pmFt8Tgwgfv*W>PdW< z=T=gWdZhqO^B`uO#9$vOBhhdsPo<0!AmJPDtc|3w>NH~WRi|Z#8R~eu3{EJ zy*89n_RJB>&5wi|Wgq_WjjL#%?>^BL?OHYb^kvFTzkUuuHj0I9RY(8M|0KG-an@4e zA8R8s^_19X@hZF^K4Hb?8>};g^2nq|J^jLYx8O+1f!Y!ayPwU@o5bobag*%xojv_1 z=j|$)?J?WCu28bjclt;)oEJN&kLjB^b*8TqU$cwBp{0~(oLA1Q z`*^@M)Dpfjm$`cov5lv+p?GAV2;{ZiAHEn_UrYq{E(4E0siGn2Wo<`UCjLYlKxtbC zb7+r;X}%F6e{JMi^D?lz%$``HDs1diEx~{?+k`cPi6vz9AbBo+kEG`bk z$!jrF9 zwn0Sh7S?+!c?<>*k$CUDv=g8wHj>SD|^1qA)}|6^~SOF!$>PK5%6= zYJ#kxer}oQzqM^}xw!*_U_w=kUB&LsPMh+`6d+@ZXpi#hX4)r57~2z1PD;a8`5 zA@0#Etl8NiKDf>UzfSi;{~`7K(&=PeHyMp@>eO9gx)e)0Opte=lQ~}|9w7CKHrJH! zq_K(UMYoK5Ej6Mi+f{`FzxoQwdrG)(zAx(2T_iJq%rk#DPneIl_4!OCgqZxf@~}LA zo^N=z8iUuS}A09x7!T>QSV7 zkH_Ex9;aS@i@<~4woqs|$6B`q!D~5n0XQDv&OP41{7oym+~%8o6x~btjU)THSUaADp!Wg__h)J-dQk>YRf<=?-|c?=pYV z)`fffpW(*na?!8EZv=J%2zNU%@d`oHBe;G zz)gv(tT4_Nw^MS(SI@@cNF3cY%$u3mav>ZtU9qp%e*WQ17hD{kA!F6X6++yj97o0?NG{q z>p^8)c$mx|1{EUrlLbPH{MbleTV#*ygXzzk_zTM@+#GHW<$mkL!7lWj;%0}bE@f=+ zHV;H?nIO?^9@Ir)>JDNwo&-Y8kPa}r7xFB|2QyF@9e+kQ1 zw(`vm)TNw5w~{5&yz_A&;#$Zb?zEc)jGBwVV`q~7)yO@~S5h|75SfZ=*~9`*TzWYO z*GcRCphoQCFhj{r_A>n)FKx9zh3i*#WK1}$#xd%;KF*iWJEr^VsVFf$E1LVxSl|y; zCHlO1h&M(@&%(Z$BJSB%gpW^1=a)Li#(Skg=C?MSsxI((uk%5x8iv1LA?kbo1=?m* zQ?6eDPO@PTW{S{!yoi4(OM~3vx%Bh2WDQDMc&<8vcJ&s%=&={}zj4R2=nnCRZl1XN zz9+`@sOJZ2((rLAX^B#0wad4Y7g2+5!A&JR!G$>OFC4K^dB5oA8CBt$Vqd{_dI_Ih zvH-n%xu86ABA-vYK*^l0BCVF1O%|8>jG-Ik6I3d)lF?BK)|Fq>_OtdfiDl4TloJem=I z_5$C$s}u?SL-5g`i-ggcn0$B|b_^dZ)X<(HuP_Onp9=Z-)k~06=mjBD#0K@DY}PeZ z$vpq4mQT47y79&T5jodM;l05g;eOi_etCIl@|KI3H))5F zqiza7HP^nm6jh^)v3Jxy@$8M%nHxS1JC>hhi>ql*|73uSUF0)KqWnIbG2FY@MrKw7 z%%eQ;`M9!>F~kRZrDq|{gyy;L8k~7yhQFQf*;f5jm~?7k>-ut@p^%R|uSGDD8O2IQ z$zki?hmswBT4NZNJ++a{^TU*nw%jn8GPCh)8~yIqhK`Z!@D9%Na8-Raitj3j4|bWH0r7KN|8nfNyO!g2;9{8=OaJtG`zZA7p-KadAq zkAi=L3leK9*o4+OI6l}O>%TVe`>(n%O8Y5ZRhEgKH+KokI#vof^3QqI?o@1hsU^|m z=dVmeq8jyg^eSSx=RI+FjXGqW)^i7~CGZ$4;9gCRxLhq7o6k{y?YwI&+9wcMPu<}7 z=m5VeqVBn0ixBYfvuL8O23|#65E8Ff@hLrtojh6_0is&*t06^b+)8Yp{2T21=QQl9 zCjN=tMSiA}I+1$`2=CU&nk{maxAq^zf71MK484G7{ zQ&X2{^75~ZLrA`~=!I{up zuZ+EiU(|YD%b;#IUA#7Y%%tcp+2fpnM3eC{DL}Ul7o0EDWz8eC1?}5CBs%6&lw z{F*ug-CkYepG>ph{9OgJJoA~9_FVL^7=*u@>$$MgXkF-qn+EwRc>Af}{^;f>I zYr?V5!lW{fwd7vb$tV+_(f z%jP^u#SzLEAKi9=@A{qt(IzWgD<}{>t8ByW^ldosR|dLE!*NVb1bM^NJi;rSZaYp$ z-lESs|I1v0k8zUB?6UYf7<*$cUOURM%PFdYYgcb!*|xR(SmZ)_RlATsW)jcr>5mU~ zUg&VoW2cF~x9P%2$=<%dX(fy+E%EegylBnFcFMl5hi=+^;X){Jdi~9DV#xx&xRJW{ z9!^42|Iy6HKojfx_m}MLz5gu0tM^k7E%imb|B)Z8_2;6Beo=;4XMnF)lH{jKXvbbR z*a}|KWvtJ3x*ZG|2k-74r!;Ba)-9txk>BT-aG5+v2PdI?zF+MbsEI zNl3ZLBs%<)aT%Ccq=dDhjp8cPTzpC}!r>mL*||w{51LATm~|Jp@|A4-ygw0&J+_G+ zlQ%3@&mObGrG-e!;3hnz{@Kbx-ry7kze?hbCx}?uI&JKo@c%h~_P}PWDYe0~i85@8 z;XR=;f2DA!;0)K_lz_T8n)Bqh$)~rHl+if68nBj~`@%4H-bmPwZsK;-N7Ui%fCDQR ziWO#rV)(>a2r;|C#`F0Ir(E1W2HGT-Rdn+*#MX;*n9?W>Oxk}#*lSwN`=ulxoBAnA z4_Au&(=OUcTH>(BCs;Jiw4plC~e{MwY1tsbSB)`ojxd>diFbC5X)10^V#oH}& zu>W%opZ+EvA75x=!1;%4`3TC%F=9%nZQ+h}%i#G?fcp)3HeTzIaC7=Dq3z@j9)2+l z@wqk-&zr-y4-X@T&}5v-jAv4(ZQ$ZE2AAm$IHA`(xTns7#WDr)ulj7zyA?M86lk zov#5!%R1rO;VS;0Q!0EDG_k|!wD|F`6g-$|gv1-i**(v66ucARfbT^f*c45kJD_cH zf1AI17ouszRLJ_}^Gl&2So6de1BN=X*5k#{r@Q>$o+o)|*eV#wTOy`amIav(!XZ{C z;hq^TjK`Ph z_*%Z1IUMwa+>h~yyWPN#Pl&@IdgHxX)Mc|3W*?YaZ$ zXjUAJRsTI;o?jD@OFW!^9pYohQ3p`C8w>puLJZDC<&h~@6`LzrsO%C&_I(qZOe{DPr;$mK;CTJMIPFL$wBo?dvKOWhC; zuF(#YMH(Zq7k}n4C;IN172Y ztd8;Pt4On5;{pZW^P;n+#==|a|Ihiu6MfLrhuEpjHeBoZS{&~;7DLutWZC2)d?c%d zh4HjcMz2G=^fVltuvs+izc##!+lo!cWH4t)1bW+&CqsKRuihC6v7<8{)ElsEmfDaS zF&rT!Ej;3ZH|GANT-(nlVmtD){mAYine&?qQxU#HQ{u6?-IhYRGb8+rd&QjAN24;E zzBi>yc=nK1IH>ML;8Zzw$XZ=cPU<5JXer?!^I<6} zp2tu@}Ou(_utJ}yWQjd|UM+cN7gZt6WDe0VIrlo5NM_W3IhlhI$>5rck=X1d!o z(L1f5WX`LI0uZ0-g0A{+;&tVVa9!|$*@*+}O>G7y^;VK_&j#eCqx&;$6dWsL@BN}7 zO_|3GO^;KmiqY7(M8Gy;DcC4SV9DRf5;j6m?@(-5OIeuUTO#ifj>2=j|Ic~8KLbm? zD&q0QM)3=qmAF=90sV`_&)kxR!fX=>_l#eqZjQH;ALnmx3mP1}#!;%kcVDYtP$(-MPFcE*`^fA7*QtY!Z3Y(9SJ{fg_9Xm1? z2WRV}TUG;aq&>kUo)~4>t8K17kHn>p+0L)dWUQ zAvhc8N#^|OQ}dv_VY^||FT%=WZFrd>IEx_d6ZzE#D^!}Z*QdOda=5n=I_ z9PyJu3AoUgbVB!Lc4%DyG`)#aF?K%>B5!u<+W_R|eir#})Azn-;yGJHR=luE`gM-}9$z z^%RLFA8GB6GszwpI0x)o>uQYrWhmL_cP16#T`$_VONO$nnS-G5?VQlJ>>=MoS(0)^ z>JKIEnZm|sgh$icp)HgZYYH$)RmHAaVm4m)Bj2nO{8~ifv&R0|v%~`nif*ytpE8iq zPZ5jWB=g@dGw@^KXsofH#tZ`OaO+kte9ma%VRS#*Q!x&`8rF-$_fv;gEp;{0%rAfH z39~!qFb{9wcAtWgt1%t39zC*|N7~~-$~vBLwGfV+%7pJXMaj%BdYFz4r0-d+f50Y_ zR#2~^kMlh@@f)Pu8$4iWKcviDu4oEdes>cd=%4349*c>kU`xH5E_~L{P&82okmZd` zHvgP8N=BIBS`WPm4g?*=VP2U*u4yG%CiiEtz!!h z+wFs1!VLKK?hwZW&BdV;QW8zRo;;tUo@hwC^pRJV;jkKEdhY#Yg`tV)B8@bB+y*}L zOfGSEX5!q*)1t2aYQmmuX`$L_Ek8j0o}%T>sP~)5kKA4eLuC&bdE_$x;AC|BHA14{ z$lX|lAVc!)lqHBtzrTbuwqW7MSHh|Ov5=w}GWn4&uL(-VVb6*1G9S%O_R>Pj?Y@#b ztg;O;810Dx+xA(!nEcwqgXiM@sQv8x^9r%omt$>&HqOL#XTvq_3S0Xw7j9;Y`G^Tg zu(le5{d?&SyCj-&?WTx|Ucr9l6*~ec$S%z%NYV}KYWeSy=lz(g%)NfStr^AzoS2;$q+i!cF2z&A*s2vuw z&D2L^+c*Z@FOx4KG!*%>9T0qbmCbI-gFG4LiK)_R!rLxi9CdL=yHO6mG-w4Z>~&yZ z^o&)mPs8&h4N2$V3&#xzxZ;N4uXNemqmPB-COaj&{g|i-D4AFx({T=Oc}*;=Ig@ZG zHlBSM$WRMiVp28nbKB-2T4n}xisi-ce&)g4L>;$ITMPeD4q}$ICUSPfaFZQr7^!E3 zIQ_XygEaCnF#{!<{Li`w@QMsdqxf5%&!p;?%`3HG{MkMwSt0f}hgUFTgtQ*zONi_M2%ruk@ z(SY~K)8dkQ%Mf?f8qGuMSq8C{+Bc1**;UJ}!ZMI~%n9QkF-F&wi@v^in5c6D?&0tT2hNO*x)02bT zNQi}|yqSbo|05$B@1;aosvOETZlp}1ScUpIn)oYif9$IuF78|=HYAVk(L1RwOcUYa?%(fPMBaY8Q6PN6IY&^qTdG zF~1Z@z17Eqg3VktzY~wv?4j9M$U3z&g&)d)S;oV&{EH6Vi~HFjJ<^p=&kaMud-B~K z&twVnG(7gTZuwH(##i%(AV#TFkx8|g8%Aa&!!+g?QH_(#m3>M zI&t{-s^GcqH{tB$R=!+52zPXCak8oh_uLtV-UDV}yv$y9>8%%r=(xdq;5Gj9+Y0#g z&_&3$Viqmsg~@CBV}&efeWpp+dR`A6?dr95Db!(PY>ubfzp=IdI0Hsj_?3E$_tK3* z-M-1tpM6GD-fAL@cT^I-<>m1o|90j#vxqSQK01{01=lsv_2w9xOrOc{cj_n^bb)`n zS%O&EspxZiqewlC*ls(^aW+Z@ccP>5<*N-?k2Sp0H4BP~bMa~{F*L>yPqbyIM5`ZP zHxKKsPsgc69bzprFIbG0!eDROXXs5Q11-p>m(|L>C9eAvBOFlbV$-r?5i-RL2ruD< zMXA`haU$LD4v0KvstIb>dI@Kg*YXf$f9RAu;iKI|ekeQuE(#u4b~~3{xs{9~eMaEf zy7PQvJk8`a7S!*SC^|c(6RMNSG3(eXVam8zOprB$S+p;AEu{N+UkB9P(Plb@T3F`N zSEAbw5B0~14kuLmd=Y;oCV+F{9Qt>!W{vcY%ekRQ9SLK(_md*>22Vim7iFxsRvgxz zF@t`*=c$veF_=R0<$0evrqwSU;RDDkl~Kp9^$5ZI_PVyVlzaM8Ho)H^06Ks>#dkZ>#* z)6?v5ZGRyTY7c_lL03o_n=_e_I=JVfEZOt*oD0xl zV3AI~?yx;vs(S%^rfXtlt}D~}rHQe#n}wu-HQbAC;>xecn?!fmJGxo8%7}}5`VuSh z^THpyF_;z7z>AzhvGbZeO1G}Eak3AC$a(I_q9@ack#h<{t ztk26dpolU8qqguN-PS{~(gmLu>aeKKj|COkokGXe9X!Q00>h42!uacKE=AhQvQ-l? z;Y=LkX2ds@`~S?(+dUtLDrZRc{2iC`AbnH~J^|Lk-&<)=NYJ26S~P#0k`8_Hg|Zwk zc4U+-RP_hqMNuPPOWMLp$`@N79mM-x%)&sC7nI)|VvDIWr|qtQiK-2}vOXS}{y}u> z)f5f7)GmZQNE7bexWT7er6ZDVlvNG7ykBV=t`-^~JgJx|xRK9uhzh<xDCcbPqBRJ(%agBsD zd^oFyrNU`(iXHil3&+5E$1!$lL>z+sP0_FSX)g0Ql5WM8kSpk8Gi>V%JXy`LpfgWM z{1|}AjZTnG$mg4m`eAo}cf7hHVzG0xv1%dh$xkYHlimh|vZTLPBQa-cZQ&#(N!|@+dhV2^~!m0GBgxY^fS@#)+i`;e_p%VdMR3o zQTdOJ5IQa&t5heVe~cFMJF70N(D=!Uk8&QS5{e1LsaU$&jko?P#L{`hLUrHFVqe;z zwaNr5>zeqAr#U!js*Jo{)}jaBJ7A{03cLOu7i!KYQEpEcE_OjYY-Kux;Z`{DB#7Pb zri$o}FG9O^E1x(y2o~=ITo35MTLa?Zs_u#S%meIjwl{7Iu26Y>m2R>nXwWgn;RfQ+ zMtb4G#eVqKtDYC-f{ddDxs_f!?M z#4vd@XA`d=)CO0uhF8!YKE=ufA4; zuTNL8t!s0sCqf09p%(o7IQs6mX^tb!rR?O?IH(qy;`|`bQy)rWAvlPTpj5|(Riq*M z$qcxAoaY^nL$I=!8!k+{A^PGmSvcxzE%8-mlw`tZn!JQ{cAvbf!LQ5_WOs?Vq^3ia z8%nhL%-1XN^tvmqXYUieO^!vOz6j%X_7vQIhd@)$4(0t<@Qm|8@YA8p5$*HQ8+71U ztAuBBZu6yuYw+I10LOy+u;=`q@cZd9L1rlDk4Fr+VD0e zo;h_P5!e|&dg~%6xKg~{AP*f|NO$^hmE~?EzrCU!_7NlEMQt?XmOJ8d* z6cpQ)p2 zmk->XkFk%`%ep0yp|o!U|48?sL$em5tB0DXmv_6c-Yiu}{6n4E3h7Xosz&}CUH)N6 z8WOWeL(5prLcURFIDHqZ&#&h%MUnNfU1BT#y%4@o{JA4RTjiGTT{q>IV$b#l5LVSq1U2ofnwU{&|Xr z{3Tzx*93^n`q_wUvS}A{hT(^P89S?)Ot{a|&KDN2x8-duF z^Du3fp|J2}CW2!}Vb9Iywftx??iX0#LHRG%jXFM(7wbyyvrXeNF^e>=!#9*zsfUgb z@v)oaK0ClB9C@UdUb{JsZzNB|(3?}CRhZ5OL{O%XI%@s)H1WfOa}lemgzjn9qV&!V zTnmS^B=A!BMSWFtWOw`~{9^r|*Fy`?n=pT(n??@{Q zm{-i#I48j+aVlbWnzC!%b?6Nti!Bx{eDi+`V1Hmb+tvU^7k?bqXK*EsSymF(+0Vt9FnK&u;;WR}U5se@ZoMdXnN^jhqiLN1F1gTqir$`% zzV^7)v|TjVopeZ($uR#mKo~tD1ZVpJQKJgEUieDbX(i&2zBijPNEZ`^C=sXSHqRTp z7FuicvA?_z3s}$-&&qcQ^?RT2AwmlFE~S~DsLH>M%tzWzJM5agleH_`qP_nx9GOiS zjq(u8*+rU;&q8q)`7)Hw5`WdDndQCnCBEP^yzbb;=N&3W$Xh*hOrOifIB27)`kEl+ zU&C8X=vF>ZN5VSmqZJFKA|t%2Il<1~^+vR&F80oB;B(8OaB|W_i4Ui|pbcve)?(H1 zLZM(Obtx`$gXxYeu6ZO6rrOF-FuKb$b=HyIXhpu~lU%%Z1r~j>fz($;mY_NcI$mwU zKaRbf;u5H4S|DW593C6F7Jv1l@Hu(|t4bAcoIEyXmNjwd-M%QGjLy;=zZqYyTx6;n?a;osKlD#Ga+eoTNN<{e0)s*Pumg2s zwmabYvh7Uy=3F>di6k@M=6MYDkow`sO;ypE&NjhVyi}0Wz0N()rX!_O6~$+D`K@Q< z!Bf}6@Ik9tL5er+uu77d-`<0~H{=_fznbo|dnw0SVT;>1Th;%zKyYK`F8KAfi|Bx3b4+IfCOFyr^Ys|+Q4 zrd&osWgr&qc0}7TCa#ht@1o%>xF+3Vafh?v;4M$xB5Azj$|`JJZH6VW{>=WW2CiId z6<&?0BCcR8YS$RydTxo>XInhRXxgAcv5fs3;0@(mGpH#y@Qn|{F!O~A26R2L*$3+V zZ1h6TR0AQ;A`9CpMq*{x^IFw(`u*xMM{oXG$a)M)KidiI-QMKLHRGbGiH;Ap{+OzLxzmPjw%b$ zq&*$f2VN-Ys2c2@3g7>9@i{kyx4WlO7uz`E4hOKrd{u<7PlBHK4j=SB7%Js-<5=H= zd-Yg?it=gL^Lj5UoaTcXgQ*zob(Px>%15b{GIdieXEigt!EE{xZGKFE}7j`*-Iv;hZ8|(8io_;)rX3-?PIC(~NDc4jOwq2gymBbji;EQl? z(z_1YaQhnt7!#(3NY7);y*`aNlqxvsS;sG5UxxnciHDY3D4I0=C1wq*!07l<_&AAr zQC%$XJimx%()Zf&>?x8x{|)sz>b{qe%zWEnzLeu|MNQ!o@pgf_wj%xt|2#QKr-^ko zPXk)c<+X>N5u-O?4Aum{V$-zZF=3-IzPpt0!^4*22XRpQ?LQ-0dqY*YSSlsN1Qv6d zyg}K12;=we65YOye$LAl50z**)7`TX=Bb648-Ai+=!7QU1p5JZF*hESXN)EJsdr&nn43Hq$ZKYm7GW5b@Q-zTh#!?9 z|H-~-Fx%52;!h_FZ)REwUyHN2Sx^?fKNtx;zb0{tTmi~c^r8An%+5;F-K}U0UJ}Di z{Z2e&rxJV1yqEBGOeh|f3B>d$i&Exd00R@_si97^R- zc3HL;x_a*vPE>dBuHGqF)1f2jA3PbB10@dz>9^GNGr$&?ONSy`wvns!jey$+Tlj_t ziYF&UV89eNG-zFCH@Yu?E@j!ap4r2nXc8O$qdI!VPGgnSYjNc7RY6vRj*)M?EoQrdF=9`RYzQI;C1Xh%OX{ck_kQ zE?11V%;MiR5c5GKk8;`DteSiRZ*Ew@`pHTD)T|KS=-+FervkH`F$&Xd+9chw?~I}l z@Ye$Q59aV4m$TtdOy12-`K)`IfSS|Vs9n&+^->q0g}$fGbjgdy_s_-87YYzPun->T zP(C6^4HXAsxZ;ye*y(LXd)Y;{biEzAjs5>_-~DPdwoI_3?y*69C*?rh={|n&#dg*{ z$P0w1kmxq&zQ#bkyC1&Rsfu=ty(cW2nJg5%xxvGC(H)2G=KpqkFP@4{>TDIZ7O|oI zeK6;)qGZm0-5-VB{fJH1FIzmnjpqDf!1>%ow$X7hjCMHU{Ms6BH8}#l=3dy4{zla2 zxF()#KP{Y*s^WdS(y0$t1;h1f#f#N*@LkFTa$#p!>FGo)Q={&%z*;_DFBZ>VOhD$% zzBWtdzr-Qq(=Z&DCwLE~{?J%Q2?Jr+z9ldX@WJ-L$*hI6==yIXu|cnbkH4`2PL4L1 z{1>)D$ zi4xr=vu!afr_F+5SPNU0mW^9aMxvKS8b5S33$8&L`0;ldd-+BSyS}#xgL_d%jPgN^ zQp5<_u}=JOTp|X4rQFJaGG>?Pjp^%6arJFIH#LmF$<@>?lJMB(vkBcY`g>!CmZ5O3 zC<`gqRd~1=~v**yLT7d@Llfnu5 z9)HrRgPBPo+&Qxp+RJ^2BUZ??$E)F6`bS~W@K)Z{Jrv`W84R0y@Q90%xbxl>3O0M0 z=NTWQYfeGYsH?osfqV?zuY{HT3)wd}`upnjfnwezu1|0CJ$*-`y;QyS-8>1wR&65xAijcAjJ1HQ7O;7gf{oB89hY(o+M_y6sw z>kKDlQ+Do}4&4Z3F!IMOUX`%`5hbp4W9tyt1bbsm@o(Ya-AjD^Ib53-vK1xAdO-Bq+T2EH-vtM0cW@FdkIR{HwAc{Xq`z{mpnz zJZVq`s?W>DOcp*KkdrVF+E#Splj|yM+e*BLm-P0J7z3Sqb$rBvY+`0x!|_;| z=&5@=ik4ep#=4%u-v-JAoniRnUdV?Nk0rOw3DFnFvOjNh>GP$48^2q4h|Drvn5=}X z;lD&$DZPkQxLq(@*TK8Rkf!f!PbNBX)xDx-?o_)&HkTOmuV-bSu?Edo?+ zf#stD#lN>i5^I?_{0i6EIlTp_n(0E_T9rJtC?Dr{DPmx(Gux#6?=F8?*px)Qcn&Gp z`B+;r^DkY@p^iZtJfGdb#^?Ir?%2`9cc|y>q#63!yTEMgMjNANZJ0Ux6dXqt3a+~r z;Orq6TusR0R$sE9=^-cKTb9*kQNJazy$rVViN3Fp6uJ=+U(%SRsXQEZ-4W)@xW_Z; zJ?qeHF4^rBX#U@$-pLKF@hmD1Ko8L z8_CRfj$eYEq|p?vRuVZq{UGRm$rs+T7d);XI#3Kel=eA}{J-(13Gng-kjU*H9<; zyYt-n?Mfu1|GVk076oR$#6IzM^te3|x9I12ZnL>$pZ85o#`4cjNIGW9Hh9t9VEYi9 z?AyYhW-Ns7XUb44e=5G#>5US(UqT-7wN&?HU`nnE`b{sb?Hx!Sq)U2mlIdc1{T(3%wGiWbrU7o*s93ISi6MsWnsB2Zg?8L zr^;YW$a#Jw9((tcBxn+g^6qpEcDQ0R zY%Ha*A?G%)+(7pGL!in*Pykl!97QT1F#dYJDc(NXDev^md*%lsUw1T>KRq4jpooz4eMLjUvgq3a` zT&FAr?1dJRH>&X5>^PX5(ubkq8kS~8-1JHr=(k_v7rP=c=8Ax4xq;%|w8tJ^;EJx4 z8_d*YA(q^rKDfSnxlU6)aqkt77wpWUzi3m(L4)v*hp_W=3Z%*Bw&zo&*sUQ6{dXE+ z`ts8(-)3AMA9>|M>DEY;9=pTt+h=3x z88!4z+Rmd}v(WNKAALnKEG=6e4QX`6A_l@`;zL&aHHVy|2k%S$zgA|plG(mg&K4Dq zG$s4|$({>wEtvX4H_3|+EX=`>Dmf~#GZ)-vXW$0S#((T$3(XbqmYzT?@-X)Cv^}i?85tNVrwscFUE-g2&XqZTuOSF0uoiu#q&S*S0OfXoo7(rhsL-8z+ zf3S!`$(6apRCi?a9%W(niQ(|B*uk^E<>5Ew*Z%Qs+8T#oz4>X$K5t4{ydwby=re2t zZ>lVVp-Bk*qt~&(K6bF~tAO-Vjr`=RMF`Atz}CJ@yzFx@n6*3B{BB`eC(wIAaRhFh zOyR};)c+M_gCxYVx43)S`%>lnE@8hSSL29iNdG(;}F6(uwf29_+Dd- z<+=6z{hJ81xK2U&tw%QA6_L0&-xEzf2Eq^RY+UF)0{@L6j^+4lRQagk)$>P8fu$n( zffoLCi;r&0LvlK4Zap>FpbZ+rf&7o`x~Z5?q~9s-Z$q60E?l49C}YU;TsAtLeOe%( zquoHF+Zb&lj@idicx+-LQZ~E?`!CtVIM^>to}Y%_t=bY^z5T~@Jb5}60Vfx+b#y0h zyZlZ#w(kyKsS$yh9U??E_2h%PMWghk3kvJ^vS$tRu+qi}FV9^0A4%sOmt)_CaoMAR zb{a-|8I|_^yN-5BvNKz1iJb2INdjIoz{^;Ym zyPem09p`a;53W&_hq=yl2Tv|w-<)RS)5f0SJ}-AJ84hH0?2|vNc7tmce!aEB#R=Vn zkB$jg=46LiJ8HPSW-_{68H2u|7bU-1Ed_@Vb>YmM9A0Thy^4Ng;XTNaYh2BN=`ams z`c|`Ro~fwVpow!2&++KBg;+Yp7P|wBB(eKRtKYE|CM9aPaW@jtNmekKSj^kzF2}QN z9vBcglGUF#LSu&lV%|0J6Ka&*9^xZ6dt{y*ox7cao90d8VuHuT?6#5zsJ zpST>hDU{g4)%`KB;2ihU-GH8?={4qONIE~nLC)C>eb)u>^F0#bJBfOET8FWF)`rCD z=>fZ4&3vv*DB3;TMMk}5$~;Id$D?89K33JAeup2G@z%(tTGx@6z z8Hm25jGS+c(%rT1@Wiwbl>-M0BY7Gw(=M)UcY&`gEytj)6VWa4u*8nu#hORhq4rUC zfnOx9&Rm9?afLi&4E0-4=J&swtk!#D*u`jwx{YaB0e0u;py^E)wzZ%KEH7;lxd-cC zB%`mFJ`&vq^Vv;t_%PB8)#po@U5+y@?XjtqsZ}P-hKRtKY@1#@`WRL!T4A)7PU(=_)-6Cl;^17 zVZ}Wr-;#kZ#4Q>3b}N76n}?AXENEv{WrZ6xP-Fl9Ie(aR73TGyVCOyG~o>`=e2FuTe zfs&5IZRb}(wme(R$p#ZsMYT#3C$xDnI;g6*jbeI2D&-F?3`6ji( zDThp{%lJr4?IYmow@d8O-Ehntd$?HAyH*LX~+W$Xs&D&7{#7^uF3k9m=gYs5m?meh}(r+aDVwE`h`awVTw z5|7uRrl|c#nMb=s;cTKM6pH7wZL6Gda=L~%=UrnKz_-)|&)-R;&#S{AM;_X#FPmA! z?kpTgRKdDsDf~Av8%jHygsqqN^GVYZQ2pH$I?mSB4u!Um^6)=5vy zPmSB1hnK4v+Rp2;^*wZjFLS<%v%R_dV%**CfW6#@Z%qt`_YDs?cBZiBUj*FIC4ZF0 z4ZeFoF5-u)!#vDUq8a`e1`4!)Y&j^LvPwbLEIr6f3*`%plW?+pINtXSW>uX-U@_~H z@P6(+KA=kkv_l>7AG>Vet9Z-|oq+C(s@TOI0g&|egxZ9wT(+|m3d{9jQeDn&d?mf7 zvxm6DU!0MGwS{`ft{+xwKb`nsa~-IgxrfmIXgaoSbAnH|3;gA<`K?N}x9$e|6xA5_fpZ%3}O%vBz)y63OZI z2XJsL$JR~M>7E=-{6O*nek$hoqmoEF^+4d3ydElWhpEI!#6sLdwV|l zWcIHZhmt?dl4w02q2#xXsL%Kg&BVdWO0as|D4jWHHIC$2pu_hHt9h1&vyFz(|Mxr( zJy(unhsI-!>tV?+^90;`WP>HS-39;F#fY2ah`}KR{6TIe*z*9aY8}J!#+zW*X?1)$ zbeFe1E5yhqZJgLE!zLc0uGjmUg`>+``O(`cI67Gm%P$S)8Ef zRR5B2>g|4h;ZzFZ^z;yVzfw9wD+wOkshiusmX&u6z^?teFx+;T4{wfvax*YRQsQ`f zG3A#Z9>>H{D}<>Ib78z@EY6S3y}6NrPy4jR4)MKl zEI(lo$|{=@P^xX z4e7DJ*~s{#BI+|n`e|4kHV8@Pkv#5hDz;GWVB*MWEM%K2KA-G`mD3t|*xqP#kFyjr zQ!~w@Dc2%EEq^OZvGGU63p-JtnYC?h?aN=J!DE1?$UtbR zD+E6|n*76C*zPKS%CDip8PhH@rlUu!v3ds*a7b}$UU2e4^3zJ z|GbgxBORl8-f_V{d>?NwOQZhJK`6~WE#0MBg!f@KaJWxQW4#O**;!%c zu?t*vVGMk!bMQYeW#Eq}n0{w;7m*WO2T(RY#|5taa=B1JSqyVuSjRFpdTNacu(j-!(zHg9?u$M#23}mUwn|0o&Zw1#8RI zF{z@FCs-}QspYO>pX^N1xBFL2#Kzvuba&2#bEhIq1lr;0d-$0A)$hhnV^8Mm;pVa1 zg8hqqJV$;RYz<7s9e%KLEYkh0aK~ajyAtA$WVzu8inz?x%ObEt&l5j}w>Vxhio&8* z(LFT;=JWO_JmSOi3c?Y()SWn)DRiR&I@3(W9p1t`8>j9n!y(E}(s#i- z%;EX4UUN$5rGzLzO!64zZR)sW`HY?%+Gm@%HUSs2^$zw=2bxMUx*QW^NfqWXfahomkj5SYh>- zRoqZN33mGKU1{Q7j}uSe-588r_guPbDfJHQ{~_L9SIDJ9;-o3| z$r?taQa(=)u_xcM6O^^lH#J3*q>Kk&Pe;Qn;M4bN$=K#$LQK&A=X~k9g&3~qB5F15 zyTkDI;zSHwox}cCr(pdqc`O=zj>omr3_PiW#DpM8NBBFO>{SN8Rj&ovrwQ28(-bG2 z19{BJG-O|5sERjajW3D2&Ua zEy-4VjcYMNMw=nIa6PlWkbtk>O)$`ZT8&&}G&K5I;^!{T3h0LZcAFzEk2=C@cagVK zejMfm-jfuM@D{4RSqZ|gbl$F+3AGi9A`fB8z+$))*TTBz1=dc!-@=y$;>@3#xEg!A zjfJhzK}l0=0s-s)^Ew@y3Qa1R%KG~eaWK>NhR??+%R&>(^E2|W6zvDVz z{vRV{zXRPlLZo9zkK%X7L3ZO^W)m|HV|>S=;nH4y^L+uX&)38U7hiU*$^et^Toh*S zI>6m{3XEP8lO?fIYH^#o;i64(yS;|BpQawsuDYnaNF6klv6!a@%$Z!`n3?(prD10= zQma&W{U?MvV7(B1CWFi6ufk^X12_wB**5J=Y`vs~aJQ{IF|Y`OPFv&8Wld)AdJw&D z-VstaKjv+|q&tPuOe5W9U3w&bUv|WwchM}^#u=T{i1}aF$Y1pj!NGoB`1M#_`i=PE z3#O@{_f;FAc6vIDDhA>F`zW5iGy~U{8DeGsS?rCx8@~PRiFmI@E>HXLU}X!e`zXup zPDj$5cSNV|7Pj`5Kb8!%6Lp)JuS1bUciwArR3)4BzX`{7W{Nxn<*VsvdNl~$VN6_| zJPaq!*s2TbSr|PB_eZM{7qOndTNsTaM~K7hlp!6H5`|IL5{$ZYi9O9thegPAOwv5Z z?M{SYqaX2*-QP&6h*{!NcuXidv5)JVArIRg4Sb({TKY??2$%a=V_Vo&*6UUZrcEP% zi2E6CA;e-)UrYG!?(Jwry$_nLjz~+E6*R62l$Vnb7lfCR!{MF)Hl%79eZPSh1={?V>&2>ZGj%^z;CX5V3W-~2(m!)^oh-;v&;+R%+} zIDE4?42y=fqv)|*wk;ONCs-oaO(JW(0XdL3kWQp$|PtHWl(IsR!dv5F_zpi6tPeVW3Z}G=*tqyVKPko+- zskbz+!(~HlCB1v*Me2#{%1x9DcsJYxoAt~1Snmup>=jUJd|1+YZm6J!->mldDqhhN ziW4`Sao~g-A3i7*dlKfr_EQPV`I>^DvvT6huWinPQmPI{rUXmOE8pRG&(-+s@me@x zNzBGhW9ak>u@Y!zS%vYnVkgqoRGym<7x_()Vp}vz){?9>n zxIQ0)_Nv3**q*;=DMVaXBTU%8hQ)nbhAs&vc=L2x&C>oE*gQ#q_wj42dT=Bv^&Igt z=LmmzFOs;SW55>Qk!1S%2vvong%O`K__f`+7(Q7Q$?A8djwjb*^<69MoO**zElDSy zya8hLF7Q>a%g{Q1ENR7uB@rZ4Hv`S5+?kiY zDat0Qq3_(gd@M0MwnrzJumVy&lKm_!_#sZf|1q-^|B06(8)b+{b&kuE0goA1Y6b zWft%BVYK9e&{?~mr-sq*LVK8~&;QiUKti(x?)sc(D^~=dFl`v_L|*1sY385VFJR~B z635{>Z%|Tw2AgY31Qq9bXxc)3+%qz{Py8y}>@fuXz236XMwCfR*An-9mmX_TH{A)& zO8QL2Koffl?g*RiJ?0mK;t{%r{A}&h`AeNh^rO#z(~M|#BH9_o&O;IKxRIAH3qgat z7Yur7NQ0i_U=Q6H2btOmi%2*AQ>F#EadCX_4bm#-SYerSIJ+6^hFry7;vLq&KZfq8 z7Gmd=a~*k99?>mqK?OVYz#prdY~k^TIN@rGVE)z@dl#unnooWc${%G2sSU6Ato(Fr znxz4SQX@W}-j}bGQ9n`THdY%LfTzW(s9sgiZTiO0cam;2H1j=eW1wIz!Ju0A_>gWf{~tWLo>lW8nw3-O!tj|)e1T6phT>a>+LMyRC@a2LJws%cJ`@!A+N_ZzwAm>i5PSHgK`dr4N*J5(0sBKgrt zq4Q%3hNlcgt9mG(ZTr@-$qKcpt1G3OsLwZVPK5?}6urE4Yp2xb;cSvU z`Y!1yY)Xv9nwO(6_|S3gc91-WiLS6ba$a&m%SvEll*P||SHQ(PJ2@6$EB(>d^ ztS|8qzNA`--GZ@7xi}T6jP(t7q?h*Qqy5z|M7}xA7Vl3-PP?Ayw~@;%gU)m>@SKAZ z*%H#|mbfBot%7hhCP}y&&JHh9uqHA zyJhl9^+K%csez6u&)BhmO!#jfgrlFg@Kd8oFeSqV2aR;thkcsRD!e7+RX^rclj88X zbd=a3Zbu&DWNQJdotLrP3>TQ14}oka@nBDcpya*>mIkRycb!;)>R2^6o^ceOD`cTI zKoeCzoM=z~7ttRs+g(~PG=+SL90EOBCEyr`F|S(ZDKZV**$kFKQ^EazYV za%^nid5U^NRxHAP?t>SvR3u);--YFJ|DW@krRf;#pbiHwBgzD|;rX-@c5~!t~f?7JQjH`@Xwk^|+U71rIX~ z7V~TXn$nJmyS;3m<<#Y5M12D)eCxtg9BZ(}i_S=vr|61pW~#&oZsbSk-QkWrptnsT zJy;cnu94%&BiF>L_hw=A-U0NSNahQA<-_mo5ESk6V;8&)@Z0C6;9awyKlNCSyB0?H zDN`<;>6C-?jn33fyoa6J5`a!$Q~dZ`&$Hr>vUJ`&YhloWRUeAxqr6M$X2!7cQtDSK)83&S0C^PwkZdkF<`Y;kVa*y-1|0W}3 zwhQKjpO2c$G}xA?;-$ekUgK1R zj%Aj}j46_gpZ^fu4N8zuA_wi77&L2)#0!gJo>H6x@2v6o8|lb=luap%Ad8}!Cce#h z0Sr>Tp!@NqwEwXH^z8pl+~*}#={Pk*o%)hD)V?RZqNkQF-HzLs(Y@vPTw)|@ICZ~r z;IPvL+t-|sZ1or_SpDi`_8G-|$<;9YbI=JrY~1;hD~oWAZk=}?WHA~0RMgk^!}@o1 zyoG#mjWT+et`;siIrI^>AIXJlpL;^YzGZmdK=0-Y0(is9G!!qkr(1>r`}5TZ5wpAE z!neD;|HLq?AM1p-r#hrvhYgDLq%f ze&8_l>ru;;Z>D43J6)vhInUKp9>C0H6`ZX8O5A5HqxVfqbl&MEv`kn^dY&y7`4sTm ze#E}0Cnn)}2c~w!6xB5<5U!J#wRZt(PO4IF>W}1cpQl3Rs8qqv_B6jkTIJp|l%u?$ z!{_#-3}&k_lH|+T9#1#a@01gD8-o5Jq4$J{G74hI*G#DUX(ygD!&+2j-MvMrlA z4Uu-ST_7jR>=zVr97G6@3 zsC#`EHuXpsmL!jw(f| zR7HLjynU@u++9L8Z&>eR8iyREr(}q;L7dyRRAO_YQ6`sy+;TIK>uu{_q z1+P^2$($r~&a}e335(gB6ju~3P=Uwq>-@y8P$b@A*yA9PJ}sdxjAUQ2PpZ-~8#{Xq zKuc*dpH#XDUKZ9kxIKm~$Tmd!=$k@y#Q{G4!*bZnFcewzM{J`|-rXGQE|#;2ivy8U zWrDFfq}AWcN7l?>@`H4d?6`U#4QEf|;DWWn7rQK6`bPnkb6(fBHc?LG!XWV`8-G0& z*}6kemb#wnIMe%hup=fZ8?Yju2}1dOW#QSK&-_*W5*Q7$5p|m(Zb>+B*axc$vRUD9 zXY4REg6A%Vtu$V~(*RO)NZw)u>ChqB_G zKm()_|H(rI1E(M2KL30CV(@$?EPC(GdwGRIrp*iQ%QM;D;8esk^o3?a9iNu40{1+r zFS0CDvhn>}l#D7y?SPlUbo%*>e*QD9AZ~MD6V%C9`YL`5vzcd%fQvHXoL^nH2< z_sUYt#&#PTi9eK6Q_woh@BLhc=q7J8RNj}U$&VAdF0~MQWAFdY!u_lLQE};p)U2fx zQNK;FXJtK08j^t#y>xN+@OgeHtQZCB0FTRiB<{l#ac8cj=&SUXUy6Z#Hn6z3f=d=G zN4F7Uv9G5iyXj_zYbGiPf84}>X_EdBp@xpTefJ{H`MCJSbJPVtlespz|&W7SEPIMWz@Ps-T&es0jvlB2G@>zwCPr^ay`tTUSnDT4Z*t5^AZdwCI(G=$VgOyAGq8^l)JHcjh`j3(MRFp~t1Iym|8@*nY{u zu{U9?Vz?Ga(Gf~7JmwL%6Nmvk3SHJt=Whd(VV&fJfU6G5}FqN8?BL%ly?Y%1Zng3kP{sNyNJ6LPzf5J*R?}+bjR3WmlCmF^<6e76$n~e&CH?&G_LK>tJgidPJ1DL$!ia%- zg6c@>L_25<6$Q?73gYo4Wds(i>h0LYA{_;D+%P^$S@?D`9JdY#FtyI*i>@WZd?@jA z6Mb0dKa}y`PIKOMC$Alui)l7mkm~hfEztupX5JB@y!|O3VN1W?F9x`{LxpR9$%4*v z2|NZTvSi}N#9vhwcla;=EXJ{FU|gFZ?f=gbSULK_xv`lw>ScqSRY2#TBz|R23D#K~ zVVq?MGkR=*#pkaJ9!2}P>cJ$GFhjW4mP_?cQJ1}{8RU+Yv+2(Q;YJ?p!hh?zmQ6l< z>Gm`4+FwWakq=OMz6QE>YlU5g*~Iivz|@s*YE_A4bi7Uz-}b*?hcBn%%VQl;pC53n z06pyOp(m%$7Jt$cs!qOR+gH@`AGAlwTU%p+D|v4aiKZzou=h=6NB28pKV<-a+LI@3 z`9nM*cCf2xBv&P*POnDMVOT(*K{YWTlRQ7@{D9i<9el z>*rKh%MV8Ij$yTRy=kXfMqYG}PL|;kPd$?(;JxcOFYZ!+AnVB}XU&oa*4Dz3XNrR5 zylnoy-+b!ibca$eM;;YX0m*J-xKj6l&vM%5b4bH^T*tL8H6#B;2IlBBOXMaz#G>a# z(0we6$X9Wc;iJCGGsXN%SPb?NuVY&eV^&vb3g21%kSuB9Z|~6_wc8EauFs`PO9D}O z^^@>l|A^ku3~UQkMM?68T5aEaB&;>TnC4D4@m3N>Off|3@iIPJH50#_9S{;*Em=qU z{AQgFan4Vs9=9+pVw?JV^0fDhVBG2jZ>=o$IG_68uk^vDJ$2l@TMkY?9)y-{!4i4R zcerg{ggs|p5KAl>3I`3vZmB}k9P$VV_%P9ooi;SV@%b{MKCcxPj_VNuddGK2Z{Ayq ze*gN4`uy4X*@)`hAH6#)_=bR7D1>W~W?Rgju1SPWwgI-gPpeV<7!TVEBe1ph3|r_B z1+6_c1SvSoy>*wPKFy0dp6^Re1&kLCm|Ke7Qs$?#@WNL?><9NaQi|X6jj`>+CAK6v z1F@E*W8XT@|J5pk(G)j4eQ-e1wmk{gG%RtTwY$*KBMM)WZSW(HIF`2(q4LBVE%}a2 zdesa^i=tFR2R%C@dMsb|PQw{59gLq=DSZ%DfESO68}Ou&xg7~YdOH30K9{*|CGGY!^HcvR zc1$3DTE~a6aFHJ(=-#HBrkw}geaYa9LdxLqLmPQUAJ}Bq4BXzW0?RF%`G=bi@wY4s ztMnJKs(nv|_OIM7bG^eO|teN}N`ax~vS_utsB#J9XQgJs#$JImUK!atNhP3f0_ zxz~q_jQU5?SnRa3!;|e>m}z<-bt}*<{!BgJbu}E{rg~#bhl-?zJrhorh6y82-sUIM zvylFpvd_Iu`D8z0+&&nE&|ce^!tfx(dn&O|497Z zbA=5UlSXV^V=Qqz!$(xdqn-GH*}lCUH^0cn%P!tf2+RnY#XwMZHNzo=^rC;=1+ZW^X-(Deu<^Vf23YxIrE-(%#fgx}1xxn>FeC@RF@RO7B4Ty%cIW5|y_(*#-sfxiLl@Fo*N%pIjt`IdO*1*$8GomwvdWn*IMZMt?)Ha| zQ#VxW`1@AoX!duk-mdnjt|DK04H1@bcL@Z&f)42s_>96V%@R=vD~Z+?Q``U z^3;p;mA=mr!)ouvr=d>C1YMT>Vki2=L*<^ixZCsgLdrKy!M8p4B}Z$lg=EM7&-_On z^YD1I8>WUhaF}n$R1@-!Ub)3A@1#NIxDsU?>i9aXwO~W+A(^^HGTP%Iw9l=CYKANl z#w^3y&=FYPu!Lp!>Z=t7TtO_FL*9}@-Pq!Y(I)K z-`1D1|8rF^e(r|a2^aI>dfOPshWun_nv&6e(f~_4%lNOVTxb$XzmM4oNlVla!6fi2 zli9M8_k9AoBsT!C-8rubT>hAKTiIKQI*cowM{*g{e zh(wZ{FLK`=WNz}5HAq!J#&S!(;Z*_NcvF{zb{R|BlLXCneX)Pa`fUQn8xRkn$5}Q_ zjdH9ucI1mX%D1E}!)odlEbMbnBHQ32@WUfScJXAogKN7gVD;FW(xbyx!!O$iURw3c zus#D}?nA|y|1q`*o5CDv&hL`w(=K}ACjI%0tl(l6jcdJZu;Xq4uOcn|^Dl3)mn6`Z zIN2>qP~=T~Lyuw%)KSBTS2Cp5Sw;(qQ^p8_GKd^A)ZI7(KxT4{~>~ zf_3h&j_!vk*RFHD3DJ;swT9~O5NY*C$_reg+!pnjuGb@P-Z(eB`Lu_J8>~iEuqNV` z`mt3jjNq`9i`m%6J<{PJ=)lH(uT&*}CH9ZD2T!`i9*+wqZ>_ed=PZhgMcZ}i4|-MP z__Z|!UMt4pTJ#WMS~uc^(~j7xlEE*Qu0?vsU@WWs!j{O8r@}=ApGQ^jMY*}~)G)w_ z2t_tJL>n_xuM0H;p77l52{=pl#|s^PJj1yJN1x2V=)hI1zlIxjzoxE%G32FrvH&aV z-O$HVLz?cDhlS7j*@b1^i zdq8Xf*K`FQJ&K-*_M@@)?I!lUIS?}6E%0l3J@+P#LBdrp95+*ys9kIkS`|Zu>#eu= z>4zEUMtkpnH`(Vp85lBpFn&B;#a^EYLYEvx%nGXKy?e%^GRF*;?K7k$9+BwqAdfwD zAIvXZf~j%mr8+n*_we@9wy%o{wSuNzYJmqr-Bt!PQp2)F`yqQH= zA$v^Oy^Njga6^)l5;UJ*=jY8L@UJ>U`Cld-tsM`E|3subc*NRnWaC_4dDQqO^N3z~ zSVlgm>vJcw_AEn4reCF-)_$(iFiq{BrYqOzvQ;t|VZ)&@}Sb@j~G$+@*V-qXV5w%_ihWj`0 zwLeziO}I54Ez)H{vATka%}dty?Gz8)9EAvv(Ks?}9FKRUJc5BUY<8!z@H7`F5nE$+ z%XPj#umDYui0c?HNG4n@M0c4Xcx4nIgodTT$3PoF-l6=dX)3O&7-D@^5Z&(eFvZ}t z$T~Z>GX~*Ttg*$k2mhlMjo00r@nraJ=GPvKA)!FRrv~0It^k7@$VYUxfLV41BH_{> z;lG(bvLg+Kq%EAX)2%&0|1X!^O>j=@U$%feMQVjMP%y3I4_75)=@JRL%GXJ{t+5qK z_9}|`sb?=2BGJbk(?(0U%9Ro%7HeSi{92|dla7`nisGI>>(+W$e|3P87J|Qle6( zE7*IsvmU)y@kQI|j{nRN!Bwu@lsM|+wvRzla2EUiCl$%xd!b=d9d~fg#l=e+FuXrU zvbM`h@`2>R;l>l;o^J}4cj{wFO%Q)So7fi$5?nZC%8nd1LC+U|h3MA1-0VjL9H~=B za`cBZvSBG+ckw}WYZcQ~%E5r~@~9kc$-8gPM~_8XxWBN3x<8We_P8EC+E1&IeX$It zIm1c!Kg-JR$H3={HQ1sfJkMY`#%&>175VL3$ls+`I7&ERmdVFn$i~J$a%i}9L%O+v z?s4Qf$q7BrO&p4lRArAehh37}lTsleZ&=C1p2C=(QJ73#oeS4i@HJNwk@Jakl~@NR zJw&}mwn}(e)x`5|77`an8UIxMmApFiNa)@aC&b8{fnLT_xJM8J>HX-AqFZ& zd)ZefBg|};3Q5Wbcz;iNH~dEn$1N+Rhx}KP_G^bwjaw|zIvDe(Xj6u;o;RI~#^j;a znA5P*Q7tb4e#Da>ennG|{WTxv`(3f}TROKmx)xo}QnvTb7dBZv6EOo+kY-=O`ym%g z!u2siL6NBhYQswPx~SW?P^QvL(;U0?{P+SD^8US$pe8Pft@!PV9XVR~-K&w0nmivq zLtJsyP+jVII2V#`{n2J`BPi3HH@U40=MzypAesEqlx2IbahBccVu+y|ABZ>EpEDBh zJ;q$r?b8>y7y%)g&3Gp9)W9<_og9H+fq~ zCS1&wq58>)PbZE2{Q(`~Rh6&~!(c@19f*-*>Up=n%Q5kfIaYPglEzaW-*1}*QtsC= z1?pSrm+mO)IX#ao#jkj8EVX|lIYT;%mcap0w?EXF0p~0wSROnromKx1lkEzi*jHD$ zKzA`CIb&Q6Ju^peOG3>Xy{?GmO6TJd~-f zruV09isEh`)i;825dZn0m^4&93d+02io3meRyJyKWN~e55|=B;L);e)bZeN*R4Jox z((j7k8nT}c+L8!p$ir!mQLxxInBDX? z6o%h=!@As;@|laHaO38GY=0k~KZyFa{yM|yN*cRx&jm-C_3&xabzVCwA3HMo!#mhf zl9RXsRhnA(GH9mo>TDW$&9qPv63Q0ZS=%XSm8RTrYQ!jFB@GRN{2eMCLydfP(ex4DYCy~EoeZ1rvvb^9)xs7G&+ zvdBXit(1w|>VwgH)O)5(d4xOF`t%-J&fPEGL+0nzNOAAa@{bP@Y@9wZ8?BZ63*`}P zCFCh3j&V2ILvCby5NjxtIT5!c_*GAAonObdrRQK)r5f#F!IGRY@38&j3hD}J6*#fq zmnQ0?)jOEi6z72*VrWqr&d%wXqW<6?an2{}EXL1Q4u~7tF5NYd_}+%TxIsFtd=P0w zi{$Xk$&!D<3iNrPiEUR)SRg$+9IEwjCSZEazmT0ybUdMqbK zQM?j6=h&h{d8dT^n+o5X~16A+(;P>k5 zoZX^#2g)k`cdIq5C06rQC$t#fV6W72aL;89LhLVao>YWkUz8wx@MWI#ex~uIR%D%d zQO3v7L6cahd!&P7a-i!r9IjTE*Z|o%kb9?z33c^++Ts`_&9=hp6)PS4StnuUO?L!O z(-uzEP^U+|3;aAX_(@>}?xgmIb;mzg)$m9L6^ z%RL>$3HLFBjQljN?-YeKhb^Fxw}g!)U#$W0-+Vt@=SF)LLSvT;tY4{1Ep+mrC&**m zC>z1HUnUA06{(*!iVsky+}t&LXg^C~2DbWeoYEvLZ>;3Il@rmon>oA|%2QQ(G-mFz z#KnG_S;LDUd>uWCI$i4dQkx}^R~m!+da9D`S04+dedY)+{TliF#7wj+C?WoY5g#z3 z4azfCpxm^pkdPLPTNei4vtB({`woECQQbP?Lq$**CTRGw9uU4>3Sa{$SEBneZd7*R`D+dFO;8Sbep@!qo=s z`&xY={Ok+1FZMKF)jt|4KP<$VFCUqTbqZcMIw*%3xx2!kw;uMzUgs*-D^OwBA9qGc zBqv5u$LtAWlTM#4jGdW|tjn6v_#MiJ`{yBd{75veT*7*v)5o2kFT|PuNH-e)_OKLt zNz!8CVA0})e+&1pLdy^o)lx6-ed@2Au@XOm74gG!CF}Adh`Q$f5odno4dO#i(!$L3 zy0sr)reL?39uzLMv!};1ac!M7&I~!n!(S7F@e~l{c1a>_u@Q#K3=lcS_m(ffo(beD z>agcB)P)pZG7z(5kFnJO=}ZH_bD`{3NHCVuSTB4l)N!$s$p(yV}BV*b1pf}Jn(){ivj z3zYCQXk%?bL?*7f=#XCYo@Fgafn%Yr$T8O5UIve59}MkRFZnTXsPJOJN2c$&lFRpx zK)xqs($BkcSCb{!!#(ljO%{6?m_{D1p72Vl<86E}N#_|ID&$oKrAXQhJ`b_D9PQF*3_T=1LpeQ#NO9DGxHKRp+%S!xJge4HJhN4YS&|1tvS z`P@rIZnd$U(a=<-yPn>4X6c;`?|HQ)wa4p*c4hRwF@mmH$Bpw0&cNxF~p)#raWn7J5887yp2yun`(v)5Kn5&l(1 z+;H70oZDk2vd+TQ=ira>01T4U^SPAEu4X1^jmnVT%!tCN@uM)_<{Y~-bSaK)a==5q zD&9_ByBBm94!YYWiTPoG7an`XnSYG()JNI}ih53$e~Yp3Bjpo~udo%AE$T*o=JH$T zxRP2T_Gg)jGhg<_avWP^gXb3Vf>}!(vF!l|jRJmz{Fa)B{NZafg*guMb`JS2;jF8z2mW*$2vgdJ z-RK=ze~2S)WeCzqjq%vOY8*o8cj`7Z2N!yie)xrEzF7gilMbTUF^xTaYlsHbdf{c$ zKE5_J4HJ9lBktl_>9&3qP#ZNJv-+QBLw^S2vY-zeXZqaKDP!mie7W7?*dyo-_NtzR zV#dBUj**hX!`5zhMK&$GiQH7L@BZ@`{^9SYl^`sA~r7q?fLc z{rf31jyTE3r$!Tl&;nV$K78hmC^%5w+}R_ADZF=uSF|qf7hmU(H?Kg?c?!@8mq_}4 zDu9B8CMM_163U9wvHt!bJZcT)L%tWH>q9F9_Ks)o29fW$>tjLx#w~uBxL8VGM?rOY zH$K%r3I|DBdo+0`vsn{@!iy5T-a>4p1@xI)_7~apHx>uuvDYu*zq_sOl61_V+_dk_ zVYL+x(~(hYK>EWkwt=$GlOBy0_xvqp`S|u{3?`kuDM`C%BRu(}AgEVo@sa_d_(e1S zzbviU$wGX~8$i4DQTBKiWi*QWg)N=v@(s1lsckD2z?03m<=hT~aVZ{K9{Q|9qJ9$3~#~8(`obS(h zo*8uX-hK92d#&G+uZ~04F`h6BFP0QsUySV40i^943zMJEfj?L)iEFGYPNU?UFJR943)e8KlAr$B;bXG6CP|H&40NrBi7C+j597_ zKR))wl%GbZ9DAAk#+1cA9w2Hvj%v9OPHSMsA#WjUc@|oG>f$xxNE6P*l}c-3F;8VD zs7G#U_8p-#a1RewNx(}}C(L-L!LO-CVU)xTS&u8(-RP+ZadE>IXUeuOiN%-AgD|$p zNUH7pO-OvQSg`E#oEv#(VnbpV1j{?}Z^Kt$W1>@i#8Q$ngwpcZ^mOIT(#H$8Jym3;Ic_1ungYu>EAs2Cl%=({BdmQbg0edcUiINH zT5Til`8M8h*!YdXc=#iUs@w~#Um=5CoJ}i9fP_1+@M-Ji0^bEmL~O>{2IN4eGlym&CQgLnt7Se z)gpgR?08sdEthsYRDd?hFPGMZ3A=V@;D}*2l)KI2Z7#%WHn+#tlmoqOPwXZ{1mV zT#(6Y_$*W<2Z(ciuUR>8&H!r%*D_&k8vbtSEYA7N%~{wSX@Hiq9m#d?Tc$_6lo@SQI`CPVmk{nE5l98U~HayR$715N>J5!!`@#i;wu&rOEbtH zgH!u)tyA-fpV=1yB^?j zVaaeOkHVdtJJNu_k%HN07m;ZhM>hrQ^J-|_a!r=DF$dj!$#>m$m>v5^@B4AxaCiA> zKKjRP9R8S%&0#;Jy8SX?z26fdwrau_>Hu=s?GEQ(`8?)GG+qTrP<+ONU6|yG$LZt| z?Q@eik#{AzH4MM4dNYf$st8qEAt?Di<*_5vFfZOv^xJQ|T!QIZ-pKyEjXBI2fVV}; zu<*Rh-$pM&Y%*miXts~KN!=6gBp7y#?z4BZ5UDwl_=Bf-b!<6h(+yyMdkou=?f}IH zM}!||s(D608j434iamoy9f^G%;EhIpgH4Q`28~HZ_)Ymx2Zcm@o$HBByGtaYLOk3_ ztK7fFNJvbiPUNwDz{Y0sO*Z*3JE(yN>+iD3UXE8s{y)%%__)vi6 z1)9hm;4gfL&cys9+M*|iDV89U?hp$W&1M%P?P1|goR&7~Pv4%1u)7Wz>(q(6jEO?C zwhIi$RI&@<;m9p?!BDw#T&eeBc+MDz?#)Kh-uJ!<+Xu#pe*2mOq!-cMK{m>T9}X+T znCCX=MZMU)H;1FYO=pa`*1%OrgK{-@z?PorvgYhKROYy2Ys4AmFNr2C%@4ADd$^ez zv8L(0tNhdpsmd5)&~Di#Y+k#Q_a8#fj-lGPA66q%jx5EkN=J-)eu3o{XHst39{l+! zKK^(jer$AroSce8y(s~sUi8HFhZ=%Eu>~IA@)KwK95(Hc68qwzWK!WvRL+-S z!M}CF^Do&b>ZvN~_MY@!thLDm$LroQ=97WfQezx{SINVMF2nK|@}9kMV0AlfgyWG9 zSg77{UixkkDyO=M8cs-JCax|VjL?95_U(3G$TeGH=8(%=ed%hro;8N)m7&r$`#iiV z(nG&-p~4%|(_9yuV8O|GDD#nbzgc)=L5zjbi_rBe@i~Vo@}@(gE-~2bTk{1z}q(|>QWf!>d@^VDq(Z`+xWo*UpaC}htChqew`RO=LY(x1J>zXeS zY50_7jS4I~mDs01cGN;-pq2K!gAKQdzb5U>wx6>U)E>35xvL6!_q~fSF;s%5 z%Lnie%`q4;bO4@?%x0;(QW4yyAkO@x=Pl47k2oK9SZd$n6}(h(5VfdP2(d`PwmlZu zvuQGaPTG;ZwTGCiy1Kv_UEO{NRYRJ&snH^MJfj;&(GS_1x$`i*OCYK~?O+$*!4f8VWwu5i3hf^^gCHD22DmqVCF7oQ_Z>Hm!h7l6`TkyA^Q}NBy3g_pRvnhf#E~VTPn$K?K z6O-d`_m~^JwuQ?AG&7JjAsFL(-Dk&n1`15aVpSFA$1BRAL7y3&-ISfb?to7vB&j^-%Zo#MRR4?8}2`XwNmoP+~eIy5yk7E)dK7)=G36=*D`DdZ^zT z3TsBr#>I^SURI}ZjVpObp?;8%nmcSvY9?0f)jGBLyB24YZ}vDEPGH{t%!MZzM-=X}rg92|Yu73RiW4?HEjk*9_ z;-K?@K1)XJQtvc-sLa|bd{5rVF)kBM-dds$)8%*t>5A@X@6gQtjm?DYk1a;Jo#NM4 zC*g>qgSgMf-%G%-?H(9Zs3E*_B#y^;Ul`YC^P77U@cYO>j7{y!6ch4bxJ(WC7Tfq5 zy8`&9>Epm_73T0#2TeVzMeqF`j}$nSnZsa?9)GxpZaOYr=v$P)O0ow~Ho7yKreEfs z_ZA>^ypNc%TBkV=;}_8GH~1*xCW4{~1tss@G*+sJRj+wDr-iX`nP^avmDcqn4^GkxT)pfysx`=<)6~wqUxdT!z!%{^9-38S26a*xfz{a5)D;tpoBVs{ zFMVYJ^_gg2;{l5s_59lqnt3mKV_;X^D^z_vtLLtC*a1p_QCz_*t1*g14(FDZf6p3dy+cq>7(Ya0tYLwtaQ7(|jU^nqS~o{+K# zW9bI^-^~AfnRpama^Ihi*u zq?}_<7c8^0X56s{@)N!b>HC}cl%Y|miTA~2ldrOk)M47LM-0TAYWC(q4)*>~!TSw8 z`Hr;(P*OC2L(?)AM|q_wmng4vZp?}9MkNTC4zZ);Y=<}uc}>}tg8h8kr~>-=qhW@( z(z_!@3Om!CMP@?fOxmL|RYcwX*TYS4`{9at{qHjQHrn%BjL>iEDgKDwqld3^f~(wG zY42T|vFSz_T(>z0k@Vg=SIZ5p+66pzAN8;k!;^kxmKNj&Pty8=>~8WsCyTJZQ4`kd z{z}cpsZz((GO>Tq=1Uq{D-4imY|eG0)b0M5cmhkx*je`=?5kD6#tE1C&2_ODyvY^E zwoH|k4a&u>yTj12<{7gcI|reZe?N79JC|6mL?1hSOdmCtm9;ov@$kdK)FajWB~@)*Z!w5C1T~V|n!#Vj$!Zqf#TCT_4;Zar^#1^Xq8l#L>)2duAk4)+vIettQUQkO(v6 zvas-_7M@>>;T>qd+7nFokMc!q1Nkt2{kSH~=t!9+|0H;wwx{0QPF(gX2EKD#pq0Od z-KhzO_kV%+kWqa+&N(*>dQ{IO0&ZMmDZG6K&*UoZ)whPf|&S z-FV7`c2|{jF;2oA9}j50&=5`tQDDSaShpaXPY%%d3)KL}?Yw^v z%AbxRUgCCD7H{=HxYo2pFgmh@-+e%tP};-Q)C~CI1^IZ;;EVQm$xK-<2=fd&V`dCJ zXTOl&{((21t(3|#wK6dL^(gpBU$D{<^#0vT1wZE`a|g2`+#h9t*s)`ootYCR3_dM< zuHMCMDpSb!WhVMC_tTARc7P)$_pD@wiV>)KU@7kTy3)nixy~QO(GMlFomb%8$N31h z94H)HnS;A2${79cWsRzPC5ZHaL&M~RN3H3|T3~?FZ&vfrzZD3uVPMMc?AdC9z>~4XppBs5s`tw<{Kn>&6B+{kHdB{lA zfs$dUFpzenQ5y}2sXd#!4J?7Js|T{$;@PhvGemZ|A*?BGdA~fjVUdzd7*AWGV)(KKr`?dZ{0+Gvpas6(so9A^n;)9*iTc;)ov}Bi$yyG%7;k! z;_%lfY>dPNVk@LLreoPI4Q%;W$Gwjhpn4f)6AtD|7i?=opiVJm0lFexYYF|o{(t7* zilQ!Q3E-pR!!B02qF;4K?0?k6_xR4oOY$1^k9;OOl06NJG+IR;rq2iJjM&gw)N`iW z6ylAR71DeCV52{!;8}pVn5(_EIv1Eon`i!8E4}ZN76K;89WPBf< zI6R8Fy#g`LJ(I=ir{S@oJeuy+@y|2L&`O@4(0Q@aA!qNQ+%%E+PgOtcg{neeAO=`_e-E(h2;}1Hs(C<>2W9WxQP2 zlluyVD4n5?kDklfa`#lU7Mr7H|JW05Y9)wnVfgs{E^Eq)qiz}MXp7&^FMZ61`lyjO z_U*OQFmbf-tz!?7dmPp)7b+GiaFe?(v-!OqqOFT8WA4 z{fRNMTRQklGK$L_VO^^zT#b!`!+RHT&mYDsQN!jSHzu5QyGV0%MQ3s5-wvgotI?gH z_w%nb-R7wXJWrEaTlBu~qw^pqf<8qYtH_ zt3;33tlMS6`4XsKamN&`>nx)<0^|1TBfG_z%N{AOeV2D1Jw>I)1y@eRIC;+~CCbDW*dSBC4!-tW*gtNrX zI#jQT4$3jyv)LY2uPzHN0_izX#I5aThmY=^_-?x_eCZ>F#`J2YzIz(JU+Ip&g$>;9 zVhY|a7=raL&7@17eHZ$CT_|exr&r}5)=!%<=iPZ8?fFSfCU7}X#>zTHz@SzGfoB@{ z{Jlvylwm9CIZ9KLaL~YA>?^Tsi4rrOdYZd=J+WfSgMwhU;kDG7vPhHVHwzXEck;qB znb2dJ82Ig^Y*eQes9o)V>7kA6)P)R$A0{n5w~qh4xdah??ZmzkrOVVE^V=2EZmJ8D zFU8@->t5*Sn#XOtmcXky7$+w5W7GcT<6@O6+$PeT->Hj)kR3vO&qw^GVjALyn4|Eq zK5wF1)eQ2zdpw)PB-ud-9IGkr^XrE$#5PSY>{%(1eWQ2wQi~ACH9cfiyK`YRNf~}Q z$vn*aHT;KCR{7omHm;)+B39Q6=tUg+4=Gq7XNKQVSF`X%Uz7K34T~+`A`zycLmM5d1%`gEUZw;MJJgOqDHmVgsxnP_nH(yo zAN5FkU(J8Nz7N|5VmE{>VY3H13hPTAvN^wM_&k**_?GXEg-yfwz4I~T4WxHN(&|@# z>xcQH%@JGM$P2wzVPcUk_U#%ZU00unU#VTi+1^Y(x)00sMb@SL^>nypT0;F%I9pL^ z2D#j8!W+9rer5V%jHHa)@n4EO;Z8InzR+xm+Qf>jBVlLV3%h=u=VM(~VHD+Cb2H1? z+x^qfXZ}awKQ_*c<_zozHh{UAP0d)tY-r`!;$l}hA7KT@<93*Tqub+)BktydLvH%+0=&QS8YyW+sl4wzTh#ElxsGo}lC z40$FCF^s^C%11&(@p;bfX5#e-O|f%OaltYapS45%KRIE|_*Cd-m{Ip%8PD#Uhqzl_ zI6U>RwDO{*u>AH@cDJN}&oqic+Ga0YH|oQu)8{`ohu%{tOWTLEVtoraai8y8T8QEC zdI&X~DV;R81y7seF-`u4kYz)?SCsepZ?-QYAC2`gCv1wbWD!5fJM{gF;IW~Zzi*C$ z9q~H4kNzS{lFo-Q=?U+Rb}%GSCzOjazF+Uj$8Rsj&^-p&xS))UAU~wKrkTjP{19J+ zGU@`mWO|!@=$L?+^IXN7tYA`vQnk?-`u&~MtYoCni8%>>4bpi~RvxN6RN%GdhOGTa zDZ1P2xceU=;qU^iMJ{@x$Co1q?TwxmM+h7L)75VqeQ&PPJNtCH#I#Bm}JhI zjf*j1z6&0eY-YnXNfXGqCme|1!RI}WL!e#{QMWJOvyd19q_I1kW0vvrP+-B(zuOM} zYT!zuEYfqna12vAL$}242Sg3$QzrfVkGcpn+#y@&U5sJLE-($d!qgr|V1|r3=6*DA zZHokWtaPDyS|nKzxdbDfq*$A8EF2y+7rAy)QNt0W`8e@M8Ck)1Sl?Ayi1E^dU&(sj zYLtid!^!71vkS9ww7_(Y(<0M8-8Tg`yUDBFX&jd%WnzH5KlbiVWrHFIz-*}=N{>@V zbMN_hv6hK_;>$G)F?g>kc~1O<=7m`}MtO(-vb3|vmwR=q3GO&eVv@lQXnoKqgoW+o zjwhC4-!1CcTG5GbSVlaw{@ul!?3j5Gs4?pGN`@6dW5s zzpnml_I*GwcHHQMQ#)y&w_F6%6_nA_5o90NMPck`;A+Zs=C&jcg1}O@kjp@&Xb`QVO)jTaZ z2PyAtQPH~_Q@Lj?9BpW3>ywUfOUk7ta%Yi;_Ls6D52*`Mj`oDn%lcyjWhDw48@bZd zRcM{ABW7vWb;&1oOBWcsgbF6JGLTuOheac2^Rk*s+zgT;raqI^5mVtq|Eq#>$3`AT z9=|>PdSLuRMSj$$5FPDDP(Ol&S;?ZcBH(lOy|~X` z?~#G{VS4cYV^yPVLi>iYHL_~|F!je-7@+Ki*ZQY8SI@<0>Y*a# zlgWP!o{zX8jB@D`?xU~@zG^z~R;gpZ5-5MSMGa21b==dV5O0^7WBj^YDg0XSXio-~ zYN^53FPWI%^u9T=luz8$j!6eLA~SjoD=%`xsd*j5eLkZ50@TV0c&qeGHh+c`OM4v^ z^wYQS`hqO#?&ySbK5J^iN916;oH6=0yd{|f(UI7bfWp@zIDcYcRU`T0zo74pT|qtAA$J#e#C#S$Ols!83t~`iOW&_qUuE{E zqG%5dKv}nHcIHAPBc~(V%ZH}3>n+Z zwuEQnR|xTk-_`S)TiJMLF%UT|Po?W!M+#ZT9E5&L)A%s*_!+1uqf5vQnLGXYbs6Ra z>#SRBFWn^vCF*0$n|jVGS772sPdqW$A^kTe6AvlFGV`#C5D*xT53736`(XihR$Y#W zrZCuU7{z97az}!XCTf2)@#-ndFng6I_CAzn>vpMOuw{v;+Yj%T0n531qW4m*A`J)6 zm?2%SoVl(FM$P&TqK2dB9uLog9+)yLT((pp3OfZ)`m;XAs_W?0}0+3w)pX+?0n ztA>E*16kz^Mjx*JnHX&&CXV5Qr>A1^XHR?_n8Z{!4Z!MYdXV01 zgQFr7b^C*h3(@zED*j{UbQqC^v+FyF`@H(8Tr6E{f`n<4SixKe^f}NdM9tjE zyT~Ww(rH`bw|3&DE8<``#~Dj?*0TCB5lFj2jH9#$es$I@^iJLh!+>;Yr%jEXk;mg>T5hty}ug zGC$62-x0?q+Y)=m*Yl%Z$>U-|$2H*zhILGj+vejbZ#D^$Q$T^Muub1a{_ef2^T= zqFH_;k145un~x3#TpBEuOvwkU)`okZP+|I;bf{jXY>3<}zN*7&SRU(z$^X*X%~~_~ z=3f^6OuxikW+V~2)P>mY9eGdXczm_+g}dff_FzLKafiGyA?Q56cHuRCY7tLiUK?9O zyTP&k??l~xL|6uV1`>;&I%kKOWx=N25<4Y-*q3E#C^dD&vZRwdkiO$)Wj;7Q{fuA)|pdo5F0oUf@>1lt_Z$G5`HOe1O!MEQ!f;Z*&Uz}6L2NZrG%OEVDH=>-R3h(@~TwJ|rikyiG%3yD3g9tmN;A^YrCiFZ@n8 zDZP8%O31y{D$e}G+0j@}*`IkfefWW+F?jDAAbKxDPNZSvrr*N9t99Hoz6|j;CUEMp zNa}pN1rLm35g2n_&^$*B=d5lb8%^(24(4`qhg+N@;|(rgQJ;j?67uIL#NfzGPu%eT zB2%R9)YF**ush=b%L~gx_l+G9HO7-id@6+FC>=~OTh1Itk{89z6w5uvop^7N1>++< zuyEZ4Ryr>mtG@VSGwtdhd!-`wo`668cckxrj1>A>ItWT@)A;us;^|%Ph|2csvUw&I zxYcfk%h?y$8K+D{_0+?$gnE8s!dg73m!hHifb`>xO!%C4hUrul;cIX_Ru6X;H5`R; z_l|JyaV~Hc}*1ddd~V+WaHE=4dgmi z@c}FID7Rt^i*a3;&vVjH@70MtCW=2PPjSfx%A3dVo?SNK_t(kzQoWWvjtD}z2Hnwi zHS#~s^AM~?d_wZ)ta(&~ZogFU@U_42V0{+)G^k_hnP`6IdoC^&8Nv7CMCN(VfpS|H z1q1h;e6DH=rd_qc34cv~`bZM`Zs`H-&Fk5_+0$W9e7XN-{>j_7aemegxGYYW?pOOM zTv?qW3sp^U@p4dP*L33Um;) z9W#$&>QT}`(zLNmGQK+sr*M&z=0sfdMAE+I{4JNY#1x@c%Li3i)vW#2bi|D{!^Y|c zUjLkaW}+u-weCqC{f@)Ph~5~y*j}hwp9l5*9U!^gUgJ5ciaaDX_`6(Dm~n$L2rG4v zaA`IFsGASRNIS^qn=$zIzI*Tk7$lopR_m+q*G7|az$Q@_lpo(O77U*(GmB2wV#Dp)k2)K104m+k=ZDG)q`$+^;~UK2AYGY>qqg7^vzL! z;lxoj(QiNL=R7d#WAz*7&nBmf`N$ucL^@eNB9b+kAvA^@r`PR@s_K z)A8ZSJ)!H4^L(0jHcne>AZXT_8tpq(7`EW#QypgaGn^Az{4Imv^S8;f@07_UOuh!8SK*2G$`!*DU3W($NL-Hqu$iX z$a%J3+L^bYhj9#?w66<~Pp6?Jwj1?DPUW+*i=ni@7m|hU?BNp^>e=}q$hkIi!)xS^ zqW!AF%+Io!%8RjjZg1SZzndx4}2IW{OM0VD2phtl2s-1;`{Kg10DkC{_jJW4n}#a^8G$M5CAtGxr=6K}}; z6pC=tqATuKoM0Zg893Tkhx(iA_@>L1I5E`^Nm=`(-FxIfNrCRCkJW@ahj@JYKzX8t z`TT5THWG6v6I&O^2JH601cgqbwqxJ63_4fTX^)p@r$*2`t1J}vd`J4s{5sYZi3`lR z?a_8 zj`dOmrT0K?#}dih!-*L4$On$24FzrDX`i63?Y^E_ylc{O%7&_bzNQYQ zTE)v&=i`U3G4|VZW%eU1QP);0W~}CIOU64FYea1h<()_5VM>-12j*w8h5v$ZE=mV4 z8yfk)M+>2{MIzp6^IS>SGFHJpRf%vfHybI-)G=Ld5r0nE6P4s{_+C1V4PNF5wG9`9 zL(6w^yM-yxv!LGXDVjWh{F&?acE^dzb?p66`aT*tVD$U5T(cq{yO)fEdZ?4s(%`4? zX7emz{@rK1a#S|9nXBV!4@bT?qzJjK)X|x>nw6AI$IMZx*fqa_2NRcACBzmt9%srf zoXW$h(^3MG+-3Vh7Qy?H2Tpa^&7GUpU;}AAXXkcdX@-vI*>}A-^EU~^38(i3)7>?) z%yrr5ovw#*XOA=0k}SM9Z;p1_A5IshU~vaxbp@zOT*A}HAL@bcxmtoU>4eqlUif2} z%fC)sf|Y@N(KNCT>lRRsSsA29r5xlQ`-<^zOIK`dR--(lK5m@dB7`VE=El@9cYU}C zmSpSmzcXJ!?#&9!KYEjCUJSyoX=+eEbcvVTBM#(Acf8#ok@eA}yq-M6OqJ_wB0W>; z)+!Q*A(^MleT_4L3t(5XpPe}2gk<*`A+NHUyF5-q)Jzl1pTAP(WK)E;VO|(;ekWUG z9EpX~sf%-A1FzT^2d|~nW2oIC$r-sA7e@tPULSj5+E?1C9w|am?Nv?r-VNB&!4}Oi z9fURJne=W*{U-NU^X^0Qu*=^D7sr{hKd#ooc#CUHH}4QP+L3_%wNAup8O$Ar#$a|A z58UpXz#?7_Km}!ORF*dK*_3OzXsU)|iM^#75%~z~(;4wOqlF~99CR|$M`Fzh)@kQr}$(e&)cPK+`vbLt&u@D=HSyzAeE4$et17WAT z!D-VT#@qfJObAMc#U0@?be|s!?GF>cVVDX;vh9?5K%kdZ(XEFS$&R|y!({c6v zcX8%_awmpWks_WLhiFas?Tp{3B*-)8{YxpUS2#vt`J{eXrXppDO0Xb z!;(Ja@9i+|gyH96QpN!$Ogz zaA$HR1PvYN*;;TTs}fwc>W&wyHnXZ=C!BGEEsDwny-)sODEd8L`V<#O|swVFhs6ZikeI z=UHlOBp#^iApUU!A09?}ex4IF&lF1HBunsUg)jVVjfCMNXy+N`hePFQJn#Kx)QvU4 zikg4yp??ml)F}^DTE)Z5^D*yPdCiZ zn#NoU$k%UhUid;c4rC|8gl?e2hIZmAiY4gywh#83A7Sh6OvfFG1O5dy@SCnl7#`XO zuUw6!t$lwA!}iV)^fo`^h0C*Xjy%2p&3ymY`RGGEQ*E18vVxP-v3{fqoa`I;Q~LR* zqb;G7m@YG+=j09>3Dy0=3O$=AI%f}Sy(agRnj}*LFqw0rDF@^%O~KKY#1AUT%Wo=HwzO? z9`n(yX?X5Ty*45Gytf84__TTm+B9rYSByyoHWy!|Yr))n$*b;64w`?%b$bYf=EJG=TS*$w3)Xf*UB zUfxc&YGEW?qq-qHuz?@TT8wK~dm?;bi^QX7F_7sF8={R={o`b@bK^l76zw!@~v*Fkz%%Fqyh96?8@Kecmm)5fFRxR@YhVxwkn+ zC0`IUw_W6wD=BXxbHFAwMXvcW3ae^dQCU;PlG|n=Nx>6S&Ya^#{-hyX=>U)1JeK`? zI@g!C$AB<3aC1n0@3$S8cFIX0~ z%H&rNZ`tvVa7ya}|J*$XU(Tu_^5>cwwPWNf@aT%Dgf`Z9QyLyVrEX1L#;so6LHpqx z{50;wnm^bIX%4MSC#HzE^o+$R3lEW*Q+X;4$!~(O?Rz0pu5+jN*Db<~mQ;Sb^)9+D z7>^;w`=y(V@8iUZ1vt6xn(%T(8ou2y67`(3y02hXyc`#n6f-5#t44<05h~`^^P2^< zThg=Y?3>TBA)lhrvp|AcecC1L^D*jyg4j!YyK_0l-Y|gi!PP8(K{}>48)N3daVHeE zmS8;j+3LRDW?dd6U`qut^n>>E_5X?~Co&9uHQ!5@eH$)VDq9O}BUAX-Tci;!Q^1lj z*JbVf%AuoSi00F0n0|03J{|7@+rm12-Z>k2e&)DRuu2+qD+M!+t;IR-Rhxj>nT|-_ zlh5btx8v#h?TGucl@(9viEU--P_3bNtGCPG8uA~@LY|Ghp^mui`QmP$HYF3C)w+m0 zOcSF*)Q+@8U0D@-W7!?Li*F0c`>VO>mjrYsyL$HkXZ(mLdD4mmwQ}gubpS$ zUr`tQsA=H8UoC;+X(z~g6-&-qJEJ+XACzEEHvg?Zk7c$<~Zoi3N+j+F}hRzGH| z$fq6Zs79X8Dn7oX0PBtz!mq3=%P^*X(K9k}&TppNrO9zivAb$#`BLcHb;q8V7}ob^ zFtYx35%0Ek9Tq~rPcMY08On~2DZ$?3O6d1qBCK-H!KP+a*oQ3QPYxAAMxVo|>TotB z!VyY74MNC)9ehY{Vmq&+4w|i+{6KgHzOD1XfSRo=**}ul{=@-3a+X)nj%TPI3VCNo zXOujthd&=oK^;Z?;)=u2!X8{J@GDOLeRm?OnlCoOL5PCN7O!66in`ME; z6VqkRKU1M)?20LCF0zi)=lIRW9W(TI^S~LavGw9y?3~e=Ej&!jijQl=Ie&xYAbpFf z$jmvJlY_U)x)>aCf|V}H!eLX|)5xDQ^jHec@3R!={0?90zc}XxtFu}{#pYO?w{#bM zm{Xre!`s#$hF|^JQ6EqI-nmt{Q8=0p+*pn}9RsBN(P9L@)#J-?CJS)D5Fm3(6pcLm&-sRGe)%WD%ruDQaGRU#!THkETlOS zPqT@xz@HF*lm{w7mxNes_qY_%IN` zv3aa>eh{Wq8Y4ipk-t{C5A)Q4*zuxN+IBq;S$-OL^lYRMOWNRBVp(+fI){&Vn*&QZ z3vA>w+0%9AXj^z*-0k~CBp_3PvTt^Z-1rXd9@Aa0G`Nb@?wbkuke=A^{2cFcpb)#2 zJ7E0jJQh1D5`#LliMxGpSr%&ByI^gYO^v~}bZFhC?%I`KS%?;WN1i+3Z&f`H7_|!F zPJ>CGed%We7vp(TM@ar1WT%pdDe<@?_9oZyDPF}G z*P9qqEKmB%q6NDaCqutn1(Q0bU~7wo*l%+9TLBbEuUH%8&(4tFf24;z95*y^vycV& zG1V9Iby{UsNggQC-Xi4eq5j|B)aNx-73PU+YFq*-b7lNR zOfGJ0amM#o`=#G4ZG>kk4@9rd#DG{t-gCo|d42f0PASxp(U&~xdF-imPtv)!2p&7q zc%#)yY*=A{?{=}$D);+Xw0j=5gztfFi&PY$hjB#UX#<1e&k}` z2jAQSS+6ra5&2jRyVo}H?`lQ(MeoQhmwre~o~Yw+ah|x(k3OAAJO*v(T{Y*@#|4;q z)fyp6RV<3QM*)9{4?Vk@-w_fq`I*Pd7tbcyLlQLlQ8uQ=yxE)?KL zqylBs`?J%$JDmGg3pF383wwAb{?=>JZn{G@{cR~U*Eqs|-&Gc$JOdy1Xk&3j1HWUP z45eu5A=+Ln*+agR_(U&!$}|*y*2NH~+z$z>Gx+f@MQ9q`0d~(?m=WEEWQ)-1v)rMLJ{zH<;Tz^C{XvAJ9xo!qTkXk%IoSD4 z1-Y2YD)=sER+@RW^@@}v2WZROy%iAQ=yi>>uDK-89vqK1>Zmvq-W0|Y1O@w3;8(5mi%Sw~Ztt85Tj zhpUQne%il9xG~3-^86B6twRR3dj`WZrj=Ry7vaQ2Mf4HUc*2r$B<|Kj*@LMp)5aN3 zEshJ)&b#=%v^2Pe8eqCnxoq6SRO*7Dt|IkHra-+SHciI3;?uwf$|oXGp7w-k_a)AY zDUa}oVZuav!F4YAF&gE>ecriv6C}H>a671@V6!I^>gTn@eg5oXy45l>^d4@^%y(J~ z#d3}8#nXfQM_M8}<=aEsdNBXeBO1Q5dVuwgV}D)-p_qEK@8s)(q^dF=MnNa$^TA;cU%$7^YJ1#i_7IXOFL zrlWAGA)Zu!VOIWG_)48$^EYx{Ol*XjngK{-_oWXnNQ4n3%7TwYCYLW=h*`S6BJ2L; zw<3H}?||Zm2iV!I8R+xAgSgvo^K5~&-co#@r~=iKDfp6VfmqX0o;tq*s`Tu5JZT^s zSmgn=5IGpxH1X~FQHV(J#mMeYWPx|xAaA}=_^4dLLut165h&wEo}Bp21;kM|K;yE{ zZ0&I36)Z5q%PuSVJX`9I{o{mvw)>?KgKdQ?bo&nr!zCSobgIH2I)g_-y&)8)MW@?U|D-G#0li$UjM1{Q&J4xc}(|o&GzR;`BlYl?qsJ!<%>TUW*Ik zy8#&+*l+T5eReg%ueak)#6K&+jVe!3w~_0Wh+ShT_i}t6Pn}CSnvsFnJ+oC>=QlKUYDg|>;@_SWqD4~??cqP9 zgU#m)q8tdW=_HakaEo$UhB5Iu`_g+ok--8Ub1_xQ=e)F}qnrI-hLe8LZ6qUw5JTYM@L6b9pREIoHrF7tY~SSa*y5%>9hbK(%@ z;*Za}uCp_jH{;|kJtXZb=S!bB+j&+jjELCe&qfS)ca6a#_X1 zG>;imjDaue;NJUPM98^4;{yU!t;Rk z8lBjDR3@omo*jAnyt5#0qXoUMtGVg@97NAF#egVd_Wp*oki7aLunntCpLLr3c zxw8_o_sHI|BbmSJ{r>)e_kGmU^}W95I_GmH=f$$tHkPQ;ILqy0E{G7zP<$!3gTg9B zkxja&@oqU*g}owwC7nWbcJg`~HGIDx-YL!&tPO(Ud$n z^54<;dD#%Rdw*w|9plkpYmXhlHDYD~&6eT4q%5sRpf^7^PKA$8j}cKDQjwF>3ieO- zGZkWH-o2@a_Kqh+8d7m=y8*`EkC$Dab07IeA=s6tif`1<;y@K_NiiPd46?deF~cF z4d6PfiJA3_#HA3)gQ#s3XTe=Q`Ph{kHtUod?pKUx+m*RCY!G{{2PV$(2yq z(E}dcqnP6kcLa9X#-|lV3AN-*(jT-bJL4~l@0^90&t~BJlDOilXzFL7{vf5>yGFScUaYebvPPlFWqFv`bOi>9?JZ#yDM`$ zJC%?8XUC`Xi52=8$ruv+k6&GSP2PL(cC7r~364K*G1r6t&3R39(>WpfyQCswrWICA zE0n#VJ-@--mY9+%Ji>P!^=8;3+df5XE{j0=b5BIn^k5#FyW>NK8r{ur2*vH>^RH=z ztLi^x|J>RG%M&E-<*&2Jpq5?eO|=sT4<%sN0yCKG+Qht$I^aY5>pa_ex41uW9Zu!j zVd$sX@~wY^uyVdDYK_jbXW1+9VY?>|Pb(GsXA{#eO#xo#2eB2S9C7q+i8SX|(Z00l zmH8V0Y;z>-;?s zvW~qlDJ4dv9ZAE;1Fg{E#(kDhnv4-=)ZoFliLYxLVH81~F;1&k?hh->9B@p!$?jB* zL=$eLG`{0{Y2WE#nBpQi%P70~W(Pd>UT z0fTO-NH^J|Nz@&qZbY1ldF<_S>StSaj`usXS6mzyiRXVUu;`jPu@Eyb_X30ai$iS8 z`GuHt&KhOewL+^Q1)s~t!D&+$S(U+W9{XdKbd$|Jl#K3CYLHnvi?xpFxH``ey%jgH zrPCLpoq{rMG}j8Bx0K!RqFnu{XnEeLG)$p<+4bfIRydn_46jme!I(0UzKcAZ?T2Bv z{|{Lq-NAp1+Q0{u_#{rl_$cbd?Zqqjb+c5yCW*Fm>=9SPPEHN zN3TKZ*c+?Hs<*%3H)>Y!gGQwyKs^SDI}PBr%s`yK7)=^;C%jDXXMOyM$4ocAPQNaS zy4S05c&)Q^lO1$79MdlVy3KdlbILp9U;M|*PezDC*^M~ReLm)l+Ry%)Iic&nO5Sz$ z9x=RM3^ZOE;AnWB{LzAJ9JL^C$&CFhV(cR7yEH~n+q2@8M=)v0l=Inq-+M=R2xQN^ z5$0geTb)lvUi2TnKILuoigDzPv{6G|%2Re@3}qkMYf3(xGj9{{y_*?j%}m%}TYJ98 z;1XNdcvx5r4#(g!d+?Bv;-3l@hc*$Y^D5cDES0q z-#CGs{OsDI#ZYP66*nn6cJyNwx)`d!qH6}5_;4YtQlIngk12aTBn~C5HIZXrUH$e; zG=?M?Nc;S7;&q?ZBLCIVW1{$6Dk|h&Sl!`@Oz|`0=k!&1($82iVJO{SzI#aCOF#Pi zebY@r>K{MyIR@n~TT3(l=;u^oZ5m)_-vrsQ)CZ`X6Ab%yZLrBZ5}k@Ha9v})u%?V~ z%@=1(>gU4dl~L!$=)b(x*c)O%{z{m-d!l~TQ~7mYHv|L~@zFOoihJ?|9LguILUMlf zr2U2PyJU~ilht_mifFw5u8%RRbHvjNd6+T43pK8%Wu2bd@t@TX*pSbu;=XPWJ=H)D!kHC)yV~`j`bJy$B0$Z*%VJ_Zel*P+ozAY z!pD9pB@baJ9&6fSjOuLpYRWs$ZsUy&+wZcdscSI&MNgda-Xpd&rQyOUdN(N_!geoo z!Y;oOiJ72IjM^p5QM^dC1%yvNFGX{H@j!JRWjg4Z@e@!%RZ>S0ep9vI;M`vM86?r=w7qdi5(#r$R@*eH?iY37@u+F0U{YNcf z5f=v)^R94vRKoPTFG9x$Rw!RtD;mgS(`ndvRJ?GIefj*GcPf}EX*eAYCgR*A6?C8M zAa1QohfaV2y`yeo@d}GDWuTIz;S6{lfgep~68G|WT`KO3>_v>G`>cp&@;Ps3I2V+O z=f~5aSvVf(tH_+H9I(}KgQVevMUr>D6V2EjHS$)~nee-nl`TJ9#+!{n8!#Cl~SU zH^&L<(llt;lMd+LhNav$#3Row+~B}tQKc4xSCrTDvM>-|45$~kmkZixv|^2j2FSLs@sb7vwTq z{?L&83HPGglDE~D|6wU&2F;u z1BIyE8;;0#cBm{FDSG~mfaaF&IOiJ0K93xR`3Z*7%zu5P0mY~L(_L`AY^y;AG?Ut6 zV89e^LeJ&kZW_2f$WN?LNXGm@=GZ>RkM-GONj|&N{L07+;&M|M-v70gI!(e#1L5-D z&XiHaUc30Ag#IlZI#8F{{!|#I{N+EMCNe+zj-@p`bSVW#=Wfkk{5gViN z;jJG2BsVcNV!oYG=!D9QV?vYIt>?#dM`qjevTbgJxLmI+X*gTguSCx~lvmp8C2EeW z$Hj-Ov0_Cf>!TWrkn62r(_BNdF$tYLbg=VajO=s811yUULev9QoFV??rUG+`bv*NS z28>6@aAY@QHQ&iEaQip^PtV!xzY=4ssek#v6S-HZD>0(;`ThZUqIgmwtd&%x`|Q}& zTd=&VJ!(#?@nX9eR3_?687o`z6*Sx1B1e0#%zK*+pJ085b+1eo6Fr0Q-N+dpTK&bR zO)KH>s5{+aBH4->cZ}>=#E%S$5>fiuXjrHv@$HRtC|k`;p`e<~>w3pvOEEoD_RbPz zI}(sF#|{e@+OcWP=ET;!%q@cDqGV$b#!q*a?z7`Og3w;07sl4_X17kHqQmaLymq0d zn3LIvIQzLMIQ^M@&5XrHV#4URnR?7VJsyv=ZBdVNZ0XZ=cstYwt2j?=X<}S`%WNbubeGKLUTOY(|oX4xRL2bIpA%^6)9JHH+vnv z7}?@u#BBL*-4L8Lq8>)m3vAqp0C-e+pi6eC7}q})&Gmoy7mq>gRJJ3c9e46y7k3L) z%6%N7ywZPs`@$JJ}m8ga)<_JS$dw3`d#F9$_ofy`MfwWqF`fgTd;IIbcUr_%oNF{~&5 z{Fr>O>r|0GE=ZW)NrvwhUCD31qeo{<9wm4;vl4Na?%FnVCvd&5EdtC^;Y;4#6aV(H ze9uKlpu4To)LNlOte(~PWyCf#k{w$4hwu41UCPz&{F{h|Wy)Bz#6jpOZ^C*L(*Lz~ zu(F|xU@=Wm+Vc+#h{Q5yGpU#SL3KJV`xEaj@F81F975fXH1l2div4|}FfgMJ7Mp#P zbu@LPPSiXpV--=7gb%tZC^f2)|E}18ZpSUC-{&%GArE%MQ$rkhSR>-;mYS((0iPr_ z@6s{Eo}EmYKA9%JGA$T&!<|umg>?Jb@i2E7f>m-K=5*K{E6NM`>Otegi#CrCU@;yq z1IDmC+H(i=E9CACH1ny4?rtAF=|21TLK^(nIiXu#ID53#2chFtFhc*5D5?oUwzCu7 zn#ts^spEdhDL1;Y*0XyHQ&GR?7xylY5XINiu&6^@-^1&4; zn7iO7FCY7^y8TXij#pAH+wmjQqu+&Ng9&^um@wIMYi|0bmL=sK5PpvI4)W6m119^3 zFBzq9=&~4zhj+2#@?mfl#QMmr7i8i`tB>kz{~ zB|^R;1=chh?@#q-cNIIKDCm?l=he4|BP+)i`UjOnC-)$9zUYXETg6Ok0`&rSb|EeG ztSEbvihZfSr8#d=x(Fu+J&|_%9yP@3x6nYpJ~q{TDR=+=xgOTF`OYqFj6=W8R#+A* z7fK7#iF4BnQNdSbErk2)HAY!t9hco%3C${Z6fE!(hBw!f&e{rNhF7x9RVm|VDzDV4e1O@s|KI>XoeLrXm+|JtKc&r-lUqd(d z-+CA_F;~=BCL>L!Gpf5BkoD?r!=pb^_D&^P)RnHK@U;`^)cwWSSz)jr=#7uF<5|BJ zcieeh$e(*hiJIU|7}lS@djV@@Q*UQtFEMXR3lh2hml#Z>yb@nNTVxzhB(A9)I?u3Y z%V%1UkNpx~mLwOmgVv&=+zC5ezRB-(S%a7FJu$s_7gM1um3!fD?l8ksUtUkq3$q zxH$bjJF+?eqsF?UXK9IOe=QXwtA29rz(LGsg(Ey-w(%IJ-C`%PO?G!{kLcoE^1e4{ z2VOxr9Gde}NR!;#OC7@v$#2;|0xjXTn9)DodvX78>>>v2pF%^vx$7##)VoW%eFVMl zpXk@ZZ}h*zR=6Z#RTX8l4;G0$V)ET?(Zj+MdTfij4Z1cRmgfAYX6nq+GsB2FUy(aG z1FCjjcvg|X3_gyaOooP}+wc6n3WG*ZKO+f)?@@+m|7!6? zHwD23+EC1y&QkyD1KC+4<*M>$MWI)W8MxvrGqe{dF5TEi(De#=$E zBT>>~BJt4nk>=p@$_b9Km)ZP9!T74?1g$RR!d@#HmgD-s@!Ln4mYXB)9LbUN9L?#( z8`-3UyR(Em@zMs&2rNy!=X|g#Qkil?7scv=wa5*n`8-M{PibC(!>78T|C%0At)=H{c$u#=q+hy^{uvG@%28Z?g(gFYwX z02nqTC9%gnhGYC+eawxm7g{wL=s_9v_{u4~c}zU{RoWvf%TH{pFU0O+UD0b+EV~fc z33fpzdF9Fr!r^;3`X9A{^D!k6u#_?y)lQh7vW-QmFM%MQYDDc>(R?Ho_indvr_e-J z_IDB5dcY|R#-U(IC1H?Wr>gn@$M}1KwyL8kYzAgol-|}3W^;r0&Ey`{$ zlI80*V8X@O5N|H=g*#)(iRFI}siF+hB@^9cxd$%Klat`K3j2;eBc?UgkJr z!{a7-$)9Bi_vwo7{kO9t#Ku|S{fFxg=_v|MrC|6|6==;#XZwE>e?Ub~%FmwOm5yNQ zaKAnL27A*X35iwRV0M-m4#Q&5JJgf%0C!|pUQXxb$E~Hlsz{oX=}JHOnvfgvtGgTN z^UuVhhlad(T^#P`x5Kk@HKI!c&G{GR(0@eS%NNu;IiMpVekk!-+Vq{tw3hO-QI&6@ zmQ;i`ncLYNc*6ds3jFEk|2(=F|E8(KD7!s7;I57d88H$kC+lfEHuY_fK`EBv*4zZd zDj4F4;YMbqE8gz=D9&9w?sIO zNJYC<&0KToK=%8NBQpH9^8G`0ivy$^7)G_j!=_#GlY`?iu~Hv}Lj*G`UyOqT+T;7{ zT5)`HBu;&{h3)bT?=BgXk+gTmD+g1)pm!h^%cvXiT$IRfNyYi_AN=+ByKL9?Bus8m z#GsZU@$f`Ce!F$R#J?R_#&jFJsIQdf{I`B|-*hv@yX(GUf$ux~_RRrX@sQ0P;{&S~ z>PTCEQ7onJFB|NJ`pt&&dzM*fwMPM6*D`)npS-WL6(tR)17!hHO0|$sG@WG+?1o{# zPxBu(`-IB%D9orgmGZOqNxyo1-xJ-sRIpo17vrA}F|^fdgRoBUzo8QTv1_e-TZ+$J7^W*4BGLK@1Me>4N2dHF?ib)RjDy=J1|) z5qgw#W|Lv)eS8c%R?r<$tMd7zigBX&Gvx^K)g)$u{XQdfXq_+3`4UCa8*k`Jb3WgY z{ziyd*?&wpvyZdEPQB}VX!%yLR=yU_Lmbf900^4+sviYN0_>lNW zvG~y@9BI+P1N{Xoe&f0#30^>J|0fMtz9wtZ~)ZM{FZ4=*1cGflNzbV=9J2 z&s(4Jx%J`@`9KmMDWXMTknBm?di3tr7Sl7Q^4Rt9xDeA$n)$uRhjaXq8CtPrEM;pa z9I-yZr?Ly8(K;Mq3+W!0rzoxu55+@zjt@P$jZN*gg!t}GI5X?4$Rdq#l==_eXJaB; zo4OctO&{`EEp@buk}l^*xukK{)tSYyaEk7Lhj+iTZIm~hI<*u23=tyfN*dhedg9o= z%QC9?<&_5%B~H#|tb#!&H++uu63Y&yVViRc|L<1YJ3khaAN=79Zr6zGb@w2ToQ^f? zugKmKC+F^`6?jsof?L+HxHOz@oQ~N-B`*yYW}cX^!i(iyvBc624ZPRb<0A7lb!|NE zhU252$hSAR!|c*#?&z{fjBcNVAX7z2!zrZP{m)DzL`@@Rf^jT5e9*;1`&^OyWIYW1 zoiR=En9Rb;h8yJ24S#%+c;6ue=I)M?$NmQGnHj0w(C>K!Yn{^_O-u464JWm5J(SQE ze)DL0m^R?o)0z0U{t}-Ynt&0z4A3)mff%@QGlpI0iRKR8Y-_Cr9*PS*rL$ZZMUtO1 z(*;v!{UpBq3Yd`p$M4p5#wt@`AJEKuM|p@>JIG&}p^SR9bk>pb(J#_;5$HGR*sP=s zoV@LbdYhY+JxqegrssR^2{FSr7n!vqP;mI0%)fLh@B5N^c2`A19tlv^2UfZX_;;JbE>+)qA%40D51U(;vm3U8u2-rnfBYu5~ z2zZ-^ckf1GR<8+6dzvTyyjO3o8x87YU?tchFh>Mlvx7>Oo5v$9*ao_YIv!{Ky+b%bBwIEJH$MAMM^PKS;TxLs|Mb7a~~A$Hj1|;HwRq8dfnIUmq;lM(^6IFN%%EfmmAO zhBjS|kchJBubsy3Oq?@KinIWKfIHzR&>JV^em~zB*=jFBD$|ZF66d<;)&r;zWO~i;;Bv>o%fYlNn&o1`wnb^S@ddZ8oDcITK)nA_76#U6?5Oyx-Q)u4AG+TrDtE2%%z z1q&w2q)a+^-~B8!sz?D`kwbqyI@oqc_7fzhC7m9ZhTr3 z&s_4Zx?Cv*F{c&bclrs7{uPh+$Jnm4V%;hu2FCZk36RfxmhB z-a{-=#1e<^7cV_rBN}I=pst%Hypm&O*~=cliZW5(cBtUwoG2WvH^zV~8RF$yx-s4G zK$c5ymUFfvzAE42oyx1khTE$U%DSOu;}iJ=|L*vCeiNU(lo%AmmdWlxJtMjW)ou-0 z$UUPE|GGb{)4v!v=IKcJDbu8QG&XdE*19rT{}r8h&-9Dz#;JJmFe4b{8C|eJxxW}x z6@Y?eUD5GC1nZUB12=;T_?KQWBKv$M$_(2==b4{O@oW~%_v%BnCXw$N5Q`-*btHXW zds`yn$J5W8_IdXo7I?7aJm37ITC_hE3I`2Gq;2^wZy^u1cC8C^7j0)&)6x*+`JIo^ z^%TXV&9=RugqHs4tb{(ZpwIkY=Xgt-6co@+p_BO~78{a;IgzdiUwcBx%W{!hKAhMc z-(*|8rt`*omi(hejIgG?)MmpEUVG@4{Ebl>&QvNx2S-@HnmB9?RRaN4MLhXY_kTA= z+MCU?9Y3OxR$_`h5sEx9o4hwatx)$OMLd2J3EkMP*mlj64WN9<46clSRoBI}LwSht zAwSpwMHa5Df$QI+c;DLRqF5sV%i6S+^!enlR7}&LjxhH^mf`Mzu#!5S7GEOzEC@#h z-H`s<=jU_cT5pnJi}4fYNIcB8xo&tecbC|nx)G(<6w$M30#n{je-k~5r2N#mOYyjJ zL=9_V^h4Q$Dn7 zAimNwG2Spr^da5peM%D_JnJsI<>~>=4yD|#XtanoqUXLMG3ajVv28TVZI>LB{FZqq zqL4Jq80E)(MShnIOe^-F3|l-absvea>FuRCKl4u@W)nBqP|HXj;hzidHm#^bh35R2 zWav7Ochqi;SgV?g)~^jPL(iXS%G{81;iNR@M9-Ny`l^coo-|MHb;Av>z0BCx zkGf4QF!}Kr(N=FAd`Y9byG&nZ`1mikIN>YZWciR}jC;`vHP0M`MQ$#N+zoNAcM;Q@ z?T5j=6{P&sDe_VHg_+<|zgW4Ec?Mj_gQ~67z{*K;?m~>q{?29MUi21p)|!t&N3~c9 z?SL-!nbJ)*+c6mp=UQP+l8{^2=ECum0TQCmv*qIw5T>Aqr1Ldm;H_x9!xzQ7st`Epbis~P zncTi-ASQZt1=qdEY|o}+8T-ypszr(AW9XK2PznB(W0~_s+Giumxv|G?v4HxXY6oab ztYZV}$Fmwl-rZ|^*a4j-D8JnSm&p67%$Y7e~~CR2Y6d7e|kZTKs%G&mQ2 zeP5$2S|;|b_~Sq+7wHj4orQgB|&2ubfunO~_jf4!oH&288(>@S5Q z_qZjD$iV856GnLx2lzf(#}14cLAlosC?KXyyjKS1DAW7G9GNUUE(<=fYDm92olm5{ zuM?ZqqqoMKc$_9t;rn6x*lb%o-V-# z4+nhxS}TTxtVa_)Q(lCnu(MO$aa3U^-#Kf8(7TfWpZRSuZ>~-C$wczsYUn~QqnTZ% z_h^T17O1>XEq<-Ii^3T49FI0-Bp30{o~@;u?7g{xh@L?2Q>5Xf?M{Q?)Fxg&Y(MqL zcf+Ts?L32pi4nu^!=dXGJQ;IEwreGI|2Z$k#Q7=+Nr^&njS&>~X9)kk?{NKKCRCr~ zF<$ zF*;h>alZqx=x#$iQ@475d3V{Me^aa>p{!| zbr+1z3}QRH(@n)$_)QL4K`871P_Ppn&kxz*12NZnz-=q7vV@)tfu#X~d~ zry@yP3EeW%S&d#StkzOK$avDRBgM(+L)q|l)EP0MItl)(>CQ6$gb1O$;UB$W_^kR( zreWdBTmEDEt_v4EoQU!M{yTrGcw0WzH4Uq?l(0zq2z&k^4wfOb+s~>ICu36ZF3AX{ zYd6ahD1+d0-304$6nUOi1RmLu-Na~ff!iNp%-di3L^CXFOKR*+0qO%&q z-?-v|SCr^&wjM(df9LJZ8<^#u?r722$<6nV68F32q4A0Vc_2;L-@djO-tT}k^9_ba zL*sxE9=J{vS_#ypzSJG5m2s>i^$fR7q@0V-MbT;VYU=UmD$V@%KXY+Jrhp|GeYsgq zDi%^6VYNJ1{5+CN-x&k+Kk3gx_q*X?=?R`4zfWj3M8U?=2*wN4MJ2JgC(>-%)O$DU z+G+{;@y(&!d`6hjUcI-A}og;AH@lu|=%g zE@(X$m2jHNqZ$8uy55ADZFr{b2a( zyUd!rPruu(mu|AMJxN$-t$_3txx6?m7dy}E<7v@(rV^ZhNAGlLAFdI@MKl6l8zJ0G z&3hPi9+_3zN;g@9KB4Gn(^+C2dyPpzaL;~dj2pqGrFh_je1qh}DSX_BpwSaiB&MRItA zklk$s{RdCjH+ru>bhnK(^Y@Qw#DD?opyCq6-p#e)R2{)whE<5KJtD|EZ;9Pvg!p}l z`XH77|FqIsqq`3}5FhxzJwJ3s2HyN>l4ic8bvAX@wSno(89X^90X^TefwRgIF^KLm zo7{{s&0{HZtFXez^VQOQ_UPFNj5uHk{dr2_VSO6zb>NtP=qUMk{ZUC-`{f?QM=IX{ zJO5TN^U7j7!YE%=zKwsLmnRPWqfVAdYG^;yrutLc&Diza4hMT{@Ld0Rm^zz7^GG%I zUnCHN#6jvVX_MENzba}i^;LaTTn(LIS83*ltw}?E>1TfO{604BjytBm-OkUv3KwOs zbK&l0fbJUUvNeSdP(5P_T%ZDlk;L0fH-^`QO!0+$k|$@#aNA}8izl|*o~WDr@zEo~ z@D(xAZ*-OVs-_Z~>-Csieq!wgaqeXjEG8-7ont|Dd);kl=VL|vdF}Y{?XhU{NDDr% zb411H1Y~&-2l7mr>}{t`{F35%=KMNNEbADG9U7D;^64)EkFG=)OX@g}31>(4dr;@& z2L5Or`8SR?z{7tiA}#mJre!r?SJD(XHD2T^D0dcpRtr-{%n~7g5|I0wx)Ov98&N>J ziA5bB`npL*S>-BwILW5`X#CgzpT9 z5UQ;+u$DLR`W3h2J=dn;cab99agVT;Zt>`su1YNL8ZnRbmhCx4I2)fYd$TePA4l0D za;Q32y%<4$QA^B=N)bawB;(yeFD%yY#|9qi0lj8LY0tkiA`hJhC?L{6kqLJV%vc@C zw}m|y#t#!Pzo#0W)>sOSt*NkGLw%!71+3AxE6fTm@_M6k(WX@d#IcT&52u2B?1uZC zpqg=sSy9ei_Q4e|ewK($)tm94l@emJC$TGVf@f0!UvPGpn6oR9o*|?`sg}uidgmZ( zhb6wHTxA_2{czS;4MY0YiZQg4_v>tprX3mH7c!#B7u*#etxWlng{zT$$`zWUqQu1S z8BlugjnBLEfVr*jPQ8>n_`c9lqBCidQ>-bE;H1l{22=jvZH45wAEXuyKRqMKduhIu zIvQHp;7s}&cI(hcgwJUQkEs{MT>aJP6YmPO?S}Hv^C)+=tu=ATgT(^#JnUUS{U*bf zvP1Qx+YJ{yW>dM)RgK029V4ubRTp(m)aOfV5M_@dHm&s%d>vvg?e>Pm`Sdx*a4OJT z*01Rwub>VCyX=?Z;PVvJv~7h)K2E~rRwKsME<}vRFZNAu2|8*2k>>oVwsAN=-2@#( zoV<0<_4sz1{EinJ*sq(RXc}pc%k^bqY76mC`gpND~>setA+B;c*^!8Z}-FUrxT7m90@zuEL@p8slq2p5(pJsE&pC zHBEd{F%S{-3~K&m2E~mlm`l+pR1~$s-SCT|_DLveeJSHZyZx%%Kp2uYd-tq*HgQB6 zR@r{!CBzAtvn~}el<`?~mHN%^I^uHvF8;fsR6Gib#r#A~EKbgqtI>RWf5sdcwneOv zbPr|H@NMW0ZZwKmZN>I@VRO&hF((vpuid0Me{ew>mX7|&Cu=rVo2F!ABW2lU5BzunO< zD2`c$`k<$~E*^W{ipLY$#nlZqblh+-AdA6KfwsA zCM{(Nt*v2j@VGSRZ;Xn>T}Mm&+oMD|R=PbMW!N&LihXXo6k55|@kzVA)+kQhm|J)k z@1AV<88=vjZk6V|dmi;%Tv5fj1ncVe1Gk_?&jCYjYjdqQx{Hw~!7#L1G_FjrE7u+zE`t7&KgU2D zE4n1f{6;*0y8U8&xTXwO=NJTf8R68M^&($m1Fj79Chyk(b|v3}av9h8TlFL2;px@* zNDS5g{FZb7xWUdPhv&p?5Mi|2cN+DVAG?!ZtwgMV=6W?es%>N=iOFB@sU>OklW(L@ zrpgLuEDy-;T(sja<1aJcX~|+cX=^TCU2tO0Kv9+!fN>E{m{k(a`c9$y=f6C@|9q6t z+th$J@q^)ea-Zx;hEE3*oB4pAmky@7k8SP^eTx?jk7ag(gPc8p> zyIQ<Uod#T5yZAAboH#lL!vF&VMRvK<^`p9o5dkBk@8AwYdPeuPswlh5rKM!b0 zJe)m7*+@-xfcwTf?00f9tZq2r`+*Z8+LG?MUA!<)>6xsmYBnF6Zpp`0#|q_H=?MGs ziF^0DDWCs74MU!{M%A(-OwEThz$6vAq1K4cw4W4Y8RFiWeA$WbG3eQe-lZ!Pc@g!e ztUc8c6@Dq=-iiox+T(!xQSMB`rYH0!{eRBCI9Pm?F z28}g1L0tX+?z10>Ta#wJi9hJoniYI@f_ImEexlWGv92W%dBpPS*tkb-6PSUTNyfO< z_dKgxwFKvGs^Y@DTCsL!6uxb+#GWJR-t8~MAby=Intz(|Lot-`F?E%g_P+fxvGwa$ zzOL6pX7;5!(nf9LbIJVpg|eJ3q3Uq!t;@U*lJ?oFsf_#bCOE zH75E8u|7GYQ0qb*+C>+|mmYL~PjDq4nUTEb${Z*fx9~&i;B~br2>t$#Yb6GW9cmk} zl-Mc%l$Nmv%H63)L-69R`-K^CFviLasM}0k9HKpch)yRQT3*C#-z`D;=e6|uRKm!OZ=FD~BI zitBCSpk!u@gRA4@+V|3No8F-k`F*x=K`2~K*`mOtOl*A|k9~C_?=^b=_PHv*X)kR+DbcI ztu*6U4)-aTqg{A!yK0R#EGLd5XDwVdyyO%TC8;_138NQDxD}CWzUS zE8S;f?c<=Osfid*17ZD)7@nTi*jX9M_IDT!mzN6C%&!^}irBrja4GYad$p{A-Z&S$ zynB%~(~W!BllQ#gScG`*k%k{?t#B!M4BJV(MwPC+r2Fg=dLOs>pn-oca^)$W)Jq~a zgOYv`bD!altUfvj3L`efaq`xZ-euzZz)aOn^>LS zTA}0W7i`G16r35^7LQ!Eh|2Mem|(XSUn(ORmfP^*SC2D=9s7kQ^0%PCld^LT}X82Q8v5F0Jw8p||$0R-HlWQb;ogzVwOE3LbP~xWg>3*n4_Cj zjj%qq5s9C@kz?5)^IzGQI~OWQ-pigQYfyc}8IjYx#HGo7Azx6$m$YBTE>CvHj)-DD zrgONMH8%^2UA2+VlVv9N9^m)Mh3NEJ8576T_lG=P|LHl4^$Ky^voCrr9nLoHvcOQA zYutR_VKMzVF?h>e;r{EHe9|;`bXLjceTz1TKEtTLzVI)v>Qh*)YnF)%A2s2l*TU`( zh=YTRCQ7w(MZ2|`7(lzt;^#+YU99Z*IiriLA~H#2F& zd)DlqizRl{pW(aCR*RShdbg#17T48Ha&_N8C@ZeL9Nzf8;acZ^|dUN=4t33V432l6~3|kHRu#NzbwLrar9A2DlQQFSBXP zfL)?3Wrj6*lyW3Kr&vf?+M+wr$iL%^`0G8`+c`b)J+(Ckt-CJXl=s7dRYki8MwxN)%AjW5xaToaHH|1hf3*}$-noC*Q zc_C>~c;^MPtf%bc;Wg;tL;WdRN@$1og3_-I+;38A)@r3QeC;=Llis^UfL#(QMyTTY z-92)7dL};iGof5}J(UW7EAaStX){-Y26ES@L0O)IGP_ zS=#NjTKZvSLJ<#|pT)eWJ1cEkF^{Bd2O1 z`TIm+--+_P#iSPvUCTT#j>4{iYItaOQB?E|f?>KdW;YwkyLNquHyu52Zel7|p_%#6 z_b>naB1jBA(ulerbE!Y$DC@1;9lxf^dDnOQ#D)`eYlzpE_WWHz(TGg8M4LNBtowR@ z$?u9(u?c+pfdxH#YcUT_&tMC*Vg7!=ZOg zGX0-Us2-gvc`r{cNyY2_fBAni-|o#0jBT()h517^uyrDa-qFH_Q8nV|9O|}cZGe|Q z+Iaui9s}p2oe<)v!ApXvqxPB|F85Cm<98O}&fl5DmtW2*8$5AhVGdstFkYOwoeBrV zfBbBPGMl``1P|ZkNIfQZNDnmFr3YJXA>NuKqRQ747uv35bGOpW_fmlJ=8Ixn;W~^Q zVk`BST&4Tq$C_!p3~LwUjQ!n8CGX|BbMa70 z*Tm-R4f5!cM7(IG8`i)gc4ss7arDtfdjDDxuR+Y840~Li{lHt{Eq!kbyCYC;&pSq> zqur85p6&F$dceIjj9Z|9f_2ZCZ9o!k_EyCykuS1;-iOlTc_@0if<^wKyknbcHswo& zSo$Xdulku|dFco-C60KHE}c>ED~zSD8VRez+Bn~(UUZ_&@%+kN{Lw#E8A>y-Nx3y~ zVJ7k1sfnm?RzX>hC1T*rt!N$OfR>GMto3H{W&2i1o}8u$QMg3B<3t-}@*c!t!e3Ve zTrOjs9hPAUMN|UD!|Vl zHrP0YvJyk1VL_fl@w8G*{}GRz)AXF}drG#qra$jz+ln__j}y;UuEFiyPH1-U68S1J z)U4dZdvspN0#3VO^6D*|>4k|gZ8pMjh8{G=Wys9$KEV2O^ATI3OxfUAbUkZ;g+7^L zrRye)rB0b;KL;{nT?bKHNh3mDB=u%lB8~fOn>pNdyZ~i8V3ys7x zw6=q}^#IX7Bo+~hy>Fpq`U2^2l42BR7slo z+h!AEDpVgWGxB9Shf>zt&jb^es_?8yk?^TB$5GD|(Sv^1^XeU;v(=OR{Mr*oezn53 z&DX_r%YJZPv4yubD3OJ|*FaO}Fv*`&{2&ST#j1GP*Gg;}umwLUf8@J$Kl^d38}*1v=k$%lEC@09_+XoNK(nCcP%Dn|?3<={d@AQ82Ua2$$e=Z(Cx> zv~i*=^i)fJRWk^;44ownKi89bhNHJ|=ekUGh*OsFd=am+9VyliN+(^q9rnD@VPELG zu+VQWPpoJV9Tj6xoT)GQbE3%~o7%|=rO$#`?}wvsTT>13#uvqvC&7r(ragbHvHaVk z29!p0$9NOsKI_oz+WLpP<_3wPk$I>+qzlb?{;Y$UC)&BxaNMa7ZV{BN=wyH~{WQeG zu~ATeWkJllEo|8qfBd^`B56BK@4_(mc{g1CsVDnP&v5zrk^Jtzm%`sB4ep)Ef3NH; zX1!>{^Zm1teY=HCnc$B(sz3M}Mbd03H@Y=U4`|kyt8*W#`m(7I5}6ZlV%>=8)_qlu*-|6+btza z;wNmlL9B_5zj@tSWj4Fk1Yt+BB_7(Js_h6`?TEqh9->cFI(qi&grk>3S?*2BhSpu- zUniD`#53!_Eo@Ns)?41SoLDPg-SA&`)!y6b@F;vMY54U-YVqv#mp>^R!^V<^I^xPs z-ac`cXiM`@QBj?GC359YAI1~s)d>Bb6)@8|OR+UqOWO0FM@As+u^kL|J@D2vjleT| zHyj^g$4^Yjz?r~zd8IN5@!=~{D7 zuOm!5WUu(<8;R;wW~e(qLY!V4ft-_el2@nX!APjT)spVESn31+RwexXUlrM<$_%`| ztALt@iTrD567`U%;Fs_hUXjF>oT-nf6-${%i8T&CJ;FP_J}>%SiGm5SGMpwTi^IfA z->=;RosS)2E!&sjYcutvU#k_b&I~}xpDlbxv5W zrnmU+Kpj&a8+dlze74<=_+GB`{~8l6TAH%($UzgaBa&s@x&b3C=OH~;8NF6emi)G! z#I!dyNk%y9OzazX_B)YyjhCpC>rkb*eP9jZQyt;?{IR@YM|W(s$mEuTHi`?*Dd@ki zg`X`hsLrxT!L)6vaOm`bop;QJqPGd2w`>=4`Va&BpCQKU?v@SOY|C5qJI5@76NUZd zFwDPTgDxBU3zv?W_+UQ_<9BUfFS^sutXnpZy%{BztZl&8JAJYA#$H*!rP)|qq=_z{ z6ZkLB1YEeFfdHeq;%-V39#oj3XrwI@k1WwA>6A3{N6(=y=_7Vnqy0mkXTBCa5=q5?|IiPx8);tZa~*Zs+joe6s!Ic zk9MTze{rr61~c#D>d-k*_x&VWur>uB@0&xnPg_33D+;!xO?f^{5z6j~^t$4Py!ni+ zp41C^!&)IQ<+>PK(jUBCA%CP$Dyx{NiC4|RQg>CmW7Lxvs|>x;PU2CY0?H&=!TCu! zJImd0&ApEQnpQ53=|rI@)(kN(=Ft021b$z)Me^tiZ0xWg`dvAKyOoGng;{XY{K#vb z4ri11xuALMMv0koI6VpDMkpiZ>>hctM;?v_m_e+&#wO%a|E!BLwm8&^KX0iEU@i5& z%}Mv(y(JpU{&m6W6l31|H)%Ub)DPkmCDQxm;LrNcT+}^bho~=Z*|!4TZlaHvt^OWI zM$N*P(q$|>-46dF=`7f)?7ARK3MdFjhk&FgAS%+Fy+;MRTkH;e?ZlwFJ4Hkg3=|a$ zIa^V&yA=~#umk&BKHnek;u6j}YtNdwN2k|LsjpCzMWVxAeTkVfTb_z5DqS#c4wW7p z8;;wT)TBNCRoiu#pX-9AI8%9<+XL*0>V}t}6Zy1WNjS3iJ0Ie+S_~^lfxkj)^eCUo zO72siwn8ocpt46eUW!ED-Uc{s*jCgX&&1*S?)cbsKP%k25V9$z(w-mSM#hNSu9#9_ zATx_qfR5#0$*VI!GYLQLwD3VePGZIzV#>Lyp*bj%T|D_8bS8e4W`3<>G%_hqH1~Xz z{7Q8a;xwoOam!8CZes`rEV0Az=t@zr&jsuB6C@s5LqZ~IethF+iiG^+nI;TRo(coC z_WTijFX*fPf6j+BMAChPilSeu`|V#DO&&?oqe8TK){+nedQ(qdVGMOM#bCf0A9T#< z&z8{V$bN4+k7lFABf3{!+x45vE!5bpH)ha@&X6?xu}zfG3($gcps}z!M81L>?a_0= zDmGQ_3{9WQ{OaR!ky*F_<+E+2{A|dX1iBvr7VTfKArDeuH1s7`QV0_pQj(B)>^nbR zFpN#POYiCYQvN-NH(S`e~r($aQOFm(8bM5v#;xkF*IT1V1z7Tq6) zIsWB*&op(J!2{}S2~b9G&162SF%HuQso>491)>%CB0_!JVbT0~Ecu5moQ@oj=KMfC z+UjqjuEg9SIh$k>D8#JO11+u7k$!EsqlQ%{~!`-4606Dj89 zufelSCp16y5$k%(a5gE22c4h8F6Q@uiGC5EzBGh-u2bRtir9lzu`-qS4Y2$=9RcKl zzC?GQ`f}=CG)xnfG-tv~?4UljD>IZ+FL&?-ZWO&=wA-;7x*w=Z-s`daLx=~0tke0P z&G}-9V-mEqzVq^RMYZD=CD8p;Rod+@9V0KFDfJ&c$ri_{ze&m868pOEl|7v7z@O%v zmNHhODB~9N&KC7s{DlYI1dV^oP`f6DJ=y1pktP}ZjzWa!voaNTZvNq}g|lSxQPiX7 zrj0FeaeRkL3@XNGN}f!uXKyepFdWPKC$Mj(*6{0F$2GRrihD|-cuzh*gVSH-{&Rxy z-P#!kipp7+r33MzxrATwRuqwRKmDrrLz?s5Ok<(6LJMEgCe(ByK1^YS5%L30u+u)V za9?eUOVKrAa#a$hCVHUzl17{5~u5g3L2ZOMg7uDY#3{TA$PVg zHOC(4T6vl;c(O~3+Zm423dG1=HB;`VLJVGOJGyv&#+eGo2cw`Za`_Z%=a;q-+q;XjiSLG&g#ugF}Km{w-*NbO!i79ub zJqn9c{H~=(pz9__skSK}XcrjvW9=0lZBE4HO8|Xa({q_Do=eM;Y&*4kz z;i8Vh8+{&N>=|M|UQFceuP39i?GJ8{9V~85%18Wr>RxHHgk24D29>YzU-{+Yhh-Fw z%+M!Ge_O#`ref4_XWZ{l#ok_Ch<*c2C}Mq5oEeaXKPLxabBl{?Zjb_+8wT(b;+e2} zM>BK7Prkjpizqvoh(BjkF|s9t&Hw%%)~@)>Gp^N(2P^39FkcUsZb!&d>CRHznp!j3 zU1F1?L(o>&R_d$THar10t}~?7wa9dpx}Z{5sauiRR@W^NMZS$^Z0ogTBPZK)SvN;?!pR*E^q z0eD}mhbzGrY=5OSA6T`QSr6YSnm>jiZLb;r^;PMA3MD3$9o8FcVBf2U!GEka0$-gI zk9!S++_;P{zo;e~{Vof~KPzGH&net^csy=KDx=S~1)|{?aZ!|Y(WA{gHhZ8Qlr#5B zGv9qcIO3?2<)4Nhlt4SlSueOOJj9B<7bCdQ78l1-_t|WBgx9BVwo&hY(oQ8tx4#|rJg zvmG{(;^IWoE3R|~SMU|f-}~X^u`GVI-5mC&(G39~3%KTn4I*c88Uk2r^b3xadB--O zF?T8k3KfK2i^Q%gdN6fK6BkVjVNJ8G+E`Q8%Aj_0}S*!@EJUNFAeJ7HDX6Zy;4 zUeNSN=kE;*#o{R9^AG#R#nz(Q=()r!N>o9yT@zE@9D~4CHCBD1jwUw?>x1G18!FMdzjv989&9*l5~X z@u)VELEqpo8#HndRK9QKkMb17{@KaMyxqc$>yw!Yu?v>xQijwau%?b?GH*6ScG3xU zvpgQZ+S=pn61gZ)BEAIe2}{+V$p%)<wjx&zaVOUOMt)%`omqT5X5q$!u6i3^!s8eODYW9_`D;@j7?tEKFi`dLtk^*a|Ms&WlLPU|cLC z9uTq7{_FGrtwy_IYgHmYc`F&}`QQ1M*kExYG6moNQ^%xsQ(0Tu?cH^1_{hyw!fi(+ zb0E zA$;{`zS_n~>?U80+*lPi2W7H1sS7da+eiM7hk1WxB+m4pzLlH^`NLNU$nd1xvCcI% zxHKI6m_2!Ss>FUD`n&|la89X3rZ}VvJ|2$c!8^B$EeTjAtmD4><}cDS;MiTOz!kK4sLP2s8nfW^ADtA`PZl1b5@ub(7zc|Uk^a? z>zyph#s$k?ZsvV?g-E#(11su0dJsdLoTHREdSNK-`Gy-8k;hd_n)zosg`=&#J?ehn z_q(_&3ayU1Q>T?P&(-LSHY$01;m@Ml7mCRUJ@bYC%U&gnNI(tk2H%2_;JZiOwU6%d@|; ze|-BQonY{hoiKZ(k65kF5NnXdD-7o{-Hl$T3M=A8jbY@ANJsl~8W^D!C!2M)0h`}U zhRHS+2=Yz!8>)x2{4}v?dmOr_+u(Qiu5AA@E0nNv(w?snwidSs6SHs66Zwc)zIdjb z!IQ=oiFuX8&h`GnUu6~5uBuE#-*^?$#GBc~voSb%xHTqB%@zl~CQ`Si88Y0eWQyjF z#B@BxHdV%p4b36sakIhAJO08bb{$43I$`>ElbdS(aUS!gqJJ{N=Rn$}Pp5LlyWoPqg1)-d06 zo&A0t1r2-ZO2|7PbZhS-GnP6zlAM{h-z?srGDiOx$o-Z4vEWo5-y%zqN5-V!-kcV` zEbIWgMmdZ3HRZfRL$Fvs@h+N{PlW!bW|`^fd<1Uogu3z6@kIZAq@5)KKBS0Ntx}-5 z&>aUm1hA+jR^$P@!{6N8C(bO$!o63o`DbGV<{PbzK0TN7*&iFlG3Nvf52D-d3~RC9 zD;rnRj4{)@jI|lj9dB12=SP?B6qja2K!I)?>n_fen-x<=X1qJ<$iu8tN}R6ZPFUBg zLVQs5gi&EKU;X5_%<-TLKDcG_=pNg|RjUNF9j1h)%{$}^=(BJv%NX^xmsyn4BK*Fk zB;9Qj-$dZS4>QS!KX-Q|;@1<$?4&7w9vlpn(~g+kI$UU7*^a%$&~r#u;1||=z}~_u;BvO)_RTba7{ly5Ibrl<2HzkJ0C~_=Y{9w8PrKzfG*T z_=9qwW?iVKoUtW4ywGV`3Ll_1Mif@%;E#$DGHz>;H`*LCBU7cj?E#Zm=)KTD=VL~q ztr7Xz=rh|mdo_Dx-32YJF7UD4E5!Btq4+t#2F7oge6MXHGVEmF`p;RV5B0jnHgcz` zFmZW)GX`{`F5BZfnICy|nuZti%nRjWCGi1zMry#$AxHi=A_*n9vuaEAHHP3UnyYr^nt*cVdL*pwCIM&E+P(I~s zUtL@|woAO(n}Y2Lx>7H#wwWz=n6QUccc~OFr$xZ=rzy@487iusQc)i74v&Y4O#R4k zn10g2lCS5){kOGN!>U0FK?S1v=(jEJ3+n4NBp;}A9~dk@P%uaGXfkU^He@BxEdnjem7vq=Yd#q z@uIAAeFN_6OhV0nDhL@7g}Hxpr9J=Q`#6McC2j-F{7Lhyu)F#UFE`mQ)PJnQS-sAP z2yK*?toFm;x#_&8<|eWAToQ_0K1tfns4t1|D_6$nU(IYjWdp5jTEqHqws3xu2*oi zBtO_bZjMxqi!9nb5sQb~A@Q6L{c`Uhm@=p){he6#nb|z4gE`l0h!PojqwvM0jQ8wX zAa6O5j2^c>^S6EWvrKeHF)QQ4n^p_2jybT=G{KIjQd!`tJalbzfXO8TUQGV&XNDG7 zcrHaO?(v4Q+v#XpQp|c?r0j6NTRd|AUh!&?Hy-Py@C6AQWn0c`LwWpCiHA9P3gyn` zDPmWkwU|C78#=R%D7#h0ghdbhK69K$-m4USF4B#LdV+eKoGoAGnvAP-BdE4~$W%ku zA-Tzs*p3y#dt+a``;^BobSM93g9}U=)A@MgZDKO*v?}__sQgkXcO!;P>%r8Ez5F7x zI=={ujLG*-+Rlyo2rNl8MX`N~U#n{o$Tzn~+l40l_zdcWY40d$JE~teMtz|@!6k*M z4)jDU<+bNt8z$OYXTou!23i&vQdYVnUK4MBZz?ANl*WtHmgKmkrKT z!ASqfEbf;JO3qaB2GX*2=Mq0;m@ah&Yl$-T6r7HAfb)f&%p_nj@$n3?H}a&&)69i4 z{k;Xeca`1jPcy)@kCeSi{Fw~f8y~q@t+QA{+>!x0DzF}%#jq5N??&O&p)LHTRb_3pdn&fS{LK4iJ!KuAq_w_EZyh8-+mzYSN%&qi)(tDx}oW^Zn3oS=r znXQ(j;a?yRfK^U0e_N&|yPKYi=b?)99+=M8Ws!!{p8B|_ED|s7WaHgj(s<{rW}!~@ zC^g$F?e@2ZL_npSG(h4i)b@(U!8&KG?6aHgAGrkaiq?4X;G{6x&>LR|Wb^FKKI~vC z54erV(oSGKH0-1Cm`FZB@A{fv7y{ub=vFo?~f6*`>se z5;MnI*B7%crtrI4Hj2AC#ER+nfv-<0sxAGThz5Em9?orM56fdQxt9jUUCkCdSJQq@ zOe*6y`($b(I`V~Uj!U=Nd&!|l-%8oH@BSh~F$ERz97jqsn8!$8Xep)gx%VT*)m`aW ztpA-)Jvv90Nz9z1T?b$X`A&+v6LX$Ab^q=5R}LiL@OH}Aw6|wxhS?xwTP>d(RV(Io z4MlC&4*2-vvpnERGTIH`@U|k!b`f!*!yfbgR-R&9?`Fj7_eJCNCe}!Ky)a`9>?;qf zNu8ET9tU%{e!IkWlTN!l)0X-Pj*4_y93HH7!hehI%6xmx;vL?b@Urqq@$yiAG#eH0 zOBxyS*PoKn`}9XXOSYdGUUfse&Sm_{o?x-RPYxE`GQxvNrLy3;@tD+$*ifHZaRnZM zqD&JhZ`E~U4w~o7@U!hOrgq;Fv&9X*G;ptoQ}xBFlPTQqN|Ef`Wo@V>E|GS70%&7o z1@$Bv+lZNcNN>rVk4=e+TzPyCWYBKk?OUa|OZ_j1x7ytq5oq~lf)jU={RR;O#QTcFKkp`g)OJ0xZaZSr59%LZ%aPb4gFBo~ zX2soUzYj+m45|2eNVhnP_hbfn$>k;_Q>Kcjtw_W4TZ z&1jT==btqO^G*B72dMLzfBhINPNg@&YR)*E8FhfIi1Na=-v{~UzI(+yx&^fRq=O|p zw8XieaacdQ1FB25vf=)VF*<@69Scv2nEy7Q@^~lw&Cru|^if3c``%LjthatDatD6o z-7mU`r3N&6yDCFrT^8$qbP?@?&63~#>`G!~AJUezdh1CU2zk>9&D6XCmfN-n=h$fX;1P$&3$m#jzvj z`5?+)+&M(7k34$YKa$CPXC@$YkT*u1Yh+cu)8P2xfuz;1KU9c3r~698`aube1!g{+Ha)g=C1w73q78)b;RKHYqOQ_b{Zsx$I}k>SPN_7%~_Xo z4t(g?y;8<%-p+6guQHN4$8~OoVZo0MsK{T>Dw0PaVUnh#+uTkajv(^6nKh}&?x*Hr zo}U7|(ihZY@ggJ0_Tm4i7BKkw0I(Z zJ#fLE*?ZXf^d(69XoY!n_i@PqoWj%jgN~l;ZmB!6BXf9bks~69CE!8SUw&hRT`l*? zz>)BFC_Aje9sH>G;g}wLQjdrpg^4(2V}mUUr(`{k1n@r^Us=W6C~@0(0|vqo`f7e+ z^?4s`F;3<-J~NorT6c(PIb2wTh!LCfi0Mwe5m}0?=hp@p%^r_R0~N^HM`Q6k9Sm5T zCPMaRVSBzawgk~zuX6`D#GK;&9ruexnxS|s>x?TF&*cdjGI)5T@{I|b#8b+I`e(l5 zipPp-1v2sGxf(hIeP>>0;;`RY15xL5gg))eo&K2NzGJn_!oZOyoUW6!dY&7K9!toR zNj{u{=h4_Q+70VJ$Fl<&zVN6@mS+1Z)ePjjf8$@?&5_BJ?&GOXKfKg9%hM@i*x!^i zSkmgpTQ%Y6)U}vn9?$xe*^(7WX6Vx%g)r6X-v`0leG)2_oiwv_8vFfQc*7y^TZbcln z%2=I{?_vbZrQ0#>@b)^9$PF^avd77OP46Rc zf0qrmzcA)0-9pgG!x25VM~E#qi6y))fp=UV#}2HaJ{iLtuGep<==_G>D?%054(qcS z(;T5byiD@jhg4C&gQX67n2Z-4t>V!{yuNYMH?XXVk?8bL3Bkk93wC)u3e7s=%@Py2 zOKAa&4m9!qVgmTHfA25Pw|v-^)xwv2KJ~KESmJzuy*}##>!j_xWO}(UqddsnLT#k0 zwH3v*hvX!;$J<4vY>w#?Ona-3Nn=k63$0KjxOaknsJ`rNUqvW>=_%c37j90*-ArAW;T>;iIwt?MGl}@^3MdPzVMgbO z;rvxyn)xo{qv5igGO$n7{oEC!FqK#kAAB`=o-7O%zb&O)ZLgQ)Ssmw!5#4*UbU$xs z1tswD4@Qf|zP)g6HFcU4?vuIeSfERG62ElfG4+?lp;ML`%%>ZRB)tq2eK408n3Z3< zAu9Adue!Tk9El6X0W0eK>L!y9=pKekD?3B|#8tMrM>_I<-Itg-k6QVlzBG>y>#NQV zKBHdN`a<6Gb-Ab^ZNImzI*#AWm3s%JpfBZ`{g#%pm9+QzFK;dF^AnpR;NQ;%_H7>e zjXsiy8|B{A#pcGJ9iz`^Lndz=Q(U_{KNU&m-}9w$Pg%P^?iit8%14bHDDqa*?>$u$ z^Shg~Df4W3bI(c^9lKN99~g~E1*Qls7$Gue<>7aQA1=MjWI8n?uzr3UY!5jn&deT( zY4)4AR`UD3hBy{%Xp0M>HIgT%m{=C!^DU*BAM}dy zN4I3C+AUZSu>nmcKHw^^Jw^MM9P{axq56lhDYMCclA(?Kz`bD?WhM`l@ID3LEIiAtbUpx9z_%(_7i<3 zQ^&D_b(T2R`YPXRzDL9vdV%M}@v4&rvR(&u(Ba$yiJ#Dk_KKNa0W{r015gcWYfqTlu*m0gX z|1FlQ{`@6->OhQM%Jpx_-zLVZ(EXA6LDcTrAsz62Z@8Fo$P0l@alFwhjwz&iU~NSfFEJP@ zR9G{XMvsJ_(|>Fw@wX;LmGXMq2jWan48~S!W8Z`EqW3TA;67-Myt8YGbubDaw3Tp? z^6y=eHz0Gk12)B*$d5&DL7>uCevuF5x`Omr%Xj?Ffwf}(#$xK))4|MXtC{9S7s%Rf znu{H&=GYsTl}YU=@bbwQ17Yji~zvG2wj>=3`sq+pwVGj~?3le6QS zFkz=Qljo_WvhVQ=`hW<+|C9U57cp`H9 zc){0q2%A398+PjPQZH?Cac{i&xrrC$R?Bu!b~AWwqBQdd@i>$cPvy>cBf7aKBDFyu znVQSl^Pk<}p>&?tuG=AEM~C6#UFwGZB9q4*C(md9j@bG25*wh9fooSAcZ7ckEa?j7xp6;+lK8V+J=T3G0u!>3N3Bxzls{i{=ENS9(p-)()qX)+ADdBCp z4-`|L(syx98!Vk}&bFR+;CsgHW(!X57D;sx=ooB>w_ZbpCHaxo#Ji$wbOI|FJ`!(4 zYwE5(C-%%9j;Y@Yc*Jrw+4t@R=z8)mpMG%`PcTS>YO)fnZ>|ux8=H{WW)_0tj6XFdU>v*pD(Uslp z+yi?@WN;h3Y_Y~W5f+Pn@oA6jYVR2)AiuRbyj6d&y@_#fFVw}Nfk(uX0UKeupgRU8 z-8%0 z-ViNIuX%&pZ)TwJKTQ+_l14X27xE>UVi&RIE~S~_YN<2pT-pIP$|rf<>uRw)WE~pH zNw5C(NbZ{LhaQU(`N082V$Ri6Y(DvxZ)z&8-DR7CuU8eY*Wx`>AeNEAVhyzGpD$|0 zB;#PIAtC~*WH-M#@@K>;{g<&i@hXCD1f;Q?=_g*E3qk);9dSV|f>m5&=xavr%}dc@ zUNPQ9nF&h7%d*XHojpMT}8miNWg_FMQG&pvE{2IVPK z)G+1Ogqn{s%A=XlZDrm)(tILNU}1<|i}nc5`LXa>>wrB+Zpr>u&EY0G#uDqkXXQ9N zow1qwj@&3uHXc-6q*;9m*qfeatJR_7=U10cBN6*@qjG8L1n1eQ<;o#dM|wHqQhD>kna9z%m44Q#CE=stc}iEfue6T^-uM) z#E6OzHpg-l#yz5(KFxeqw*d>S9i)!hq49-yrTvDV3+%&{mZu;pwuyJ2yGFQ~q+s7^ z1=RJK#HMbeJ7d;1di#`%bx6XXPy^Jc8HoGglm|It3ZeCbvtzrHppoE&F@xlyLtZ@bF?zrv;*(6_sw>WfhVhQ)wu{GK z0ubq6%zv6j%CFu`MU90bru>kz%a#ck`Jfe!JP|^ZPE3DhM!|uBpiDhqSw$i zyzXllo=>zu)$R=#H+&F#y;{MXbrtmSMMoG;0jJUMpf;;=YN6}dLKa#P)n7<9lE zujcJzeUz7CM7}zP+&?KgY>c3uC@YN1xbJt(H3D(VI-`A!1J|P8gI3RUzAd)67S8F! z-F?ej#yn?7+&yrz$7a6z{Q%J+nDX-4Z4iE(*qHy>@#g6}Bu~!jxsiBFT}81shKTxa zl+PX11^x~RtZC0kc)Zt;_WaHLGGQ{gfs;fbt3FVG8tp&)qVH_po8GqOkw1CYl7+%? zSqjWF+Mvsp`K-ak0p1>!(w_g)B9eSA#4Pnu5tGWOn|rnuT2_^@NzF@9<7$DXam3t{ zdn4<5tTgjOhk2kXJA*$g%@HZJiHQ37gZp^e*RCxihJc0+Y=^0G?W1v!W$ECw=MhnP zst9T&-O;7nLs>=VK79D?_tJfK?S~C0`Dq8AKwlBA*bA?llX;PL5bJ#31JBhnc|uHx zXgeVbgDh2XAU9s-cJ~cp6sIG&wz|3 zt76ZOY;oZ(^*CtHK#74Go3O%>i%2=^IwVengojb)qP^5()ts3E+ZZ3p2c@$(XNHZY ziQL&aTHJa+1b-6B`G!~4vQ_^zVaJGJIB0o`$Mzsk>@QU*R~y(f1@}i#-+gOGc6FRB zvg!}=n{KsYLVg&gylaog@n7WI`y>&!!4p>FYuI^N0Dcck;*Xmv#$zSZgyr zpE`rgZ%@FVzni&M&?fn}AQ{$=&*SyG7qWT!?l|IBEO~O$DzjlucW|@Z5?Sn&3{2Z- ziess5dEfTr2`o22(BMRI<00i%T)SY`vEIyawI%8N7kT%-RbuYpQQ&lQw@=?EyFEY` z{vGB?+D?bWRWE4k}*Y3A$#T-}6)K209rfw5YC<|ch@RLt*s+9k& z$i<7+df4N4g+2VV1gB5_LOvwt&Ru=>6@MtQe>Nm{U5 zF<#u6nG8PA3g_;GF?r)C{K;34X8yq^8_-tUPGVzDaV$antG9fd!eBoAHgT&oU-1zu z)(E@DN$BrRciRhr>=oUe)10^Rc^kKiP4XCGIch=WLR&Fbneq`PCWx&rVS9EiMcRsX z*fag4xL+0u{q7E!)=gh_=%ykZtNo;Ylhw=np)WblKTrA~?{1om46C0!BtC=n%Uyyg zkuRh@zc+CpTP!pY_=WmSbdxb9&k|3^U1N7yGB!1LM$R_5xIn$b9}GPaceh10D4;70 z!$Nsjs~zIj`ZVbJyy0z+9+xNQr(t^u^~LWK%#t|F&QDa4aZ!lNUNOKWO~k2b_!(30 zjHU)<7|D}UsThvmKJBG`lf(dG;}>+MTmYEiIUfw_8q4S27$fwYZztWxpPn?t7MZ)!Qi+I8&Z(QG48<$>i|| zD8pN8C(Zm#2Rp#YoqDuB@?5Y*mg&A$b7*&HR}4 z87Nz40`Kk>Y{vMd_(*wtyL$4j*wW0;v5@#VnM)#|7vBl1_BinViUZ(2ID_wW+)|5f z>F5~P#J}l0XUE82)7NPecYWSpyr3OE%dfS>L*BR5hR<`XU{fz{7p(?HB8BpLZTyD_ zjY+8pTt%#qo(W9RbQHF9(?BNmQjJm^j3FDcxWfPy+198B;N^4&`BcK6Ela}sKi_%M z&xInyKOaFZ`lx-fmi>uxfOe;yp*Z(28@zNG7Eh&q zK$`i-8@#2554CnWO=E5_|3?7(#(HP-PWpeY^8n^qyAn{ofyr_T1{bZH&a*7 z!gT(!dx&^;GaL83RUu9!$YeL)V2bWkwAawY`{6Of{M5vq!)YQtHvygRm`k3VZ{4k7 zyR(k3KUXcr=7oTMD2a`^>>h zkz3<Ta%4p`O7RV!-}ncqZsm$3#cw zzTXzM;sCezuN4+`Vc7f5TwT0Q&vUPg$Xqsy%V7OQ3q}(>Y3?f>T3=#KvM2rF-|!SN4HRx{M0R(#jN=}KhcOM zn?#G&$A%%uH<$Nu$&p7pFic&Q%LDomr)#ta)<4+9NBgW3H!r23%uExy#v5e{!G-iY zwZ`nWM!b;ThVAP0rI}x`HV;$gd7)s&FgBsu5_Y8*_$|jOF(EGi8+B8-LFQIjo8G$k zeQ37SU04^8gdH|5e3zPy2jdrp7Vfe(-EE;x=TEz?9WJJeRN(qLvB(T zi;gpG(c{K7)^-qe%TBeGy!TDbp44Ly#XnsBC7Y+?ia~)1eBPxB5#K2ZzSqC;)v}%P z3u#RlH+~9KFIe%nj!UUCnmUX~+j;vo5)TvgCGY+1!!hX4jr7>hX1r7}1kLYlq+aq| zS8tqo9mS_;#<7YpPrO!6m-PI>TZ)l?RTI-=J21QDoe-E&EahqsWW^x856w*C=jh8b zFRC?epTbcL*#y*-A6N`@qe}*MGxTl?~(z%u=Cc`GTjXtP#mw zk}-bLcRuHRAUjUnyOzCM`0VjzBK}bfK7?yxOJ!RT*C!TlY>cIu-+#_BsK|Apo_bO^ zU!?xQnGSGsF_3XTC4BJlm2$NT$A&`bRVl~u@A7n~WGsEy!Z**zU?$p2G5+y0$&(Y? z7>x%#+ej=0!}r8epxt%So*S&+$Yd{S-{k;c;ONv>G{Pf z0oXgGkhg0eA>R~}j{RN=P$)XeY{-*y_r5Z6hRDUypE1ywrYUvQ7WGL)<4|){R+A?u zGaOrXnq$ka7;$%SA_gbBVPy9~>~M<@M%;|%CytLHK5zi~#uf6sA^T-2>hxXY5hrOo zvIFsWZ=-^h*Nw#jc@hTqBTv!ho(`oPF7=Rk zUS@}gUD?_GHh-}sLeM%-J)XIIsZ5jEZ+Auegj_x(t3rfyjK{kIWr>GePu{Q%@^)~! zznLB1zZA=_5wD=~qzD!f#45IsGPbLNNR#Q|D6tgWgU2BGKtBJdMniC64ki!!$PYF( zGrfWCSiXoju0#8aSHDxSUavLwH@0URQ*F89)^e7-Y=>AjEE@d}8lbo0aPd|14Qk)V zW6iK9%+hTX;@#Ep!|0rNv`~hijj`Oe?`J==ya$MR?TUBxC4A@hWK2Eso!68v7XRte ze%oCGqaMv?N6Q`1d}TZTx!|nWag{p6b@bt~Kt;S+odq@L?$Fme!lF`_VFCI2{1s1% zhi1Mw^e&n^pYO`D&if(wb{1DCEEJyPN4;?P8!s)kuhpjP)!1JusNVmby-Z7hf)05V zTG8+NF7;M?GRNWBCuN2yefX22W=YTA`FI25Yiw|1t&dPE^}=n3C|=)r3OhE~6VAcJ z)?ODP4qVE_dN(Eb?~Ic@|47=7!(>!HXoGh9sVC7?6CWO@iJ@T$NMB)wTXI*nFV32B z>c^y+e{F9Fo-Vb;+ILUnRndMZ`5Ghna~@XogzNr1KDXDHT2u0;Ee`m>=N^B{VjfaI zo0}2-CRB=nG?Pd5q1z?-Ft>O(@vHH2sjt@Y3iZ){F-M2S0AW{5e8>_z%7R9)%%?qZ z>}CSjS`jPun-0TZ*D}6zij8b^N)vMO29XE;CO;`l#v0NFH}9G!{w_#{@9%b4u*QLf z+uGsXf&Ki{%v#~yng0H}m_sY~i+nF>qNNa1+8S{O3uRe% zDZiOxit0r=d|qrM@pkkie$H=~0vvDg!YFFk?yqcxJIl}W3ezfauGE8=P7%E2X`W0o zO&80j&zAOlt$xIXpg#0}4Ez}4kv_I*g;OoLtZl5&$ zp98)r+-6tWC*$D*cerF85gNf>2+@e*y;uL1x!Jg)@mIVw^WEko!8Gn0pR#KU=K$2y^CL$Tz&R3+U^_qrxpxdsX|mn1wN(jGU0LfP|> z(daVoFSqkQFIGl`U<&aYe+)B`H+L8T&Ga0;S6`JU`KFSW>^c8@V2wy1M%hdU1=t5o zV^@4!FyqV?-c(s8xL+(BOEux7q%HaoH~82OBk0IWSXbX=NGEOc-`%#u-f)cS+YueD z4Q0Q_C?RR2x8%2fo-!0?^tMn3?|1piwK=fut&Hgx3t6{_rC8znlykRJ;vKyguJ&ky zRxcyv!>m#;&A|c@M%UTwB~dWDY615id&C{1RM>v^z?lUVbp6pvJ)f8S-6xwe(h}$x%kSTLEOw^G zW8WnuxXm}FJW(3-AM4}(zF@ZhR}bnSIwkG)J-X6ewWB$V^tt@N!B`C6z|8Gqa9#ZeX z@#irt?dd4g=BZ)Cz;j};(`;DymU4XqeOb4C51`$>3;Jy;;VTEGV9UZ5zI@yg!AXBO z5~hZNz4O>^tB!EIx=q^cO;1N*^m9EdwNMqGNPnBz$B7tB)oirqa#*i4!$PBz!uEtO z<~Bv~mag5{$alWzu{nc3+F2kR=ySJl=2w1O&!KkhpF|`ZsKT-CCksub&*l~CTc@wJ zx5`PFb<+$t*h$&Gi2i(|&pYh_b0LP-Cj7PpT_?N zgo@Aiaxf-K8ISrV%HDiVj!=Jk^9CtI!kUBU(So>4A^-Jmxpxyq;W{_Vl zj`x`zBfJcTVjbOOj*hpMouyp4eCGh%8+wzEh>yq7GfL8KANM2~xvuT-tJ;Be7+{Co zsnwF6lRYvV6*guVH{*+Z;p{YQ-Ry;gaKXxE2cq(70iU@?UF3NC6CWU-`@ZeT)<26! zFAL(^Je^SEFoAyl{I&>})idRwXmrohho*M5s4Y)}2cyoou}@`TON02Q7Y5R9uM;>F zFPk#xrk^G6P8ql4zF9nbPh`p#~`K$}hOpE0oT`I(b>8W^8+`^BP?3S;*L=5n^ zs+8ZaW7E1X!?S{~{2vebhz9r#D&Kof&%5%tBk>u4;-$?$M*R5f2ZM?WZU6UO) zo8jT=P^MNh8m;VpksIcm*nXG13X7~IzrEG(BK)d)!d-m(@y$0-)kJZ_p(r({eJP6M1H}SROzsM8UH6wFPe{7%gg*`dv2ItpXxo&y7 z=wBX#FQpo=86GLO-IRhK)7#_R{Oc@?@^sV9C{Mj&kJz#+4a<`~VO{)NR;SPneigye z-S(ZUKjPwY`Ks>Wa;^9j>hk)^!|ac++ymWkf{O?Po7~@Gbv;BMmroz zFKlsh%oXOdDHFwU*Z6Ul2(kI5C;Xb|hL}nmwzIAvlYn%$?R6soYtJj8`_w%7{*Fn= zcGV_-STT#=w+y%KRgrS|qkVkjsbJ!2352tf`%R&(mNIv!@pLwylL+ytFdB`554XYG&KJ#`0 zZr<0Dx=!{+q@sF)1^KVe$nIb2%NLJ)Bk4KwPK6NX@|Y4&>bicKg|i-5>^b-tD=+ z;C>fjowaApJd=`=L6?t3@GB!9U|gC4P97H})30@~ZaqeHyXXn-Q7ocg>fmTbI-j^P z3Hu$bVYcr~uo$%OmuRQbn--$ri2x~Ol{j8iiI32C5yTj&}k_A5KCpcAU zRBEllf9CbXX|r5P7kTqBZ{o$RoR zOKpmU7ts`7indCt^|SG)mGC^<7*o=kXu$_I!KKP1zSSTR1ua`4dXo=(5!MoY8qd^#-h|ubk0t65^amd>wQg8zBNVh z{X`6=cNIJB3oH6AvNQAY9gsgIlG}@(sCU6}bmwBK;AnM+{k3Fy&#yb5gUlhSuu`{V z2BX{Jgh7!!^G{EULyt8&vOn{ZxXZ8D+8m2UgtL)tN8m~64|(SIRt?AQ^$xIdu~r@% zR*XqoA5pj2fz;109hYA|mRSmY#=nKvl>m5#?qfH#JBmI;!6X!W{=D|_DC(+S_ALb+0i-rAtN?(P%382zf&jc--@3berxDrDK1l z+f9MJevyzDeyBg;O)?T;GENoxnpV8wNH%;TETHiq zj9GOQT+Q7lX+_d@u3r;@q7GJ=vRzWn{}ztb5snyAeTBIQ9m8PaHQH7q^qh@esQxd7 zmR4%9F{3+Tui-j!N#Ddh7bW5XsiNclT;R0*H>%9$s*RZS!U zM_S`|>ODoIxIws0afW%1*0giUXmRJwp--oGR_{F}vT3SssjA64w*Rrvt9#_r370 zGusjTMnscy&S%A==MS)x#b~d zuqmFOejkCtNmepT!9P;4l0G`fUY!I(1*W!%q>ww2+~?&Wm>nyj?Oc*Pj-F5yvbsKJt^&W9Aze4^2mU znI%2l<&Q2e;;H+OFG~M5gkPrX$asc=rHMP*sWf$1s86hF{xBP3%Pe4c^afif_=ozg zR(Pyc&Bv%E2`0bzJ>PU!n#yOlvPVj6!(v=UZdcrtAn|^;-!lsG0 zd*|W#WSq5%*DR@p_N6|USYIy%)s|vMQ7eRL+ED6(Xhd5!MM_W-A168le>*!MW34xP zc&{bwub+`;zJ^s-sN}3BrjaW(X(75IJ57}L{M=S)$guiMD_1)47yVP<^h6yCuI90h zVcvM=Sw&`lb_q{NEFR8ohEXGDDBZ7QV8zY0GD~4%Kq|Z)JaDR3_yLx7f$qLg;XV2) zO-=0tP2*Tv9$mp_v`s@(r_a=(Nu~1Ls}#JPr-8|t$Jw|&i!pS#$T|rI{?xEr{DmU>);3T_WPnHWzmoWGIMxE4mqsvsn-RzqjJulb^V~&n103t^ zadEGe(t6lN!2x?l;~o3ajGt+^@cR*EeqX`=b9#$?-T}z=-NzOT>WJwhO343ZIq&pZ z=sA0J@av-?U-&HvrroV@z;82C30Z=(JN`fOHPxc9U2v0{7Mn|2SJjZ+=pk!6)x8EG zeaCuoH~6mXUicOlPx|Bg^-rwHo6bmYSxTRlr*oJ2akypK1m(q1N}se;IG?pfTJnFa zRCw5q1USNJ#bMt2cRU#aLVy*850wuRj3u3*E4HNnUwI*Rt|^PrjJ1ot32y1gSHHd(_BaO_cn7+6LC}6r2==CJZ1CHdIWWt1sDzI9D!ClocaPUd~ zEF%(Sjh4u~aaZxam*{G2=Y-NaXKLBSAIHq%s7t@~)w3>&cS=nXC3>c^3yz-X`6!Qe z`S#@|^HcEWj+$UpTC?vP9I2b`23FjA3lEzjI?J93Hk#T1{zCk_{7kWhgijUT8sd;x##l#To+I+*3Qn9*hz zG^%Z)QqObTO?Z;WI2+4eox;2fL(44+=z)x*FPTjK}=|9h|Sr;3GBbVZL`2_7BTo4o4kDukjJ`+P04`TM&k1!B(*K zd!o!I1>By6lS64CPYLP+sck+b>=<8ty|2)dEgR{6+&kvHr#swMZ>IQh0X$T6eKsx@ z{>Fks((<4VlwNt5b=jZDrLiJ|zsC|`R{lI7BNsV?B@EWdX9hzUjE6+hp}=V2OZ3Gy zi%gnu*FuVNtrdMe;^w{NG(G8;jGk9j@nO?+zEa!>Ru3@5fih>-@4XZ1x9p;xPmge? zRS|eqX@NmqJ}K4ay}=gWH2gQxl1$!?h5LmZ+Ulgk&6f4Vte2T&HXUr(`b4Y_P?7za z>Q%y>Y$I;K4_`4Or(`&~S)%XnBYgOJfiMR02MYmtNNNyv1&U3u*J?Vh#$sbi7kM5<-5MdXrv`NXr>a*=c#_~DKhsb}K zh|c%uZ9FsuXmKTyey>$${--*@^;s0{A6>z{&!&ld&qsrvgmI!(f!TU|~!?AHO6cv)j zT!qF~ADt*O@O2}4Vs(d&r{>?vJ~&e8OUB8y~0RL9_%Rd zkej{{nul&@*`N91N;=l>t|h-!9eB;Ex7dHMC$dL=Vg>s|SFKMeIq%KjZF|Kd>##Or zyGAR+RfV6>v;~eFy2(~JC*%D#2k5^!%%%55xHiuhdt#cfOOM^ru52;w9=MGg>kh?l zi(-T5Jq|{Md@0W$Vb$0M7wx+6C z!t)$w0ny{fRsR&?lV1<0eV)YHr%7-e7*2hINAXXqJfWwbNN<)@NDC&k#H-tp@}3{v zF9{WM{*uOUE57}5Jl;Em+hVvcm9EbALZvsM;VAL&qnzEc`$ z`}6PY^PlcWQ{KckPxTA?-#~nUx_V-Mr>uF7I>zO}AS- zjeN%(#lOY9 z&YR?!Z&Q_tRo_eyk-J}Vb!bO7kL{QD{AD{L@%E+#4tMb9n@>exj*bHcDkIsr^d9J7 z5GCvRQ-X%#`_bl$xZ6g+)xZIHZ?-Tiw*aU=kELt$O?j$MFT4oJqCana+0T+B zxT=c|o$lkRcH1Z8ZMYtmj62QxTus8yG;?(FIKrE+OvL>YEz#oVZRvd398$C}q3oh) z9<;R|UW%f6hnDM?A$p9iLbnRL;AXjIdrRh!}O0mFX|VH_i9d zC;pV^3>95PHAZ+4o~lR^om>}OEfBQFjCLo5~D6jA(bW<&&&*My3%Y_}` zHnorj_ATc+;qmzOM++C88uG?I#pos24UL-BtZl_o?Df>gzTY*x%dIqg@8XW-9a>2S z_Uahc$4%bn(YY^XC+5(tppVL+S#QOAxCd(L8rcrP0C3gbKqYt6xkuZ0_|DP7lSfg? z_*}u;*=LW{A0D#p!cVSdXpToAg41Z30Og)GC|uGYwYThyxlRk^+3wTT4{wJE-8DK~ zsTSS?KV#O@k*bxfIH@xho-QW0qYL@xxA9QAYNMHvu3~w=b%?QVfmVT*bUG~(KC8^J zeM~Ihsa=Gqi-c>@lNjqHVQ2bU`tR^auGXhJXuG(}IBk|f4zMPE+|DaDN1{uXIVRtfl&iJZ;a9E)Ud?^OZ0v$y zvMQ6TXZ7H-4s^pGN%+i-HQ3QeH(bt1lQXtg8xnDO$}bumm8%TW&Begy!iVO!jg33J z1S?0WVw&Yie(03&$=?;)X~R85$7Wf0Whr!dCvO^_;*S;H(KN_oeRcRBPvm@zr-^@3 z*ujGC@Sc@Tww8VPfX(9Du|WlDPp#OS(~dN4*zZ4y6b|lod?+c@?}Ug5&iXbHT-Iq zVR-G3N_oZs>_?AYcz;iL@10AzmFSUaXYiH~+PZp%_>MS#P=kA+3Qc_-kABYD2)T8L z2Z%TL;lk!9n|@w8@+*+81U#2LIkxtq7wLp8Ui$cO6>%5nxpplLe=wQ3E$)F8J=3W9 zs%Wll=?hKuVhYgcEUk~I1xEX0gs~dV1;t}|krvjp6gMXSdXd}-LDt7~*1^6NA_g2L zqjCGV;pH%N8gGkt?;b1v_%ST%A0~V6tGD>!%a#mUb8BSvdiykVX)1P)v<7DSs5|B- zlu`2AUi^b|ChoRqie;JmBtNZo^u&6f?7jc_CK9V3o6DV67Y3$bZf`d{X`0ST&nhsa z-&*SXERwsdACAyr#dLg>v$W(=EsoW7k@xwbsT=S*wW+wXM{rH&R1``2*uBnKu&snI z-e9NbmOjFxxp&EHg`Gp_2_q693yVuBRW&z@bCh>)Xpuz!DBI(Rjh_TM$4;J#6uedvh<$0%yD zElIg)I>Y$i$y70FE*oU)i71hq)-VYb9PCU?5#EDBX}zS_o`DG>FFF6c9@)$ny`ou$ z*jAFnef!5D<9>6fhjwH8585NN|4Dha_ddnYu`G=2))hyWVD>InzUvFt$yPe8KU&Qa^B~@IpIKhna zmcXyELEhmL2F4;U+z83>sR~n(F$u^p$HB>F#Dc=HMPG2to=5Pb5Bp=(-30pWnZv^W zdSXOl{Qv#-SN!lvA+l*tPDr7y?Sww||2c2bEFKq!Y02J8KbvIiDKx{T+iTdQUL)}` z>@!(}p6ADE!tqJ;?$rIUQjT;Rgbl$-wB)54-POrNL}~iQRe4NQtge?{W59lqIb&MyWXOW2GIR}BQrAWf-CvOG+}=_pV3+L4EEGS{f;Q* zL-Sl*5^TGua}U_?*lse^8m%63wfWiZRpRA|e{T6XY@o(DAT}z(xDx%*f+s6o@rTSzN9F35X7C87T zj(b+81kZR3OG4Y6A2jZQ zC3g-MoJn6jyog)EY=3sgD63=C?#Fg+*EtG`?`C-9!;}lvW8qaQxcVP&GB0$8OUGDh z(@TSm-sFb!JyPYpePEU7lJNXZriy&!rla+^)OQNDX=#$J-BPp^eUMl5Px6YF;tl)E z0%u0mDy+{$f*)>)soqW$yLk{?nkQ1-%T3i=o_S${Lp&v}O=Zdv;=3aKJ6qpUpvJAUaEL6*3nVl1^k8RNo?Q!FU1d<&O&Fjf%Djnq%=Rr zV+4oa#?BCberWK9HbSGDXN^I66>On*h~U+U-S0~cZ}FcH2I}(YlK&_+;)Mbv{LBSD z1w7@G=r5jCM{y@wSLZ|uX4f~tMc<-A-xrH-P=qE5>JD;^&uO?e))E_6o{_Yq018?1 zn6-3{UdFPSAgV~PrL{3c1t1GV_L zy(b)hs$v-8acGbxwj39~pTaZaKFA#5XWiKzp&#>6hv-Y*%{z1M}M09n;Tlq~2qD@sG3aV`}11czo1k zmw&aP?1j77*Wg(Gdt?+IIhy0_WPg5B@D19{>WJ}U(!{$JkW#~FRc;JV(HsqGRYF5* zT%^k%YjMrX1Jv&{EqW??Hp6~XX2f*fMZBTROay0XqBCnJI`4ig-y!Ss=ZA`1r=7XH zxA#g+fv)JSSTo@en_)UZbh2eqzXDx8A;epBLu>J_|EJG4Eb#}^E~Ybj^OWVM((z)1D(0%6WEyTu zajLG40)L(4je>P>F4X|4T~igG0-|9*%p4sKi~nC?;li_FgR;~J?rJ&|k%F0X|42Ub zFY<;~ava@A9>n)e48V`oB{corN$Cl1hi@)9a;M1$v2SR{Y2eA}QGAeT3an>{+{(nY z>`$jrXrkXp)@A3p>y`*Sn`bNc6<${>!DROv#LWWfo^dv&iG5zfAdJU63cwK20Uf&9 zl5H>Pgpja&S)Z?YAQ+NwG|}a<5g+q51DWHjWbS3yvSl!zp^JU@YQ*gz5}OO`(B!D8 zbQJ2CH>JIttMaHA0dw)~7(C#w^5sJb6Bp*vkwjni=1@1-EG(g$W$SolMm%QE*FeFw zD5ZIuJUFJ<$@_fs4B;(lYliQ+JNN;;LXrFM!CZYU_U2D#d^t6Trk&o#N44_D4WawJ zx)`oJuO;F3i5$A%vxMb6@IdIhBJw%4h~Ib=kJg7ZWbftY$1!j!)kl9VJ(~0|O0d<< zd(53WpF#UigJ=i36@tc(KnYyB}4W}{$uR1_CT0C=M|3xA7;dN z`o~FImYsvXH=06wZ5aC#?}K0WOXZ`!JoEnyN`&!V;d}oQ$-Z?O zi7cV_-V;9g@3)!YfrrxB>PE%$6Pr*x>@&sqE~bt%(qM7!HT^ucfH#dy74P-m^i6XH zdzsM&4ox@E?Z&gB_a_#vJp@bBSd(9x6N|JlmKbn(6YGCD1Q(~9$@=`u`J>?$kV+3% z_hq3k6{x)%Pky=u{Eb=~dbWN|1=+2uE!(YwiSWa}c%w?iokh>}OKoK2Rr9lp?xL&p zBsd;7V?#^(kZ$l(nQ!0!VK~~iv%!`K(P@&*kg6X__pGL}`e<>RvxyU|=P=$pQ*^IC zDyK*96w<|~wdnG*hu9%hVH6pU(1{vYbuOJ>d76T=Z%r{~s5>)w+6vPh57N-kef*N} z=`~$1epXGMC{q*)4FA2Ha-SCP_Mv_8I5Lwa^6}MIW~U+c>TBvSp@FSzBf8SAi;PUX zKlh|eG;A~!jL3bGnP*4(JZ2voIWCcJ8y1aQ8s^xwtQXh$T!_JY6o_eF#DcSXV0p}1 za(ExZgXj0dk*-;^`ICI@xK&}B#2zzLH@S7{dItkUPH&R#;8j-}mwy0VPy zBy7F)jUw!Vsul>J=N`LBm}KolsS8CXm!|;?%=hx>m4bt+VvFBCcci-u=F^Lb#-u+Y zhHD?|i+hR~I`T1HIW@==ZQ^3+x%V_?JjxT_R5Iz{mQ}pdEy2t`r-n`{MbeOt1(?~> z3}#`?s9Q`d+y)pRhmyI+Y2mZ&YJ(b)Em?xIFV|cyAOH3ti>KW=SeH5zObI z^2{&EO~c33S7g4u6>smFfECXDUAH5W2bRpTagg#{B3dC;wyBWp}*ukUc7r<(&V2_d}8>;DnM6FgOg-&10@3&7xhm#s;lc%e&P>sX9Y<*7htM*c++Qtians8dOcn5cijzaOXX7WuoBRC%S>RaL4jXSK_ zys_BxEQPcL*3w2z_-yr(sAZ`hOJCrI30;#Y)_ya;I8XFJfBs6L3-XliD+;l!wHX#n zsAR4}$9}ouH~ri54}B7zmKA2$l73$?{dJV+y|Tl*_fC}VI~X2_qf08At0!3dqODC5 z*(}Rq->SRAUo%7Y+b{Nbi*d{PV@mxhMm|oIw6=h0hHv332E?M>W8pn97|3Vc5FH;% zM+96>U>mYV;-s#xj_h>vH74l6u%jYON}(tYzdtXO+#GTOInq(fDgZ# zj>OEr^iRW?`MnLYe;3Pp{`QT+&)H31-t$|Yj)kjfa^gsR-)6F_WpS+&-`zrA218AR~K zZ3m+5mNE+NB1t{&*P?3+AZ?4P$jh$BW*-X-e7BkJ7kA;mr<$Q}Yj<|r*$HL!`)T)_ zef;8`a5Q<<9D#$LC^s4rN|h@pUT-~LJ{Mj z;Ps7FG}0l4yA2tDcAqloVY8Ofxn>U#FSs|C@13H-eMMK%lJB%^*>rBaz8q0zdY`aa zYJbB74bz6oe0%NOK=hnfOo|szm50UK=d>G`aIy_Fj4mz3aP`5xN;?DEb|V65df$45>1sB!>v>ms+6T ztq88+-3v1f!s&`dI#d54-XNc2===IX+}Xb;wz?OPPW&-xfMa{)?8%a6e)*IXth%BN zN6(4;`Rz1B2_}hkdN`9ljKajJA866t^L(apBKIVbG>LT_NEL>`phS6;rD3#9cqfHH9PsP{)rg-#tE58 z4bmci!PDD6gAP?}#*LpbStWQoSqVVgl*a>1{`RvQ_Xyw!j*N6GBXQDgeQA7v@O&ZMu`Uhdn zj3RP*c}D7e#2!W;R?9Pg;ovm9tNcL+*0kW0mZsw4CT-DoxR^c4@`B}?YAQ+D!GC=b ze^cF?$$HM{)EG?e-x4?Lt~1}KLGbOCLfM^r@R|~lo6d@&%PTcmkL_-#Ymz9>{MZSi z_p{(L{qx~CQ3(zOTflViURLR}3~iHs(u->~JmE*Q@U5B3e*25b(YS77hi@~TDNwuz zLxzRX?}qi&*S`0_(Ub&g(J71NPV>YlyL5Ta-`+e2&)n59=aW5iu5CrbujI+v&VIyV zz)oF!DICBbj7>(~q82zYIhxg~j}o~n6?x{*t`d9?{RPzVK)piu#%B2L{yUW|6d)Nku$ACBX#IDGA+53_nrKD3kQTNJ;m{hySx zVZW9m;8HV0I-KNR#tg*`<2V{Q)}JjH&=UcXiRAsNnC~0kQ`|uFX#emhN1B&pVQjrB zChkzDAx{&~Ypgn2)*a%e!pD`}su{|oPD-^u`p{e$#xoC~O7rlAXRiP)e zSwQUlI5yZH&>9&}-2@N+tkyvB^Vmp6*A>z_odr75xuu!8bXZuR5QC zlkLW^*a<4v_sKJVso=UcDs;in8}K zJncL47rhnxzZB6*;jz)n%fiKA1AJ(;U;6O919h<6E%#UzZ4%weqGx&T)&Sn4NX*+Z z7nrwCW(lbb)q%^XCOV2Q=rIVkXEW);1beBB9-zv#BW#bIqVNT&c-8JZ_5V48J6F}? zV&8EveHz22-*1f$cel`U^=fWp8UtyeDeS&}Rc;d5?aj%p@HTHZYc_c_{`-_jCL6T) zVn1(u(u<}JAG)$-RweD*4S&LjukZPl^p zQ?ZmMbeKacv=Dhki_)gYVa8oOByLIO%X%kc!uS@@-Q~l6sySl$iKFtK|I)<=-f9bI z_rU^bcgJS<+If(y;a{K74+qZ`)4Yn8$_k&iSU;){_VoYFu9|g3`~u+}vnu6}Mb>^- zsjl2(RX%7Pn4JUe^nS=%j1c*VAFdeTQ^l8$?T*nZv+2{>Z;~Bz$E_}*@~t-EiyvCO z%A=0U=O~wJr(u8CH#&Ub7(2Co87>*Tl(V$ougBy4B7KDYOjBGw6@#0jOu^zT=+mDF z9P8E`y%5R!36GWOszvmrw_sLZ@IjbXH2t<1%scM)#04phTJ7F1{aM!@uf;ok-N{=1 zc6$OE{DkM{wBRA93D#2&OKcH;r~PtABT?BP`*0e?&E2DU3;5SsD+|&`p`}FvO_-rg zi!8Db`r|s4tXjiYp6!l}3scEvpV&E71mm%5uFONGd!mnWf*L+q8gZW?;zn@a2yI4` zvtvJ(K{-|%lbvh$J;6dbSlt52#ir8s40UM#*P6`Bp7Y1^$HLmMfEKH$@$^j$@53@> zZO7r9=m&Eyp#I(&{MB`#vD>O)^u%c8i^42a3U5GV*&TMGF&YESn!#cEPCm6;0=^D( zgn!q1>EH_wY&bHFvYKw^9!CbDZuvSg`532s>B2;RbtZM#y@Wj(EPOae^XbdR#k~J- zk>wG73Y+gb3b(9y*xu5Ej=ll4v5rP-7ZbUo{AXYSYNk1&G2f3(P9%{LTSBwjkLJN| z24cqZ44M~QEgcbeqSXUe$v&Kox|^{)$q0{kdGHF8LX2%=f&rT&S->D~7^zoNb;AxG zuOqnWl!Z>$3Y~FjFHJ>*bqxI5Aal@ZK`{aSS)@v!=SCvUF?pX07o*s|h z%)9SM$H)91K&q2=CtirTj^IJU$N zCr-2`@3aXRD!wUPXHRuYL!imlSh9#-$CT|ov2$^%%ujgfl8bjYML*Yd2Ntxy6?O5; zm9?GBdT~$bpfCO|hVWCpQt(6Mg6I8>X7-{R;i_N}?-+89Yb@xFJPM|3iLVvq%FW1n z(?B|B7Sq6U0}yDrfxL9u@w#PiQGCBQ?9NoP$r-Nra;QkY)fNcO>NFi){N1L(bK8rK zk8m@@p4!B;*RDW$gNZ!zb@uf{`STU@Dz+Q@;;KO0n<(mbKaZOVPm9WD!4$H2ab%V7 zcdfqpgJ!o@ArGg{n7F5$GWO2l)&^-%2{OUF8z-gsE&XU>>qpFLcQoH{H5!9mY+<4S zzP3$Q3>!Iv7C4S#1}zxo^%gtl$O!)4ejqlE-9W>(D5T>;Cz-ZefrHaj@g+YI3vQ{Q zC~zIGa>>Ri!At)++KWjio$zPtUU}x%Pme%QYileHdZO(0PJy017Si1J1-$HjPrMnM zK)U(Et2gH7V4-CL?YIBVx;*HP-fs)3!z_P3FTEBv9r|PZNliB9bbC58YNy<9a&TNU z9xgPI_59C*m$f?C1sgvkvyl5@O4O~UKCKh@we3AH@M;`Yd^D4Kj(&jP#qBX8{S>8^ zZ$RWnUCjOw&duK!pp%XXnm_8yzFE0|trz`wjYs&x)zMg-X@YyfUzDO@17+_W!T#)K z3tRYN?R~NH^nI@!HNyudCPc}4{^sT>m=yL&*7FaGTv+uj;orbnwrO_~&I&)jvdLjy zwlzs;bRsL)=eA^hYYuG*)1!BWQM@>}Cn}Gxpq9mn%5I{|JLAATGSWH9ZnqOYUiEZZ zXST?~KUJjh{`=rsYc>?s)b4dh zj^RpD?5^M|gNI<(k&P7P7pmloQpG#zGu^5_%Ir);=kkcnWVAeu2cC7$y#G9!KU|WHp2DxC+ZfIIEFFWgJ#XnB8*^?!1iV75WPi@I z=>FIU&6b?7=e%XPI+cV0NfAfQM;nG%v$hH zM^DV7@|BDEOqWEFBT&WiH#&+#B^xkmhXabdoapMhXoN0p3d7s6e3!_ckD2O#hBQAm zZK~+@S+G#t3P$o>uu2#`&ot<3qItKG!m>{7Slmn;6qT#SDJVxJOtJHE4fB7gKDvII;PF+QA zW(~b=RAmo_yQ5WQoUG?xv=YB>k)LV$#sVcxPJvZd4fy`Io+X}JhSRlQDXp}Ie-ydz zrngPteeu4clWPpR^tAz2I@1w*!KPajDt8y2i1x>|pYgOYA%}GnUTm{l$@J=8Aiw!v z4$k#a#R?w>p#ip`GgAuW?!q_g&o#@}}ev&5&p2^>K)5-a#D{J&5RHaALk+y}r za$OIRN6Dh7iibyTw@$+}@eUfK^P3rZbcQ6@4xgsZ;gcT;mb=Js{bMPp)%Pd8O%G+3 zLX}pe@N!t;Pl*qIB6x9Ew5O5Xm{II#4+)FhqbMaeoKJG<4_%k_bS2kYiWyc52YBP! zSryS^CipyGRq=erIzDr#@bZl}!l5ahnAvwHL{Hg6bNh=Mu37}LmRe$(=VRq?Qy&~q znM3M6`8?=%4}1@cCEjmn^{}s=Fc?-y&V76F%k65h`duGf7^ulM^%cAQ=pC}(vZZ%4 z63m*)Y_yH>aiWu|CG?YpCey%Rd2a!|TN%Y4_ws`4%y25`XCyiMKfsRswy5wvMa5TA zuxUgi{qz?e`yK1B+d>B|99`L`;V#gavRU@n_f3k%*tt#RUh*j-oXk1n3!gTa*qK!1;^X%Kn6xd%iLirrQ zld%(TpIz3-vb-xDm^P2>`{~I&R$Wy5utf@?!efa_m+3u$HE}dpxsc`Ad*kNvR0=o{ z%JtIM!$U>k#Q(pB@Z}%l(BZcZwjE4W)Jj4- z>R^H~>E?7z@Wz|1wU)b1MhxyQ*sC*0^FTD4F0zDK36YdGb})~fmQmC!|0V(@s zdsMf~kaznj3zDE0EOu{;AZ}hNn0`Agga#YKuBDDa`k?>M`M|dkLbtGzyG|->6&N^h zF8P_)F`MN<7^I(1FT45hHh;Y!jZYPxLjy)bg;zz)`7M#<+{P&h2U@A2+QFEwS(%Ka zXhTG|D`%z^A<&+r1p`G5f9e_yYsVH?W@{$7yj4eN_f~S($y*W{mqK)i`@UA5b@a!e z$=Nh(eISb(+6_x`a^>BAw|*jqy!cE1=DhDf@pEf#2#@iXSho1Shj*|>ryhs-LbXho zYqrC-i$5htgDhm_?<=81gxm_kEoJzes!h-08qB-367sR+6qusnoB;0kJ~onYHZ+cM%zs+0z?oa&>cF-8KVz7HeVDxn;~_yvTu` zJxq7{?c}FQqcMAs$b;B2rTgAQteNY8(6W2XOC=A_c5~W0Jer?tLP&fUNkzAsFk9}1 zRhMGuTEr&)vsoI(iwq7X6(~E;5u8;!HGE!E#3nBaLF(8q@@{`1DhAO#nxf~edx|#| zanPx^MQFD+G(BJVyRz5P;xVPw%lG*R#&|eQ{x6l;qC?9Ibl`XQ@z8EyY` zMOxF~Ow+@2n7hkXUM95M^LDym4nuf_=!<-yYl$+aC}!N)9wnF0kiS<6SHCFCUgdGuJ_9k< zX+0%dzdK?QDYT>Ojr1>9H8{UBo|u=CZ_*t8Gb3B@XUy?H{gR}9z8_6qcVFh-cl;fJ zZ{tLFfZ*P@%MZZJ{maQKcP@*aDGoER*bpxk-~g-p9Nap13?-c&W3! zkQuUtY@B;?#cIJ13^YV#U?=8x(+QPFchR`3d--L-pUEz;kogIxYZdr2Vm9%(0-o0! z7*`Ipy= zzp1{)2+;872Mxn=b~5@9Mw1ZSH7qSnm!ar%y(b+8oif^r4ODU_C{{ zi_*mW{6rx)X7X8zOcai6f<0?p+4)EpG_l?!x_giC1LRTGXc-JNrTOMY?~WhYsVbbe5(-zo|N!=AU9N;@$Be z#89v%tN5?cS=i`ekHX4l(!=%($gHa#{o^P2=nlisoJcySpQD@*pg^5=1RdQxlO2ul z!Hy=WGBYP{?n5kd^G46Pb<$4vWNdh?DsG~h3T@hE>>@kWYm+VB7yl;mxI7xUFlHb#c0Y{ma(46;d*eK8Z#hLLK zm(c{SUs4qZ{s?yHX~7!WYf1)VqHx&M3R$9G-kf#EVeiQ_e!B3*`AZm*7fz493>Ll2 zUZ~MdqUM47rHi9FpruNhJoDd)+?-bnRb0Os#I?tYK1VZioahz9)+`>29hcwG)$tej z{H#dy797j8ZC1+FRSImqJChtH*RigF<5Au&m$r;l@HgiJLCYI4eq$KPu+j3}a)xczp8XkQo8p^HKNE&7)^}ntTFEa-+ z8TOoy=+z6qr^J#=r#H&{zP&JiM-~;u_GUjNFW5%pk@c8N-dSYyW@P-Km!Z*0)5-td z4tfaKd4a(u6|U{Aoqxolm_u3~0p%Nl;pup|`J{-u>Ax{4Hojj-)0dIrs$Xyfb{Y<_QqdmZEWvo=ZC zUM@O%40|!ZU4$pEXOp6M6#p}HES_D=qRx7!r4NbXo^yVQyxV_ml?vmw??`KqHQ&BB z9c#~PAiHoWd%VmCKI{;!wb;pXVq+0v+Z6Hhp}gCWhwi~{s2=};d6pL7Ue-}6TOG^y z59o$94J)Wqh#EVl>kdo7XZy!bn7u6xnR`Ew-Gu_>ZAs+Ij;X*(zlbHT2*EJ#Pjoe` zhHEU2MNSj(Hhh0y@oPjZD(zdy{DfalgbmVcs;bPX{(iU@9QMXisZ}nsoi1{s4T-Xb zZzJ}u*7G(}ZsZkdb(j-^R-{xpx8O7cm9*v^qKjhs$ zJW0aLfLXL<&3lE#k#ek5Jfoq%=F>a>3>fcuK>eRB`gEW*C%)^jG!Um5!_CmzV zcqJH3ubZmEP1PG`{VHg(Ur&D0EEPl68{qoBP7HILG2&Sz#n|oR8^lf(D0;j8<*Gg# z`5>wLbZYY?kJ}XXKw;-7(w;P=Ix(UUhuSyLGXoXUvhqUl)Zq-?mM`fJR4bN>5@23xQWR=g>1Lnon@-hwal7>Bbxz zNpp8CJVnM$+36&$zmbmJC5@D{Aeei&XG80L6YO2uj&;85g7o?_dFGF38zXL)Mi|!f zi!!=dCi?7mh27a|HcK!Vu54IBqv*5p^Am5p$XQFD%eu0X@%`~%m#t)U$gZkFClzd> z$efvdLvQ9_RYtPVx%bpJ{w-IFf&* z)2Jzt>`|}+8C_E-rs-PVd&NNP{j`m8M~{)lG)cjT5LNIqnq)RE9-CB}$QphZk!8-h zzXCdg@>#uYD{OjSCC~iI1W$CCGfB=^9emad7mWjDJttAzQnzc=(hfZ*zGk=tr|$){ z#<2JQNIDO{9RKf+(@slEgsifO_PVe4Iqe-OLPLqHD6)#Q_uhLeMI#_#!^ZxV6rJqa{9ze;E~Sb_P1nfNl} z3t9Uy8i%=!LZ$qD^t!D*b~kT>hPRSL&X{=xW47>n{^|BbcwDp`G>+^NDzNwcslkjb zKkY2J_dpLlj#R;jTj`XZN=BtLDV)@uDR{Lc4vR(P(fhs%EFFl!uI*}k-YT)h0v(bz zf@?(@N$MilX&VIwk#2O@FeBVFDhWQxALYj6&&5xV()pP`z}U+-jtoJdwHNJUGr3<7 zfcB5?kn3NJQEkTsP*OfXvs_}ZuWl62K=vBT^2=!faH-@I3Hj%ZEw1^H_{xl~phjq% zodmPLjv(?`I_x%=&CmS1b8GSX3RS${H=PpOGOSEdXP(j)vSZ^;ymmqqM?Pw!vtnbh zX@D_ZS&warE7Km@C-Of0S?wOE*_H*5L;eY;7cxC?Mk=JPC*UwCP-2_XrWAX|qF(yL&^EM|`4F3cufHka=!OnKS4;wSPa4Z^64Su3m&4100T7v$-}-@Z zz_OhqV5NE{2{SaojlQfmim@?;P1fvQUk%U2?sCfSHNo;nHVIANM>maTx#mI%EG%6> zC7-3Dd6p{P-XBBSMlHwNKL?=D`YPSSJg5^l`oiAc4}!26b@+VgD`;>F26h6+^2RcF zv33kuUN;K|hZpg>y`)JJy0N=wl9o8V^s@rRTUbxe+BVWtvI}M76?hFtm}P*{_q;%} zYzC>yLX47+hS|qU>0}c?wXSsdtk!WxttSH~8GeS_se>fmLl;lJuK=~s4Rq&&0@Ubd zTxH2y94r2VcfF6ufhkNkX8G>G=23jV$sRFFJT-kIIMuBowwDRcdmIUe=0sC;Ux4#^ zi{aQ4GtOPZ1Reg=LWQga4N}O!FKcCa-6rDVRBU;C2xe*@V_mwj_#|8nk34)W^jg5! z3)lT&=yMV6Tw{s4zu6wE=H5Ezf(eF&7xKD|1bvRa->p$WTAY+T)P{L0_wx+2k>&BY zYe*jL+pOsymKQ63Iv#`76G=#i3&y7Gf;jaI+Wy-Y-G>Um-eeBV^Fi*3#E4>3HbtFx=WSgRI1M+RnKWzKM%<93PcKbVAK zvn4U_!BJXtAcJ))j7C{}#tE8&LC#g0_u+6KSwrx^4*2&qQ@D0K!3h6InCr8iH1-gD zUY8CsMUm8Tss&p4RX~%h6Q?SZj(Zmm!|4U$u-TpM7!M>cXmuK0r{9f1@;mX@%wkf! zOA{Y_I0emHn&{mx99I7gfb9-t+|m|h94T(g@9?LYFXhg}Y6uMcA-rtTgM0hUar3c3 zf_2)A4^Rrtk<~Q)E$iL(lf-=c0HJ1lG15PbIdA!%R5G8*pfT%bdAN^$s5eD#5r4>5 z{=><{>!QQxEj-`2`@R*5C^IhWzAd{VJW52rt^ge3oTD$d?p7fDJo zpIL^$I<*kJ-c7<@(V6i2X)JzIXSW{4y^LkL%BV}LVC>~Ya&9WYd+Q=$QPm>)+1dpE zZAb=nljGc!_PLl`#dqTw(O^J z2C-P}qsDtLrR11?YaId!6Mm7hp*-x^b{))xd#J_~Bi5&u2!5MKkh$eL*nK^VpXWMD zQgKrGUl7zQ(CduDc9{8%_c$JAEYO|!XO}3hKHEkEQ{u5uQXNmWsdBE{#Bk`720zbt zxGhJYt68u(XBeH_V}e5)l0Yt0KuVXJqDn{se7~1VSKdiM`$fOurX|zoJ8RKMe-a8t z^%BL4toLEL8r}{%MLk)LNlR}6<4yN)Q~v2=wZ}5B&~Bsw$(Fb)DH`raL*W@HlrXjn+%U+^c`UUO`5%oiV75vZXQXr~(`^NW`EJ1>6vkM1P)R zJ<+Si;o0}*#A>WHUTh461vWlZS93WkHe`Vyno+{9Ovd~%!Te3Oe-?YDN7g|812)fF z8KbXL0;Qb7$!OLYeR9rmFf2VtXSpTehq95_Z(|{B_m5|Del+gVxJ%LkSjWfaQ!sH# zJk$0K@yE{)UY{qOy7-xC#XJv(^-7qJWm!?C+lV|%!<27-;hdn1{M@+{BSpUQ^SsM4 z88eF%84vKK;D|~b!bCOv@puX-O8er1e{rxjq`B3L1G=&u&;veF?YHAO;dq>&gOkM{~VJTi%%SPWi6oZBN)?3aun|9k0qVi%kkmvetw5H zU=|cjzg2MZ<`;qEuYIi3_!WHFw*~xIw_{^TCdi(iL^F;eIIxlpnEifPr;??&I1N0I%^0WZsP&_nG(Fgb|8~jqe*30-%$Mu291b0rK~z1Mw_Gs_ zHcu;~wTrD-t~LuK>blNM&C5mUpzqLKH5?8+(ZhUU1w0wGk^VeZhANB3pjgF2uK%Mm ztZ;kG>o!N2&(M*11;djBba=Y}*NcYpy|j_Sg-BhCVW3OE{juxB2-cH5hjsr9%A4Q; zpS^JXpgA4J^h3Ko##+CxO|+gd=F{ebQ2FI3O*tHk;Z38^SMon$_iQV?lfD6(<*Mi{ zZ7Yl&hz8d~?yUiKZrG+*3a>Q}kRf(on{_N7XoEG)*pP*mT8vS){t$OEeh#SB)R9AD z6KVS(;|9-S_pcsyt7Sff2_KmjIw_IFR@malBSA3bYZ5K-1=Kzl0cDQL+-1QRbbUV` zvo#;U?SC0)*Z&DNJPx1>UZrE{#UThTpF$=qn1PcrtNA%U!z%&BGv)C_YQJ#yg9NlO zQAZlrNMwfA;h+8#Sn@@IUU{R7d#?w<)zG;_Cy{j@Jnjbny(>;D{z%8!Okef#x=0jq zl5sV=$v!=Nj7FH`V9WsH&zrntJ&(a)XDS7g-^S8ICme9$x)2~=GlW||vaa@&J<$4O z9pU25u(^bFeA|T6V~VaQ*4qH)Ydtv;=^T8<{2WOmMnDhC5MA3Z&fj5cKINh(^Ltbj zTawr#nwVF85|+3(QT0zY==GB2Zno^@I=Yn6E5s5=&TDF~VU5;@GvRT|b74UX;N@$@ zAU@2Iv{}wa+rkpwWB<}W3Ac2M@!p$u?IK+1G7-Bn-;mYwV$pq(DvnC2r=s6<@!I>1 zFs!qlPSUr=fkvj8yj?FGVG1~IQ87HI4<|V{_0b@q0$xtapaqPDYrIJUMTMDyM!Q6O z*C@~XZ6;re!&n(LR11!!S9X|ScfJ?o7R8h6hdB(A+6|7)t~8r5K<;HFgZGw`T#W_G z(j})t^S|e`s6Q3e^MAu5Yfq{b#h#}JM)2I5TU$(U>fv)R^3#4gD9!prU7g5CT&1|Hw8;FAPr0f|Zv|sQP{Z-h^ZrZ7omkywhdj)=X%;Tt_7sbL`8JU!WSI zK-*4rqpspg?Cp^PPt#D;{KRtlY_=z!Eyc5Y=b^^IIh^JrF`T=6JkPiEb+Ewtd5mFl z{6AsRO%pVHmH_SJ1Z1zT35sgv!JLOVG;eq+`Z^E5enFhjv851m<|t!E=QARrlYkj> zxsUe zG0xG+g>^pLn0G4;!?b_H=9UqHSIh%^{f`7jO3Fh$^DQgvk;8rQiBvOy zqIi-g!gk|3$cO)R(e4_{ z`W&?+@Lz-koqRV3C9TxaLhLB<-m@FeHp}t)jFyEVdaEvlr*CJFR!79st$TQ;afX{E zx<5znon)9$h!&id4y@(=IS~@gvfe8b`n1 zjKw+ms`$uBKz-E-j_~n=Y!5$TdJ{2TF9O;jhMF>#b**+1WG2nz7BZgCjfXlo(R>&l zV7F$UPu1{hk2zJGR)mEG%9uXhj7SGh!);lOaGg6wy_x=b(wOx?9qAG_LXl!-s&XJvRX~~aQRRjscSRA{w;a%>XbFz@g@(qb+9?J=O`!BIgfF1 z>Pd4{GF4`*-9AG(e$IcGl8cI`r=oRP7ST(!K~dig&?J{cm)sJda6%Xa&QRoR?Y`q3 zQyrX<`3RKkGuhwpBV7IyK*urNAoTD*C@|6_y#-9O_p9RPyco;)yxb(m?xX#}l`9f( z8oM3;D?UK--ufY~WZ%yRBdD{kAx`q$4DzA#iL*u~KE3$?0uT9|4(-Xrh+V_b|Keq0 z9+`m;mXE+ES5LDZM)q%=RORomx4v!xx?BpBJL0I$dM{L9{J=WzQlXPC!4%!y@K0+! z!Dv$~_DSUVmhaei-iCeWUxqq!W?OSnP#}t$(_~<)LNYGU66f_9JBI>1(>WfSm)j8E z8=AODa01FlH_^8H`Z&M99cmZlahkJL@JO;bzt7Ke%t5cVM__wai~6%%p50(RY;UzC zzJ>GAX>Bps)YQ;rE12({>CEy`8s^iU>?vnq|Bc&W8GEo%g%awI#d@GnqA>m zz!y%I>FwuJH^7|1dTMvq8mrSXz}Ibq&{B!RN74l_WlI=Qku<>1`sE-qDuY@|rC^|$ zIL1a~3U+#D;Dz%lm@#q!Y}a7#^2|f~IX;GU!a9dr`1}O7KT{h&d!@i>#ZLO%Ee)@93_wqWCvB-H&XJw4-V{jJa+V;~g z3t~}~dHDa=T{1#`5qbn~hwm#yz{|%Iof)S+Qq+W&d^JXO*?91Ek|A$?>EJ1`be?Hk z+?~qq>;q6!sX*UYRAB1T(Rf+yB*|+H#Vbm~@$|JensGHA4R4P^Wdl`Cy-^HhrjF(P zHg~$0;ggB!a7|_y_0M46bKQ7YRlz*5-9|WfXEvPLo=tnWbgX**3#QCW5S~6%fsH#y zO?YcR%keGy1IN#olZ!5)Xc^nX@AGC% zODsJphwb~H3&yu5q3?q+DAP3^H2xx%J@(^g{-||;2lAO8>~NqgLRTIQdJD~j2BXsWvsi|MvWiTxCqriUVKCF8646rvC_I=L5YaNf^pLYn=v^K&?KeE8^h9Z%!n2l@F^7uP! z@X=)K$PnZ2u$eV!*j%K94WkD46W#tMYa>pE7PKPspXbe59;D80wv*D+wA$MA?6Z=)> zW8c_e*kELWBiB`d8=BMd{oR<6y#gC&W)T0%X*k>N0I$hM>&N2xBg%Z1s-@42^;>$v z{lOyoaE1-8){g?>wxl&k*Bq~&Nr7$3rKCHE^&N-iLgy?SI_zx@{?{=a|2#O%y*N1! z{vNL5HJssp6R`KHES@`HLmQa)e%;@xIJP~Tkfqjm?P~yJt0dB&j1}N8Z!;X)EysnA z=|i2RI_P=%37j!z`I?G%a5O!DcKK#vbN*kTcQlEE+)O;-S;>2EMl%-rR|7eeO&Aa+ zIJ5m{iW+<79Ux0id*Qp9NGMH^q~RM8XLaua-`S=_W5yz!uxcM9Mo&K7+?R%XeSX2# zRTqd~M+Pq2Dvi^=o~C6iZ*pU~Dr${*#@VkAfw)LXe&$a|1T59^g`Gzdgw8%rm~I&d zDssDs&lV0P#gpLK*a+%h=8P}fYoK_p2e)%w9v;;e#RKki}lo|PGs)bVxT42ziiM|vwK+h*`P!*WR9UjLz1{;vy?QhpC#Xl!YpPz=!I5e&$co(8u(?Qs{I{ zrwPXx+bTvJdnaWHH09Vkmz)YJR%*aac84|URK{ONqG<}d(flr33OA<5laxCIjc$kX z8qN-u6`KAt5mrQ<2aOT!$m|DXBh+1(htYXt^n-6l!rS!U!Lg_XDW z)BbJj-Q+3X}{h|*_M#%`elvD9{y%;X9lY{ZfiI{RghVdB_ z={)vao2N7m^>wU?QkEq)y!M0o=brSRqZt-BZ-MSf_1wC9Q*hn$b>Nl%iYj~C;~H8H z+on7co^j4Z4Y@&h6|k8+?-rnTVKXfHbC7Pmmw<=X%it0X5UR0Up6R!Vxc^ocxp#LZ z8iz4va)cGt_BO&sPPd zXx#e=7F@bO6}nQeKScrOjeI3A`JRYRj;LW`!8C~df@u2G2clgITN^XY(4%e(tY}Fm z1@q0AcPkElg*nhY5!T2xmq2;VZBF#>R4~O1vbm<7#@%3SsO_S7_{u_Rtek~QAFJTY z%6Jmf;fdqAzVRAP;V={Y(6pHM)%Q%U#}&y>VX6EUxEz&>N0&SVHPNj!im~AG8Z!Br z?{a)L%IN0u`uz6^$@u)92;W!Laybp3?^eXr(Fe#a3`dU}GCU_IK*t=dr>+2n1G?nh zcEH((cfiw8C3Jy1Vo)yg>za0)8C%}Kcxw_klPE)JhaS2LN}y3Rkba3OM7`y#+bjJh zXL!~T=2fxYA;!rmcVwLfP0D!2LO}ofYlMz*?x0t{j5JRG)FC@y+s!Dt?urv0kIDw! zd}HpdQYW@KY2*0UL-0_Id7IBy!1H^|li$v||7yLl{BJrLBQqUenC$2Ge2t)3%xzWT znZ`F*wqk;T2b>Enr2PV0wDXRHKH||jcND=nzY?I!vxr2`G{ucH8;Xjo>6hiXm@Y9K zPmXWq65DjZLVX{xNlKvsdWpE>rVMIU+0c#K)6ixAIGhucOlYPRUK-)g^DW1UnPS!6 zU>InY=d`STq4Gf;ta9mq+l)!L7~g`Q@fvFLt_&@$qb(-b=l14oa5IOgXJ*O6p= zx@;QA?!WaHlXIPYExUMblYYjGZF21Xczl zkOU^(?vdXPia~C)If+Ayt?{tj`Xo1c{5q?rwz@`}Wg7#!=b(PKoECO>p$W^x{%ql1yd zQ=m_|mTvuAhn7FtT|Q_A{r0IF56_k%l^Ut=Dc@70&X`_#r7Cg?)4Ed zbeyRM!cA|e{djxaDjo@A-h2`c=?Iu7Bo0(>bA*l;pkG@y^!ew}dHI=mXwol`|D7l_ zHf0{R9paeZag7XjWgh!h#%Y<%I;zwSac<56uuo{D`AZgI2-8ENQWAxYl*5lE@!;*g znSAau!v2^Hpi*1usUK;WUj73_zKsz4Ok{qW|3oqFl^n}gCgKBo8T_K1L_Kfh;`$X+ z@bmQrWcGbaOf*;lF1?;?h8tn5-+B;Tx0lmCFa^<^vt0uc(cr6VBDC0K@%Hgg#C^ zm?*_O1l8^2z6OWyXB>v9T?eT%(}=X$XX>+%2q!E|#U&He@k-efGAE$~om`q>T1GrQ z$b4j;|2BfQs~8!#O&5hB;SgR?M+=m48T0==lxUO-Cy^e;WwOV=g(9HR7s~iUA9#;V zR&X*-elCleUM~d2KJoaYTAAh0G~os{$1#t+;OEW4R?#L?tSjFHUa!)~%lBre*%J#I z!yW0$K*kvC%7B?w=eh4fE#^B*Wu1Zh=x@^$T-7Lo;ViG=*_@A^f-$(bD1~H|d11wo zub|7i!c+4dah?2Huvj>ZTW3~}KSw?Wlb+2Gd!O~DH9v+IQ$lH^nHjE9&W2ZUDkO8% z9IRK%fl&@u>8ZG63>Oo@f41Uuh}}vYSpF_($$qkQO*jreJp!ALT%cEXo1t#YVvshP zOZ?gYWoGpbIDfvBR?Kikw|_ajuX00s9ez|5#m2mm;9jqfVS&YbW@`C^Jbacai*qWj zatZM+P*QV;q#cc=3D$AAHdqO3I?d<{Ib(c&-4#Z~EF+fM1gl4dK#+J8HFR)9y$2ca zOw@>zGV8?l>N$Aq#1J^6305vIhy0^R#rKt9&u>Kp6OK5UOvevj>iK=XbW0p&S1IA4 z)YrniN)8RCErpfRtXIXu79%h30ecOP)}um#$61%|kt0PUf2%QmewP9Lv6gi5lU!V> zKMXf+Z00tW>A>vGwPc-63Jsc+g4fdIaBsW=HDx_|H{-SOr%Ne$r(}&KmAxUcS`nC!n+8Us$4o0Cd0q>RFCFD)`zFR5_BrYT+Y0iz*Pwzou9-rL#%nrB%^Ks` zO>=X0hj83of@fdk!0OL-#L!L${c`hpU*$!X**p_J9Ch}u76zQp!%v%-Z=|!6Ol8^g zKR*=N&6Mf$yI9Z0uoW;AFGgCN^;us%(@1?A=$PjV@Kkpe6ffQ`+~!a4*R~uuJ#80} zPBFnt@nw)bltran3UE4ON3RPj6@0y1jJMW}!*Qo)!p0eKXtYBSO>aljSInC zI7JqSZ=yqZ4QF5+hr{Y)!Kv~D=ix99YY!&y8qT(?Dts_%1dcluN{2O-ppq!_SH~uj zTv0Q8fA|cnnaDggGnrnI!#enmj1|@!72?`6=b+|I1f9N5fcGt8p)pmC1i#Wjud*aK z@?kGkK2wEaGe+R{?^EdZhxwSZRTc#i2T9_YFua`j2hPN|(IfFJ=QzZ8YdDH)m@JNI zwW|Cb_JXSge)8T1>snq5_oNDN_?sA*-OG`E%wuEtI1`><%B4^4r(wU`H_(|8FI=dU zfjyGqc<1DG5*M6>L3K(zqki>=R21Jm2AwpzIfpfd%%kfJ{d*f}mA4yK_r^l<$RuIB zKcZeX{m@&ov zZf_@T=>q&NbqJQK9;5>-f8jToiY@QqwHeq_wj#}cndKxQC5j)?{TBqy4e#rzB_ zg1|prg53Aj#aZ!TaMPoXe!Jv`vyyAT^|qhzsCy4qtJ~q(5D^d_*JU2_y>NGT3LR&k zg6DTLePhu}!SWjkXx*obk2AHHAKMO3CHO&-NO^1C9K!NP!Qk(kN$d^@@bI4)c$eo$ zk6vc`*nep-bodH} zuhn>{3h+y!8-#xA7W~-RfF~p$!I4cN@HfmGa|erI?h}1Fr_vawq@+WHl@eJSFbCT| zXYpE1v}g*RvK@}M62$58sC?Xgim?O-j*$^i1NYeHh2slg7;ATbnL2SnWJIH=&qPyGm%Azbh6t#emE)zt-8MW*B1@!?d(~V$XENk*ot{Y@Q{J3hBge z;b!PW#K_Eo`7rTMHLuk;OC{k1(-9at$(F9SOlAIo(fH$bBH6de2F2#A0HgJZ^exM) zM$`s^W3U1zRWO8ObaXLlNf)dby8t_SD%cH8i>{u=a%$ggG4)<7`N%wyk1I?0y*>Fw zB04FJz#WPM!Y|6@C?`J~y>DD1W8TQ@=Ho>N7s`dPQtM_JmU|-U?&xit)33x-rX$Em#Ht zyAp*S|16OU-2wN11d$gG0vuvJ;Qz}>?N_zJ2La4G4& zY-5bQ|4Lw0Zzff3PDiCfVmLE0N3iKgIhuT)fR>-&Ccq>?W(UGaD;E{eo%BSJDZ$(y{9b z+o9cekv)S<1B5ehM*IN%$Gm*whAW}8ox1Snc6%(%T?uoR{vuz?3h~c{b9^3lGFsr$ z{}Mp4S&{gU)5V6!Bz}iqWtxrSqJP0FI~5vkQGoshvZ&U3kf`1Z!)x0AKj-@y+ux{( zG26A&xPm?wG!Iecclg;|8}MUxHmv_FP2KL8Va?kp2<#J(gR40le>@WuMDnSaQ95Io ze*tl~c%jIaEY=Grj=t@;h>CU=wlL56|8i2F_H>|s#0LDSW=ItB46(hyfuHje_c4Cv za<*^CrU=!ltQlh}Oh-7v#jyD}g-cqje)BpnCVeTB&ZG6G}2bnKhUZu(XVFf@*3 zKgUX=+UGIBr`Yye@9wuJ6{wVkLim=1=5Y z(c?`8EH3I4N=NqKb_W}DH*P1lJX!C#RTZR_RnaCb*2&KN;T>s2*q@({4WjBO<{5 zqNj${2UAEwv^NIUe+IilSLuN$JxtfOg^s~4f!%&d^A^@$aE=|G51uH%yJzpgyQMqn zo|U$Eds!juZW>R{x6DDq_DmRL+J4ZJ6!d#O3|q!a(0%XIa8;)qzt3xF?ZK-1Qs@(Z zf&OMpyXh^?;Q4J9F^(0Wp4J9fFt3oByakj#9Shj=^vvBpeXMI@y^1UYd#~g$y$ZG~%iI)Oeinb0jMG38=|>edgV;gM&BRNtw9?j&|Gv5D`Nkr<<}I zN)-HzpU(L)zfJeJnf#oOX1BsC9;LtqnbXkTZrpIu12_1mlf?7WaeP7@yk$Mw;>`bi za}@JaMZOX?u{nRl)D2cIE}{S1H&zY=f!K@%tx;P|G5TjDJbIBwQWu(_eO?;edTU7? z$|?{pN#MsOAve5!K70OD@qOa+Ws-16S{n1N+t60VK6-X+G^SK1k<};caQrbJ*!e7p zJ|bp#F?}6$&rsmr?H+EvAz2sq$o&UKjahhS&r9$qT0>=8EYVAGFWfuyoa>O8g(JdC zc%Qs{WfHcRNn_=|0pYgN3iP*{jWx@z5NlDEmsH;h9cdDD^9Oz88vMYU(jTt%e1CtLd%&d_2%G3UxQX=Dx4l3S&z|`D~O#xif}q zu7VnkEa9Dlws=b}6nu2IlCt&eb6gz@A=e_P?iLrOgO#y z3hwP4hQfe!s>yO#o2%q;-v$%b;i84Vq?^I#;30ZXUl)%}v;vh)*<4wZ3I@J2gi5E^ zv~jx)S}aY3;N0iJPX`xZ$Pwo09lM;|o2r8|OLJh=muh-|vAnvq|H1z_#>1J@)zRzm8&7)pbXJIr;p0@E1+vr10Cz+hnLP2gIi;)aLAZ> zl2cM4^jHX~yJCpDS=Ue3nhd(_E$g$GG7LRTGX*rQ0=>dCu+2*w7Qc@}wGRq-S0RS} z5eV@0OBc9$BZ1i51=OFvk=Nv{4{`W?YBade6I{yedHBOMj@M^SOwVEr;qTCQVFfic z&%jrcMA2*0F0wb#43CPP;^+MLS8>>JPl3-y>6$v@1wTJ9P5n!_BZZhuTOmXul1e8V zq2=-2V7FG9h{)@*zj-`ZRPUv4M%lA>ztz%et+thvN>BYGOuq;o=Je&}z{} zpUh^yL@Q++Tr-MOTq%x+#FhAcURb#Z-CWr3NUu-0sKg92mPbNiqJSu^azNK{MKEz( zC0+L^9gXaJVcCs%;b3JN)-7XPJGrZ5LR}V0tr&^dQch8$Im~-wtA-n!KXL0{8sZuU zJE&=Eq)A>IP$4N3t}HGT<_ZN^H8~2h=LeC6e$2adCJk<9@1O>34>7Umg+y~1fsplJ zt~fRf(+ikxW1Gah9#V{lpGZG#WuEZZQD~)VNscnVR@<{>@aVh`UCM6gBWA7u<*QYk zYJ?`9tnuYJ#*I%F;_hMPp!fc{@Tpr5j(4)c+cz%|Nja7y&a8k#qpIkoeTld^RuVma z5}_o^ssx#h!_JPEJ}aH4ZQ z+;(;oPHxG@j>4ay-BU@{&oN|q)mj)ln?|b|Q_wMd1omsc6leylqO=qWp!`5Uz8?}2w zDh?p~`@C?aHlYP5Ic^lM+bnJM#s#dSRx*L#{Zrz#wRn<$vWv7 z=(@I+pYsW^|I2_YVENit!Wac>+@e-HC%EoSqTx>jSb1$N#F~!eJg5VnTu}s(ODEBrTdnZGv>Nzn*vW02Hw)vS z7(}Yh&_h=CWCMC7v;APHe(ngJ`I}tw>+&*T807xw*f#N8WqLHxW>QvSjm=hVeQja?L7ve+G;)>J}qix;OBk%NQp`rx>< zG@L$Rinq81cz2qkU2LD+`Ia%j1yH;&OVU0=r567=Yx8>%uol116ks@(Rd`!t}OrQhN~hXVgIgvVSf#a=FP zwh`WaW(^Cw8tIzK& zSts@!<~na{;`c}&{@$vUkd1PN&mrf=SbCZu{!=Q40P%_B_|18k-cbetC6#nM^S~IV zOYpOO%$o{)aDE2neEmt}=PbvowHv@rjd}dCOwntiKS+p+k>m(Hth~hXm~4liQRs%{ zE6XA1w6E|FyR#oZQUV)%7Z6WBJ+xA;0;T0CRR2K=P7IXB`?4;Kmc|k*BWoxIp5&nGd18!-_l%!^;Yudz#e?lC4twBFHnc=x)^p5VI8MM?hIL@lf-67j;^3)%r80YRXUhjeL16M zRf;*tu#WjsEr=x2(58Gffq8VAVnpbHC2(Hi66I@!f5CzBhb( zmOj?VTEbASJIR${-;IJ$coUaQi<}t0`BgGFelg-=ruX2A8}s>|%a`o=sGd>;@{`S} z!qIe8)fkS#)pJP1q8a$xWG_GG!#~7flZQO+sC^|of0ba8stX8Kme3?`4n5-oKr7U- z^%3g}9vK!6CI|D##&i>$-!);fYWx-1&MK$B>ibJ{p*>8x?++T zmv2MER;A*!d8!zxok(^(bVg4%AJ{%Vjm~5|($`_Wu>FWE=kPrY9CF>{qpf3Far`sflEJ1&waJ=MiK1(i@f zE`Vz3vhFq?b(}x=iPOCI5bEpw;M&@c)Gyc)$BcD@>-9;(XQqqsvULdZtwIw1Hke{{**;M7<>+FT<2WrTi+3}PiB-W= zTzByhzt4N=7~%L=*05(uKDS3g6@PO2yl(S6%Nds|roh9oZ-m!v%<)5ACY&mFAm5lq z+P5#8zqhU)nTo^0|3YCM zbTPm~r@Y|Ki3a*E-5uB8%z!%|!h{PNOwi+7G88`#Ay$t~Fyuxdm?dV>>IrGMZq*RD z%+C_&rl+InC|S(eG7eT|#p8b?6tLJohR%26aBQR#s0JpIM?y=?w%r6$bxUZ#1S3pg z@Ac;=G;B;e5>-N+R_Egt0sk6=VQnd_PG>~I0+Z`9-xB* zaVW+7-v9I1Bq=!I^tE1KdvB1`Z!SW7bQ*GZMbatEdqAFt!t-Qla^Zz8)5PLHc5*FU z6_$;LH@?Blcgl3Laynj29fm)OtI5&YU8tAT2g-BWXzz*?B;!@kbjN5;>4G>eaFgeI z1}i@-WgSLQ5ZCud_$q+q#f}EUnx}e%JHz44fK=Ggm`Bg%Fy3#3Gw76u#Zr!%cE9!Von}2))ZLudh6DUuq0|9ZVD2F44nJ zrNK~pW+gEUVSP8hl0c?u8~v%}jFCNc(Et9T*&?xYwBGd(Y)s|h^ZO*swwFL@u_QWa zRspV^Gy&r#xsp4nwpi)!4x6M`(9>!**!z7WwA3Hw4qnp4_6wdo>tK*^y>z200nWY= zz6?b?Qe4XNaTAF3=K1*TMJaUmRMHsMVRUMrIPbC1wJkyc>*qS^`-!v}E<=TRYhWqk zr9Zl`1iQi_p`=-jq&ex~tBhdK45*{6miBmrvBz_FEEaBS=kUquVu+7gK#p7KVZq7@ z_$$rsbWc+-c^1o1A9^8Zf0>Al+9PptHKQBfcfwD@m&5Bzm94(@4tS2~=ym!<#GU2( zYilFGeX29f=`&&8PR8kFeZ<-YnjoSQN4)4>+Qj}o-R$opndwFks2Abi-zu0`oJtIy z`=IIAkNnJE&EAzR1lz*vS)T;jj?(6{u4v*Xu?tYUJRkAORcPS0(ZNbn>{DkQYKqF_ zeEeJ-nw7?T>E~as#iZ3L{LJrMSBO#zRrucUG}Q<^`&FEu`EG9=(Nk<0%hQ<=?Lg)Q znzoVU4$3L3e?T9pNSJp2$r*#+C3xc8d-$bo}w0mP7uy~q_9 zxPqJUH9jX5vNs-$p30$$q=1%*=;Ne9VEV8d*<);r$6bP8%cgjmI&URvus+jSYaO_L zy)P)Is)O_Gq_K66DF&Y@0GC{(KbQu%W?%@8Im{uF!Wn2briRbMmWRaSv^qJQIq|hH z$X$TmA$H(kT12PH0d9?04W{zWtfxV_*LJgf2V))lI`j~tqgH^*?GN<*3xYeR zJA#FCys)U=9EDYDp;$GL{MTxZ*&$J|^i?D+oacfkiV9)f*~Q#l@oaR7?}a#PNoW}~ z!LgpTaM?#dubpE%?e7u%%)jR~4aZ9yf*aGCX!%1u_FLoNt49tOlAwwc{>|rmNn)y4 zN5lVecFB*06>KKF9G(Ohr7g+FS$bG{JCpZShUcc@hgHAf+lc_7#N8U4w_XEJXMZIF zJ_&gFo*afAY@n{Oi}9FjdS?MxJ8mM|ZFA>h%LRH#?p zMXFp((LE-gpZPCX?*7>7LD>9Xrr=5tV{+b!`@0seM94(Hqt(2R)*_+_&kW*Vsre-}7mppysm$o?Td+Wsh>5)bLU94(hH z#`gtV;kdOlaXzVsS`TA*rrD&%Oxzpv2@H=Z(i-D*ocHw)7`jxG+@HI#_QH4GZ*!+5 z8Eu)a9wJcVl=H-~KvS0I6~6>u#;A-1{bCV1=ei!#+ctr$v_4s6!F)2w$q+IwkGir< zU*7W%u+}I+=v$S}cA3BMHR39nZOu9>10+x)<}l3}mX7tT?`)m$6IXN02;MBR^?>*=HKsl_lhp_04CdMHAU zF5|uQ2UC{d8MQL_DEV5rD8T~Xvc9c5L6gX}q9>8tnI>|KTv&iX^nc~jcntczJ+-PkVlhf_Jn*!y0ac<+s`tUcqDsP9ZO^s0bA6H@7lC&_3$B#vP%&jq5fd8o*Ip;%o9$X6drX-UmtV1eWJ{;~JcB0#AjB)w&1o*u092ew16)H93c&+~Gf2pXT@f*%% zy3%nhBXGB81l|;lB^fd+@S^j37@vEU4$p8wnX^mb*{0!~%IG@m9)1y8T-b9lAs@f* zzs%44z#nF4mzM-lAC(D+YU38oR4{43O7EA};`Ap<_+j68Iz5=ND^HEVHhD@;YDHki z3)UCb-$vUr>@Z~OBA6*KCQ*wxY)JIwwfc3p5nJ3Mc&%Qo$PMj37sKGiW2DE~5GOy# z29wKyR92bg4*LE=K?~*fUR?lR z;eb*SD12bv+A`KRlu-s!qt|dUqVu6jq=f7&Po$e`lQHn7IPN=ZOZU7?!5Agx!JCyp z#)`P&%LSg$A;z*f8w_yVY!5Kd8o`AYzQB0q(;na72CeKl@^5KAjBB4v{YTD5i`snt zCR=_l7480$#04UMg#%*?Q0l~ZJYnBThK;boTgRNCO}tmQa4+ktbkmqLAT4BZmp~pHAGT`>az4TKJ`<`12@VmW(PZ1IgWlVY3 zMLZTI;G{}fJiVxaI=mL3xVIIQPXELCh#2B^g(Z;lUju!(!ws8CS?|N6ok9a?Go14+ z0aoAKN|fIk;c(3yXbH)n2_b1%kns!t$F#9zy7A6=lDMUB3`nj`V0U?09F`tKTikV- z2gU@>Pmd()S?}5HL4SxD>rPpm5XG;C@tG-&U-NNzN+f&^>ZA*IWHXFIH#`parOl7h zan{R0xThIP0?IiIi#P^b&K{s+7*nhMge(rORTmakyW#F;Plz=U0n_otxL4*l#5P3I z{bD9qFee03I;6?uS9@Ev;F%Ig(qk}L~SWQHg!|~hAuMn`T zjcRR9#;f&A?>aP!vmGvh>W4<~yM4vU^*DTh<#dvzXiOLDni;PXszG}%5x#nxj?un@AeP6p`eiBqN78x6WBImWoJ57Rq@o>KvNz9to#$h3 zva(7_QA$chD%pEyCnMT>7w#+Vw09cXOQao=-s^Y2|G%F;?+?%UoY!$4$M?X2UeXxs zd5ESmPtG%zf0I(~;OGrwWWRFg>)S_l?*!n%dvT!al*6xYVmHSd(QtIm3Nk0c4EbTH z(5$eAHnG2XwfnU&A@8Dj#@k|CyqDd?w<`|a^Uo%`irdhaDK%XGG#&+_1Yz7la> zpo{Nsmcu}&8alop1A9vPW3wB>g6U@Bc@>Cz`GpifWia9;XN5gU)xtO?J%?7j&@q z0(B`#u4?-ZoCN2=;`wsuZYjoI)_rtw!y5WAhH*Ty(qOx~A}Q&oh3}d(gx&s4<#sGh z8-`jd#?h4@w&L4gN|^GwfqVG#+DPhmrxWc{NiG6Iw0d*8Vbj@dn_>!wgig%DHjg zSqto^xe4xX+d|~xM0hJV4OafKrUwn2vGI5<938ca(>ksLhm6aK=kGLnGAjdH3i@M* zgDu<1+cCLgCGPn2nv8XF$H)78;m)O8`nJ>%9nW|Qv%Ml*Rvcw-fLj)P16;eA?RO91 zct<*dNfAc3AoN(j)70@x=iX8O-oV+yylC6fORij-49jS&;-K(y5ofn|B<|DK60)(e^DR*AS*$SUowWYrFC_!3J|&B{>fl0v>To@nI!E)|PQ$a6(HBsHqx&{&pAk!q5UfP|FZYJH3J3L?Hd^-!* zoR-1e7stTT^i+JfOdcmyB+{4xfIsW4!O|+7Ts>-m@uPxa>?2QlCQpQqAPUr)j&ojJ zIyhG+PS9{{l~~W+<@aECF@PFJ=Hik$z3`uIzj7jn3o4Hay8ZW~sffa z7tN%5VTD008D+f@r{sQx;SuNPLCXyMXEp>|Rw!}5C1lX>;6ULfn~^scof&WNN3#UY z@if8ZkHW!hh6$NBirtSAvtaSKathmAP;pi*L}rNjFVQ);3A+IHUm-s_^U>Bz7Ug|T z(JVQZBYrU)r`EJ{annq2OshG>&D>Atv+QSr`&`KMi{eL!9B@!PV`yKFB_6E9#cn6_ zCM8AFASq9rv1}(CK5)(4NWKFPD>`BK{w1*eUj}}=E``xc(&?G5Jly?I5zXUliGHRN z2JCi&ffB*=3!C#*60<@1a5eXIn;N$Gc?sT|2c_OP_+}aSC%@vQX0Wi`-CWpkTZznY z(nGxo<*@Np4V`)?9mgE*C+PMm(d<2LJ_Hps?-L(6Pv(jCfsTnr^z$Y?G!Josz-@mx z=Qe#@HF1fc;nMe#KbYlft|%45_&yi1YOetnYcS3L^ILX07vRwYviR-F z2hk4KY@9xB7*-6K0Y@iW<6~uepswYOl`D*K?pROQXqG`1v-|$gv}j?@|7$hJofRn% zu6v&QRiz4xXT}rFF?BR;TQ(-&_ytn(?$mx>HcHFNV3AflxioV=hL^sD>etQG<+vG2 zL=*5m`cZV|<$jzrtQi#Bqaei$a^6~@mr~N zyfx;pWNe4}=MDX(2u_=t1{2z9h)J&zMn>m>j?{9xO#=P^AEEA zkxwk&vCUQvzk7@5@QDWa=ZrCYvhg7DA1zTnX@QW9HLW+sV?)D1^MNW?Q_zh8jB!7U z@v^^Jm|^I!&9Ei|sQlt0Jj1$jWajCUew$~YN=cQV;k;#DbfrQ$40e6PoBN2+O%H6ta}m19*OE2^~1W1Q*U@jG$*XxFgeMVe^ebSnJtHuTRWEjaKH<``*JJ z{mQzWnug(Bi$i2}e@DEi>h#K@UE^cU=j%hr(DoO0`!yRZP%gwq@LOIx&A75n-q2GY zL_)t3d>71S+RRwGAdSH`EOZHaVLlNrtq6M_AoWO6FV8V_{`LDhmew8@b1 zocFB+rNPI!!ctxIoVO9=cDK^KtQ#eG=^HrkBY+08p3@ymy5aT77}6QU;VYTLu&8Sf z9pRjYSI5YqSA#O&UgC`@zCIv(Lkfax-0P zjLQDdC+uKsnQP`_^g8f4aX|f;C2&qY7Z)s)K`U)` z^I|#ovs^eDvb0FRAvd(VG#esALus-|7p2jGbpvhX*56gb7&#AN=D)t|g`(6FcpmhU zxBf3LmhzWT5XazQUv@KzYLUkAI&|eOW)_wQGauJjo8$Jr{sum&-#&-X?5i9Uu8DfA`E-ACFHpfah9j zL}mfI<#E2yx4D%5XtqX8y^XNz+Vh4DjKir{m<*N6t4Z8lVj_94fzG1!*=VWc)b}-$kW>^>rKiiFI|= zR@Oj~Z6qi9qzz3a#lp1)tAy$F?T@58@-Vf2lw2`(C#2a?xra4+6yV5{0@!Fzf1 zcLoL*_QU7vy7(L2MOd(PH0!WGO(HBE@Sd9^Tg-p*7duVx!T=ALeNTt99CE~`0eR42 zt5Scri{Mug)3uu8h)Spd%B?JikzR}G!K4aQ`ZXLkOMm2k8a{%|JYPY#_u7XjwO_&Dw7J~03QY~vI)W4JmR!7~rSDNLx=G`~w{Wq9#QOz)B zP_>}v=$vTBd5`>Y+LdCm!Dt$~$nS>wYX|7eLSvLWYXrHkia6(EBk=*54xmst|ot!&q-$pC{r+vwD+Y@Bue8~pvam@j6$f}&DsJbC^$ zQDJ`UD|cmau#(6&UTV~k;UT-RH>81H{D9ms+f*L8f9@>R1&>DX*M2t z=?XGmib&!BYqZ}y58SSJ(}osfoFiHSr*<6TrrgoR*ca^ki_QF)ey;dFtr|`Qj;AGK z^YK7Y7aaS#o|Nn(XkC5?COp|oYuO$$gmwLV>Knr!Wp_Y>Hd{C``Zt-o(+$sOhQX_P zO`3Sm6t9(q!Nh-q$TC#})RK%9JoYU$PWWO=CB)}k<6T7^SbD+^53G~{(My)`Dcug& ztJ0|Np$b%U9*-|$r*ohBr18j+{=&>3*WVsbx-EbMo*(%>6@rh$Bfuw~BZgC1uG23S zio;517Rx>iZ7hXTktTe_%v@AF^aK9$=VX1+#k{aOnExk`b}EUPKY-U+K5>0X6mQIKQfaYa&^&x8Nj4SXQI^~KZ|0XOit&?25zDKbGFQ{+ zz)nj$R8Uz0D;)Fi%WT#mqMbwYScgUQyHV&B}>V3P(nf9WHu!c18&pgw)Wh?Dv~(FNyzg z&pxlO!&MK}P#1d$J+l=5MTf$02Yae(Y=si-0bu-V5ScyS0BzKQA!hXsdSE2G9du;D z!LJ^C^>r(pU{nfGC%nk}Y%>g*Q3-F#bLrKBA~eyLLqE+9kyxb&1C}YFPopkKx4EGj zGfE(TorCaV^D9u-y-EjL+hMAQ4cMsnh?KX>h>H_Op`A5_ z8?OSeX<8=O#^}*E62S8H$&ipUk{A!rMk}9GVdjte&j6~^}AHp*c?OQ6Mjjj(`u z_C~((BG>j2q(@z-VD*sTp6RFCjef)<{mr1Dn5pY!EwDn2qFgpW&K^Q)&@p|aS5o$)KFbwL=$DA5YeW2JKxZb-@_-)1sBcEW7v`I}3dITNf~=?c3}$#J_cd_wVOMQlEP9Zp8D{*jNj zA-H%6wFx&ypM{UmJIg`ht*HsD@KRrBFI~jK&ZPRcAqK}H2kJD&oHsU z5e?F(kVoQ2Fy+)7Xj%1$w&Nwx7IlDUN(XWxJKU{xo$!Bj@#C60IN@DQiFz7ZL<|ycwY5iWG5NeT zOi=qtMxG7Et(I|cYbBww|J{g#BVeiWU~*l{0Qbjk6lVV0WM}MVebAE^UgwAT7vMEz z)_K~!og`-JqSDYhxSg9yFFh{ChqD+DZN?N%#X$x&`bi1gv+K+!tbU8VZ7V}Egh5YO!MwD_mS_8a-HE$Bia?l(4;Nh#gB#LFbT!t|Y%!5FBMYja! z=#Ijo<6WHO6xJhIXuxuk`{}S^cIzKF2M#P<#~Y^G;pe0nsJ_0Qq&?#BPFf@r<}oj;GW-8JjO5ak)?${SS3*C=$5`#|g8FC=J%Nj8 z_h?<5cghNMdMdcHlhkp!r;FgpOlH5AOm=JQ9CwRvinGOIM@m7oOqF;g>fx$qMNsKm zLz~%Wig-(4?ls`=6=h)c9$EZ*@(%gcz6d{C&j;;4R&;-#1@;#Ez`?G8WM85Inxq8@ z+RkMUdu&R`6lQ+nc*JjmHp5{bH}c2X7~S5K!Miu?R@=)MII5Dut@dYf3I0wRh5pV4 z@LI+lS3h$C^S`x?$E3_~ccqJ<;aiVE9Qt`4Iw&(TCDNE=TXq(FXmGo8XZFEn#|U}%4NddfBj z-w`S7CA-M++naFq*MIQO>KqM!V1Snw=m5-DCm+8vAGJXsXz|r_ogC|E2wM&zWe*zW zUNOZfC*wf=)K*gIXoimpa$v4&1g+7oMElFq*ekxneH-ink=$8gJSmy>D^J6zM+Ty7 zqlotTvHQgtBlxZ9PZH{E@IhSwRGKH#D)wG89K8tYeox^JR7i@y4A94sLq_1S$!2(b zRSvwaBJ@Uh8ScFziC#g*5VI6Rd|k`kpChXqD4DnHE?$ zhP|n?T^rZPnBn%2P#D*{ncR{B+~t!5V=8T_qlX3VtS^N2e!<-N*LtvHRx$Z=C!Mxd zu-w_UeyAJZKu`QFX51Ym%&X2LhwMGjdyEV7%;eJ9>^%-UZJ}IeAZHaZT>R`TV@c`ZURFC}(XThwC`J5;~38$`A6SSRO_dGC?CP27U8^0!i`J_!DcfmsxHft}y>Zk4kDWp_Q}ngU^5G&Y-RUKHucn}*uUn9V1D`D-9TfAmj0miHUg0vgkiP{Z))Lv8z*WRSjrz`$?Adpq5agteJRF1Ww&_iV*aDNEozpn zfrq=+k)8KB945>5z^*8IrGaUQF`L18c)hvG>+N{wr7WrwRnWb>4QQnoO9%3^v)hj~+pCCt3GmDAd&jzQ*5!rk`5B^xZ$OaqG-w|Lnr zR(N_K>u2nlM6SHm#f%r5;dXX4UA{jPPx}3X3>)O%vrhIYrv~A`^LI$+^~Gpw~lC_j9>;CP)gGIldM-Gyf9amdC_{)1gw;9b=x@L-Uu~#_f+R@xf+q_$0NN=r$nx z-z*1Uem8SI-2QSU9=N)p1V`6PSzPw-48dMk0;L# z1!1MxbI4%&%&b+#?r2%(~2cE7PFLSf37kWrWjH*TeGH z3dCcpHeyebF!P_Z<>2lYequB%fb?RRJ*klVUJuxykqEn<+tR(` zozdKH3;1|Pa9wJ;@Ci1P3Y#?Qek=F?$$Be{@km1ktZTT&4SmbHN{{El zTd79YiJ6JI_W$5NZO3JOJ2pQLLEA0EV2KgSU{0`x#K&Fy2wm3WJjV)}@6RM!!vIge zN`R#r!|GG)*=;U66WY?FNk3~tH|3x;6rn-5&{>K5>t!uWX1tCP0D z1xNYVfNWSEfBJ+2da1BH%fdCJf1Nd^wMK&O>IB-7YK~`C$ALsWaz`yIaC+%y80#?v zo}Fj<aIo&4x+2B=ZK7EZgHlWKPBmMcsZ*f@(SbFep|1KO%X_&Kk#nLZ$ak;88i zlUbQKg$zPT=Y6zJ-T?m&*8n{Re5qMuj2vxuxwtwXg=#GG=40Fca_J%qvMP}&@=#l1|`u?@dh|y zz6Q9-#}kbQHh7_Y4j51Lp{3glv6pqR{WtS(9@9g)Baxu@tCflt6yUf=&%hyL9t{iH zf(JDvG3-JzNtV^YmK>%7yxB^x@M)+^WpKKt4EP5U)z z@C`FOV;Bs!ma;_dj{(yR*9v{&fo-n%M709+`)=?SBRL%Ubqh$wd65U6`j{A51JQ12 zbeH!N92xC}X&Fm6-PJOv6x>J7GpCE3rX3ctd*!#o@A-|J4DqGrT)5V2H`^8yJY*MMHqe52e8YM?w`y0R>pYL4H*xoy@q<{51*Oll4OMdvX@eJv#`mX-|dsqvqnnF|*;M z&%Q>-iHx^4$sYFRXOb7kE%1=#a(HLzN+ovMVb9xC$k4yVjdxaqlBrRGwiDBti-k`< z!@X7y+Q;6E?@T>$zsf_Rzf6Qz-kbzpZx@vw$QWF*T97#Ztw>GMSUmYGyXU#}V?6sZ z+%T*Gt|&*-U_&vwJxTzx1|@Q$SsVWyPK1dcnrS@a`TQ8l^uUG&Uinfs9-l9PuH$!- zcC|Q69oGwc$DE^8r5wI@)`#!Pnq-!P9S#on0kaQPbisZ*^hjL|D~7&mFpy(hmzY$z zwQM)pG==f~)@BMm{C3U~Hy^8Joj!5g$Z76y=vkxS$&{Xwj@RzV2s8isOUAEuHi6FK zg+%&|Emr-T1N2rhbz*mcp6T;p-XvAdcDl59F7ptZom4{KW9E3ZHVfvT26|J$3>Qx+ zgVz16oYmWzXqQ_i_;&JkrQ^go1Ms57TVB_Opz?Qp*im0b=iYR}?=ExU`v||r;4Nl2 zeeptJ=AS76jHmGsL~W_zLT9XLD-&jZjJ*yhkIE;%m!{Ib``M@*E`d%19q739b{zR~ z5zcz{l5A!9{eY2P(2Zp@aI*mxO|gXYxdXXaUP-K-WQ2)hq;SBxAWWmBkTgz*>eLwH z4d#1H>Ac2;DQTh~d$auK+v)vTh#vEX<4)g`WU1JN-Ki}h=6yFG-A@lY{gL@)B+<_29;bP-1y;m+2pYbg zts9#Eu>z~?d}h11!MBUN1y0U1VvV1DBH-QN1X}52gR)L3;Fjgc)#g^9bXq%fh75rw zSrPuaP%g~*Z{|6;_o@VLOEM(+9@9~5Qzy*%vsaDL>b547RTpt2R)~!PvoOFJcV_UbE(TE4sBQu zj+L(}S(wQ9{97x5h%0HAJ?nY-!{+=^Wj-U#7FQn=!5Oz7#H-T{i_Ztaq-C1)E7OsF zJFR6N%kA_g%b~onD}rW^i~J#`N8MY#1sZ00kvzujw;59dH%!xL-nvYb7(WPQW+-u& z;$+YvxrZp#y``G7EYYRQ6?U9@$v=2uh}Dn%U}=&8x!Qyn!e)CzP%*vP;(`9dw?f^0 zD?VG<5_S42p>Jy{`Swl^{jmy`oeQK3cNE~xM+&Gq_zP#$ZHf^SG{OAOe(Lkh4sVY0 z28Dt+zCaeRu62>%x4#_@SgaZcg=^PQaVTIUV}IF)o-n^0Qiujuzr)7L;h@j>4^8X; zLYYSf&0)W5*Aa5qv&4c(Tg^tl+ZJFnER-6T=wYHW0gcC7xzxTJ+XBlm*-Z&0{63Pbo&an; z=?sbwMD+V43*7O<1*ZKOK)mKKkENlX;I|K9H~IyWlOR{ll{Y^mVhn>!7=71~_^|J_ z%WGM$6Xa00$Jsb6t`CkBKNnpt%fhI>f%tRvRA^&w)vBdhaO-`3<961It>5AT`4Rc# zE_>G)xh{pSfv!|q%Mgu|BcbO-J@<8_8obe6O}3cTQYX31_?>yKhOk}Y`tS~Xs_BmE z#~+YReGcQLPQvmnyXb@MmUwBh5r~Vvi_~R}#XDs!ak_Co6om(3-+OldJ*Q6%nWuN! zo@fy14<#C^EE|%Q0Mc?->FzAXbDrD@K7$9*#Ph5NnekCaJ=#HhUE*+%UJvU~I7b~% z8=~3F86bB_op`$derj?UIkAWjML-K>uKAD^jqmC}8 zN180~$gxUTd2$nXj(I>X>YO3Z?xxVahMD-IZUCCFF)rQ7c9Pg>@SuA(+1Ae)zeM=K zj0x#<)+mC5P6xw=Mbo+2Z8GBfii}sAJQ@cw%_r<-2K*Zbv^(4s?Nmx2x#}6`Bd>wp z;!1{*?hV59 zAa|%LDWh>Vu6Xci0JO)Ba5d|C>uU<3zqjY(&zgSt#rPqo*ZUaWKX!-y7u)En-;S&ol7q}8 zIs9R!Ew$_uGabyI6sOvviDCqdS(ZqjvD{haob_PQ0G#>^Pn2=q3d7Ge5ruc==sm6s z!Y-RrHCp%{a08sHCz2aHT1+U^>iuiDWpxu9lu&kc%rvw1I*_D1Xr~2iGvRzsvg@q`EQ_ zRmB6a!*U<>WP94VXKJt@rGu+(HOB70VmM^KhrT~O2W2P3!R@N`{M&&B*e(?T&HhWs zrs)n$FJj);0TuMk2p9A_zXLARxQT8gl;f1jLD-g~4!>9zoBSMU!IM+iNpN|UHhi~F zBiHWQ;>x}5u;;1|E&ODFu~lKR1L0xkNTA~_;xxf?vcmBQXWWo{|vyN$pt5mPwreKI)o z+Ne3q(m+^Ct&c z(Baws|!}0w1P4HlJ44pF{@z;oK=ox*|{E%M}R=)iPi{^{~Yo#3gkHa(E^3He+$(*ly@F{l0sQJdn% z`050jkLgl}Pp)Vb<_8ctj67uwMuk^%1ZF~mwl%I=n*dp*F1+S#wllA0S=2+0WE^9v zG+!!$`q$ZXO>Z_XW_=~Oklq9kV;?o-u$!Pu+eQeFt06ZsOfgr1-M^H==~R~YjMT4$uBCBY$8ir(J612S zivw$!ANY+l&Jq#&I)V8E=c+?fj5`???TF{kc)_P%sZ_($5Zl7$Fka9kF8IhmvA3TA zP6=S$dyKOkB$*-X>T|!CGA{!oJbZY@h0oK#b8NQ%$2}XAmVuX>r5P9aEzgj3=sZ$K zU>7GC63n=33n9}T8aIxx!{vLILse`gG5CpiZ09D}aLA4x>0o!`^bGi&5WpE8W%K-J z9vQqNoi2Hig`-%O^NXwRlM=bG%HxVAfNuTH^)_Htw6$eFc-N* zMSL#W7)QU9!IrQ9)=QHQYtCxWnF-97lA8klR@b<_M>H{OY!(?VhG$cK&ui@{)cyLottk0du`q$z% z!?l7G(w)LM6&&-Uvb}x3e=bU2?t?w4cRBC=PoRu>mH*=;EZQN)+E87=d$W0^0e0kZ zu;`&L8F9rL{eLWloXH8aT9NfKKUxRV%8@(1&l4~H-2$aOP2`&`%Q3wvfy3|2>5DJb zIPJXx?mO;8vii@!vC`Xw+1~!#2=hOx!`a+IPG_GI+Poht?CqagY*1s-QXuyp^NJ4* z&^Id_f?k`E{%m&&XZP{yC$-dZnG-(lsD*`l)p(VQIcVwJ3ymQ+Nn%n4ma?1df8LwP z>-Dky$P~zY(!og^nc&QNfYodE(Dg^`QN3)r;IZF#iG9|dMZ>TqtH~k-j&> zT2<_V0fpO{mg^=WTdQ#vKN$Bs(tsg+I!+V!$JJ*TCtsAbLbH|6H^~t}p%;y$89lk^ypv~uj@hEJdtz!-E$+%L5S@U4$yJbYrQjEu2 zH-fIsdOFY-(Bee~B)vUu-mFoCtL?r3=^73Sk8|)?*&p~GkxA7q7onuj5bSVtByCEb zECUFja(5}6`9U9-tS|%h)0LdwP{zJ`VXO!HNU4qPZaB3k)8=9X$6h5mzbbvEWpkW>0}V&dX38rhVgYS^yetX6bN%B*iad)pLoMOFij#73w>&Q~rQ2C<4 z*V_pF(pEtJ>oVf7&>TnpO9h4L5wxM$68&u|z_o1?rWg?f%`OASFYS*K zt2pY;xB*gWYOo@~lic|dfb)I?v%A}7TKCofhuL|;#rBEZ&{A3P#rp<$)^jYb{2;

    cpG)hFiptago_nitU`07UmFaH;{AOIZoX6)EJ)~ z9Ei7K7ofIzA^daFp_I+iFq(2YF$Ve- zKx%3Tolsqa7A6X4@uP#2>39OuN4l{$*C*`+h3~AKvwtvtFg-zYKRICb5My}b zB}4R9nP7w(fN>4$;C5%du?h1*{mnf7YC8Mg*&79o(yNK%YkNG9Rsgf|w$O(fvvH!@ zPG}GI5bZo$h%>tS;rvk(!D2Ye%Nw#DK8Yln%kEmXk)dZAS+^OF72p}V#-eS78lGK%#pwWLw6f%&Li8y-8^d1nU;l;Z6Z)t62%LZH|2FSeC_8 zErEk}N#rQYw(NMj1^!yir)BG^a4_@L?7t~VR(F|U@dtIdxaj~*6tmBlwTMCd+|gOhr@V5)K^ z-R@X`)|X^)AJ~vJZ(MQpdK0+zZxNN6$KH}6Q<(6giZgeZimw@FHoEB*)s}R?(9#5W zB6FAjVaeFbPZ{U=zA}0J*8oKmb3saf8(n>eF_ez{1UY}?OLi6Dqw#X+zyB$z`svC# zE=}N^tuDQwWQZevn80-9zg!l(kA*OQzUGG=G+)gLKQNxWLx>mu{<1mp%_*R#=s^B? zo8Zk$`LKO`7X4+BgKBzRAYuAk)F7FO{vV{6=B^4Poc(-43G8vmB$u{XV*io_pylsM z-5IN7$AQ%X-zIn~8Qtn4`}8=YJk?{qJd@?y*8ahbeZ;!YiuM*goz9 zzc7y3wmN5klzBOQk`DNz$`Y;_IyUb4Y=TSlyg^5&fRu+>;QhH9;Kez6+V#~HM>rG- z+1OFZ`cU<VUNRXv=23nZM!6M>`tIcKA7aq*>lMnMC|@#js2h=Vb0Ha#-T@>7#`0uVDC`IW*@K#q{9^JOT-*5 zeat+uWgAJAfiXUQnFsA=Ayn#lAuhTjiCRA%bMrSnfwR}0!C9k?$}be7^cD>`eK>`G zYGr`+<4xc_=gT_jEHQok0tj9dN6njzF+VLF9Gc9zW&Ip*giJou*-ntSW^+6eUkD4| zn$h}8RhVQYhfk{=$kN~$D4AX*%z1+k-q^8I1RZk@a4L6|Fez`e;F))Gw!$A_K~Pur zkWXbSujzl6LCG8bGhkB+024DAwOgfL(W%hx-peS&_XfkY!1wO$H_-0l_ zJs;%ZEbq6FIc8{o`iArKz&oX#{Y#Ey^m;P(4Ky6uZ0PQH*M%=w~tUGz&T zh1`Ez>8G_BI6uB0-ngdBFSoPAwS6!y_~ z^SgN|JgC}EmodNAVgF(%?suF2RY%Z2tq6=Sc#-Mn4RNqa1*{&IPSaNv;GQ;?*_k(% zYxEs}w?o^>&3W(W%LJxJ-Er{1h`VV~FgS%8UCWN~%(XKvLvbBwW773TcCv51l0Vqu@( zf7Tv*wk(Fg*!9F~J;6z?tKqqF6#a6C@x=C(Lu1BG^UBm()ajPM2L%&h+u~ddzx*4F zb290<$$2OpHvr8gEyciPzL$&Jqo# z#z1$@RX&69Sbi=_f#?Iuq))_rAdjQ%IQ31YRI|!2xJ|ShX>}|M4 z4?J|WXzOWqxB7wb@2)hd$Tz}{Lv8}ESY@I$9>2W-lpi?r*C&~x;?hK@@3tY5%T002 zlzg}~KAUxUF{hstIz3f|{=rr_dVvN!T3gzfy2TXpu9*o;%kwi? zKX}3dsJJ(q_H8i7fOQe@JFbb_dwL3V{|q5}hcTc3YZpxUSp%wDM$x66tn({`d1V6= zNct#Xn&A-$(%4Net~AGg`HX*mK2*MOVCUF&s~SU4~EJrNGSR9Nn|o1e579 zs4*Hs+6{E^dhP}YAXjP4;Cu|}egi)D2hh^4&1k;$AM6{spWSidF<<;09%!ATKUH0E z(M1C|6(k~M9xfQX-4*Wk*3#Zywzs;tLzd%>hMQI<80)(XPS4mvYFQ5~_bFMJ`Kjra zs4SGWUC#f;eZbA(}f(#3q*W^?sfrbOjeTwV^QcukJO& z9F`M*l_1X*r$~$6rHsa$5%1ylu?1-GG!GUH)1l)GXJc$;AuNCLp36?tLYLAsc%a`% z4HR;*NAovq((2`pHn!ug0Rebw_E5OE$`%hOXu&r6h2O`1j|0z{!dFRcGRV^!lSXc2 z9cqg87oTwW;!+AID#emEj^#l6@*rv55?Zu!3mTcQ?5EKi&awLmj0on>v;yALeNcwI2SYjxjExJQqOWn|KTTca%^XOsvY|+$+k^1uv4oN9=xOW;nfm1vR=doQH*L5;)&*fTU6A2&o{sQ+wZ zbf1?4hf>Co_xE-2!R!)vFJDQ67G|QoW=1Bu+)gv%y>b69mg8u<%j+3iqn~mawA~9JAK5OKFk&l& zsbtbYU!UUSOO8yR4CT}Z3_$(2?}go-b9F@HLVMul+W61kO|YTd4RY#?$mYG4xUw?} zEU%Z)w-R1>F}Dcr?6%_fuz9sXtrS*oP9-b#3{c{CDO@@jNUL{k#+RvsP;{!3OO7+g zh}KDrQG9@!d5Q7iK>%}`DBhK^VPDxZJ#bVAnYhaem9^G^_)aWsi*ZEV)*Pri+GM_6 zwGJaEu@!#SAv}ju^^%3%-gh};HK%34GWBg#J~$h9|M?2c8qO=s z&&Q!*15j=7V{&pW(~xtg!yuDsRH54yJM>&w|H4qB&Sw7nc4uL?-{mI8**{i;>Nb1c zm-&J&?@I=S5GRuU*$lI<=fTk7IrQJ^T+G<`6H=DE5NQp}#M_yYcojL7e_1s@2`zq!#g#29}!B7`q$D;eJ-dq zw;Hak8$~bpcc9$?JN)f`pGXe>A4z8&Rn^*caT5g_6~v$v1O!34&VJUSyF)?=1ylr4 z5Ca40PC-;au@y{gWk0rFy9-ea3`}eV^;_@x{=H+ohZu=7MSNA3;tQvZ1a1Dyl*x%pGo3s4UQP`W({~mr3o^B{E63iK&r{lqJA#L zi_{tSOyEm&9Wk}f1TYVZVSCs4;g*{|Q1Gsht6lhc^phTmpnK}X_E;mkRG3=YeY&Ut6Q6127d2F=c0;z$2tv|ZZ^a~AJn zMi=eT@t!t}40|umTxp8weNA9j4?UKhWrNmc$uRoSkYo2e1*~q%ghsh#?9p;d9J;qe zI_Fnat-~d2`{2Fg*FsQUGelD!>VMfNr*3vQ#6t@-YI4NJeP$Rw&J=o{r+cfV1M1BS zga2`F&NrFk>)SKozPGjD94DYJ`D_(>HL%&_-CFy-Ose6`o$wyRGM({JQw5W2BMpbL zX@=`|bAyML_?s2CsxGo z%gd#C*eRans8Rj`6w_ym=e)~NIruk>O}fQ)?j`Svum$=&2;s@L4mgA9NO|=}UY2Nl z+?)>X^?dIp%CI;D1Lxsl(K`zq=NAj=xpP=cEdBo{U(Nq~@;CH}+iX$=L+9B`;vQDu z>}`KRX`u=XZ79XMGcp)am&ZSlkK*ogbtq=pEOoI5UO4IostRFTrkfGQoOLFa{tiJd z*93>1i-Ll>CwyyMIL5xL0slu@y#G4HVzWx# zzad_Wmf+%!GI;&Um-WA7fiGKX;G|{&KUYzS`d-9vh*S|ic=kc1IWO4gZ*BZD-3v1G zoniNhx8e+9Czd4B9Md*qugRhuU^fRUR;=WT0X{e-pbWa?Y{X}wfE)LfLu-2m)2^fr z_l?AF92&_#7Zjt#s-AdZ)GI+aOFh?tDsbh&ZsI_?Vdn=&aN3+EYAOez?83QV^e&4v z=Gvh@pAXj*mhpo-Y;l7cY2B(vtQ88k<0bmu-IvjTR{LU9Qtp6+e)+_3D8zl^df=cj zjIEOR;WteqD4Q^gZ@OZH#5O$lw zi7nk({y=k_NbG_q`rEk74o{p#+_rYF$>QG84#a26g(1FvY-G3u=TJ8D=&xe_D60fr zEx*7I>LNLEt^g)HcoGEZB!H4H+ zm}5Ic!>GFB!l%-4p#66`OHSRulc5YvD_bF@$&YWD_nz{nj-=n+Vbzs}CZ_XPhWcWCwrT2f*3$LAc9!9;^tS$PeCd!ZS+L3%_9`J4^rDr^^?@ zTfIv>H*F=prhcRvQI{m6Ni#?-#)G$Liqkrq3)W*XHdc zK>yQgxb-kA+&st&mY82ZzReLaxnVA37HwclDQ8#QmH{!IiF}fiEyjPUpgzWBf^kA1 zq&gjt?)GC`iqLsZ54`JwT(AFJyuZK|c0SK%Ewz65xZV@4T`uJ36Bx$6@q=A^wS*D5 z@-}-d%uudy94=Y|*pvJif4XeA+5rnpq28!1Umgnfae7$yp%kXx*w5R4=3|;?HynQP zg=o|r(Yak6?mMmJ9`b&;Qr#2Y1cWzrF9B@U3Xt{;_84Q2*$a}v_O2`6zS;`gGt%Hf zVvxWpjp6s!JSoSrfq31Oe>z~7;KJ3q7vn(1p7`NU7RxLQ#C@MlV3v9rFHpB6uD%KM zR_P~n{Tgrc{<RDSxS#(invD%ab2T4$u-lbgBYpKh(*#)XV$iYg za&DOTtq|V!%3;6XTjJiVV(4s~#Y-Zd;PM|6?`gb1E1 zzIY^HL98XnOp0O`J)QC4^DwwHE`z7{6!3dx9C)Rm;9O*lqxI9lKzRpy@|JiVH%q}7 ztohu6YP^25C&o{+XWgAAU{lW;seiJM=!P9nb-?fSX2JT4BHsBTFP-^~+nsQ<$rRYU z{-L<&ju~3^oesJ$tXX0bWszi-Nc*RjEVV;rW}7O{ea~wZ!rsJ;-NWg z0^dI&+<^FaN;yi9e7Hl{`oa?TtTl!`HVypWHwP@77y^UyqQ###T~V)L3G^G7&W2W6 zqqS}tJlkEu7r4{6QfVb*kF=HiEvUrm4V}<*ycI^sAp=F*piAkd6*g~2eh;Mq=_}FuZ5{QGWhzVPWbOuC{$L- zvmZugXmvXhYMM85ZMuUG^(}{mYi@}5dn5M#Sq3NP1hT92n@IdsCDrXc^l4{vruXs~ zMWJzIAC%Q-W&i66xAO794lfs2lJQA&wX?uyHm*{?O^zMuUHjstKKT)=BZ#rK7UZ6I zicd1>p7^~0uy-n}w>8DZPpD&PasA~vO9G6?6n=Ih!|;rB$lkHv+T`wb9NDisZY2MpZ=--R zuWBLeia8Gqsl~^)2H}z0eoWHli>J=&LsacdE>HLFnOT&xTUjgY?5TyW^bY+W({ksT zFm%_?gVu^yV(;a|P`$GhhDHx(lc=vM$sr|eN*3K zpO^MH<7o+e$Jwvi?18t z^r=j4zY5UdlnVU2H<3B_v&DzCq?cYJ-EX)ZrlhinpHmL*VbL;S1_VR@M+cY!<(|5z*X(Y7ceGDLKF%T@8>;QWS~HK;Kl8@* zZO)L}oX>kcH^#;!2dI+NKQvw6Ljegk(Y8}SwJ&hZSe8*R&z%8Q-aH#A*uu~zQyg%ZtFjWYdvzFKRgyYK#f#9qZ*Q9>Z8s{l^!mGP0 z*`_pmob@RYcFVZ&GlAqEYfS~u7n6nEq|@9zohS8D9;+I%p-DES5pT z{CxJacOZ66F$9PDQhqtb0yAbCLPUm~P|>Vo^D@y26Jmzq<{M$?X_g0e3-!1dO+7o5 zDR|!Jp^(cA(5O9Ay64}EC%taUXL!EwkJz)k2qnvi*YU4`2`}uh*mo=p{rpz6dqaH1 zU8b;aixE2(PuYYE3t`&&)t~*gLc-?ogEvd+j>i)ZyMAmev5JO9=N1L~$im^|f!7Fgl*+!!g}a(E{3 z-v6b-*5BKh{vvuiA1Q&S`PN)czZ`3vzJa-?1(Q#mfX`2pm!595`fZl@Dq2a}QQ}Da zya4ARaJl6LH~uML>Sa&Z+ImgAPTeBimecn|-HLUTn4!tt#nO%v%a^to{<<8N9~v#5 z$SlD-aUWszma9xtG{RAnseAojFt2}Ng=s@Z!u2KJg{QxXD>B3ol#Cnrg1=4}SQHFH zcFzzme)7ZX32E@)Tn^iGQNVkSX;SWu$yXn2Fjxosi+m-ucUw@Vp13($v9N1(A!^qD zgJ%6K{+N2i7Jkx%(9RMzd#Vpw8c_D?Y$P8~{S>XwY^lSgUKm0*#2GGO(A2G!4{e)* zm*Q8!pBb7wu*@7SP4XdDWeltSZiJ2RR>Hf`b^O?cLR|aw9|VSv7FV9ILAf{;_`CZp zi>-*k9mb(jUi~lfSWZ@q2D9ps>@?xPllF@r!?n*|ipUvzxQD zm&(@G7n|Rw!s_acd}j}Tobj~;TKe0G<-@5TIi(OrtzW@v-kYLw_f=rj9KokfCeH9@ zdOO$Co=xW!$Xm}%v$IWp0ki}3|GmNQ?HAROW#HuCM z*_yl5X}j<}2)k^=oiW8Yeq?v7ti8@+mnl6a7{6f@+rlCZ$E<7g;q%rX}lwY zyJ5{dO}L#Gk0vW^pz!VCrvCI^d%RQ+>SpG!bn0H&q8kMLQhfO$Ptquw!r*!MF=6R( z$_AT+GkNC?yzyHZ+Kgxc(afJeQw0oJT?<>kO<)(ijBrYP9h5(;;jih|KYob{d_DR} zlC9;8CA$RZ8#Dl-1_z`3*x6u%6Zw+>@^3tig2Kat*#X);k}f4mXZ~n|a#T-ffdrkt z92X1JmqdLoZc~^%F=l73p}wu8EH2j=fI({dU~<8R4Lc0Dfo6{B{VE>((j7a#PldXs z7stoNdEwlsWia#oF1Cw2_Ol+-%#Tds<10OJ@c3#N-#1$r?l>8CfTK!YR&QfTSsV^SITmI958V3JW$-`#wXHkeXY`RNH{TBC|O|wO*uJIrg1&_ zerNXn07Hyj_`+M{8%d#iXizpYc8$hU53C^a^;#ad*8w$bnFGj-(2s0=l-v z>YnJF!4GV;#r4$P6aKVNSX$Kr`O6&1x6{r)#XDl!PIdUcKTjNAP2RdnCz!iuDeGzI zj29jUf%eUG9zVefvl6Gn5`96)9dAuODB?edY-eh~(4wUnMh=s3XUe8UQr2Lb{#)VV z^$FOrbB%P*KapUGfx|}79IF&$E{?!2w+BP2ZyQ%Q$ME|OPZ+TKy4ZBp6mwO>U~IV+ zD=;_1l~Wc;y9ghw@j;K-wcr+`B_5`4ag*FeupV2;R$nke%ZGKK@IIIa1yGLZ*f41x z_I{KVPTojw=llllPAsq9pFN;ScZztkfqoZv;-R~13j6t6z~b*KK;EN_|02AR0`YHC zx}hZ5dMoxGAcvccCP9xUh3Gc-A9zJ%am!#E%*;`iGL1iL`(V47BV?yW^7XS#uzkLr z^lsZT)D+WJPL=NYXV-;eO>-4!&CufGHHfWot^gj|s4y1=V?09lj{j*pzg`t!>i$1) zb@C|jafTZ%yQK-27XDzh&0g4zGHYum=<@NC9dT<*AhgdO!rqV<;!#YvG!Ltw?SevC zEbEXE)h-a4TpnKdWj_EVT@HY-S?14YWk7#d*|Yn96k8 zOmXCr3g}oG!Ig@Nu-@q}v6Ws3)9NMo{;MLSdhOw#WSlXq$_iHfS}vA9H^tW;ws2xc zBztD)fCFB{!{WH*+-w`*>oqH2_QnI&3-aoa&;JA^wWHyE55)5)C|jLj$xTTo+??f$ zho0B6<%9iD>7_O(rOf0KWfL^-r42gYYlTsDT39g57_PDBye44{KGZl0?^0Fxig(0I zxw=rg=U@71iux0C!2A3LuH-}=oe$oEWj9-~Y+n%`p?gi7lpi$R~D`;g+Khq2rAoe|ovM8I|xG3T zYoW3JgxID* zAZsi?O&s-;4o$C!;qd2H0DShZWj|Lr;0x-Yu{!L=pKY~5gOnxGIbX5M9C{_?vRQ@& z{L!>BeChfTcJy}V=R=ApxAF)2oyug-UPNP`E^{z8uI3rrEbuPqLFH^YVaqskn+u!m z@KTvF9&QiAs~uTTps&YUx|?Hq*#bBy{wIw2WI%p_bQqD`#4iy4w!{BD^bPD1|MnWqit)L^elhj<=Laq>{|8mZ|r&-T(ezuV6lH@m4p=KFlnjqY)e6}92bfFQP` zi})UAC&Q7)8T>Hmw+TZ-VV%E)&}Qd=Q4yK22KF(fM-10pDuTE156)b|G;hC;5wDq+z;CEPb<0LaF+@xUBg9R0=vVBT#JEUC-SG8AO? zTeHAprr6md3Bqc~JE!P?Y-SnU9H=a+BsyTLMjd1>Dr8-;#yIlhI>;Ft!ev*uVE#l^ zDBjwOeV}*i)LDA)>udwB&j`a+A+y15>gpy*W=Kk=P9EB7nHw3r-bLVTVQ8#|EgAH|=i z7~_IN0_gRv7aC8RqRpgW>27cRYAWV$T?rq~YVyuBEA*P12RBSqSkxC|%(_?xHRspy z`$r4$dEZV5ygf=xALxWTzK((TGaan|>E`zGQ;z6r8oe-=1lV|hFbe!qra)o{Qwr_v#z!$b`4 zMLNL#Tre(5WfMwFarV)2X*PB{Wxy?>x*#v-h0vo#f&n4JVRG0WzGj|19uG2s>!vAU z<^&_Wyv-WSA5LK@Mzl)|iGx!XsXR~D1$7cAvpG$)9y@9a`qX}fn7gWQWk(s^A>Tt+ zb|H6hEykfHe@LTd%rTkxQR?Gi@5z~5JHr@vT-E@6k6J+F4me@kYm2G^kuPYk;o(s!f`-lPL#hUvt0dDIf>sH`Q zy^Sm3zd2QW%v@jUt*eJ8gEmTLDVLzej=wPG*m%f)5r|fIwBd^C)~17}0W11Xg0O^Q z=JwtROGirsTBzCGWg}F>T1Yae;g__%aMOvgu<6r3Ns@*uZmF<@3F!mjY|UgmtuP(R&gs(K#0W>< z^ar;yvMivU-UXE1_}|Pw+1nAn=9huurbFU4Ma0{z8p0dH*n?~nVt%ZL;)C?IEwMwD zx{>gFm?4{JPB*CqlcY2MNEGS1;SQkp`ug#mvX(d|W(ufYTgzSt01lxW+@Jf2eCl{W z!===T5U@yiv12k=`|g&`{J67)sF(2@s-qacUI?haND=n5Ol9#C12J)XRQ%zi!CH`B4n{D?EU%uXu*Jv+Q;GYgJ4 zy6``F*0_`}hQpab!iS#bFk*Q&+n1Kloldyn!Cjl-i|!y^n@c-G%s&XN%4TYvQ^_}_ z5C6nUULk9T8Uu}CZa;b9jhUxS%A{b-b~MCkA(6OnZx%cuKKa;mTO8XX4W5p=E7a>u z!qL?C_rIC1rtOHEwCX_SR)g4Gxtty_-BEYXUN*9a3yyiC3_r>`MBmM3nBJfTuiW+6 z-73U!(b3=@HTc;6AOTx6mqJR_5;ka!6^URva{jat(Rn57Imz5}#w$lOR^*?~b)5lc@|ci!ZC9-@6BOoM~7H!|C7q+$ss? zz1hTEECJQ>3&EgJ!dK94Z#!ib#ALJ!PI|iNu2KcPN_O++#nw1xnLLDeR0$)Ll~7%` zpLDk$L^;H@yp9Lq!I0r6VQ&R9;(N@6qGucVjqZ+kCao0qRVa&%q+iY- zu?{ky6)-(BHE#I7q7D_|CG&j{a$&e)5Dkf@bwi^?ca7(U+B#P-ps=m2jSzdqp!^@ECO_ z`ATL8#jpF|-)A?Z8qOjaJ9O2V1cMTvh`zbBQ*k@^t!~Ng+;GHzv$Not?HayU#}Q-O z(x7|2shD=i65G1xK$Lze`$Sp1bG^$!*ciblB(-4qb*eFaZoqm80zPb$hrMg|a2?`w zMUBvhnXbuVcsCQA{M-uWwTH1k$_^NRZU&fNUd9y*1=772!wTz0>uWm%%zKsx_K}B~ zg*xExH>*Kc!-AjsSBDqQ4?xf9lUZXZbxLMxz_s16e9L6=YrPx`6JFN}g(tO;>FG-~ zoGbNF_?J8zD-XOAW34Rk>7qpF={}qt^fAK$xtY>it>Okx%=g;@!R`ITr9nlwRp%EZ z4!y~)E%L@2Tn!%Xo5ULjnd1EXabO+MDfHQDL46hg@0z!9zRm#;OqmHQZn%p_hM1sY z_jp+M9@u_jkp=%pOiPzF#Deoex362^`||aYhtw&rSJ4S&y~l&o%s^D49>I`JTbiyL zIbct9BVbd@*_|j?>`?cGThIJ?8~vtCa|5Jvz9mNkPE`a+Z?$T@J#gNTN_h8V7%v}g zi}H@u@cWS-yP;%+al9I2K34PDyv;-wjlnxe!Stf3D$2Q|CnkOTe!{!9}(x=ZhkUv^rfEe zBiV3j!Cb+0TM*cX?qWW7v-q~VMJV?E4QKO!H|a|7p1eHxUJYj1Rss037U8UG5udly z1pif9Lwpcv^^r<8O{UaK7f7r!1A31;rGk5s9bb`cfl1@CLD~O-Fnp*!7O?`jEF9oJ z<`m&S?_bi{p7MeEMhA}ouNO5uGFgHTttNm;wPRCBKP!yZwgJ5_Wi0EF9hSPrfLFQ; z-#dF6iVG^>lWe-cD-0oRcp6JK&*nEG-LUTHMle4-kdM1mjC=NW!ofXROlMahI_GJ^ zsDq_E)`#u_hbIEO9wcm#c-rWy2I4JsLk!ZHgLjt~z=|q!{@2U~?>jGtq=whS8Drpzh1j=pA+&ml(msSg3w3M)Tww!df z-}|3t73Kl`o9>DFa@J`2Arzhj0DCr+e9oH^q@J8Dt&Z5YsuV_;sEGbUDls$u6U;2W z!+KGUX~3{rsctj<7GVC1VbB!QC6riLWBM2!(0ty&kDdS=uiyk4$y3E;XX)=*eu>nF zvz_(_8{!0ZcLK@y^V>1FdtaQbW(2tr#dzoEZ!npd%{9C!_iaBM%2+O2H^m!U%q6gR zLC*>D+E(wWI?M{NIX zG3&W}b0LPg{{-#&QKEsOGdekpf_XPSvw%2n9PB88W9GX2+%00miq_!g*o)1(Nj;>$ z0wH)W(X)v4lzu!Fz?6$-3#g-NY8GgncVoNPkXL6|xs-vh6JG9>24&OD#G{mj z+}xB67P>1~(0{Z)G?hwcduPQ4%FF~*K zSxk9sfzK1>!m&-m*(gIZeEm0FdXs%~#tlbAYykaBvSLYXF?l0?!O8WvSWS&Lp1!Fp zo$bGFnc|`%b!e1y2`Y4FJnt#MN15&XT?O6l8zNv=oU=Hy$ecQ4=0J3;9SbF&Nf_PS zpZS#YPiMXH!{jY+$)`?YMY*tT6Mj+uvLk2LXlWR~I>roBOvtDGQ=NSx zPDm+MOMN&G#yMfZW<_Y=-z3eVJ2rnXg(IT|!~9?V`0hR3K|^(Tzk|m3YNa>SILWcR z-o_Yle<)=(U{Ty@#tH)M^TAdS!~OMYXWsJDcxbNH;#`0kH6Z z7IUP|3)kH`;D34*e@c6!`zagvwddyXKc+ z#0Y7AZY zx~=A@&@u<675E9u%gtbzeTI}#+{ch^rVcM5XqgKyP$@%`$$vm?M-KbDKNt-TYJmT? za^AAY3gh=^g7dt7f}W43jiHJkF6?KB=ZS4_nzDYQyT}uz#Q`# zMZ*HXCQ9~Lw{{!cZ?F{d`mA6{HrDugQ#R}@oW+fZZ?IrP4eSjl7Sx>{!<@Y!<(TnR z_SkrEIGpRBE1vQ)!?-`{P&qh+?Vj$751c1M@!wpYcEptQCSREF(p(6sx5S<)^B_jp z%9>pPa|-i7GFHL|shHtn(^9bPcp-dh)x{Gn6;geE%WXG&X0HUZ-8NGfuo5o+EF;xz zbZ`3Lj2-@Pcg_oOx`H|Wb&P{qwww6)Cysc$s|f6#D2uV?#3PDb1^ttA*!?Lc7)|fW zJB}fIBeTHRC34Vc`dLt2ZH*sK5cjy-PJX{1;?EVf(%C-GPl8*@fPHyJ_RnAaN(F`N&~F+ur*W?)uaFJw{ImHQ4KxT)F7<2oa7>4H+2zFdpDcuJ5tQGcAODmzDA zFzZeg!H0}>JfNWnl~;X(y_%!Nf6tw9`vwJwT=s>@ucdd2x;{*AAIo3V8RO+0rm)|z zCzB^l{>wifDH|bYmpxvXybQ|9Pl#jITHw#(47ghE&bAZN$#r8HoKwi>?J6Z``tt|u zJft8@)$EI(BQ7#^`p|c2r()Uzf2>*;2vr-s*@|}3Fry;C_s}Z7>9!A^ z^vH(g??LSL!5T|8Wjl+`+8A1)Bc1cB ziTnBvmxDrBo9Jp}iMrk9z~!dlEU>#79-Ea0X`OZa!gD)(leY#mJbQ^rNyT_1@H;pU zxy8~Arl4EYIMAPF#oZ1Yqlc_A^d0w0INi?@uT@%6H`X>T>w$RKb_)FW(owwejQmty zaj>F*=KK!Cyq>(>XmS5^nhLZf&BIgW875Z0p=x#gu@l%U_Sb?k;Zl0xvviS0LPM z(dP4s5pk;46Yg)5V^^|_@yekXSaIYMXD=P`PErxfKXFKm&;#tcR|#-%3iIqRL!*y1 zaQ107uNy(LbYMTYs;$lJFC+FR4#rr;)x4TInx9ok!1VLA<7SiraT!Xyte>md?@-cw zCM|?_9!dO{o*CxmrNPIGvxT;p5O6eWU~&1`e9H=Ag2jJ_P0hf6ezn8uNO{OzF^y?d zc;UlnQyAix$CIqhaocGNQ1?(1biOOte7~fNQLb8OM_K;!52^Dv(vd4h3HW$dHe6o# zSXi@DAGf{8g+Wsf@B@w|xa`yq81L~$yqRE!)4R!olS>Uh)x#Oj(0in1o^Mn0H7ndY zRRY~y%2{w6z0p*sLDvD|Pf|wgL_!?c?C}$R95jd38`7m(jq8O{Y<~Dcnx$I4v2zg!0j9@FKm8|M^QkG!0GgG94i3C(Xu7zS$HyH|2ZQNN~s0M3DP%Rp{(x zh%QH$g6!5NUOdqb>$_INp!HaD=+xx}B>8wqdAe~9zOT2L2{8f zWZB4)a{;%RCpa9c`)m@7EtT+SZZ8P< z_JT_+J@D*jcbIGYL`>AMNBN^+aB7S*`(s2N_{XvETYfWNu-*%YRhNU>dJVDVGsCyr zDxh;%4jVe!1oN`jz|u{@+?8^UCawb@>2{}Z;fgg1x?`bz;7-0|3*uS2jrM51AqB=PsN{tg0DJk87V(Hl61LZ(qVo^fab6RiwHBdg;}^K7mBmXg z*&x&pgz)}(tl^^(ZmR48x29mY`ZYxsu`jubtH$i@_T;M@O?!Itnkw2 ze1IML6z75JdJPurWr~j7ieQ7{dfsbA5jJ*whPq>;M6b)fIQr*E(0BaDx~n_jxX(JE zR-w*qDI+-Mx(U3V*^5<@R{X}r3z|GO^WFcvFzJ2YWqlyOsr}a=vWeb9%4! zD~F*+3%JR>68u0tq)8G*;k0#M6jq*-&iSqF_BeT>4qP7oRMb8u!N8@~Al$KF|4}E` z)m_n`JgJ7Kl1ciX(NdV0YASvpEoD$d7TC^6WBm?WV54IRv_?+j-*Z;u-=ZG)Zo*fg znX=pQBl}6`ykOvjbJTSq@y$}P|1x9T?`Z_H_fBQ^-`eAU#bMMzu#~TS1sJn2Njm2r zbVHmklLOm3jqo28!bk5s~{`et&E?Cqxiz6Py!xDeFTEOQ?+d2J2@Z{`Z zFgfQa&TJ$uS!yiwHne9)WGTvpTmm40yg83JC>%q!HJiFd^)wNB&~G?4b?-!3;GU3W_Yvb8|wI~ z93KpbSP6Yf75R_%=6G;NF_@?m?{uyaKCP_!Uv`PV?3#{OpJ~Fv=>CFCeKgi-MZsfV zGu}u%$%R!x&`WtJb2(~^qYa~^v%P^>&84dfVE(v6qERj2g^kp&(LRNRj3m*Uni$C>t+7Q7gY zG#2q|gDkPHdOEB%PY~W~hr)2VdMTswOHwJm3I73u4Q#oMyEm@*X#_5fd3?(wM{F*1 z0RKA^h3@N>Y@TK5q3nnWXwhkpt0?oeX_W)_C!S|fbSjkB+!i|8^)Ycrj&z zXKb{_??&oyb3}ikUf$W}0r_P|hwEZ=WGH%34slkcHrL+fK)2cyNGrWBOpB$r$g&jp zeXog2n#cn`a2@FF-XrGFjee!?S9rRhfoa+je|Uf*G#mX8^EDa%3LOWxZyB*T${|)B z^?{2Oa>sl=JE85}Ww7N)20L#e!6Ct!@Jch5_l+TMOl2t?K9wb;XFh=dc|oerlzY42 z;KZR2piv-BjAK`+u&;1~J+DoL(Gp8^(I;Nbk}XW` z5b-5$W=nlFzDF#vd{8MIzxrBeHrK;?w{ofWK2MdnE+zwEtzV7cSFVI-2lSHe?R8^) zaQ$g7xEJ?atV*D}-eF(p&|u7-bog~!XGu9`T01<@Z7b;m|Hg{`bjSG;TLG_Kav1+X zeIm!#KzvCEw_YYe-H~z-SoA|MG?(D3Ms=7Qy_5eQ>x%oXIm44%GsQ~Effmd8fJ3m{gT+cBn*Z>vz6#&Y{1~OE*N@R2ktBtuzyz_r2c2fA7ne?%UMI< zctjyfeC>~kAI#wOyeK}5`1V&H8G%mw4&lIfa~#>z3)FZkckCI9y?R%`E_#=}@FMJH zUN-!krOw)jqcYI12!d{|=hwy*)`UqAXZjNELUQ(^b@qrya-?#`SQH6W-92>kuJdioEf$ZC3E8P2~6cj(?^S{(r zu5$7_6WSG8#UWwlXgJ3hR>m2#;wSX|HJt__XXqx? z(+9T|rNgn4Oq@>ai-aYGaAap5bJe!Ou`i3^)xGIlTwIHB^Lyi=?VZADH-@;qFIcPY z4x+bD?{gAR?mvg^T;Pb0+^52Z70dZ5BPTp}V=-J@c+A>un}8cy zGoWhzA@=)w89wZK3e)Zv@IjOh()i|xS{rLvwx17DLJ>;0M)NdXdsNt=3HMop;Jiqi zb}9|&Z14Xw0>9l&0ofm~#8p>_NqB1ssDDsnKm5&bd%95+m}^0IVjFjyu|XbA zh1WJ&WJpkTk}7mhDPX;2s4rlpEBJH<@y;)X_&UK6TGt&AlxsAgVu>endRWKRhfl@$ z^J`%KZWX@Sh`7GPDq&hLJ@(Fuc!RZ7QZMD0jd8f*v^M!*hX{Y~2I5F7Ur>vhKzAi~ zjGGt*-Cm4lCdBu?S|2H$?Tha@OIh%#X3cqKCoo&32nqhc_cH;;QSPAx#(guEUNPvvVMPiiu`=UjndZj|l_^ z6mg&Z45w6E!J5MH!W&V^MmA^yF|8(`tf>>;y}cM3*E;d1wDTwhE`!y(Zwu|F2AG|a z4g2B_aG|*b2mks4fAijmk2)yRJ!1fLbFJl%)!fl=x*oinAJ}w?`Ydjqngm;oikRX) z(kKEA;ntJP{@H0%{eR2O6ZlMblWY+zkOJ@E>8R4(88E=oFWalkeW z(6%;b8_#>7dQvpRCMg~3Qnf^PgPAaL?R;W4QSbKNbg4cgqbWg$xKc2?lPzqS{)D_a z*8krRK8AL}hGFn$NQqcz8;08sSwn(SCOaD8hsW=GLW@Hlk0cMRs+%(uT9^vv^aee za@Jw6fV5?oXSO)bGZAc0uH|n9HW=If^NlT-WBbE3B)*>GUI~y-xhD&e5C}cLSoof>Topw zR}91b3i$QNQe5!$GkgqH6dHc@LB~*$&B|-zgQLm2zEJ}X&Uq%b)l#p@8B>@w!-DnG zbVc{zFc>kYnlJxCJyXQ9?d@bH=Js^OYcKPmGChwam(zd$uZ8g6&1w9&l{a+;?E=~7 zn}tF747U!If!C6~d=F{Vv&_|{b3XDb;@b{O`12y3{8uj6O*RZ(US7ddUb*6b{!75; zm}q^3F?73>4nbEBF{f#W3&)mA83iV9d<2+((u&*#N<1PykBl)?kKN99PnnKg zv`@w?h!r#GU2Lo{3##Ir*nS-ea0R`QQ@GMoL!4J{2Y12_2#d=!pw~+`=?-t8 z;*R@*3*oZoQ11E43(Gs`9@=isERU16bEs14t9iP|9^E43;E3{PiGH9L{u!(XLzfPL zC-PC4aw!x(audE{uP=J@8E`CEja3OIINUWHVjf-M&o))yD0WrKoDVr~jYsQ>A@I#) zc9fVKYwlOUk;_?p$8rl?albosj~UNI(mxl4szNWVD!w}|46}j*VeY)|$8D+vd|u!U z-|B0bEVDs{$OOo*N#Yjfrg&~#3QXNIOL%uD1YX!|mG*;QrkQ4$`4M)}XIgnGeMf@( z0Q)qRC3Xg2B;7j=u!yhg0vy%T624_?3GwHYY-)#SW8Hfld`0{6VB-a_>!TyTIGXNI zVN2kY-W?$#%>duIW`W<*1KiuR1nn|Efuhc9@zQQPoV-&OYRH3>nB$J0kLiHjk-(;r zq}e_J3z!jD$#NQ;@IqZEoS*5=oqg$B>^cjC?~?_?1NI;aIqb!`mHc0BIkBo*L3@iE zZ>KwTGId5=_%?~9?+hT0fdcF(E#c+C{-|g*2?m-g3kC+xHkWAE89Y%JKZkkZ)qm5# z%ua<*^Cb=ZaU>|mo)>zx8{)FcWN>}m#EnUx`FOhqmgVjfdl|mR+m}g`{Wbtrj-z|) zzrj#(;=6ct8N()d6?pQ@h=G?o)*XugJ@XOAx+htpQByQX&dg^bro)fTvw1H= z;;1hyg&O5t;fG!;O!{mo-R(aQ@WQAKLm>52u^96w1YJZ^uo{rgLQeZ&xP~iujmqVB z7Mh@8rlWMX|MpVAUBYa*>$rn$*0e#JOPSy(Bk-+v%yD^L0hHfq6H#wLo_E;LTrJQDb?^O^vB!sIqS>qiAz`Mji1@hZ~CpNy(jR zT=nuDY&IMR@#~B6S=)OUV4uY|l0Rzas6J3%pU2>!FG`B^;QEG0E>b>s&$$U8e`ULH zI@%m#cR0bXd98fujBuP^nhVLRH2JQJ=2(-p1VZvhu`+^dgv>60h5I(}MbrnkZ}A8C zaCEfj-a$Eq_95W&`!5@4LLE2qT9D97i_dy(g=gCgp{r+K7Wl~=H;#6O1iqOs3yi?e z1M=Wj@k6oCBNNOFr#)ew6I1sP@I7^O9y2ZE@!!ia_3l?#a#KmjQSOTyHy@R9Z(_9U zFpij=l~s>Lw@UikcxDV)hL&tkhzs=^hk)q5mNx}C;~=GExIfQK+;-X;WvWxbVPh%_ zooI!s?+R#Foz6=}+hOF#I?%OQD?GT*@Md;Tm_2JRf4wIGFV3-pLmpM)q|vr`SORN&s zzz~lg!k$3VZQ2Hde@YDZ+hv78x=JwM@J2!YrZ$@DsY$(*!3xA;vhW0z3#Uc>+1A+I zEgE`1rhgbg|NVs&X@}H|>2?@P4FBDBJ;jV{dLxY52m#3@><$mWWmZEWX|V}^wU_qW zk;7qxN~aJavBHc4lfW%@JHPnL37bC$!4DZvaYmOJUVjn}gPUyF8(RTy*HO3c_98BG z6|kFDDfDnGm#CkvM91Gh;pav@NbzyUwln=9&Z@R4VfbV$2{wTK9qZWRP9LnJzD}Qm zq5NnQ_59vNxG?B|aQ@LaFiLf1UT4?yzYBxVeZopO^mi1GCA~Ure;)X@sI!BcjL<4z zB`oY&&12u&;j*56sC&CZ(irZE)l3__4-ST?!YMe{!3P>Q=<{D=jB%KsExa2q%Wk0w zcI8fif!i)|hliCop!f>R`76si!^o>}rvw(B2xX^>3N|npYtvr%N~Jc}9yJ zp>A}?IcgAiX)Ql=#~!brCRQzFV_irCv_0t#%dXV0nGeWMC6@??$1Uc1zZ`I9NjALv zwp_S0AQ(b)HnD$QncVbgG3Hdihc*k~9dx6=Vk`qQ3nG~H&=@>M9-Hx(s`xSuAJj>7 zgm0l{LjOBTHcxMAqQPw){50PQH}sef7iK&02z#3O#}+};s5=5V8qi^IrgY{<3ndt5 z`T>SMeI-Vc-$tufAE`b++;20QeaM2H(L0+$PEa;8Q4iW~7cu&6;g%7>5U|6Ydylol z;Ya7d*z9m2Ta~zFx~c3P^+Fyw?25ACt08pc0G>>_8<%}G;Nd=r{bxje$<@Ol|Nlrj z?|3Z#FO1XPMNvqlG9qO2@Z6ts?7c_GCeqSSX{b;}HVsl)mG+*vKkdDDiBcLW?LB|z z`~3dBK!3MRN&p891-&xt+ch2NtpWHY}=btMjyeuWB)y{zJZ7e0ya2MSK# zL|?jP+;1EK8(S?|$6G&qb}J6te-5qJ4wm4T6EQF`ESZs%h;6&lVNuX@zJb1;(IG{k z=#(S8>3Br@h^6cfYk1Hd8-x46ikv)giem)!w=#!w?HO!Mos{Qf-3xtI z^n>C4n}sD?RZ#opPuAM!8GnA<15Y~JLGR%$V(uDOtfidD8hKCVLLBurw`dv1SpP5a z=(etabAv{T>vbwnZRBg(fgiH|DdrfweHH973+3%yqjB6<%4UWQWVVU|^(v}C{-qr} z;VN}F{&WGkz}e#16brof%@GDHnZyQv^h1^9OTp@BB_Ctqiy2l0@FBumdOLR=rbs%V zsdY58O)SEJBi_TkmQ23hLW+1)9+Gb^V}rf@@t~tV441}mbGmcw&>Ab_AqYj5Sg7p` z{mLHmzx5Fqdo&CB_R->3%c*xDZvj{ZsWI>6#KqOifxojW`J!J1`1WiE{3#nM?&;-$ zJ4$FKZ2ZcWk0mbpEN$@qrp@Q&OL4|a6WC(dllAIph4Z&KL+0g;yy{B~PV`y<2m3aQ zT{X?|q47L;a?qJ+t4c8{JRgoZ=knuwi*Ula_poisV4;3b4^&D!#1_nd&NmVVGF3|* zPI|S7x1nRz?iE<6nj8 z!TuPS-49}CCh*jM5`6ef2^2fk2>ms6vDeRG@ICb@KeYsK!($JS?{iwTs5C)#WjwTP z>(4SpV)>fShY5)_T$i4$^B%8*-t+s4)x8~Xj7k->JTG9=)`Vc~QANmDZ^?J2nd1+4 zMQGXmQ+VZXjYE1G!q*8~_$GP|HV0DAnuV9Rez_|SoH-lPMh3Dh4?sowTk`5!$R}r$ ztfgBB2Wv~DX>uNTp}gmRzP`rSHUieC4gvjxxvcb%AIjZu09E%e?l9XFZ~g)3S9wrK z4cCD_mToe>ncmbe6i2Ou1GU4r%0YVW-&_G+hc($bn$_FJmCAN|C;IyR?YjJb&Ql+~ z!zC@)qoM$3PR8N8oq^EzpBev2Irn~T9~NnkEbX`h`R<0n%8hGz(n>#6-Rl7D ze_u9i4D-gCyWtQ+{t!#@IWK=W4IFmOhN3}AoJ|(7zm}wob z>nrl1l{T1Q^@qus2eadE;;_Zj6284z&E0FQ@bPSYu(+=w6rWPDT`+4j-dLlH-o2== zaPv%9cfpz0)X;Oe`y5CdeoM&eVT8*brNh_U1Dro`q7JVbXqr|jF0^sL(AX|;A&FRU zwiD35U>uyjKd~{i#SWD_TY$lrHLOnE1@|da4l%`ps}Tr4Avp{_U-J>X*3x~Z+kAF9 zkeCc*C79jT1k;S%xw3*YrWe(Keu@>VHw?lDNdw?-Lm}5&;(_Onj)q$OA%e{i7hA1o z)>un9(TO=>c=+uU=zMbw_kL)F2mK>uIjILaCb%hR280}HAORj(^V3 zu&n|n_ljeyp9P{a8vqw~{u57N0M4NMol0+K*8VCUFLj>>Ve9qkkE#OxXpV=zI~KCf z)QR(b-(nbbHjz_I6CL^#LLc880WLfO@vAwg1+?>1weDyh)>G!I4DQVEqPhx9!Wg!F zZXmYCID?AI3jTA21?ITh!@^CL!a4d~>{5sX(Pkt2M_vnM+KmTC34G{ROAI@kP2DTc z1gnh(_~aaUW`6GCoqJF>caa=i?o=ThzN3P(K7W$U`9}kN@%uDe=(*^LxUoVYZoDg8 z%|s?42Keqy;Z&Se%OAgT!sUmT0i0GB=eyG9ZbJ@Owx_fCo6Ye^QmM>Wsi^LR=@&c0 zkiGJ(BvHVayUK91eFuN;L5%%o@Fpo$garBxm9IWUVyTM4)-_ZN$ZU(QZ#AeP-;EvOt5#g~?t zV)te(*=|4WA$c87+sWp9MPVdv@mmg&VOm^ct_$XtQCIu8F>HT2b%WMWUk2qI9~Tv3 zj`#{5H4PPSUiHNgo8GX>?+^Q&=ZTYuaZ&tKhiggbhKoAXgVUMaBmPX^0DCz9Z6ntv zR?jc@1aMbq5Lecd4z_0|7~XeccfDP3_({s!%CF=xG`G8dsUyzeU1@W251f&*PsTda zigrPj&BLI{yiI%|XNx!TjiK3E$_#9MFpd~IyFDv;Pz&|8bj%>ulcgAJ?2qe1^B~Ew zknJ5wJm(`hGTnZAxC6aAYykNiYlV_3z-z&O*w=S^xSNFw2GC6C>Xj|UF`I~b}*E~XCpLoD%ZDW)eh!MuBUy!*>iv@rMp zi&xvTrKIU?+S*sK<|ffIFc$nBw^wB;#}Gqb}B|2*Jx%~^4}8+oqf zgJAT40ZeI-C7yv~&^=wni>#ec`(-gi-s&RycBS6)uuAZlT*$271fc7VK5(Ykly8f5 z#gj9K!_k-IMI`3ck1b=NCS?l`dFY3+#Sw7rZm@W23VE>8D1Y(Yf%$j0MMqo;ZCXWq z)n-I<$_%>Xl}N+n%kT<$w?5Y!g7O2(we{@=lV4Xf%6ka->9vx~W7!z#k7MT90lOZ? zH>sK7(qT+?lRY~{8@AUuG4`&SYj29h2%k0Zw0aZ|Tp~rY`W0Y5M4Nq$u|S`UQn0+a zo)><#N5kdvaOBE+Y1>avyxo5kJg^x6&o+mlMJIPKO)}&^o6WG~HG@?)y_mPYIl4hG z3~{)`Ehf65|Kd!jsy-qXy_KNxooq<@8o;y;Sz@QvE1}XclXGq2x(CRC*;PZD`j z@2i1a*;?KsREj&D44^XfTEpzl5uk|(<5GBXwpI8uj%NPmG}&%Hx~+)b@7{p^ z<92cJS$njOmzUjY-`9mn1cFUuK7gKAXUoqBX2P^-w&!MclKiUVJWjCoB_# zVWOkA;CLa3GO`6M`+61ss8)&_CqIzsIgMK8I61uplxuWY_4*+Ea-lD=%L;i8F{D4H zjE2M|szN7A7uyzN^2VLlLzQU>XyKF$mpdDCpW)_MZWv5A;?u%}!zO4yb2`|lh}=oV z5mgn7;r^X1;^qrdoVc$HR4k*}t9PF0tkeT`4E!qoh#+2cFGa9DqtC*11)R9U8MMm! z)XPtmV4P1l6n>q})I1O^PcMPQ>(lrKi3M7yWkS~TG+~(8W0+HHCgWS)X1>^J+Y78r zi$v!V0ewa(L(|G=R$Li`C#j1$oNj+FldNdA*nxAbMEE(y5-+?Bg`__WQY#4}-Ks{tBR=E-J$nW-%%U;f1|_OB3D$g86K@pm#kC#%{G9p_uY zy|5maT)|Ky6xoW*V^Ofx5n^*MTwe|DL*oYymMz`*yc;l zc*}PxjCin`_a*)CXXawa9mJ$FTpaLNB<*G=F0+7Dl%vdf33tkt^VLsm@co3(Y)8~G zR@c=Z%jr4(9|OUJ@;k*ZN6Yw@`Gc)+79b4X{+J)x6M=SW8DN*I$?wk`kB4ZFx?W($ zo;zCO+@D#nM7M?y%_zc`uiD}G7IpFL-$VH0^i;U?gScj+ym5Ph1|%yGYw@ZX>Y8Z6 zahJ|)bCngE?m$^bNx$@9oD;DG4tw7akJ9bqki&FXt?tB(>gY~gn*&Oe-L}#5#hN>H zP+4+c`Y@#jdac|g%f|km<%|bAt3jyzQ&CgF0`o3wLe>;x);z)&udEG$^*1Yd9r+*L z4xR*^ZkmXJMFREU%!lcdm$LPggDag$Jrwj_qeVBM`X!C_oJ-!$C;N4l46Wkc@2V?#FvlHZxit9ZS=8do7JIKrGS6&2jQZ_%@eF+>XFXAP{t9I>*fJHNt-Cv>u+Gr@t)lUc zhZJ*S70Gk5g1xTyN44z$`kll1Vd}R{Z?%T5Ne2bD>zd$XWhe7nR@p?Nw6+BLyN%$! zAFT1y;B3%M(OE{Ux=`QUr=l$d|ok~&tFgNdadtEMiqJ;5c!Yg*0~w$L1K`@%MD z(PKtm?D3e_5ECSJ^JuxQa6T4Cz%nsQHWq-BUJ4KE5Ab1o?a_cV z7L%lP;@T2>y!+xeQ*Nx_Nq2*A>?hmG(E!j#3mz<+Zg zcTV)i?|K>(7*!RfR5{yTJz$0lwDj=MoKRHrjRmu}+C1l~9U5m(gb4Lpf<}u8nlw#; zH$6liJj4&9ew9JbWBbLiC#5)M)Ec_^KW8hZ3uAsi2Cqm{*{!xy z4{x-)(G^Tq7l?+`dC}c;5S-f=!+eE6ROn?Z^W=OYFRM?HC)|s165MrcaPjgms2#bP zsT)kdIo}H*Wl134T}jWEky-HT(Q{#sp&@3^%7vLdck_^iNbIcd?CGqv!kUXJ*wEa; z?9R0D5wxJ=c6IA-dJPT3HZ5J5oDFye)**caz_TSCo2WCiXJH2?eEtiX2lu8jO$_IY|75hy=)Cp zL*v-B65{ZGPlWZYt9ZKuu{!gqGx3YHw6)9ub4C@y)J|8J19>X^M!bX}lmWkLEg%=^ zdg#5Jji?O3WSYHN`mub=aZ|j1V3cgPKSR&K&2Io)dbje%;%H2bTn1aJwRwz|3*Jh~ zfU!Gu*p4O%PVvZsE4-R-IPHOdzt_V1mX^i=3lHI|{!?IX-~<@4z#IQrYJjqzF26d* z98V+N?HW6?>~bqq8G^UJ$u#(DqGKpn?)0x@yuH`=Rc7yp)qrYEF1gxo(sCvl7?yBO`I}hHEP^? z2W!qWv5WBmINYim*t|30ivq2&-%s)tT3N=I0d}p>v*ilC5Av-tyH+a5l57D#>=mypk(HbYDse7)n#2{ z>RTzk8!-UnO>{)SJsHb0$CWz%vVC61*$1Qbv*2Q(D6$b&xT0hkc!&D21GGyIF)Ie^oaMY9^}OUv zddHgV^jNzx@%#&vWOKepcRLI_qYs6)cN#RNTH$p~0Typ5W0hCz(5o;8W_Tv^p@*$; zsM~B<9GN7)Hx20nc4Gyn)F%wm;@T0>i;gdG zkG*-QtvTji_k)M$yo4K<%)z~Fs;qNxM9)&ZT6tUM$=Odiqp=IA`$Ia0I1Yj6)zl4o z{4C(b^geii7z>L_l!QNnU2F#%n4tM2J-m?;iplhMe*e5SS0pdcG|DMQ7n~AKDVkz) zP@-(kA4&GbAx*0x;paZ_{SN`R7p{heztL=0HZk{J$V0y07h>H=&?m4j?4Mx30`CxK zY$L+U3BBvPK4WOxB?7irEnr*dGwU&bJ{Ys9Jn69op5LAUDc#cr?M07a${1tVFu0vh zRPsja$DN>OZh;tK4k-Un0W7Ry85`zweb(58a9Z2d|a9QR0M)3zk5`6np9EHuAMLmBK2=du(%S5hlHO2A8I0@{M1t z@ofA{)>4|mWfpFiDrSL|EVwNxF<sjjJAH^ehv^W;7bqj~ZdOrBcb0~b< zsmn*#S>TOD8ZuwKk+}rFHrU7*2=!Cl@vqusNU%FCx{=Q<@BU;slJ3mjCj#EzkPU|) z=W+Rw-spFy2Gk$jk=j)Dz&D>a%l7$+BRtVDNd**!w~Gx(FMCf+U~Z!mI}{g)-rL5* z`%5)^*?GXAQDM;In1ML_lQsU+SPmnP#c<^en!~Hhpz2_mu)UQ0Hs3o~P{v*!^v?w+ zg(<`HbE)E+`@}b9BVe>$xNyHWDskzL)~W&+U)5E-8_sZMz$$3` zP5kltAXF&t0#=vIcv@O8rnPH;_U}PVG0_G~hik%?t6TW=Y)9-=>kPA2yNNwUh2xpa zsbKed605q)&~M)ySkSG2_x#0hI&m`39xjr0*4>1GS)DMduK@RExMQ>5FJ`R1uJHlo z%S`|Dm1*^J6@5sgw16HDf_YL3aT?<+V7S~N;ri;)#D}n9!MitbdF5yn!i!)f)8HqS z9PrHLU`EO%KJ=0=?#<4Gilbb-XG45l;|$pjZ%#cvEmqVkcPx`H>?2@wRXZzx zqswOYaKyKh27)kaEx!}ygeNHDzq{!{!%G7TyfvIMP1{zpjz}kbwl@~$XQuFLUextT zS)Mc9rV8us(vHA4uyH%GctKqes@-n`ioWmrSs7tPE)gR%6424oWpu7mc* zMbAe=RMsdVV6&QSiHAB$6vyJ$rOr6yZyXfQB=3#46qn7KMbGgEg5z%^ROy`xYbp-# zvDJ2Xd}kR{YgdQ^>GS?C@&l8`RPe*U;<0MiSa`K)X5->&>KQlEf*X}3OknXK;5W*JgkQW?l@Nfx?G3xXn#yu z(Fx9G=kuZ>$|mFwf=RIhg=9Au+t5kl&~la@o`@cg$99Ckd?!s#)MQlY;Q^U8#|4r0 z%tfOTK;Kp57w0>p@xTIDCD|sP83!2la}{hI9?Q<@(r5O?KelniH*wMVRpO^9?h_Ti^ZAzsHr7R(UHjX`6450ym~lL zHro%+3&Z^r^Qn(1h<_m##E*wX;AZw)n0Ubu9fpu+Mte6uP8#^LQLorr&9y?eaWvcO zp2%kV$H{IuF=(8OOTX>52^!0r!ojy@Y+H~7b18dUo>j|T9#5k^d=13cS&R3mGdKI@ za_9(J#wrTQhtRc9#-*1MSG>OUCmVUY8#^?Cx^mL{z&)>>e6u&{ih5&+Pa7e+?k5IL zqbUr#6w4C!I8jzB8qVdf;?$ImA8oS1`=_6@AkP7n$Xn=YcbScHEynBP+UU5K$;UA} z{C4{_`>`>by{0>?3ReT0@MvyhZ;mq?)L~51Rzdxl6{cOZlI`%5yL;gi$eD2w&5K)r^gAXVMKFX@w}+Cj{p9XA^j`qyEo?;I%alght-~h2)b-DuBxtABFd0=^1+JFRNT1&!^_tVyt{Wc++)@kR$41|Iq{C z)ugA~`X}*wv}~dGo-<-)jTF0({-5_snH4uk@Vf0(I5VM!t3PzZ)F%btV%=S|yXTDG zbt)iaTM<+6jKE(5x zmiVWykBm#)_R|Mf&_Q80Eeg!P@@&h0nxFQC()k7Ei9?Mi-*!_EZ3Q zO(S?GJ>r2}&45Qrn#^jc4W242hOr^lT%;0@hxwn_(wX0+Dd!#V=L}s)>_3zrC++Lt z1ao+_zZZKRPybDGZ0EI0{73mje7d+8+S9I!R`k7`4^D$0e!lFUrxa_)QQ!2VY~tAp zxVxi`eTdX!bt8PxWb+W%*SD6hu64r1-ecj`-vBH{J+_3VL4HZN51!6Bv9(6p=<|I*nGyXn4SgFi>GHN%6jy1P0k z?8xIwr`n)Z)JQO{9VN`CE|tr+< z@r2phUc%A-=Ah*p&kSB>a)pawcqyj>ekBj#3e)ZI%O_%SzcXQ@%EqHXuTF5$h1f5T zB5+CKC~&aR6ov+o_P$gfn?vKn60V&!#f&|1kQyTL zrt`$9IFtt`oVJOUL+EBLlz~y@Bz93V0C&Ip$G*JyE%w|+{$7V3a68+8UFkwMBXxgR z`F3c%y*2f-*d&3%qa4=fD#P{rXTkL6llhz%R;X*94xdJ62!VmE(2soJ|J_^t2K!<5 z+&|1@Zjq?;))Cj5DZsk6$t;=ffCIOg$uh9J$CAz#V+nJTt%R-Tt?;9VFW6_*GLlr$ zY;!XFI%LfcP>;{1e9Fcycr55?jl&sVvOvdiH{V|Gjr*&AGPP-&1x*!I{PpdzOq2O} z&jAA$>%zv;TcSesK{zj;0%{*Xx}WluHGT4+y6`I7^rRU5C$+(}VOiW@jvbEO z_ll{V%VxpPeQ>FT3X~p?;4ho${qC6ttXAADbP%Waki8X5Fly!9zj)$o`$TwMH-vX3 z9*eU>7C1SWu#0=m@!iKIke#`n`;4&1GmF-MV(!gGO=%t8sYr%I{cNs!(+1BT9x3xr z{w5!bZKIWpIc#0zhj9z1!;F^~#RYVa9=d2Ul-+Y>A&03$vtl{$#9aPsA>B+{tEu1Z zuC%l9Be-)djkV;~^Qcpv_~GL~@W^c!j}Vh;pn(c>>^5Xdll`$e+#8O{SM$FMeew0+ z$)Gh^5EogwpkL`iNb8-&vNqe`lQlXuw6Cr-}$c~f9y;yyM| zZ52whufr;fe4Zy~jZ2;t(EH#Q;rFyajGFL^Rehbr7so|mqLT(VA2=y|eXEO~uMCjw z>Y2a%(DZ{BtiF9$%=L{y>9a*(dDN6e4Y0=ER}$gl+#0@WH1QC}hWO1mOD7X0Uy3IG@tb1drDe>xS(YLPwL{KGTv|G8=fGa}nq{GZ(yJ zIJXX?4pzMknDbVXVSqLHxC%jaL=~4i?uv`IbucrFZ_?RbPB`Yi4h+*&=cmHV@zYad zNRsQtg2~4f{nMQqfG+XN+oJGQRUXX0d`V1e0Zd!B973W(*|ljl)E`j@KWUe^uv@^n znU7eUuO7QWj70UcevmY(f=^U+LJMLc7D^v9To^CGyo==1plsBkASYDa7!GZJ=J8IK z>`-zl8G1fR5neP!LhOeMnGVzQpcj6)wE?as_T;G(i8qzi$~xVdz;fUDU9V7dGdmNj#}?ffV}^6XQRQ!IqgmxPP_>gg)@+iJwg| zTg?@2@AMGz<0UZi=cNC4h&YAedtyg)e>0dTKPGPNkyYTMV#?ZrL-6mXe=I(xn0H@7 z{UALk@0qAb<<>5?eM?CblCi!th!yg!VEcjDHMVNfdcS zg)_eIk_%a{w~E&5q}ZD@{Ef3C*~Z7g*b?`TnH$M-TYBHWa-|FWovhE40{pSBi#M!w z9a?XhVuRzC`oh_SIjr=j9q#^{4DlzE_|~sxcwIgf0u7f6e~-7qmqYrpTk1bUUo?sS z%GR7J6eA?`%uVP6*K-n>yK)d7HaCai)ZJ#R&oCy-ni%X%SQ;q7!^6Cxu&I`93Uxsf zPTp@9JFa-a96NLt!ydU-!Exp|9DXJff&zB)BlSLb@#_cHX>gq|u1Xa@$2?&F@#NFH zIbdmTO<+kk#S~XNe6(8%2PF=yU%M3=-SmLNw`zELxGkO{&iR4RA>uOycN`Iy2Wgx0 z*}j1i^tQ-{W}`4(^MGNQaLvN6~oan-QnDto&1R&y|;GNgwH*q#5HP&;Zv>Q z)1cYx>JeA`AdczLmyYysmbPc-Gn3huC*?s|o#kfVQ2 zD(%)2?;Wg=amjRFP}kTg1ZWS3)S56QPvhaqzR<-2kB%h3JB5c+K zQRkTj&gm2j17hZ}tu#-3cc;PU4Y7Pcp#-Z32yts2gVb#qG&(y$HGW^ zUjyb9KD?y26pP7QtC#alxGNuw2gZG8k2X!=^RG~6sHqay;W!d3SH)#ZWQ76IQ)8k>#`)dA2IfT6T(*<;xFiCt=osP-XGRWizo}+9Qpy4XPUx$sT)q8`I0UFxVCZRI!{z@ z9sn8|Ygp7PAKZG{0NSJ>d`G$|M#mdKOThu*HrIrvDsz?@Sjq3N4@bSuIj{qU@v@KR zcsyevOi~}gM&{BTEwB(iU#;eStz5C6^9xoml!?y5_1JvJ8 zW$7m^&~bsQY(KxZH5dmG+x&~~X^~&I!$rhzjF=nFy2sFNJi7pjZ)fr2ZSE*f-DScb z3pRg}6VAQX8!D(f+o;4H!~JyOo#Nw$q4dnH*k&s8$?S}B!8>#-&2?MAM`Spn->5n8 zaNr`Ld@JP!`mU8}FYZT+F=WmonD+$vnrhO}lAD?G=x~D1*nTT;9(#0H>uH zLF^Mtp>&v+ZM~W^)cpeFgyWQeP+aw5vIg9&TE*g3191OS50FHU=lkT% zuxN%8e9!R^j%8Vb`{h`+VpcX+P720P{a3+MRVDt9-hXvcOQEQr3EM>;2D8)O*}G#! z9Lf?oB^@5AjMsc@BGqk7FwAr(h!hIVv{CqG{ zHrtauNh@Bz0z~cY;uK?g|MDt;t_#9ht49bXZ~wuBD0!YqT$*coo#5jHeReB73X5BV zq40rb{nSWX>>#dSVe29$S!jz-N6i4WZPR!Qc`Cxm4_uqGL0hQ`ne=@z|*z;8fO1-bXDEw={WzvqGRSkviZEL%n79(`hv> z7};q)q>i`a%c+-V-df`AJZlvmH;zN~Rm&kGb~jh-9fd9Cf0(hue&OvTRkW$S&Hn3$ zvU^~MXUsI9Z}%JGZP5m!R+z%XWP$D6V2z0{++nl9MxNjmhBYc#@XbYEJZ@)$k{?T8 z<;-+8Sd-qb&*nnnuL=AL`P`Oew#a6CxieruYZn-Kb0;_6K+oLABjBEDgt)QR5ev0}R0j@cLr!`)Z&yIrXh``mmew|ACaau2|qUd0f6{UPgARDxXwKY|mO#hqgS zC%n1K6sKmgf5cB)lcNAnLL+(SdIt<-=6@iu$ADMM0u zXZG|5G5M2>WwZUpIqEDv5(i%87sUED3mkGH3T|$6W?2^)0%a}#W7JHw_Cwbt8({JC zd(stIJ+R7d4U3aJW2mQNQkgm^bx4?-)D~Y~w1kCiC4Bm3C(QUe z9!wle#hxxc=&HE{0>|aCd!+lNk0Oup@pw*^Z8*)Z5H6fuDV!jNkB{^|vv%0W1MYbs zg!Kh6b*cFEiyg5|M!@2w(^>9DZ+x`G5juP__$}wD=tl1;>}ZosE@hK-|0aOu<^3#r zOa#twSOaI@_;REi!BR!)(hB_`eC$Tt^~>*AdSoJZRP@3Jru|@B$v(l=QxE@Y^pVZ> zl@o~F6gD)!^u+t^E05+E){$@OX}!n75L;6+#?f z>pX#Njt<1b_UWK9asyY$2OJ)g4ohYhNnZt3P#*s^ls+^9iQ6tLTx3UGjon1sUx4+Q zU0|6!<>(cBaoAlw*=#SEZ;CVa>&f!1PM{61&X~#at=%U@VA#bhnFl_aI*hh_SO9L( z8qBkRwB_6Ruy$=VPYUzEhHlT8lh#jZBK5e%{?!DH6T|uHL8QGuHG%lM{aDIyOSDm^ z{>rYGxp`+VR7_h0m2>LFPj~FG&}%uAg+{R2r&3f@B5g{{<|6`Kaqy;Awy@lcUF+_I zrn`DT$6eCZy#w*Jw;{-tylUu2of>tS#<1{CIXl(rg3*bgaAU^;oC$+x*>zvIu5E$?7tMwfuMTicLt>H# ztb~U_>%@1r9dV=BESv4GgMDz@>Hg5}64F?Xfc_5Zpdnewru7Iw-5sv5RbxCqC#7Bb zmp#0w@DSvdn!y-{aF*34lN%ll!3V-hxOGK|-zc`imA6*FxUssdwv3p;N$*+E#6tcj zgE*Nc{ULt6itu)%t8HwECYIOfp>|aq2F?wEs*48vwxS6JRNBJSJI92$b!PZBJ{*p% z75VDf9+*Ea7sgcX6uZ-VQg^cc;5y+CeWk8J)czq>Lr0kMoyCK9Mv=nlQlm9C#90t>8b9fgw zG+s9k6zAFVx531ar)LM(Y89?Ej6zHAE72N{d5m7vZ8R~d7%{lZkdP*wyzM@Yn9;D*0;<-n>3dF&^7 zj~`l5@4&=xK2x21w(lRZ%oTF1bOxZom@eS;ekZ@#+YxWc6O8;ul=wY}-oHxpz?go9 zG2^{3B_s;&++54|EJ;Kax~aV#I#IeoLixl?OX0`EQ|z=U@%isI%koVrhlqW8E*_F#w^}3F-hR7p0=k+lgzh_ZxhRpMT75j6 zs8VMarc3brlvLPnSjE5A+v6;0DQpS3*?1!;828#Lf%emJ{OJ#Ke7i#lV$wUabHwoJ z>Te8pDmU>??-(YPdsEKzu=w5F1?MKrfgVdjS&u=~Q`|ot5?j$J*_{y|TO zd%i@3VB$V~843-nrm-%Ieesiy1N4br#>b7Y#=#}d@K$|?&HWh?e4P>n4}R}v@fxe~ zv_y~|+l3}sPg;ac>*`vQ{2KV}|B zqp|zMuk2B&z)KT?Fz62L)q@AJDpdhB_z)OyU@LEn3&a)IoMG>q5b>57@%@%LLhfK& z_Tiipeq1{PqDE1+ojfxVr8KZeEt0MrzMk0lui?Zd6R^_v!@R}M*xAQbjdGu*7&qe| zyR~Npn|aS4pLe0z{(S;ZAx-Q?=os1F{z_L9uJtrxpXY7h1tsNp=-p8`?-t6Fc3GiT z+I+Y=d?f2sMek6Nc@R9inwuwj;#uFvjC=l)8V(>&sm>_bY`@zi#l^RbV2@XS*5+o3 zjX4go+1|Pr@c>JtKJH!OK=R4#aGC=K&plaj0)0HFuQo1*-ute(;{Ak&tl@(hb6-jC zq|3WP-NdzA^GPIj-eU^M-@Y_-&16^+YXVzetYeZ=7wo4n9##&Z4&R@Mn^z@*)~Pwd z!6lL4khGeS+nQgbyTk1p%=p=PMH zuzsnot@i%m*lCY7o}cQ0GmIwCv)+w&nk3*Fhl#Q-?^lK<__T3`Y;VsQHy-QstDs}j zHc^TA9)79ey$}PP>Nu?D8K)-dNo!TUn1_k7nl2Ih2OU3fLEX{TWdBR4}N>a{>wBiDfPxL zLLXRKtRjg0JZ-lZYGP!w0j7MQ{sQt+%6dQ^8ROWa4E&Og2@_h((BK1gPj46b)Ds@K z>S7KA?${}YykTgeTmU+*(d_fc5PaCbgRRw;=e`H5apjcX%v!;a9bhE(*&0FWr(X5P z+Rah3zdfv)J&pNj62Isl`6a$hmY;qCz6xVtb#XgC`Ns!On6)vt z$;7A`FU8=>zij8v2xcIJ;$@w2kUu4l8-`h7BmMk4ce4_dDTn@4!v`J=-_9=6``X6% zxzPW#1Mf~8W=-m`Iy|sdxTtA_I*J)GO~&2B54U!I!kSdK2%9oh(OL7dOk;07;e-mO zhQX#cx5at;%uyqK3`7sGWN#KxZqd?Frm=UO?1GcU8L}?#@P7h+X9FoRVw&@_L3UkCEr5!V%R6kP+FsE0I*fB)``7ZdKV(7-&V z@+|;&9O?`CNip2WR*LsWE5oKUyM^AQ`5*0}FVomx1<%GAJC=gsbQ3;|JV>V#Ccw&P zLs%ZYYnZF0fZV!DzJR<^aB3xN_;j!FTSE};Z0H9W6Aig-7fT%YKmn{&y0G!LNh^Lx zKl8>-d^34(}J4#1kKc@ITmGj8>l_4>($ zOYqaKaIknkpG8&+#Pd&uxgl|U`5rI)=~xDaa@E2-i5+)ZEYOjM{p+3r2g5{lReR*&&Y}V%XmPS$$!|db(@4fTlH{UVRtaP`IK*q zcf^|h7BDXOyx91}3|k{WmSd{4w!+{3VQ_$+p(&-#=yhWmJh$&6R&BDvZ1S#5IK7Oy zOpn4VFW$1glcc*P}jSf*O`yUVI!Zh*n-YNB=x0cz8wYiW~2C)cyo+%*8#)Qo-9Av5_b==lg)FR z1BjE8k zO!#@}q>)nJ&G^6a{J;0R)zh!Ax7rcR>t-MZW%Pv!{qlI2)ojwK04@dj2|0#_wx%^2 zShI(`rCU7lc}WQIuiW{d5bD%!j)19_cLlp56KpG=F5A_$bwcrILlxxY?GSBbW z26Z*B<3JkkgbVVrdEWZj2K!qo$^4D6(*y8Ahdo>|8c!V21iX+q2h?As3j>49Vd&#v znU6jHa1^?(Sp_bFDu3)j*;`2tbn(+;(w-A=tYJIrW>dnioC!w>X^+P5MhUT^k8N_b zCaOF(!lnN1sGDg6BV5&Zad#8U4Ux*`dFW8Oca#M~WP`{LPYJ|#{R&8DJ|K28r+ekD zESRbm!g_xU#nsB~?3->U{>Ke*!M49l#lV!AXi70P!vJbe^{PMJVS-&f1*i#4WFCQz zIQ`EQu&JKOrQX)~=zR*@56uv~_dS8v!~*@#12Zec4-0=iVtKAb;>2YFI&}WU8iXiT zXfgrUx9P*(k9nN!wZsjRbfKq(r4Y24dY1%S==`{fHImQa&1AawO>pG6n%KENX2aHw z$HGNJBTPJ*Cfn7SrXLzKH?gPB>x9+QRMCIcIaa&4jX&Syj6Q`!p-=rCar8Y4JlmoT zdJ0x7)Qxspi5+AY)bPRTKG^p%Juj?Bi3e{=@kG=D2pg2aw$VIaP@4@`)Wi9n34W+_ zp@|uN@4?Is5Kq+nWK#lnaZdwRw5U)AyP*@sZNcWqBDCOTLmadG?1TMVLSfv*b$oXl z!&58N>vY=;2_XgH`-DiR`D2 zIpPLi$qc|}-W70fO+{sF#9P}t0OrScWy2rR_c&ZnwySr<+u|xW zH+V4qsCdlR2CW;ysVmu?*$uYEc9$j4_e~yuI1@1YN-k_{IwftEJR*i7ar;Kr^OK7_ z(Mq8!OwM~L9-K>^>A3@7TdpbNhXZhBUt8Lvs`<{NzPPL*6drJ?c)Abu4{n(Nr`9ZB z|9NXCwJd;Bi{tq24~|$M6j2dVxllC24t+*keC?E-7;AeKAyuHn9Nfv7qx53YUgBR+Q~pV;SO*m}Q^bsrLiXS80j%{`@D zGj%Gi>8%2qe>7Ovg#z~7IuIJKZ{>j|_V{(QF-++0EP8o6V<)dEkSi(WOH~lvwxzw=KV)v=kj0Sz93EZrw8LCE( zhNi^_giZa%z*6UNvMlO|%h5Rc>@ql(H-h(hO_}#a8E~PSAsb5U%HdmbV6aCuk0H-w zYb2PpZ2vMJ}2}{qI;Qk@h1xebAQ=>P!k}q!B;Em$Ui;k$${jzMHpHJ9| zGpa(tD{4>UdFmN#@2v>?-xjgul0ZyMw*|AC<9XL!)RX>DfMrTv!k8Fqkn|6e-AuQf ziA9Hpq^oNUytgk4ZuHS(M}xz0w(m2hcBqtJ5WI1vaW|Nyts#+s3HA;SBa zke+3PPb!wmJTU2}ywTkIE*tw}lc2dt6{q@~mF?#$8I%*T7z!K9?}~}UPa7Lz11C;; zvrKJkOwhKIX)n=sj(Gg(Bv`gzRoq0QWZ3sb@aF9@_SS?rSMk}9KQEjw>Slff3UC(yZBFgC!C$4O5Va~ab>AF4nC_1YCq!GaBb>gnNMQ*k{aIaj}#k6 zM1pFQmGs9$b2QVN0U4_rn4IHUR6Ozo#+}aRV}o4KcJo!%lAgy7h6m#B(Y;{gff(-I zC}7>gfpAQIui&R^jo03fk!df3Ohd7j{O8lpjo@81OwnkuKZLDPVs(iU{P-YQwx90} z55mC)g^-klN~t7KqP?E`oYUTW@1bE!DU{KU zL`E4=R%R&K>HZ>{>|~FGjEvVF@%wsy|H1p_e$IXF>s;68S~`Y}bLR|-t@2pg-UHmV zZRqih(VQo+jTw*NoV|D#d^Pl__~HkU{G3>fIqMCYu0Ug)GjVE55o>!aP*i9U))_TQ zN^U;Je)FTH9+Bw%4)2-22Vm z_2S&20@2vefv$H^#sk4K;Dn(MH9WM!Gm>1^eVT+E4%lMu*}XPZZB|sUH3aP+*MPcX z1l=+&!Pv3h?E5rp{u~zIq6eP@$%_EeTXY+K9Z6z?IPdGTS1-)FdQ?y=8$*W*x=B5a zuX$d+eZMKz556KMaKFKQB`fT!B@d~7)>NVsD%I7)w{wp{OEDfZk{54pwV~VAh4^$; z0hk_-qRNCPV0z7(g%9x{9qX=WeyuMYI4+QcGg>CT+r>QYb9|1z0Y1!d5WV*D+v0nY zvful6@{H=SMEo{nB{So^^wy}Ec=vjd`XI?xI9(5t7pX9QgGZ79Ollu15CZB_sy&DWwRx$eeFp9 zRsV#4+ROD{Ui8jf9TR&#JAP8rkq&f@L$hz2;mcMyjpD zbIW#!C$*et+Oc!c*|~xJIq61|$PN722o!vASf= z09++OlT2^nz+-cqG&~Swxn2}?Hz71s3~|K=@UjP9b9QT zzf+4kO7*%LrZjG}6_#a8hLsQPD01)w?4>@PY1B%nNs^8x^?Aa(y=^#tB==Npf6aDI z@}t_mx8NUJz=nIvWeDq}sGxxH$L-w{M^lVxyAA47InhId(p_vKoF z44f*np*1uTQ@U?w4(FVx@vAE;=rXaeUZ8GQ!ti$=F9=pe%IYy2PmWx|I){W%_AH046n^hz1ZyiI|9J)w% z_0d<|==MNk%nH6D8szaj!UHojUeh0Tt6I_4SA5Q-Y+_@&xYA;-dp~78MBAQRo_w;1 z=VTXizH}5}uY2(MfHf;9@}fQ){=&c{IcVcd`&Xy><2m2mtVYw8{;uHPU+W!2V#Z{t zWQLz=tf7$K^sZ#Y;?kVuEV`9YtP2(=Ifb7r8{*_Jty7UV+L%eh>$thF(`-i<-V-zt=jlBq#tb9 zZ%HAlHaPKi6WhX>1OAH1Sor0*c;OKD+4@b!0Xm*As*f$bT)P0#4V!I>nD+fR zs_ruygU;IvpWa5;w*2A!a|J0B@XC|&*7%^}V0V`IhIcjo=Y>tyMW(W&-!(?F)fPoXc_DC61;=u0Y9o752G{8};wH9B=%zfDI2K z>4nK%ud@pwntHG=aB9F$qAtqIQ>n@RIWC;5%+t(Px;l4Goq z-you{Wnp>fE^+iM&O|cI!~YsWA#Gh0z3aHkyO?^g3jW(s8qfjm8piMM!t|otc(7_HCI2Eo&UeN<9uA{GP$g4p`DzgXy^DOtugi+lIrmw6R3)HP1l#Qfqt@ zIP5JE{R16neVhx!iTPCTcC5Hx6pHa40$h_fEGSy;VGY8 zV_!@{)@aY3FNq?fugh@UoZfKX$%tmv%$LsdHCA5at9uq=i>ri{OodJys)wSi^E6as;>YWc?Nk@uni85;#xNm>05{6?+MDHksfE~zMP6{m9yYz zk`3+JkcU}6BACuCKg!07aAL45>_J-^7xo6`%G9twpIpd)w-VaL$BR|`8Lr%|j<B!EuF+L1PRD(ZH!`#M2)fX`9y>JNHY9QuTvlE;>~3VpPT5=0&U?M_QF0cLz?CCqP^$g#Qxt~E}o(W(-ADUTdg5HxW*w4p~w2^yMzOOM7?}9t^-kXRH zp9&%F2+|&yh4Zf_uxDKN^KRjNtPRVAh*aKF`SK`uc^_b~`McET@N!-JHa9-hu0qX^Q>!OTe)k&kXjM zh26s|*}ZEvbkJ!AhHfjC`~@3w`JIc87T=?jdiYSw#i>}i_qdog#**5%OvcT7y}|X2gxuuwQLmzqrSje={VS*7vx5cPed0)m z={ANZ(BqFdD`P zb-g2PAMm`cn3h6Iwt7D+7NM3;`n;=sZb)^DsO8Ev18w<%kAyrd0hq-sjNE-8h6G*16K4A5IHjuh;vxAI%~ zv>*{md;;jQni}sNSj66$2~-y{0&fhL2*Lc$bvGga2Z{BdJl})5aW>S2Z4T@c|E^ro zHXX~`p9`4_jp(FNrgVmHT*+^F{M$U_N|kW)whA3}JO)SiwlUrPp488Nu$14vTHAyM zRq;-%hx``6?`172Ht6wfD|=;}K;xEWX zt7%2whWnvyAuqAw>~{m+-8TI1DQH+$N;Y0MF~7?qw)UDI-M{_^(l$mjS?gG8UZ#WT zhi(WrIA8r%m=;!Fc*<})_s=`H^FFviY&2)GZ9h5*Kk<9YBx`GGw3{Z~!{?~Gk=wjw zc)8?GgO*1yT~zJH_eMkZdVoNgL;7O2d~aCYO+qeS|DW5VINxkWhzt5%J0ULjHYM2Q zfyJfvaBh!1Il0Wm2)AXdsTpWnZUJsjZj`LL)ti48XMmi{bM}>YlIs5b38{J?#3@SF z6mQlO8+V&P75|O=vK)`ae>Sl5qx?xy;f+ti1+izQE5&S#MZL`h;8F;*(jAxW$7+!Ylu?5-V!UoXUqHcOypcoc=+x(t&Ptl4#22a4JI60B@{ z!p=85&~Hwm1^y^PI#LOHAozt`Qmv61ec%g>!dfQ1kjKR@>=J54j(; zcSV`xLLbgxuU~D#^JBK zvU8){Y1gEBco97jPWgs$-)t8QtXRg9bK|Ior8bhpUReLfm-^1}!ibYztY;j*A!@p# zdD=ChkD@6RZ;iv7iHF$NYy9t4R)qPmK~y^J#4|OA;a~4kR+KAE-q!(NjeHx%a~5vS zZdn{)y9!36`19^06Fe5dJuTK@v|&XMw(6z}6Hbl8;${bk;JN09QzFUmI`>p)4Q577 z7PNI}7H;^d3l_fNbcOGP1*$9A5e;kDlVG8vV7sNl2Si`l0Rd%EtZizPekgca&G zbmFH44jEVl%X@I|aaugOb#Y)VOE~jq*>s$v-7Yw^7?IoKIXJPVhPCi)zRc!h5VNjI zNbRjk3TAauojg(1o5Df{;?~~}MS=I9MrjPe^a@jG-^n|J>dZ0y)mC;rD2Vc3O+y*d z6`QzLGks?~hV#OaQTm)YJT8YDOC#9@&Lf@JeiXLdk%6zDZ7F8ZQ!toY!>;7H(lwCB z#uM>kvA!9pv<|^vTPA=?MmWXg2J$|>t!&X_D=Ibg!bhJ>B`I(D&G*+-)Ogeg+Pfn- z(_<}mZgORkcQB6qn)|9hvqI8B^ghkWrN#)qM|6POjsA&2;uq!ri zH)W6S0R>O(CFQQ`q)2G`A$62b*v?{OylM7ySIl^LR*ZdWN=eZ!c>1nAoV{jC)rB)r zen&CWSR|oL3+`9kb3!6#D@!Ozm3D2Mm>Ec0PJDr!#~;KZb?!&f?uJKp89^)muFtqP z9^H8V^2rc>yU_+b{&t+Wc@gJUjrGO}ftiq)&9ji+GcXYn+5AR6C+BCP&HQ5F4d*G1 z_T2~iM-DK*>%nv~{X0}P6^ON)9BI*(zNj}p8GbAbpqCOOOf1P~>BdBc>ejeybFB@h z4pG$nK)kJX7^YaQCrOV}I5uDf)2TA29|z~*^^+Zf{-SW+n{XQXFPYA|_V=N{74KnN z)&ZgM>==5O`w{jJdd6y>*i$L*l-&6AtoVlay`H(mJu@$c!|I7vRMhN&Zjwzb;D!%{ zxn$#i(_}?Sr~`fUEyUsx#cJz*Wnt5 zLkU%~dVVjSeQ*jc?lPEZ{p)*O6^nD_)FHsyiW0Xj#36bW?Bug3@-aFGmaV;n1<$?c z?MOvr*R)tJ_rm?WH5iMFdV>k~niecIkHtAovFoydZ}cTS4s?BI(;>eWjd^D=)Qf9D0Hbyx#GJY5gn z^}R@An=@KkEM(u(oat~#1fH~>C!FE^=U&#u(yVB^dIWVB*P!9d0gPvQX#Uv4kY+a- zns0>D*Z!TLQc%J=M%Yv9Gg<62P*0E_7-bvC|3CW)skDGUpZ@-ym|f<>^!i%RdviBD zGxCPuy26y==EY#=!9z@QHqUKUF2z)r&0;^k54*8isg|PP?M~x4Z^TB`zrnf`>1%8+ z++Vv2PVDlbmz=9VJkgJJ?=z7q>te70as+$M5&UBB0%Bo4=Zr;BYCGqa+#bwSr|>&b zc^)dSGla2mynCIUg|Z=~?9Yin@=*B-m3hO2h5!%hKV=LGfvQY!H>O_O4WxVc%~R$i z-|i}%=WlqR58dh)p4G$x8s*UrPgqs-t+(hb@fsAk~mJpm|+@7suVG zL3uPDy`WTok9$o+<{RPtv(q4ke-mxG5{+Ri(%Ba$e!Co!fbaWc3+p@EaKC}Nv{R%0 zz7NehbPR%?FB4buUVy$AAHtA<6JR`Nt?Qjp=Dp{Om;%rKKPgketQK?O;CT<;-RXp{ zCLaI=&haq68imJJ+A{m=W|S)%hX>|768e2GA{Eng=^oym5JAhWPD1^z8o{-%D&6S0 zPr8RIOy}MSbw%77_(Z(57ic-ZeeB^<`Gzgl6sKS!^(DSr8%}T5BxBmxG2*-^YbySc zfT`J8@L#Av&TF%=DlLjlF7cv^_Yc5T{hqL&dnSkex(|(oHSF%EU<#P0j4yxA5_7`s zXb5OxgUl>=Iga1=&8#r)W(f;5kx*AfFMK0sA<@*~_o?%VxaIl@(AgV7pS!HVw27|F zZ$%4r7Fgq(QG;=}56@Nkf0WMi9{${C`&9;CG}Z|x4%?94MpgXJvy~O!@uk;2U2%2m zP_~S}PcKXg#i~~$pl~wZ6=^7cy1%h?BYZ< zAGx2(&PbfrMWE@*UU+A~d^mNQX#S0_A~b}eU4@)8P2HNl{oJvP5N=WW1EH?IBG zK!n_So`YbxzsCyZGtQhwL~zFM^S44nYXp5wW$^dy40iR5Hzloo1=|e{2+fB2)DqVL z|9UhIZE>Kbc3N1Hb58Wt^rUoVkM|t3Ky!%=ZC~gi&5F)z_M-cP7I6M#FVQWS&us_J zd0SEf8dsv|tJ+DJG2fbPGjpWN=O04W*`9Ea=hO8z^+4U$-R!WxJ>`wl#8-AsqRdzc zRWCO|+sF2xeZ!edo`#}k{YsYk2k8CQ$>_3TnWTCj(9q6oG~U(%kQGXLi;qLk_uCo@ zRwFH*-vZrbi($qdKYGABvrcRZWeU+i|EUkd{H{#c|5yiK`KrU{K9%g-ssOrjfp`CT zDzh*A*1Xa*2LD`ChubeKDM)cX&z@}H{`^2vWJh4;i>|_3yB%C_PsBrYIZO-8DPyKG z4$qW@88@t`#K#E###~`LRe<{P{&b)0-Qt$jZlw8i4t_Z>0cv>{-kaCFTXXJW7FBni zf(;C?Ex8U744r93=VRF0S&pl=*(?IU;%1m~{NBKT1{hk@MyE&oVx@*G4&3yNJ z$9ss%4zajBZgg>M5&mhf6z%#tlgs*QsGd;4);4+2CC3-AtvH~;REub$mJH_hE``d+ zKJ?U6UwZdEnrw#RT}SB*zm^_JU-Al3LmTW_d&n(2c*3r=NC!A-cMKGATl9iwI zBHOff@b?)a1oIA{VF4rY@Tj4zd8{ezdasWgmY)ku6{MVJ}%Cj^7|N~ z>BOnvbDx{ThVtI4lr%QOPC{Q@ldz^PSD1#+@xTr>=?w2%QA>%oLs2sCleoZ$@3gLW zVY@g18s`MlYRf@Vrmk{_CGDshf=ALUgxEE~RCe4GMb-d@qdaI}d6ZNSmskiiiSv^+ z;H6+U!kET1r%Gq|BAF;^oqhs}-q#A+-BhV-@*b%kKIe2inZ~K(&F7!Rm7K-8Fm)sb zXt;qmfagQAjB%CeR+g(CPIq5TN7WOf#lh}Gal%x*SDXh47C>uuXJct>G^@MhO>^}Q z!2ZuYVYCV78%(+fp{r}y@^1cAq@#%A0%nLx+<(>Ulq#NhHWiw3dCqjYA3BV#Vlrx0 zH2IDzzU(xSsI9T2ffwWO=m-%!wwBR_r%hP5U=gdIdxuV5v_iA8kY zne2L^_%s=O{kKjyU&4D{uJLXre&6&u=tGTq&iFuPC{x$rw~1hTJby$9Xcf4Q@tpbjs`xtnY5YV`fzY!?e$^-YvEdX`y zRj3*{1A`r>u(C_$RPH|;hkPv-oVGg9i_cr3&+vn+g7-hF4}A^I0r}#4-a(VcZxCOO z=YiF`5Yjwph-G@bPmSwNOG?M#)68m{Y2}VoGcN#x9vy?z1J=`|(G584$#V8ukMqjr zrlWi5TVZ?v_p}^40tGfR*s90gwC(gW=?qtL)u-}R?a~=;#cxc0Lp88_w{xQERsM|@ zX@uQ92EnKfYs%{8$~kPCSu5}CKDBf{es+)*HyQa-T9>8x<7X+XD~_ZU>?lCA70c9d zrdgb@|BsihvlZ#Tp4~WmYB#&}gL{>CYT(t2&f=-_lPP*-1X_%l1!Z%*=!Z-cMrN#G z2?hd<$w|P|@=GQAuOUC6W^*pV9dL6`plGubaOcUshDlqU>G8#TFz~?&xXM|be}i}z zs(Bb&&)MuB!}&8cu3qRouY+lqRN?H63buI7bSgc&5Z9%SVo|z@)Tz7#i*7o>FEty| z8a*FJ$5pa|o?&#S=@8^J_Yjz-7hS*77ccbGVyjEcNu`exnr)N?gV(&TcAFtC@xH=F zaeZu0s|WV2-!1-p9zne_@-e&X9PnK#P=5VF{8LcKe(mt53-fBhNMKrTvQh8$M4s}KDc1(qbWkZV=QWF zEdu551?+*Y8?6!+;qQbVEZy%s%{0=*{tazlXc@u5sUP9awh}gs&vv82zS#5kc;Ue` zAKS(kqp0}z1X^$GPrW8NVeC|I=4fP0+8dGILoW-f6nWoAO*m5XAvS$V86B5g!qhi! z#LJyd^zrpJsm9`E$329R|3O(^LWA-*Um73ZA7TGy$mAa2WD|YV`WwjB*;&%6p<^*H z*jwm&-W+cgJ4k)zIhyN8tD0#fGPOavteZ z*yJ`?7%<&~RQBj#>v&ZL4yM!`JQ~+7JSn^hwxD%-j?#HvpyWt#gJ)pM{B2^Gu?gAE zNx_F&zA(SXe%@cHB%S9gOx_dybt2dRcj>0leCw6X^K-#K_C=|UE zZd>zQ-sqXQKc$8VD`V)C<`JNWb%I~ADkX2)Ce4Aq4hp1))&0@NrcFH8g?pYs3A<`p z!4^e6&p(Vs>pxrA;oND&_#Tpa+(OjVv!==}G1B|ykA(sm&0c`dRioIiYd)Ogx(j|4 z@EKTaM+PC+LA|ktS?YR__Qc+}!Y@fYo#aQE!K3(ZAs2%4xyJI<9UI4QWj)-0WH!2C z_;E{#+FC0bVi=9@Z;H_SQW?z~dJ&_-7qKm-w&^NUF|INSndC#_&bdnGhy zmLV4X*ke<=z>1>x@ywmqK5*7vPbyE2;pmIY*~sS>wD@Bhj$Zsu_~aZxZ<6tBO<&R+N(E|cY(Whm1pFyux&)DnBPUK~+jg02;QF|WBzFG?J-bK*qZ~Gzeq9q$;97KUj+Mvo%5qdx6_gv0% z%TldoqaJfktPAglTHz|5dF(>Fj$2{31|KL=2%|ZsNoad-BdeMhOWhY2U~adal6KCi z{>pg>ePUXm=4%Mqo!$qU3ELV5^!K7y&+o&mjMZRd5=2i%_m_5FtTqVT$xK@r1Uch=fU!f>vDq2Td(^NkLytw@e>pB6+`5o_z52_aJ99*cfZ3cei z9`98<1XA5PADfd4ndh{#^uGIWba$zRLeYs_wQj*bZ}~e#2Rb{h8+MMnef(saKvQok zquGOUi0BzWW^xXgke9=>wOvWcE)Xwoo-bTWjl+&%h48(wkSU*wq5EgbaO4j~wsYHA z&aEAe+r?Hm=@CXl+uOm>e;Jb*>qE-p`rzh2#=@TMKDMT^Bk80^O-qbS5UlXKZ77+X}qCi8nux2caI zVQ^@}LOGsO9^VB&mz2WOzJBDXt&27x{tQAb$vJh5wA-i&&9PCig>_Hz*^Jagn$P|A zy5(xDw1PthJC~t?q8)UOiKH%ib)1*5iaj0RMK9VpQ-9ZBVO1`F2Ni2$%}Z6be76bD zfaqfUffGUiXNgoEw!^`-jCFFpO3~RQT;Z`rROm3}Y_yr^^TH2)FWpaBo$@$ml`jh# z>_J_w-GzD=fgia7>1?MSic{6N?N3k>cUiiL%*d6#G%omNsnpVY77slHKE@boRT+T?&j0nY;-k;C%rMa+@&TK_H? zh$UqfLiis$(sDP&=*hdmm}f-~l}2K|j0>~XwC23TD4f&nnc#fIm}ctCz|&W1*n`Wl z{99u`Xq@A}M?Y2iHF&dBC-128qTP~SSoQOPxKzQ4Jk}}T7X>Tubg`l7k^0hp>c>R^ z6zLp|eFPnGbfXPb_m9S%{j(u-B+!G%dH7*n6sy#oKw24f;N>?ETH5T$apYx4@2p|p z>b>ZVPA_yCHd(y(4CsCjW!#}R1D^d1qW&cg7`JyLdn4M=s3DH{d9b-8iE9*&gX3|I z`x&@a96`U>3S3y~!Y-w@km5K!41BGO15EtrMbmva6dJ|(M;1$F5XP+pkPTtOUs&k#3@%!;*gIbTvRQp;3 z2lq`ujnrt$a(o4)#is0#S~N||;NRd+G+^2>K8Kr?P)&XZ`;g^EckWs8xadjoD(~a7 zm>Yyw_D8_`yG~TyI7Paj_vBukojD8f^ODn&o&H=i7XzfT{lfWB8Z@F6oSnajhnN4; ztAD|(5Nn9a@+TiN9XuPlk=b!wXy1E4hlw_#ZJ;S#$dX`wQ!+&J9E67q*ZHd_vFL}E z{QG(q9<^L1_%3#&kgRnu_{KrDp6B;VSKbBLwK?LdRT3)e`vtmuj)%SVp>$PlG@8v_ z#Nu+1R-z$i-PhRMuW+Hj16;r5S)u1<6KKrseDr$c&(?4bL&xE4EHnKpwC#x?)tqXW zojikGF^Z+PO|QWH<0+wSy*>@%?~#9Z&tWTFsbwD5C=@P>&DmxojuN2>lV8fiR0ELM)2ENN|2D?*Xl-pxBXdl|%Fs+XpnLfG>wsTj3!uUX{o!ST2wS=>+N&<~LHxR9T z8iWa1Bk|OV!BWk9;<-qAcP$Aw2dS~~oS_}%6@U+pszN2thMc&_JJBX=VEGHesPx({ zc-vD(n9|3eZpg~wlWHC2mBRZV372G?$_+~C6&a|m)l;G0B3Bn^j+Y96Jr5a1}xEPwfc@=J&tjG?p zK1*kdRB+MSRxoajqzln6U>xs+@~HA8t6~|tiG z67Fv1U8UE8P`AfnHmTB)77We7jtS+W#%X6dW3wK@FIBM9T)%p8=^l6lg*6B~Ul!{2 z3znZMh1)*<6t19yjTr%~fcG^F<2l*>E4_rqd;AvKMFP>Cxop7Hc$!vRfO)(tWP4{2 znUpL=ow0VX?@SaajMxj4wM*H|eeM*q{3blUH%Qo3=t(!15678TRaxm16Y8>K1Wr72 zLfG4%XRG50L;hn-h2OLEOcL;I;uf*BFaK`Zl8lC5{J|)+jt;Eoi%H3TER}bjPMUZN zKCcpB+r0ofX*&|-MAdq`-e#nCPzRaPWbom8>5}+B3@Mt;Iy#Wze#YV6JNZJb+Y9vS zIz;L@r1b|Vptv93UB8KE{~V`nA$EAd;}Hy5!m|}?`bj&U9*&mN!WCWCFLyX6=uQ}IhT-h1`V6Ls~6ivG>K z8+UaWhW=gvTlOMN51Wtqo-yoMVgglo)InaO5?toY+gmFxLjQiXthOMWA~}EWRq-6L zOR@uvT{sj|11VwQJ(Jm0KfPtKV} zc<4xf){eQ>vLKHiuFE?*|YS@>LWHk!piKfv<}t49WAQ zgB8Q^C97Z?9C>%GssZ}1)EBGbOsLx}OLX*|0skr3(aI%pX!kOa?HlJzy~?sNS9zV# z#xr-CDy2~V=O7E0^`q($w?Okrj_9?)hWf|9gMa+&md@{7XL&Z^pJuLW9z{ndZHLfaGntj85AXcC z0XwV@2rH`eX_nbN>8@VQ`vor84Z&M4&x=Jb&B)=pHoE7_!$l(-n);ZeK9-;nQFKBl z8z&?vh`V{l+2_$Bv~n&3`}yJ2H@XTo&$3`|^C!^Zqt79Es49%(&wSTepJ9AlHH)lr zCN1Tm+&|zZdKjA1B83rnrH23|FT&_WK`aK1*~A8S+E7+%II0|9BKf5Vl>ieL~ra`5kLihdt%}6aF&$Id5LQVpz5aMLgOD@ypX0W z^|AC(45yj{u?QY2?DPUt`gGV2Z%%kRfXoyty(*cuOc8iA5fwW&?F7~)S9oias zU}NlD-c3`;uBe|SuQf`T^{fWQxVY2guqLos;jYnrZO||I!mjMD`Bc} zD;&;=p|t(2kU%Th-wF1VVD%jqG>sA-9P#G)bSqq(>&{dT0^Q7XK#%8lh4@zP9}Wn> z3j+_chxsm?@05d)nH$7WcFt60Tm~&c6>NxnAf=COfoTUL8dl2tP@H-XJoafL_$F|E zxSSSNP7YxAzgWELKpgVPN4v9?gAR%Id7uhGOBj%~GPJiA}lB9(TR89)(cs|SZsvw=` z&jz~?uAGFf3wMZ{FPqYBgQP!!j;J_ONc9k@ z|8RA=ITg$tflVD#V1BD7MQ8-z*hzEQ%41w>^$EmA=Y>M`$d_n!URjz6%D!4h#~$=V zgOOjw)bBBLP4^ibzMTse1Hvg$u`fElSi)9_p5)Xp41J2-g&B?sv{Udz$)F4H(Vf2s zcZcAzb{Dqj9QT+#3Blp&twI84TeUk*md^9RE$2waN)emKYQWEJsx*J?TIoFZ-{?h3 z&RwPcLqvYlS=$#ix>|w`->Ljmb*20Hvmz%Nu-Oe`G*!e0iM+RQ>J*eL;hpUKUi1Fd z9O*odR6R#8k`$0-ECiWY&Jxc#35kxitUx}F5-jBKYsf;;V}uXQOW{7-x@=g+Ie~5N zmN}QZy7)MjauSADpPuBbPMf!VZAO`)C!)Uoc zimSW5qpVJY^YyyyvvWKswKpvU#`Q8#C#CKKBvt zp?eU7E4c5`p=TtS6fMI|t6n#(v%f?^PX?mWpJZJ7Um^{7`3z)Itl5@f0)77Q2CC=u zf{R=W@@tUC;(#6On~@KtzP7;E`_766r#W}R4Dqpn8=P9`KsWxxVV@&Qnf-4|QVgDf zo~P<1d%1r8G@jpgxb~7Tm213`H!xPu9J;#rQQwj3$O9(q2hVl(eK{JN1{#Q^@3`q? zuNjsum=1bT+;cc27CX%*veWOZ>4Vcu44qdZAjzH-mdp3R}1$o~GMB0h>K%go7LODbuDI{`FR54{{;j9AzBpeo<80ZAsf! zXk+Cn1+E85h$<1gn`~i66KrYU%_wY8?rezMU`g*?r{l3(IiOh@K{q~C!agrcb^wAY z6>q}ZIz`yUd#}=x-^0^g)$F8QC?!W}WA8KJ;>X>NXTS9T2j_5NRZ%$Da}$df zEGf%50OwsNBS>%Ixd(`0cc#i%*n~vg;&FsD2Aqrj49S7|Q z7hVhxri}SA_;~LqW~gmNE`HoEWY8A^yV}s+O*+z9-JupmbMj(wfzLUyV-C*@dWPZR zhyHMpcX@lL@od+DLRNb8EH$ObqgqrgOyI0t)#5YYYq5cC<=ML7Wj!%s>f7U;KakEP z4?vx@8{o@2-f?rz9DB@L$cDX=(6y_GhfAjk-S=^Cpkj`csWsapgytzO!Se6@n7Ha3 z_Yw@iA*-H&lM>I>zP&5my{-A&u(9rs>#jKnPCl`=*$H~oayE_pZ+O%E@8AI+A<;g}f8c7=E4Q|6X-l;Ci3c>;v~_j+lM{s&6R^Pd@vS;>%$e{a&5@SYt{B zzcr-UpShgN@o|j}TKk`1QLkJmY)%sP?XgqT@G_&Xy(Xh_g&!O(sUyA0u4uK?kNH35 z{GwqOV9+T6Dn9zt<2Vh>d8|_Jc$#|=)eO;1XCY|%@I9IPjxHXW%N)OR9k^En4u6>^ z{3&>e$-*G)arQOacj^GiWOl>jk>5mfojA&R{t(#gJm}~jKt0xWN4cOv7RLR?%g3nU zFgH&@;%rM{dSfsnZzq&oiU~O*#L`qWzqCaCvi0_*u6Xctw<3KmpaoGWhD&Go(sLZ`;hZrQ}ov=XPFQ}=RCRhz`$1$kYq{q*?wqs z`#6j*kE4y5%kfF9C+iV@kxn(q;l_1xIJ5`<7S6j2IlW_9dp}$H!!vp>Z`290V zyG)fj@@P_?f+P1&q{6?Cz~#IRTca39F*{_@=cp#^-3>Gkb1@SSKM`gydCzG)Gr$2z7?}6r+JRgcq(f7*Gpy}k|l2ikoFJ_35upWmv2Fo z;V-dqg)@cq`45I)=WCt;_j+aWf8U~w?As|@>U(??7Hu{V>vg#o%*G0%O46aVyFE=f z8i~V~C9zl;8|qxZyPo4qgg5h?NPWU$(8)c-JPvYx@}qO`bZL$l#CzGaOW%Y2lo>EU zDS(cWRMNG#JvtaC$6VUhifrn=5p4Pzk_|`7^GzZ>s&3Vz=HNf00*uy~1 zQJ-`H(mLhA{4Wtxc@5@AtC?DuE8SYGgr|z!#mU}$hY^jiYHt9TKlP)a?|#^`M>*R& z$BHJl`eAwLV#)kqTZ&(rjw`k9Lc1gH0eAibmdE>wqt_gxAAiQ7rekkR9pO)7yL7>^ zQK2l2Yn5(~<jX>?~eQ|$rIcJ7=(}W);SY5J^J%4LKN?k2+n0k^BA3FhaPGm`UZNYL?`}f&>E+C32G>r{cR_737Y3Ll*na#qin`vLOWneJ z=teZ>Fx+rwpRSqEzBUuo)NK;dcwTJj7H=#|KFrod`q86`e4Kn`tJp5%Lj6*UI2)#d zrB(*g=+aA&suI~Sj`JJ$DZPec2Bm;}KOe6(3=driWCa=mxg8#Xf4=z(wduy_RAdYv zHsmlLnGh;oorV^IA{*S`N!NGhV2z;_RGp8d_r4q8_un%1;&>npt-S>Qa{8XPym_bg zP?WPC#>}`Dm&-M`Z3#`n!@j&rXt)(VOg+KmD?MoYmWkNs({54!rUjjvIvHKv10nVG zJc`t*fsF-&nBrtF+R09Xsv1H$@0+l7Rl#GYhtyXrlu(7i2y7jd3IgL=akCdDbaTySNi>4-KH9;{$N7y&JPBbt0p4vG`N-qwuD~gl45D zNay*c1@p-6{yylueL<+%z;B)FS4y+_{VoTR)w-@IJEl!Md!P5mjh2;m554D|r{(Lk zv3=-PHiUB@vTo|))*>4!vkAoA=~-}b3X-DQEY2~DW^*rR(yz#UP&PmtF21v; zSxv_vx4M>9JoTY_4xO-f*iMltyA^=ZWGR`v z(25j!hh4Yl4KU+B&V%Zgj>%UH+0w_EWIkmdn0=@LpH~5t*nSZ#Uc|6-kCC3ScDQzM zzp$To96bBgN9tWMe&I^3=MAwYWFV8Rr25WM0!soh3_=)<+>e6A0SqC8Aw z4;l*mu2G*n-evzb9X}k7;Eb9Zuyn97OD>F{J-cMEcjGYVaRaFHN=^8#||?SQHytn^*_LKa2e@f z{L6vnXhceN@`~G*^tJ0Ge7$_BaHiUcZj8-?8=DTXb+NUyZk{%JOnxX@|FNgb(e1Eq z`ZTC-4xlz!6^xb3XRZy-JhwXrT_+y4*%uQ<7yZMrtp9ZwtWiOO5^FK%yQJ7`-k(}^a=>+FlQkc zLC4-)f_*;*fd=1Ox{iGg)@{{n?K)RF`JVy?R=bP8EX?WKcr~2ANdjvO_;jk(VUXPsUw8O2{7t4nu)?Y0vQGv4`8$KN0DwQnfvRu@deR5&}`p+!iUqJt}C zqoJNr)=ogk6zp~-4D*MwxRE5hGUHJRaP@FoPxQ}A0 zd7xRPGw|KF0(SOlCUxDo17iM1(s?-a+|{$yvPZJ{-RJxJ3m#8=PWPVse!pI;BH`92X9^sC7R;M-n2v`l z{kZ)BjKdyR{Z1p=8`lT7Jj?}L;zOfn7~-k9D_Gn#e~Mb>gFkMk3L|&L;0~)4$qWx# z9>x96>v3G3GE0OcIuC~-q;dn46$Fzo=L!sk4ea;<5BgjC1vLC83ZL}-$wK6gGoDdt zNHd~S{S5H?;cLRuE2ebW&_gn}GlFd?ojZ4C=>beHx`WmC4xvrgu7Kg~;X(kP+qY*9lsJZ>d7k$D zSWQfRepwh|$axxvO(k=?+|ZkBPsd~Nr6TdOTLf8}t;5G{JTD!WOiewHz}Sf@O!tWg z^*JKKkyL>3&wcp&sVa`pQ>&Ee&$A7(TKKqPK0M{T2*1;An7nZ*)6VC+nhUN-&y$2M z!*&!mDoHXbpKFt7-j2ht;K6aRbPwNs?WzI?=h^U8VG_wd`3qS?Gg;?9J96nzz+V|Q z!mJla(`Jpp0>#6iHam_Ka4KF)3}cqx0_lz0TyzVRhRxhFd$nJTWNyd1C6lGk0qC{8 zURe2U2t9kA1)Y{{%#piFuju}Od*@$>^0iLXty&R(s5`+7?sC1lLj%eC0JEs`p#ELX znCGq`>hmnb?}0v&+_;=H(LVJ#_w zCq&iG5P!|LA^Tx+Sh`~_JPr+{?^BG?Brl&ux=kiCMSp(w_OYI|%aTqk_rm@sMJPD7 zi!2{94B>vI3H*CW@ZZmWKE;qeGK9jd>R^Q5G}g+wvU_&E;3Zb2h5KODjv?TtYAR4?~xu4(z@; zkQ`@RY$z~=n|=LhN!&o(ZL^2z=sA&jyBwt7o@OXxa&X|`#pyL8(upd7oPkgj7|%q z#beh)!Qa_TpMUQob1I;`yhPadd>k2fyCm7G%+&UxvJc95Q0kWW`Lhuz<*B0FCI!%R z;(gdQQwg_x_liKeoH-MRH1`o>&X`h6S`0$Jm0-Cvj7+rG!;Us{Rvqj~n*2nwJw+Za z@%LZP@6SN!TgYb0y3oHpia73vtGM}>3Ay{INqU{`R(wxl;2}AOk636yYhpam-!s$t zzZ;ewfuNg?=*(vJ*=qaX&k;)%wx^gN#rtW zFBtD1BrMh~qOD7vaA`#v({Qt(Cz{CbN&h)1YIue){$YpYOy0i^ z>D|EI7^a;IQOyCA(}%Mc6j!s!v78_4=ZT7^QiYsuQ*qOdWuPo%u)}Yr(Br@BvGLdd zwv&?RsP0}+Dct~(J)`O0tt-&{VI|jk$+N9|P+f zgipQ9=ysVanyx5kZUe*Uutp{}UO6sa-{?fMv{NLxaouhHbo7P@>mG(wxBs!By7|rU z{rWagF7hQdO9gL^_G7DgW&2siFckLtatDwRzTix(hOeubbz>k+Zl8%>W0Y8Uf*Dcj=uXZ+Y&0)KzuvS31Ca z-}%zi$F7*6r7hac7HHuIFRYxk67oI(?P{EkOg5Yq?@prVgdE9ik1w#NJ4cR#nPw?V z42q$Ik=^k1%@pxJ{;jo2f81ZY3W9jf=g85CnDIT24O?eLo>s<^j%V;~E9x)fiH~a; z4B}z&!|~@(srNeO*)5p@Jagb)YcUv^g;PjzEp#nOVAcHH;n$fCcrt?tfjqCS-_jkQ zjBa6{LtUwd-e`26(w`~qGNb)&6LG$&DqP^4QcqPc4Aa`ns_Vn)a$5$Ti+@vH`?#KZ zJpK-eaZEDz5w6Wm@v7)+{u;t46ZcG1INIT!zLLFxOKd>W{0xj$_?X0+^ z+JeTI8R7;nC%9wgOyj&lQ0o3hwzX5Bvl9|OG8n&a zcVsOtj#Pg38O(R%?hiL_nj!YXaQ|GUA!SD|!ZmSdh@SYTp9Q^;F+g^EA^4ngrZnde zY$}||l6e+)d`>iK-(DwZxjNCc+;Nb5A8vca!ILq8 zw5(wOmRGD{lhr+_xl|Vo`&3!k2fESw6}H&WAwtf(Np$JabW9%U%$^P8t{l&4Sk?El z(0nd}dN^jlp@4a8MspZ7+&l-7yP2?m)OhL^T`M`0pYP>E-BC&68>-@6(eXyAc$XhO zA3w9E+@r?meQ6(aJQ_g>9t%*jNJ;E5%ZdzF#Nt~_g`QW#D0x6S3|6;bLuPx@h6QDk z**^T24duOf2=4<5+2J+Qsfq95FBHraHMV-wjdkO2;f_g=5*tc>jlQ^J%U-5oZ$U;; zuBa%RXTb*4M^s5fD)m7Gm_w;LA8$itkcR#eRyFaMp@6(2iLgsp%}4$IRedGZ|xCXw;DT#CK#q3ut_U1qnBoxy#L`v887?diwJeL zXtf2YZ&JfEFD?qR$}GrpuK`{!IL8ig-%~;FDD=rYE?U`f_s8!%Uvn)DUL)%p7cI%U zr#p^3Ai~GE-Squ~h`HlHDJ?@442p1MfA2cdqk@Ov z#A`Aiz=>*i_rgANwzH`(9Vq?jaMZu4FUs+bVd;Z$SY|j69vC{)$m5ex=K2gaeX13$ z*&c&Slr{?G)A(6^LmY&RDrfiRmeRyP6k~o?V&-89)4KbbCKkYD;CG z>to4mu_em-+_Abf)sAj$5+6&CUa&tIGWxoicoQ04ea~d(vmri zl6n3*#EtI8$l)Pn5Am#wBR%^z9Cb6?!Nfj{?4rD}TmOCRAa`ZXk95Yxb2F`Jgg^_* zrgAsv9XLL`oL(d}!sSJM#N+cD$oA7%oPA4$zYqD-h^!76@5KEi^d1rVeM2UHukb1J>UYgqTYjH+cWM6`y4Hq=QD0rP`~IVuv-@{ ze3$pOo%^MTzMbxCv(7J$n%(|E@j+uYis$WJYWZH>SRNMgyKuu$HO$Mr!Pq1_+R$Z& z$Bq_>sdA3wG${a=goT2}BR`s~xdOfaY-g2EFVLG=ZSZx`33$KMnbLC)!zKS5HpkwB z`{~z2V|_AnR5@?n=eWD{?T6XoPskA^@@k$k~~(vdlF?koC4FE;nkh1Tq(Qo zDHs{$0DAe+s7rnEP=+6S-o$hGo&zQG{MkVh{M2_Gj9HP&oR)>skJOpySv-J!bvGxO z#t8Ht%YTQioJ?O1ErUINn^?>55PI>k0_6QQh2A_j`r!ns9QV|O{i+iTF8-J_i znUfSdy3RfC?T@0_;N#b5anehOd$?7HTOYsYm{>QN@O?`GH!xnThF}kG&Vf(Fv6rk^-@(^u z)#`Sr?AZ?&TneE>swbg)8;J6%_HgdjJPpce zM(oLWM|wJy=hs#$Kxj82-z45YGC9Ju?mAJ}py8SSX&~y4b)rML=KS2X8rr(KkO$}0WTekzy+1nA%FJ2#`s_|& zc)Js|JqiQ!4dtvQ_#_2CP{Qmh&0=XO(v6S?$qfHu>Q77k6!2SMD);{Itp39Z718j$_qlojgi=MSr2~i z$YVO(NmN`(=$FUu{>FwhnR{fcr>eociB=T7I8xHtKX|@^_ie91-mGvzxx2S*FPS6M zxv#HHZqrm+-n|P(?loiswYkTqND7zj=?6V(`B|c3AU=71gFV>pOSMLJxJS84d^^UB zQa9UT<32Z7&2s|LPO~v<=z2E9rH*R9K7!rF#UR$WkXqM%Xt&E{TNJ`++Ua+2!R=Gk z(HTf?YX2Z%OAb`2Pa{p<3#*^Bo}KfH#@uOh;FnDr%i^BsXwFdbPM2a@m#$FANABor zdI?W9hEm(uGRSw_$ga(Fr8N!rA<#-ss1Ej_rU9e4YuKGtb>qyRy3y!X&>$o~HX{{J zJB+$f&V0E~9P5^1zW+Y)-w!9c^D#`qKb)-;M3>V~fR%AXbz?jCxpcjNk7@^CYq1}( zpYmvS#g852e4f_618`?QFX7G`BV2P~6jW-iX2Xx!QQLhlT>r8=tKUD3>_XP!{wZEO zyA??*q?W?kN88vb!^yOAUNM}r))2lP^`!uJd9-;kj2RBLrh0>cI63IDpcZLK*)`*_ zxK|C^zK?TAQe1K8vV5_JRsfB1NWsxx7sAr|a*BF(70!*F#N4wkQDdkk1}v_CHH!S* zKTjHiuPRoyC<>(Ybs(PmHxD{g_&$d_3g=x*Ve$N)GV`Z^PvAul_aAmn~1=V4XJ9bW^95 zy%#~iSAO3gcY(F+86- zLv*}uMfdBv!23@;?5hZ*9Ui*aJTsp;&EXlXIz620Z)z>eIkX#d?eUP22zdoO$0DTR z)1mI{!s7-?ao{e|JAJX)GL+OZil9X^j=h}ZLrQ-hNzUX&{C#bI*mw99*}{B=xYN@+ z!_h8i02`cOPHTIO!6T`vpgrA+9u0FqoA`XDm_L;^zfH%x4?a~d{CbIQOlgE)yJld( zwGfJbUIF;TVq$FXTNJ+>_}&l+By`ARYXxOz=X~yjl!^D zw%~gvm{vWVis#Sdvfr1=Z#u5&(Zz46;Ctd;H(yoc7ZSNWynexwgRS?9=BJBLu` ztyZub?F&W@4rF^q3RSOcWe<1r%;(i1JnubGeAQ@1Z*Pvq=ey=Zfs-5A$Od4M^c<%9 z*N8q_1fYdRrl9HPOijCZDEw79o0fQzcXkx8<7u;K6z@uYu6H0WZvn`x;coPNIW$_B z%4|1;)3zi%e4csL>M!q;PT@P8UdK+sndp2v{_h~RMQ>qR&X!bL7>W_nAB4Y;V=4Up zd@y*pl=Ty%c=oRZJkHb#0aM0Pz4}SXjzx7ccVB*!k+_8PgDhy>93@;9r3C8s0Ka@?gXgx2Cf?n7!}t68UmIgK;puF3dV!6TYGb#Ma89s}8V!-d8mKf3u?76ZLB*bQ^ug)iLMOz#aox-xMI3MzbHTD~mC|o(kbBUU=lAXDt*%^Ag z{XA6t{Vkr#tD{WUA(+wd3QqS7C$FRJd{56EI;r;b*-{D>m)ZzJxeht@s|rrKaS%pt z<6PDo_V{zNJ1f%XE-iaUR9N0BEao1Qxt{~EazP1O-8F>Hw#<`cS2na1QQcuxs6XG-+F#3$Uf6`8=jD6+%n?Jw2Bo2Vt~=Yc_#w%hdGMwBXUwb-b|?$vajgsf+mkzwaHp;6|DWN>Tg~auGF?2IuL|=x z+wjUV2P}X+tomgPwJl0Rz26_IzeHRn`CWIQW#CLS4hx~(ZpYzu_Cyx5z?Ym3K7tXW z213|eqNn43L3HvFHYLZ2T(_w6Tza*rS8YP&FGpg@YFp@YAed(lrlQ(@-uvSml7~kl zaM)BTGi4OC3$zQrm(D(=?{1J>oUF?o)Z z|7s9!P@O0qt>U?_p*py%b1wKyb0fcDzS!&IY^LjKPAgYVLJymD!pB+scS?dYsD3MF zH!Dxl6w}`LaL9A7LKbYSuX zymRIhy!jGI-NWOs{G1m%_}hYdB~M1RsP{tN&scij84LH{EM>8rJ34;p!r3Ch?qn7<2qHo<=!tz&IOImTU3@`(vr7j&^sP8tStM&+^|yyx|KBA#rJ zWf#N(ps?b$)Ub>(bKV`ozP(~l4v zWX_g)at8IGPjEO-0j#40y4R>AndeV3{U}-raP}U~Dz`D^d}(Vew{-X=T z#oF>OaJJF~I5qqPj8}4@EZ3djx;KY8@b6vc&O_)i=yg>}Dp5-1SJ>;43vM0()G>Ml z?#5MYo4h&Aa2<)SKTj2Q+VEUeMZCoOnRO?ahR#gEhFAr*{pA(Pd42`9Hot`Bn|Z&$ z{x~>`TbasxSDGPr9a>iC31{{%>!mk+9`A}_CS7{L9Hkgz2Awa$H6>Qm0 zTRQwV2CGi&5a&lZ)9O%XNiMNUBbYXfEPzRRQPmN_e*Dke6FbfPSdF0#<<}0tlZz(_ zzQ>KR)<#>BEjR6SrMQDWsJyl}D;a1^#XEgbXw`(nXC{;D$;mK3d=tBrF_|(?9e~-9 z8p7gqKdSrC6BmSNaGoLGB?kA$v6)weKR+$$^1IP!6I8=y%h=GU7$=OHxL1ti?`50b zhGOHc$zb-jf=;wo0Gr0|W!*24^Q`y=!j?uW3`Dz;iEz`C zXWrDT(05@XOS@x2Bkx+FmUgnReeElZecVgJ(Ymd6hMZJ5X{qkF_#yu?k+CYiQ+@-l z9RkUB#RG7+$Y6Uo`)*IxPnb8xM)2=WH0wcs{IK8gT}rD+nazYKI*f ztwP~B6PlIjkE&ZsSi{X5WN3aF=IZFcjB)C;xMYfC$8t^k1o@vCkH^By*?>))C!qfs z?l>Tr{uF5WvVQnexqxlp9o2woCb-{asQBb9cibT0`xna~@SH8pZHU5Lw_ZL+YSzTnvpg5<2hTI=PSk%emtJf zmTs}3B%Mgk0KZxtoyz$_EBRaNn3wQa&*mH>g)z8(Pa! zN_scRyJzZ)GFr4s8aFpOvAq?1zWuubyMNk4$V>;$%IgAY{vBQC=Yf;!RM2j^zG(a0 zl(uGRN#^Wm7O{^caya_WxzJf4d~ zrbf|npQn;}-qGSu)2n)5NM)!_OXgDz#PE-5x_O3X?!{?IPC8_!4EM^~2__F%Ug{JpFJxD%r6-4Dck!<5H4& zzRJvkK7Q$g9;!+pZ6naz38V4qf_+T)nl1hDbVPRHclEgG{P)pAf80E8C7k0K{#u^^ zC|byU%{S}lvd|BGX0Cxl8#p^xrUs;girBR1P_m1W#ShhC;#&<1TJXFNjwk~-5$i=o z7G{`{w1XKXS<%d=fR%DMI@SU*QC-nkdIi&hekgPZPW}PYqsh z*1hkiK-8U{!|ordBISOi!2U!F;)Gl z-(N=e;Y{P~67lzCGcxA<|4$d)pu^ps_OFk|DbZ`$tsk{y(5nI_<5^i9?AKW`{7afX4Y!$L568ppm3VLu)Kr6 zQF12CuMwUsRWPCW!J23>t3fzf&v_9V)_BvZf@%Ka9P(MAXgPnYctPZM!*~HA2IVug zUMI;hR~ma>I8(hX)Snc1PONnCen>yyLuzNFu{p+vZMUPI1=}o)v&od17MP1ht0Zs#O5+{G9Dj*hf@9FQ}?r^ zvH1ju1(Vs2k~&&6x*rZsDF?dYOc{wk`J1>><@8QlD!1#8WlD)qsq0N;S)!M|10AC;x`AOfxk7o-7v#v8V;PjU`A`(EYTt4iLhVKlw|FF z@%qgYcEsxj9n`1->GBcaoS{z7IO}Q4$~LBGSxnV8bn)pN3wCXzEqSYb0Qb>0peF}Z ze@OvH$P_T6eqNOG*%(Jm)esNtF{O>STZ|;9Mtll%yBx)eC$m# z^XozWaE&m;N}v+iSMVRJ{F#F%DWt36`aBgj=QVdedT3!OXKM7^#o6+0fI+wSu!R?G zsBlJ@WS)B_U!nbSr(w+e*{C)mlol`C4Skdhm}9&jIn`Z-cLf8%Wr7Vo=HKSOXGhrj zKfJTHSOuk0L{a3stg`pRuw}Ik6b5l_>Rvz0^4P(=ySvecJJV3}`c-TD`LZ-osZ$7l z-O6nDl+mX2pRjhR6N|hyneq9*jiwn22ldXJLId=$ddtf0po;0J} zEyIx>&x0=+|FMsJP%mpCljHe^f+1e`aqwE9Vif0}EHQ+|Yb)4~9w$jwgABd7ldePfk{?f5?p{z?n9Pd$UL~y@1-xde2Syvllg{b_$@%<~hc8tOmBKrL zcSKeGzVr8tCO)}01~j=h#O}ig3~1iVwmREVLaQx0z4%p~mu^iam4W!eI2C#+Mw9F| zXHbZgCE}ha2?kDIzuCe6@X=ug4met&pY^6;alfq zR{W4iP)IPb$MWRx&lg?j(gf<)B99~P-DHe=Nwj{C z!Ksc#;x=h>a@b~$DNSy0TiTwagb1vbTg$%YohR{lAuQ7^f;VL@q#d#je#+!BJD%AX zlzknVJ3FendH7Lig%l17KMwi)d#UX{6kogW!$=+P%KaLFBNL|!PbWmb{v!&vTDz%e$e>PYq_j(uPKa_r(+G{EonTSW5ZY z_}Qt3Z9O!H^kU~?pSa7S)jeB!(jJBiUm~D&`B^%!r2s6(1+!NH$z*iA7>>2ZLHcNC z%6a<*O6Mw7O80T0>u(3(ji429Xs$Q?Q!&A(R*7tSumhETcffu9GX$HuSGZtF56Rp< z(5sSk{@aZw^yeOgCV7dpUK7nVH`)`gl<%PB9(+;+ECCwd(uIeVv@7t=$<(P$TE z!G>20q~X#ItNpBjba;ocRbF!TcAe=-gZz!q?%6QTg0QB5E^8FJQeX|wpFDMlL}7Uh z8&lHL=78=8m=IYAPcJ#rBA>OOdaR87?ZwZE(fk}O7cYM6ZBP5&zK6B-^P!FJTM`Z` zNY`1*r!xBGi&fUTPeyu1fCIG93 zS6NHHk)^(K+Ju1xZLIghB${J(1QPoyFx@o1e~>)~{kJ>7rZ0Y^r1KlbE#T)C6Bo{? zRK_uV48`XIt*942CqL3&46m+x(91|S+^jK=X>Bs3Z-vfSo|rDo=dP>7DWl^{2V&)mnp?k!A)4I~QQX_+D-*cqc__k157`UHUrmNKc=Nu+6e1TMb4FN}#CPqnl5 zNP3;-+X84u|G$vB;-0v8zYSeHERR#>tHP_@0)@TRlI&8l9NkE(#Tno3=`OYhxl(#e z48FUx9ty8T(|{yv==y8Tu3t(bVcZdDyEz7aTG-S16{q3U)gqSk*oRge`vI!&e8t(< zcxTqWC+ZF3n({&3lzPShWovgZJ?>aEFc* zG1gR6tcmq&69l!5;duFD2yC9Ynr*Yoq1P)C8^_J_WC|Hh6hCb&K0fta=*GKmCRS$nGqZx}MDM2Z z)FSk`^+C*8z}W)RMnl!kd?tKMA`izSP@b@|dcRW>#hEzr-Ruao;PW=I^*8*t51%P( zPYYudQQIh3=o4j(8)Sz_^5oumZq#Dxf^K_yvv5Oe>frwLf%`|p<~N+Z!_W4$iaQx9 zBvZxYBVZV5CbT@gMHW0acuqZ+edp{%XFI-QPv{gvxSyqEq$aj5sbN~fXVU=B8L0Wa zPR#6YLW#@W@c9QXxYTl%n&$0>)@{LTZtrAT5qJcqX2wBgn=_49`~bJxxubK8Gi{Af zLi=9-b(JQH;OxJ;NXbl|C9(vn?@tyCq2X6*(!vwz~trX=ca zdITQ)*#bQ%luD|u@jGr7(+l&Uq@YgN#ax7s+-JJ*gc5GqSOj%^-@bRP34T{`VdGC2 zQQk%aboaO~SR6B@2xkw}{ZPV&l&F(lH#ZoT-Ns&@DWyMyw9xjw6{B>2%6j%4H0pdI znKP5Wh_wL>{?Dl;~ zlr9E!?lCX?x&j{FD`OSjob{bm4deV0MBimL^fk5xPRGvyn|OZ;>OTk{n&h&>-}&$N zb^JU(%ES6KU$bxWv_wbE8c;qPLaN&qpx9#15?LJ?|HuLPaydNwA)HR=Yy!+lV4==F zlsH@jrPdl@KmVq}^`F4;`sd8S+M9ZP86cVA4?Y@Ed*L9whLXBX`bmG*nMaYo}C;#hfGjP4k}`_NlOe13mpnyO$>#r|n>tdPda4&;DHCltUm**9@&FzHzzVtZ->$o+t{}G&UCj(QR0<2o^44M zc|&oG_ad-M^dzO9&UpFcJZ8AkfV-aU@ejX0`W$zm(^f;l|4Rj1bT5fA2k(>2@P=|% zn#)c@@}dP`@r1KmXZ?WxJVE9I9I5l4JfDI|8kq?~Ah@rNURU80yn^ zB2;<_Ol4XUUA(gws#cAGr-D88|5Oa&)kRF5^Jf<7bV8coC-Q?8rTQr1?@b!!q^Ed@U5(hhEClK#VLKo%&|$-d3-M{T3il) z`UKLTj&pFE-`0=z_M|Gy5Abr;H6eVT4nE0$Em-nSWdrZXdrugHZ!_eXW^@=8Crv_| zU~Ay3E{ZwrhrM6sv*$a{QAWZxD9E2CjIedKohrM6{>jVP1RtMCj|blaT{LHD9u72o zWE%{&=@0oFH@v*97oLs0#ca}TDb8^OnsqA_qh?!@=OPoyJpXLxOxZodvGu|_*6L74 z+wSawISY%yeVZ!b$>+mq^TG}A zbk-)em}dp&d-Atnd2``Gq(22{s$xDDr*&z1QQ8wd&aZwg^i8!Oi_OM3DY1g(o$#Qs zy{6!|fP8Vo2^TWwtxq@b`59C4;vvHB6LoO0hCltZ>w^C>hu=-? zDDS%*YK)pJ95XjTA2l_}F2&kEnAWcH$2q>rY~B>kbMSMM^gS01oI-79C&Kg*JJ}%p zWa{R(4+hQPj)wP>N$1yZsJWrdGMCIE_Z(fkeD=3+@~stFo*jldl{HLNbRc0dVSUB{ zacmiPzXm#EFuzZRZLOkg_suXhBa~^KNutVL`#?)S4%WFl^ZxrQ_%&6j@=GsAviZjI zglm?83E#hMA7+Sdlb5sN%ov)xGz`BT$rT)SbYNjZH%Z?!Qn!-+7;b{nn1A9AIeyN! z+6Nu|wnBaQG;*GQ6KtPvVF!D8a5ngR80qCAYz%Ouk9rE&d&P0?NA@Ch-pLvgY|oxg zGo-+Sdbn@rJt6wLDFr-o#Z-k-CZDBF9zAR!#kY-}eO5x7T-EVurzL9|;6Q&(pF_{d zc5vY|?*{&nL0^{wmLu4byuKEm7F5L1gU#sv+=-I?$;VD7nqMA*VX?97W>-%e(|dKW zsh|)}uW%wO(b-3nFgY8vNe`+pk%Jm_! zK@VN;I$ICC3)Hj5j58l1@~r zA6lDG0V+zhg6koH+AZ!&_Tm2X{iuEX09>l1#vXGo)yPep>2$I`JnOKgUl+K0ozL_8 zyZHAW7lHLojn!5`4OBmLJM^lUhmL>3NV_uwJf<45Vcd!Q{n}~xJYWF)mA9p3A0JER zx#pQE^jUE@roer1LMT#uxCYvFxIvRf7@g1d$M~E)Hqp zLbu~|;KmMMrH_*6xAbm!c5w_iare+iKA-x^oM4|0_|k#2_fWXpPh8IbU!)gL#E+Lb zW3A4deyJHCZceve^x2b~-J>ykSsRQJE2*bW8eC=%WLS!oV8H!Ax->I=RI|3g;2s?ipdU`+?R4nZa}%32YBK#! ztA_4w7Q&=Cek4rmj~B;yFvDq{)M_~v9S3&^0sQyo#BTASvd67gly>`PwpOw|)WFL^z1}l8peI&;4Z-2zskCHPvskzfBPtJgP5iRTp zHo>BG10^$De(GeJ9pQ~Lw<@vZbUT`Khv#e?^}vq%Db_t!g)J&sY@AOr<+<*Lzl+U; zoVF9xVEvyLX%&;J=d5hr?|9&FMYy8DJ1^SmxZr9H^Wl8g{U;pIdDby;m5V9e4|2ki zx85KtTSf0Cr@^wvAYMJ2rQ)YUfHazqJPR*8CIeyf0JG?yqn!^fmmm zpGI!i>cOFQ3%kX0=l<{56axV(k8YgjgmMu4=MJnTPcj`Ui zppF?uIy*~dc;Lc%vXa>Zrr$N7cDXtkKL<(o$NX;zmG2*nM-{DD*Lnw1zx)isuGoRs zbG|OqmO-hh1U9RKBnpq!bp2AMOEdH@*+IzRiG7j)B~Lse)k(xjSBuGZMdP z@;s-d^}k}E+ZRo7vQiB^(+(liy|b}H-JV%RU!*YJ)vc_O#hvXD)U!DQ9J8jgl!3k! z6H^Wv8MT6Up+KWw-jmF8aNzv6+JQKAHSczH1ky}0z+2f9U;%du^qFLWZgP9rg+@1; z^)eg{mNr(0uWF#PAGSchSMzX^R5+F_1KnRSd-3m&Q6E_95m zVnL8hxy!b~l`#rz){Coj`si3Je_jh^G6AGBowE>o@^4|M8;u^@2fy4g5^X<4Q?aZ$ zI?HZ{gWL<_b;Tb0r7d8?tWD@gww)w%*b?T-9YDR{blMrVFFu+6?br(8Yjedd+^KrU zt_X&kEP?0i0_an>x3D@dmGw)qrx$)b@l&@ltL5vt$1r?2?j2hWwyM);0tRD*uRn9J zw4*g;zF2ztyYO18ffjE12p-S@vb2{roQ?7B_Nusa#gx?1pf_h<*hZ}t5eM}vm4VLh-+|0>cegbL? zO}BRb>r4Ai#^58?0TIU4^u;L&8k+iwLPG-?2YmvW!zvhhB9saao`vWaQLJ;J4+X4j zhxsRO2=_+lV9L>ELD3?Iz2bZIc1{j}y|S#n*@RBkj>B;ahk#)!PiFqt<9)A*fKKXN5}nzNCe*9@nXPb;BosUWy*_NOrp zN|N`@tyLD3v0WASp1mbxNn6tABl-wOE4W+AkpiD^ei7{wf2?$+oWfrG^W*N17v*%4 zJNLX2tE#1Q-5)(tlc7tHvz8x&`5uXFV9yv;cM*^;?O2grt3pA|r>l=ZN|DusQo0*ci% z#y^Uyh34rUSaatW{MQ3|IQ4%dorgcw?;FMmMWjU8R8~{=KA-!!t?WI@h(sh>@@*kP zQE8V{D(y6gZ09_Lj4~>fc1THk@A^HR-#^f+mvhejxj)x^UGJ+Fcbl$-2dN^oI<^C! z$$fy@rSF;CABmMdb#M=N(5e}p_~&Uq%OAONI_C(!k`*Jbvrj@1yM-M!nnv^|&Z09J zzdAf-D*3$d4wtpW0;|3|k|)zj=--+<>>XqyNZCz;kRxiC`NdGUpVzVs;OlQ=iG92c zeaw1ryskcgeflo2c_~9^vHfaz)d{+`-xhsB)rfMVfTfFFnix(IFJ;8 z>-nSEzn@RLIA`49J&`=#O?Zk=Sr4_VF^Lnchfj>7*cP~e?5QKv`b-=4nI%K*yivq= zRvbRrkqMs`tfJFo*uE!o0cN^2aJfw9PtosyFOeukKgE z$r4Ra<=dgn{Tq>#ivO?n~ zMWB_3 zv%W8}0&*gbV$iT$Vm4_Hy<0m6KOB!H!S|)$2aQK96FI1hOQj5efQRv%u;^ zG+tUg3Zlj#mAue|9aRsYZD}TCC^6ri5#wOE7115yzIaBx58j{k6=@5OKxi(>I+y#U@)Q@Z`F6aHbI#%X^Qpz$`r zQOuKIKIR6^EqB7L;uFYl^NWJKPtHi0XL97ZxnNq$-l^s064^sL>7Jrilnee34m0o2 zjdu2#Zl5pQ$t%L<;JLnHp+{v)y)RB3?1O^Tvv5Wx5QiI%CYoC5tV72N)dLmCgW=I! zvd&zRy~hLgOirisHaOsKEyiMv{v{Y$aRn8sm&2*sy%5KC;9PbypMNKZzIZwpkB67R zB2$k0EaH#e-HbcUe1@uwFRkLFPnrkW-5daa{pU(1kJu%+bl(+&hkfT(R+4MoER_ukpjx7y4mKt}lJ;;EvfBB#HEm`J5u(f>=1o!zb|#OsDd~ zp`S=9Z;Ygcp++cinMbPTX@I?IBu05jgKJza?f0(3V*YIy_j5D%u%ie^&bJZH?eEj< zaq8h=Cd`ge8+Uc z-&VO?^YItt{q}Fdx$V)Ng)1iM!HXl+f~sBZICJv=JdAn=E53$e?BPrBN;!wR4Y{Iw z+C9+vIEy=MiTLESh|rgE)w4l zvporN*6V{-wHnTLngUXb2B^=063iGQOXM~(UTd}k)=G3iM7AAlc};M=?{AQnIY}+3 z3#wEzj@D@v!8Vq$(h_5uwtFUAlXb;WvH?V8#zOihya`Q?&x22QlEKc(8FO1^!`X|M zsP_I+4BszHP8@C(w2WZBR*|dFuDt|guQFDfsSKH^nNQDbn};#khGa=;AWykJ6u-&3 zk=uVB0SW?9*M2@pC}Bu*&Fgq?ARb;lk|Vbwf>ESq5rpksK*twEp|(glWX9g)d~E=m z@3aW#b~$_2OYfB?A3&MTA8v`(>*Pq2(Rc{e0Gxh!rm%ClgFQoU-f|}SKF$0Qao12U zCK~o+EGHuS!|-px5-_-IOs_`I$9qGiaQDRoSpU=xkF02iT@MRsLW2joxsM>?ZkGk7 z$isa_3dC058GvO}&o?@d^^5apQKb{E(e@?p!kc+F4ExA|KWl`0_>g8LX4^KvB<7!d zuFE`irx@GEjt?JLzingSBlyQ5SF!Y9-2ubNuTf?KMdm@eUNoMFDI~*zbU%zuwI$&l zt0=KC#xzkI@*{U67vABDjkZ#*^OO}a{=_w^PPR#pZtf3;*RdhBV!>kK?$Qk*)v^U2FA2&M)d*6yo;?e$q z7zC=P(p6JB(4pWS@b?)&ySzRo2(pAToQ^EQ`dl+IcAGvm8qWHjL_WhmhV3!NIzD=8 zJju#DMzxkZqVW+^;ZDA#jqRWLKIEa#7I2pNnNzAdq*;ZGXyU1cX|7-oR9pYAdhg-hvAT_gf!vnpV?79Xod;R-RXtBJMKd6UKP;!NYHfAPxv>(@Au5YL-Fi$@hcX%7FiyE8?Uy5^w$a?=&e^1Ku_K6euA^Ua?eUD62YLMS zhoJmkq^<6U-;g$9J$Wq`go?J&@H{t%&UOi7&zd6P9zLASaN5L}PIEk{7MqRh)+&(0 z_1)b5!`7HmIgP}8tEBH-2sV^DlMNSl2`pK^!<2+R?h9pm(UnR({jmX>-35G`+!i$7 zsZKf^l*v6GKiskQA^ZyPrT0g9;{jtyV%-ra_9f__|S zgn7o+q{vqTeC;A}ipy{Ab6PHCNKcH6X@gDuo4A0G5bSt30OxmT(;&7-nXLW=uAkfbeTP2G#}}hZVe37{M9pB{9+tgITkga? zGetDK{1g6Ve-_L6kpIIu3`09)dDg6-k=S)S-j2xQ$> zXPqBvsNt+D^ckx7mEy8TGQ{4VM`hYr=eX5VxSu^6b}AyC+y4_P^-fadDks!dS0@GX z$^x-9?Cx-9GP%L>v9;`7-q**Ulq4>sp?wV)9Wn<}UaW-!i=9zF-yfDdyhNwUl;YbH zGUWY_7QrtS7kqHz2ABt}0rU^R(Z{99z2tm4S1Altj_8w2H-Fxt0$WU&WJK0(ZGc6& zVNAD)C9hA;q9bNC;q<{E*tcJbsEWs+zRZ81bT@(SoYjn*HmMPlL~|HIz&~lt!g;=T zZUAZ*N)y+~Dm3Da1=iJ#A(xcKgC4Vk;>ww1`0FE-*4eV`vl}sA*v4P)KMyB;Sq!_i zO{sQxB%X;XWu2H4;g7RD9;?3wN=9etuYDfapEsPW(6}s+U>>=wAO*5|xigH74`jUV z|IhHMVT@O-HHU27+s+eH86a!&BDsY-1+>_!3I`dR^iF~Y4LsS5{){EHtUv&-sXxAY z)&p^Qhv~qK5IpWGL&n+L3NDBv`a3Hyu2C`^E%L>(qa68kY$aXMWr`9aHe~6dY%XXc zn==a6xKHWTw0mwP{+dw*>*NOnyOmn8#!ZR*di)+#o!G5m*o&Xp9%zqP?rA&kv6ln$2z7h%=SAAv(C>P7TA2|nUZjwFbeJ~&;KezE@<~Xq5iyQg# zm)%R+_!tq+gAnU60?QlixVEYTg0_z%->X7#@2gXgc#-KUtzKyH=q6}1wsYfl=@Q3T z-JFCc(=JZ9;XVs>vMgm3&8f4*?pb<7ZG$>o?Pg3i7kgp9+m+7^czdHAG-bwdel}6K z_TYKQKVV4J4|!vHSvN?ys=_x7#AekmP&n}hJsC6$7wRb!_bWvLTSaqp?$c&>3TLpm z8-h(CktFZVe)>9~85N&9!oTiLr!#J7v&|jy$stw+D+a2UF=+Y+cC~4*mm$R^ZIH?lD69(6va5S{2@n*zjkxy8DC|i z@)Y3={}o8kuHTUuHSpVKnSr5^ot zC|O$%?tWXiiPa_eJj9e7jLoEhqIQ_N{u|^Ow{xpA*t0csEV*BFnZ8rE!|UZUiC^Cl zLC+U+)M8$ye|mUMVk#!h5CO}M@pOr318#oM0Q|C2*fDxGy1;!1EK#kw#+ZA%o8H5p z!DX;LH2{yaX_G)P*5C2Q8~aD`hy!msH)GWca%$mwh^!f;s>Td1{Cqep3#k;m9@T-% zKX(AH=N&9{orepK6hfrNHX6z@_|9ToAbEq$?PYBIWPX8v{_w0QKTMylMUp2u(fYBb zs3WIE#+KjV=CbGeNfAOM`bwCOy&1<+3wXCm1Ijn6q31?Lq33Y$YbkydksvE?^Jv00 zHzXZbp~S-le4-G89(;f(yOZ>By%YNzDv_QyN`jRY7PyQtxc<%UAb$^>AM8ss*2mFl zzZ&qXxrs1?FZjrO&M$0Xi(MJ*@x6pk#TZ-0y-gt6?SePkTA@RBEtsqhz-Q}+6N%;d zG|y%p*4IxZWy*oPN$ITLbBsP|n9&G%HHWbw^%x0QxRw6e)r>|lW{{~bO{Ql>qi5G# zXyp=U@$+V^nJ!Pb*XD3a4={L;FJ!7Ljy{WD>jKDuS^v?#T*e0X9YvDu6=B&74r`}R z5oYjzvplBEV+ZoRwuK+PGXlG!=fLeTW>meq8C`FWCC(l>khYUCqlPtrgU4BFv)vPy z_llCT?#luzQ-YC8<;V_cH;88b#&K6HN#4obG>PeiL?vsvbm8WH;L~pr zRrsZ&2;L`o(3R7fW@0TzT-Dj!&JIAgLpLEv;|N{n9*qxJZ_BN(u7YzXZE;K0SfaFL z9q1qQ!p05@GVWdi4Pi5C1~?Iu@ZH=j#$$OoyNoL+sHVLiD=|N+2&U8x2pZP2+sC`H zWRL3ySj)b9KX>1Re;k!KNoVAi{$S7gG8^$D-uU^FCAl`5&@mbWS6{UwKMs809z2f2 zKaa0-*Sglx#IIerbJ`UsdT9h}y!A22B1L$|{N7!J)=OuQVTLnlCF3WAz-w5@^xg}x z>~AuXv0T_4bJsF=_T4iRdJEs$*kAyg+iqUzVEB9qe%#v4wGYgqyNcLu<}HBk@Qtuf zV;0^s+yPo6im57(b@qjH3HNQg7JEFc{TVWHonb=BY)lT+A`a^h(m8D3o8M+a(&G2< zW(7InNCP+Gqxt|eo>IIcJ{3AU0N# z7v&M-21ssEC7!!w={nXqVzp@kxw};vUN7cwoPsThsmrHIuJx=laT=VMwU9fm+Kz4O zFM~nS7Sit=iZdBwc4E{t>T)*#_q@6ZbCfl~B^L4Chj%b6;0CpKn}uLCp41;G5_GZd z3{~a}`j^c-aMuSr`T~e@=`Omm_zK<_X&~gKH2AooOCy3ZW9NnqD?`KIVnlJ!mfx!4 zhsVvYLq*P6c;d%6;l1Ld^HCao#JX&}XR5ON&N|L9IGntwcZ3PL8Fa|Nopq>rlZAp| z)M#-hCbycy<})whcXT*D?ev4D<2&g4={0DZBuU2XILyr*aIy26)Phsgf^APH`rs@@ zF>>IHE7g3)@QEkKkbrl$xmP1?&~dLWIj>knl~~@epWS*k{n#b=&6wMg9%bA~UDiXb zP=)U^il8h@z+aZsjL!ebk$1jI-+IPdZd@@Mr6ZZYdy%yQz9 zGYuv5OYapdY?ugAUFu-ksD^(($qF^_&>NS~aI*;c?>t8}+T1bSs2O%IafQYwh;px9 zL)_kzw6D$!pG2yX4KFnWPtTcS#J36L`+`-B!Q_P***--2?qa&`eiJI))P(Zz6zDzT zf@)?K5O=GLo|C+U&lCSb&tR({mUTTln%##^_bs5Ff?yp2;;P_m8$itLl7w%Q}}$++FB6nI=3frvZ`CQe?#Y1$fWh8v=GMr>ETjCl*w~ z2ai5_pkg+<7mAZn2UV#Q<2-ohNs+VC<3YEc+2EV>h)Dhss`856TyosWq(wLReQzUh z*hqI+>0?G;d}zX%ebPkmW;3kou}8&Ae8^sPmX4J6#72YPaLeYhK&}Gu3}dp<_3rTZ zEZf-@nUS}yyXn$ZjyQ(-MlK#~L%`-U7IK>f?>b6<~Oi_5LUodCYb@y+j{=aMqCZX)O(#5%&* z44+ZxiI#6nh~`Ie0X#Fq9`>HB^C<;vi{p_$ypp>v=}4b$l(cO;`4JSRRzl>GS-7Ed zGbE8>T3F9myF;z;uTS~HQF|;6cne@k!iE&ZXXOlM$&=xTF>)_;` z>ydMz*M$CXsl%Q)n{f%kLPk?HYg6=lrY_88x=aTA@SSDM%~=2D&PF_Ls063YQu%Oa_ssU z;o7eJzxMvjZ+Q*$IzMz>!}f~hY4jy=N6R`zqA@Lnlej&bbiK5JN!&VW-sg(9 z>fK2DRZ%)4wil%~=!1%s2-%PjjyD~hg!BB+l^Rq&CPth`9N}7?x!9eWe;J=i1lwK{ z^Tor9M1-tbW|70me`Lv>q#iDgafZ!UKaOcY75yfQSl)-kxNn!>-7_}~I(~@zGpB&= zNv*<;%o9-kTEIW#k&FeqF2aV;dN5)P%!IUdFt+xm3Rm6HI_U@e^Qg3Tnv+)pBZNK6 zx9c4+#%(&8Y$Qf6hcewmn{|7woB+QQBeAWwm^+l4OP^{rV3_6wpo2MFmS8TrF@D|g ziMn*bM8s_@?=Cg$Dz{%7FvEKk5y&-Ab89;sq0D*`tB(i*oGdX%-ijO^&uGQeu2SGFe+e(-7hs!90W2M} zliqe^zUYh=c=f=Id(ZBeJ+no~&nsnc$}14J7-$lMLoRgjRF?PIqe)&oyvuE8y@8c) ztw^{?DUCeWgn81+pnq2lT2HDmO-~vYX%A4fEy>6iFvihY3A#c)81wtC3$>KUY{W@B zUJ7?|i7)=>V4y+1_Dm8GmPyHYtVQ0sr9d$CLXYF#B=GlQdM>{a|5_?R+?6Ew^3;Xp zA5G!P=yGarmyG8&Uj#SNtpah+YE()wA{*B}1Lt3?v+s~73FHpaAKPZ3>}Gkgd=baX z@p44kGM&`5U4a)5ebAuEmvpsQ(>WI!@KP#chcA~T>HkGzQkDm#s3lP4vSeI+{~`ng zyx<%d$87Sx3edXHM{6?uS$~K}4Mw8k1t%LPtB&tFGH69j)>JY0BtWU7S1DEgd zBzNI9-zbyi*Th_5UyB)?%{(NpvMz$Fm@&kvGYz??7W#_M(lZzR&}x||*__cV7_reA zfBaEk@g#rfXI*vis%9iFV>dO4b4E>P7ZRJ=%uUeE?K!Jn6zW zNsPl*2uZV+!2@=?)K3tAe*Hdrn%%5@@r!V_n=?IXt2pau7?lB|XZWCkj0sWmOr-f= zEtp@_ob)VaJIO+KELX_ldhBcHj+AN){&GM#+rQN$Vb7RCIDD7&sr(MYg8hsuC6Ptn zt#iiMw6`!QRc=!r;(>zPaYTBD078d3;o5*{MD4p7{as^(>+c#6C$C;kD`FY0dvTZ> z<+Gl;EPaYPBPlpDZp>CUeLTA}R;Y)siz{Y*h1z89(V4V{X&@5ruizW=ov^B49JNuJ z+)+A4GuVD^_Gc!!5HBXMpJ;}MnBRN!nPkR`k3;7I2GsdxPoIZ$u?FG`j5odo?y}AW zyA>N?MpiLBG|wA7&t8Vao!)}>-}bmyXGpl8hX?qh{z(4fvu(rYVtlxu3Uo zkuQ7xdK3Qr=MXtF6ZKXWbB1AU{En6@n8rH^GNEHgt5F0No9=@RGOVk*nDv)^x(rs4 z9o)n$J(4i7nfuozp-Vh5pLsr4h>fNyvaFv)S(PXnC_}Us;8K=7|JNm<*VTx7BZk4P zq*2;c*64rES#$c7H<(3q(1|4{s!%Daz(oe zdGgx3RA7?8a%6hy#BQxKM6>s6*~vcSbmndvKc@*d@`nlew9cp9@Q&^@Sgv=7uKkmQ z`+0?6GC`7`)fkAY7+a~?ES(lI|KulBB>HM;+~H^Q$gT_o>-!nBd8-@dE^r}d)rL`7 z^+&i!M;^wxGZxse80;Hv3%pEr2MJ2XD{BkE_+B8lgU$0>$C=0CO^~f+nlH9R{e*vg zom$m?_|im$Jo@~aJ6vjmr6(tn)rnO!XdLU-dErXTs`3R>Lfx@ZhJ7bX3uwfO8hq2h z`U0NS@v|t)cF7k)N^czmnK6ISlx7IN=SMvg-SL&_Cs?{*J{J{aNq&Y57v4I9*f-}o^7|D0`Sdh*d;d6^ z>D7QI1CGJtzEUvW?~h+|uRuw)a!pXH17<0{gpRhgFpXs~q}QsEKRZ)tz-lk-+G|7x z2DfsJUtbV|)aP*W;2_mqlZhtxin-)3WdhM-?U?@UESQ?T1F^O+JiT`>q>k816;r&h z=}tWi|KrN}zx77ttncvS-X$;>3uIkFs>H^`g*vfpvU8p$abNO~TROuEADUSRHI_>X zSMYiNOKuYD8PpO}N7pgGxPO_TQkEYXdUOKPtR?7|>0Wq9OaSf$?r_1_7E9CmL8;^< z?QL^I@uIP0Sh=d8lWCh5j3$ud+Uvky*&7|D+)2vlCG^nq2ArVwoLkYo7Ix~mVqwZ8 z$hI!0!xkrDG@JmLRXGB!#H*Of@;JsDf5PA^=Ev~(0duY$q@I%A_+rO6Vhgi)+gL|) z^;}(Io6ou&mc`7mxoJc70Q0ms%^dXZ}g`vhncFg89BKO(J4VN9ZXj_TIYRll)4& z&mS8Si4b85Dhtf%aW-%FJvu)YKXZ}Vh?{| zduujzKI4oVtQnhEsoX}2v02P)6v)BgI=B?ge4EpZh>{&r%N$co9%o3J&p+jS@>4M9 zWDb|TBAedX-HEXEC{!FZgiH&4oIPcpFn8bj@*>(Fn?R~%4QW)r0~XvJfK?jGkeN%+ z{kx=ao2rap75?b_m+7u!_S3`%EPKc^A;sK5 z-j20CxYOO8Y&`x9w&!G_=DS?3Z*?c%=W`P(NE`qc=8H;Ch`>*NJ7EPEP34=sadRYJ zIM2`C*CzT&lv^8efc`Y`!Q|9&B>(Fe`l!PcYb}*YVudnf$8*@nwg%Byz=7+ysX?pD%OOvZkHVpQ$B-wTSee{at-GB=)oFATdY~y3#Eb^RNwdU=wZ9N93cL#EQ-(2jTk_ue$D#+H#z#qpS z{tEYhx>K|87;I(C!?dTO5G%pMAMTnY{CE`|z1tPH?{FmV&mRyJ7r0~LwMfq3c>yg8 zu0grVoiMejj{lW)?Tzz028y@pV98y7OpvdK@P&TV+rot|X_wkXqYHEsbo^#|fK2+ZaUS>I5lFaNw(E_f z{h{q>f8z-BsPSQRL;!Ydt%odYm6{EA5EFEJVeQHPV2Nq~<~b?}Z=L;!f=B<@)`~*b_WiZIH#zpE%WP^k=UBq}nPmi&l@eNw&Usl%=BYFHdU#QkHcJgi7!K#fCCHc^6pY<5S_VdW4plkwJ)ZPC*05gfRGlKyAv zf>kd^k;aqCf^~Mx&(NzzEM!t3rPUM7&O4F8;COo4rwM(EYPmVblHt@kSJaJAgw?DI zcmd0H%?UmPCl2NaN|&|bl72&`mwW^FIRU6~@e^c>$fxr=?6Llr6q&Kcnm3Z~hL-E||qk-RNRT^%9R zUQWFYz=C5&PFPrbcp4anKZNX%_0{tPEjJFpZ z6z=EK7Q5k%wi1Z*+ea6N_+V<_8&J@+6fECkj|YBAlG&B1F!!DxmO2}dhw`gv`(_g~ zTQY+TJl@D@jP<}1Hs+kg-5UBVy#{?|XThk(LBShA5~f)k1lcRO5YiHj_sZLtFK!zR z%67$(2cJPoNrlZuZHCC&Gn|xamw=bMJ61|gB~6>H=}seaYOlc z%s$4icI?4U%!h1gOYq9n$6fqDp?t0y#YqBewp8s zSHX7Mi&S=$4`Nvb)GPQ17AH93`<^Glc`jz*k21Ry$j5_hKWDs-f*X^_&JEjmu12ot zW@txNu6hKw6jITlc|Iq-?=n9wy$R>%Z-Y&dqshKKVQ6Wz3HnGRee=f$uVz(3Tt+8n z#d`0x&(v_IhaIGQ)IIR+;nC!+tSmjjc*0WV+GKl%9<2HZtYh7Rvh%SK+8Td^6|_)2ClncwwMdIk;=6z}|3nPq%&m(jRZo6RMv0&1;NshUc6DoK&Mh z9vJvQJUETT)fF?Cyg!YGesafccO1xumSJ>i z>UE5EuI6Tbcnv>&Bhf)ZSIAVE%5qqroezS#XCQa&yNjJ(=0)`C39>b2-#wM7?5?-f zoq7&ig2y)hV|z+K&?+AOeW^yWKUC4;c6W>^VgEkl3yQ~kU^y}8M&eQGHm?>vzGs0} zTRlHdEEzvW90d0tb>NmAg7=@)!LP4Dbn1{hcDu7Kj|=m;z=!NEbX`QKpIy0MNg#>M4bVBBm-zujiJ zfW9|S>HLs$9L@S}x+TcY;|=uspdC8lB$D>_h~UCHJM_F}O=_4o$WAN;??0T!{p)&r znHzw!E-?SRk4lYP2*Ifz?t;tl6|k0ZDJQ5X2($U!j+XdzxiT3znas_|8zNc3y}}v3 zy)+#|%wxH^nWciR30=tf=fcjBAK{o|7{-Zi0+S;-)Wkg;d#5$Rd6!`Bs-rJT&3g+E zyUU>KQUFFB97n{@In&@hjKgzIgB+gM&jr1-!j!GX#KEnU&MI!i4^J;}Zc8>F5QG`0?lk&USecSTwlek;w|sEhwjdEt2t5`avjp zkR!O+(u#3w3`mIochJKCY_IzOci$eQVyhicpZQRp%iHisyAy8r&?ON)EwCy&20uX< z8Me%W7REH;v#cV{`G^$pAF&8GKAj4F)&Eh4nq*wleGq)6yx__X07~pWC1j7+H5cO? zS0^$#A({SuW`(pz0ele$w z{>fOo=OA#ejG%OgbsQ_5hjTN}QHOZO4PfrsjKmJX#|?9^da?;gvD#0amRn$mz9H$d zEa$n-mcqo|a-L|^Q+oA94KCm%!8Q$VTB(?V14DbD$Y43#mUqX7?dOHMib{_UzU~`@ zsuh+3GT$C=Nem}v(^Fv#d$)a|IGtGe{YS$D7I>7ePyP;V;)YB-aIUiy_v}jz{T;?w zsSlDslVh-D}D#t`eLv^xryE8w$t@9T$um%G1Sj1w^2TBhx5`UNJqdW z2(b6U1Bp|Jy#_}s3pfn*WIJv7TW-^v#rS!wCimuhDoqT(k7sRm!RoWtU{Rot)8#yb z9+h7sOL0UN5cx**JDgVFKGjk z>zoFT`{M9KhB~)i-ht|33r>pO0BYYh!1V`CSR)Y+&%Ia|A@lJbAE<<=*dW0}_HOI6 zlJ&c(x`6n>K>VyFPu}wm(9N&x@u}4WQg&t=Py4Y8PU;7u`{p5ZKH7jE_84PIN6UdbaJI^xzjB}npCsv#D*{a-DH4D_VXt82hcp`4 z?SZnoqlkIRI_}NUU~;d_2u2O0Qe9aubZN6E1ES(IO8p9&Jxk}zM0;VcTO<})Dns1J z-Lz>|J385XfK_!DxOKx^?Hany;;CyvwpT^{kUwn*t{-!wuQx@Y%zhQp{OK3>x0;73 z;VPsE*0i6x1Za%G34yCz>7TV*L>urmK_g z>R^ocS_Km0gQ(9}50+DY3I;WiT!W`Mp+-Nr)9x8m?b$5$4mgPpsR^%+=&+~>Zt-ma70 zVx)VZf$r>L-Oy25qDV;LF z!H_f^atOb|NA~~}EFA>>o`W>I)&Ubfi4#XH8=iD4;{x%uh~=KEU}5Bkdovu#14|p4 z_r4L2TG?|SU8G1^(E_A8a^R!7oK6bp##4vh!x>3C(3c^2VAUa*QQt?krib8A@*7Af zQKzHsIAPC3$pd17OKN z_QG^N&qZm7^eB1qijQ8VfnRFTJ}n0BqYw32(Sf^148lN7BkZ2)f%UA1J!^d)y~F%_ zv#R>wh_$8Q%x4~Ucm0M*t5(6vKtEhjJcUF}TuEDpFn1Ogq|w+TJ$Te16S7<^VRVu{u2i-cYU7JzN>J-F^QZ(G z(&r_!&}85?Sh}jf?Fop1!$pNN{A`a0+PLYE7ay2V$F%O?&$eWY?+(bXi${I`8@zva zPrp3o*PWOET2nHiit&it#zz3zbdi25yoAd;uJfO+Xk@vwWw3mYEb;yn zhFeP3!iw}rs?FZHmOIoy($^=P*EBuyqQ6w=Gql?4gHS9Z)KY>IEwS1}frPD8gWeMi z6Smxl)P2gQt%g_7K42y{pt^+nd)U+N&dR^!z!+KE|>^)?QeH&CsgO)$U`$b?O--jp&@~PJN2G-9w zolA&24@Hh{_+$1@?%zDm4X?yX^G=8{cI1mMZbFgFiDZ+fCaLuEL)GM`;QBa~4lplM zKVOneC}!R6F=6CtmJx)Cr&HM>PaL)nNl>R4V@ zSTSo?^Z@_GG47(MtKDCPlbBEuWc!e1;Y%g@!GDu0z0CTFe*BUkyw1nm2gZ}X{9TcJ z3#+DO8(dM6Wl{h2N9^ExVC_ITZ$bT0`Y50lW%$wT##GPO+1Q0sLWaQbs|Fch?9fv$ zFTwYiV7f5H1IL*@f@bANZiBu#iM{-Z`_~7gJk1%8U7kSx`yozuQ!{j!GL>~pO@t#C z*z@ZZpXbEqE`gP4|GC_W+D`hVr(eU(Zpk33jOV3g$a)pNX&&4&OLRA{5R(wObr{PSzpuf zWXcQPxksgfxx-tqSN%Wu*Xic;I0yrOCBpT~n<#Y*$J1*o;Dt&sXEBxapEr^`1!3QsXnJJm=Mf*qgdD5iuGw=ndgf{ z#E#rlUqGz#^j=v7W|3y7D`^*u^lrw(6Ew-bkze5N zU;t|U?t_24th}$Rm++t{k#)1?dDhKB%u^?lvCXhj!w)rm?MQ&A4PF1b0dED};XPxW zVK+P%Vdubb)|vbtof_PM$~KSTQVI_aA0imCJ`a-S^wTN+MX1b#@Fmh~=?`sNyk+$l zbSl&!E)!97vyyNRZ)k8v@8gz4L#vCwY7# z1V`J>(Hf~@+`QP5RGiVK??oIiDoB)k;(3A2i6AsLm`-#n_ET$FE7Te_jogi_;El?A zLDuiOX7k7VGBsw0rvX<5&{!wWdTFmP?#)f;yj=?;nV&?=_9!eF*hfd(hT_eR=PVfjgro1IdwKTyq1Jy+o zAa&Ytfm};FYFFQf-=Ds~r_fM*dH(|NdD*mW_#7Mz>xZkk4K^F2-Ehtk39{X&7M`#7 z$C3?t#O>nXGKj#8SHiZaGt~p|- zV;87=bODDLe;k=EO^ny%(Plkoyw$Bv4s71Z+wzy-z(WHP(0T)|{A$EQ>F0PAN5%=v zWZTd{JOT!fj3tc^W3cALD(Kh}PoHn>MzvnX$GheQtG4Qrjq5IOcTOLqSHlDG;WZhe zsINc=94ztpTsd;lSPg8Y5swTSkTpLJ(U9*=*d2bJS8;nW*H`3echhT-TpurMd$*8f zem^e-nxIcN50AtMjY}XMJsGCw*?wOjWuX=6~4)90_A>3zCmCUM)sCO z+%m1*H3qlzRY0Nj z4Ei!75`ALd!u-^?+-{bo4V?H3n#MO$8$Bo7EUivV@F+3}Yu2A*H&C^jz4Kj>H~tnx>ZXCr=s=9il_4wQ*U=dV zS;sf)B>BfbtSlZPU&r1N&U2-S8JHX&%}W}8NicRt7go3}goOzo!Rp%_tmntT6TMCJ zJloZeieCiF`$1f7f-iPvJp|>dGFZx{d|+oCoR#7C(kJy#^u$qk-Vpk+WKjNXA%p`slhrc5G}9=Ac)Ry(GLUxQO= zr)aZ^7xTa{|HyT9!I)D7Ur$yf`_8Aq&MejkaSzFc?@Q@Bt7c4CbAdNpG8Oc0D{1nwJ{;cm9%^2D z!Z$;LLtVK-o&3352>xt;Cfv^(6adX{eTP*RD)1^F@$ir$nZLY%=5;vXJqZi4SGAL$ zoO2&fI@a+#^wyIVri<{y7BO&cv7wvA8gYu-b=c{@2^7Z7!u?Du{yFSCUEJb>{DHHyFu~vAe=jM8c7M+PwNvn+?}OQc9hicb__|OjGjjISpNZP94o*u z)`2kphA)+HYhZnsP0%M+4fWlOO~g38+m7$2QPWs<&*T=ESDOoBU3s{9><9SALToDW z$CO>#WYyeN)QH_FeuY|-KMxOZ^O=8gU0i&1Yeg;P^7ts)%R#;6OTozTQnvj?Bgu|6 z+T@~SG%o#F1bH*J(Ya}JFtGF?9DmzjvzM`O?Usv@SeI(}c%1#sEhh>0_KW8j2l(YA z;hdMdxB_+Ewp7b1WYCO`D`>3i1kXjM!d=msC^w4TLcO2Tx#vr9=z%0rTx&!pUk%21 z$tR#%I0a7Tu@17`Uxjo2>?|h~}BEJl%rtm@!%j#R9n z0T+*RfKUDDkaEcxH;#6L{5Kcr6768z{puvdJO~oZ?hL`Ba=q}vdmczi2H^aAl8ken zN8M)6MPr+3B=B(o@4cNZKAb+2Y!&H-k?%L5q~GD{*0DGFhl`uBTgn-<2F8%M*)cd~ z^dgY>8b|;0(IY3e6bg5BevK!txhYQm-j=2A3vF<;iX2(N*MI|z?biBZI@xtEpIVQ- zf=-kAt3y65=Jx-IKsXTvCQE11AIn>CQIQhK`LzpT#@J(ePc!^CubcX=@W2Vf#K~5v zGQj}@f?{GUN6&QfpAOy_#IVBC5AUFbX>30?d{X_r?L7M|+^}kR2lvmH*ltyYyCZAB zdiX4U&IzWMwvHpMJ2Z$5%e00qz9-aMR$2Jq!Pw#Cc77VS=T$fOgIa8WLTdmzg)8K+)x|M)5k%sp^Hmj?MX zL6QzM8Tg5nUn-`RTft5b>kcdFv zdC%bDl~)|YGvko2e0Dd-LoPa`d7me=EJ{I}Cp)Sm?8nh) z?kd*hyFugd8t8Pmgp%GYcbJ$~b2Qoor9C@f$I4WQJ~juhO_nC+)6-brJ?q?IoT%;v z8QfvsOCr$h7HTXv%G1$*WN!68oqWmtPP}aE&GerSus0(b>n&oTtZXM0+Z2W$9120q zCWzaW;)fl%tQR%A9D=tn4z}G0qQg1T*ex8!(6MA7vzMFy%o>+1nL=itDy7AjT2Lim zDc{dj6Ry~+kU%bOpY)CAF=?C`TjBZyR;qA99g zC^Jz^xSyMHh^(NTc)Ur2pk6P09b!e+ACITuk2^3zC6jObJ_9V+XSCH&z#Y%4pwm>U z@Y~-~7@X26xK_}GeeEhlwn&6@?+d`J)whKji`C#P3_kV~6nlBRKVO*tlV#INSZCfJ ze{ZbLw<7JFC9QO8!a0{W@;7Enk%n1IacliU?#;L)x}>!aL!RA-x+z|u%lIwZwrvIf zQT=qP{YCuz!hj6hn@ppQ@K8Md4eS|Eg2c%zce6;Ij4dmmw{>Qr^L#_{N9}(kop)T0 z?-$2IQj&&Qnv#YQ$!I+HxlW5pQ+p^QE7>wCX`*OJglG!MsAxX-740Zd$qFHg`r0$& zcj@;xe>}XN=iKK$=X2igCgJHPkFZoRL+I)nPJR{o?EbyPcb{A*2pM;uAs5 zX(0}{90o0wd@5<_gx}&@;pd84e#%)hd_C|Lc4pf_j*2@jE}SxWr=RPFs62K$Iku1& zjNUDQPwj|8v+n=6?rme~>^oJsU6sA>?<@l?b+!xpa1;)XIZiJXIWQO7 zZBSQUz>B#E@Lo|LOf=pBhQ^*KmdCh!nS1D8;)Ms6nG*8}Ib3|29mX3Agi8cMDirL; zC67OG$A+HczgRrM<7?Z%(_uK#-?j`-F3W+F7h~y0eRfNz{}A3TtTnFUtZ?Q1U$9N2 z42sV>;%8kIl35EhP<0-1@oMC_vmItxvH2h)*{X5zMqnuGoM@zq7x?JP=E zHRjNwh4#p=Xod$xsxYS=afH)HP&u4MHAU@^Y*Zv~8iw&B*j@0mY;|&YXDIB;TaOb; zT!rdt=5+aj8k7#31wS7}!o+8+ZoeU5C0Rh{j4#5O3Zmrq%|gCf*9QMO-ek9o4v_8Q zg8l=;N!pK8dTqv1T>Vm$)MaM~=GcH4D?|G94GJd^((Ln>mK|Up2rh z&ZCHpmm=e91M5$;2k$zke5gTh|03bNTN}8sk}ELjo7-Rw7u`~erHQg6ZF>^T7BjAWYEi*kw|b|q%0Y~!x2uW+v7r61EMIMNEdCZ!T2AA!oAU#VC-?` zV^u8X{@n_>KP$z!^edpAzff4ewH}X+97DQ}sFCn(E;uK=4Xl5K(XeU<{Gl?8j4=!2 zj#Lk=~#jAm~9rF5Xqxtm=5fHTqW!XeT&yK1?jVXF?Poo%C8W*A7JW+CBMOgXS z#+#`6!ICVu8bT^-op9@r;lyEMFnz>wK^gXwi1yrr+=qs@#7FxMoSx82OB)ZM#;hQr zU2{3_`??E-)2$$_Wf;jdTZ4^Xyun%XFbzzBZ{-N(ig8SCVlA_};xKL|j{5nFDNWUzkKQ=aDl%+gh^K~+eJ)ndgF=3p$<||qg zTZ#t`orl1ArZm2lG3Og(Nlbe^chwV1m5l_Kdr2Z~#7^CqM2pqk-0 zV*E;kG>l;E)9ZIZJnj^|X=sHr>b}F20T6tycEpwHO61<}J1~j8uhF= z2r3<^bV#5*a_8#7_v1XiQjNoprakb_F;SYwc+^TNj8(Xcv7>EJWZ4{Y@J}lD=z<+K zZYUS(EEdvCyC^JaY2oy|a`-4=1I7ehg@d0yz|d`L@agv~nD!%{mN8DnccnIncd0ej z%(KFH)-(U>$#<`C!+R^(yX|8$YPxbBepFE*7dF4-lC#!gPUl_W6r*4&&34dmLIM7( z)q>BhGqJ&3X>cDp`B5S67ybsTSUq~5vBdu_y9w4`CWEew39gathkq=@A-_HG`Dk^L z`dO0KXZu|F8ET|7I~2aGS&v=b?ZWgoW;A1GHI_b=hXU6~cxYsWy8Uxuz_EZn9Vo<- zx4*$WtB^On&+-^kn49d01MFuz5qtM9kUb}XzGAoVB~@d{`40(#R>o-wQCmPVzI8K} zWesL)>G3B%jN`{uSL0m;1?c2QlV$hUqJp<0X!~uTka7=WmrfwxPCA0i11%!5Ka*Q_ z;uO7j&l$T;4kfwIuh_z!U|zyW zrZ#ZPViwI}e2keEqeyLW5`45a!=g_W(7UCL-u+;QF=BsUmc})HuA~v>WQ`wnaZLCi&gTC)dB<{8^-b_9P{*_DV_e*wo>P;Q=4fW&9J?4|Hfu~&4mk64tYmXc3 z6v$4Hpa(7^nht0YO=TUBhZUGVu}S!sPoV|lt5NK*JRI|nJUJbEhM#(L9=a}8ArE%g!oZ$jjClS+s6S;a zAgz{`?w*i4^0r@k7WG=ZJEdOHKItmpR$BaVXg#bi>2TMajL;y)@X+2KAID z5}Te_t~ux}$=}>Gm^1I07loI$zZVWqy2^W}KgaTr*|5!k^(gvlQMu6pJ{BLQEkz;N z{IvkSNAKVc`8cC+MH7sgTntBx9PwL$2)W1dx^r#{a9jQ;vcdTocgoioTivFRuC_vI zlT(MsboKd9OO;{bIwc%P4CE}nchd&{GCW?G3+EUI<77k#%C{B3+p1l#Yl|5+Oca9H zsIxTem=|srijm@BnmotuXrdI@JQ_w5_ZnfJzc;{(zT#lFgPn;wVmZar|9$b;w*6Le#DzW?SeYV7vs`5l(w^u8^O z`}q(zWt#KtEn%eO^m?4-SjxS9B%p37b$B(l5Pno01mj-zP9b^-9>wQVPn#YDH$tNcM&1S-lD zaFIlgj^9#+N45Wy$Q566dYySjCd4X| z#JMlI!zcamsk0)lzm#!=meio-(c$pl6)kZ8H4{fEjD>ZYFX{OWA*l8@4?cwt@cJv9 z@KL<$Xrz5~T+6o`8nFdY=3uuQ^2p;dxgSeVt{^ccGj9Gad%Ca5d&0=S~TE`fP zvZ-`n*FxN@EIU}+iW-}Mqy#h6#6Sz2H7VTOag3kx?z~_x2EWOP5@De4U+1N(M z?sG#khaqHNqL9D($^Zr22=eZ&6^!5Lh`s0a$r$-0syMmCiy88gUI1t8t@b@93 zVkSf3(Qx{cWh_Nme%pP+Pk!!^YFxZ2oUbu`3OX!5R_v0-tva4U_XXa-=_%RZwIqil z`qrk=JqK|0VGomoZZ0@3z8?PZwO&LZ7HYhP-CiABlMt{kM3U^VDyP01OmTOECRw#N znNM9}k7`CE`Nc!CnU7!}?n^J`zWT)q_ibpwTIM^NQL0QtBbFgIDivCn`Otyk%v+Rw z1I}CdaW=JcNv6sJ&iY0;ouq7sNAky$2iwKz+n4$nU^{8>#^0=FCAQw2z<*%gsJuwV zd#M}&%hMCNKRJH*{^1Fjk*`A?_B)``=xUg4_=x-U0dd~B*I>|CO*!?&m>NEoJbZnI zPht5PZ#^ZV_tF+hba&(NAyfI4jdIkovKsk0!=YH@DwH<_qh5R-O!J;wu70PC`3q(e z;|F~(w$KX|Zx18G>ci<)_8bYFGLgs!#c>9;Z<*J(ac~Z!_dE>6yr=UMB(Cr)I;wHG z>2T=3&<&Bp*5L_h3+SGcOcPjcbMv)4=&cLnUT;1%_Xs=$c_$3WWL zf=;*?jOtI$z|7X2Fsj-N_k|Qe%-pk7=b#-9ll}~{LzH;MBnw=hI+}QzM8TDMCyZs^ z!{V6Dw1MRnE5tMSe|bgGde-M}3gn*nmC*G$?Aei<0_SR4_~g7`j0-yhe9;LolD0*= z(h6AUpTaT~R+u-?4<_0~;2`gf#;26YqM?uBkdh^qp41`fNweuM_IvN$m&rT2h?COl zAUy4Ugxew!Nt@NBOd>|Vfbv~o@RD&toTWnsvo3d{mZC8DCJ4VN(;jx?pYh=tB>5;n z@@i8wlN?3rH)hfWF^kb~=?pSU@2>FIxK2DeuZ+Je7eQ`I1mG3RSnh%jM?d@#Gr79% zK6H5Uuw=?2{Jtat#4qI2F)^2M%q%rBv3?4zWVbEOt9l@Jk^{`GamGzj%pY2tLgzQL zd$G1zq*uI2Fu6klheUoB`Wbdp-y0#gbaOm+WTF&ZW><}CwN5~Fdl_V^+2L0j4c6~c zsfnor@?Anu4x7&ph%y{m@e?>LxeM-#J7Qf8o8tvLa<74#g*mq#PFplRXw)=o$gN}jm*t(p>`KejPd3_v`5q1GiuQO?Gx^OoE9|c z>*CVgBO!U!OWMP36)jjzST$sTmug#%GIyJxw`nFEDl}oY3@-+2yB5n9>YtYxtnDIt z#wgOJOy&*`2NVy$U}HzVXNx)QbE!t(@12~waU?iZvRyx@f?II`z0wwpExWVfyIwHg z&e*WktA)^-;{=wTF8HhO2Ncj$8XM<;NgKuy)9J?q(_PK5v5?)ooNk8~=8;IV*71wK z)(dZ#R-yIv$K1nADKc<(HBL304T&9 zoEpZ_GBqQ7wrMyCFj0aPX9=ntV+>)oyOh3q3+ofE@^1zLxszoMrqPoE2=6a#GUpug zQAW;%P%n1dVibbsgzV6*%n&TcnPUv=qx{s`X=auiTBrPie|7%zNyZb%6enxN9AF`H zZRo6rcIc;fLzUdH?qEXuRN$jCL^PW}|lQ7cDyeHfPaE@J&j5Weoqf|B=* zuzHg>&i=0+hL4V>n}0I4gVuXU-4Vid9bHO%%9IChiw>|p`MrfMv6LQ0#~rT5X&x5` z>-_QP)%g8sIAjO?jyjIx4 z{4W=5GGU#&B9YEshH;Ha@O85f9V_XH7p~WWyX$6d7xN7G9B<<^6(Z=HP&<_PHfGQn z=R9IArq@jztn+;*S0L@Osagk~^T>qqBzVu}ok|WxKb)GZuz_}a$z)}dKO6>PrzhK;8ou@@_$<4l6 z=n3hewdx1(p7~Z@>RlNx@wN`fiazIhpckaPR^c7ld2o~cHb;nsV9)Vv_+1>xb*^i| z$d&ANRc97indOX!$NzwTJ5%*VzRc&PLQE zblzTXA@9_C1|;G3*hVL z^snnS9KQcPybPX6y)s4JWC_wtGihy@Et-l=Cmqsl!o&4XFg2i` zmmeQVJ}}-0F<8$1$M`l)x((GG7(P#lST<_VEJte$ zT+ckw#x9T=?TlVc<48hy3e{NTjAjwD$#aW4g5gmT7+W-vA93|1ZB`1!6>C;=e1{a> zv9}K8BiM~+hmh^XZLrlZ6ppSxMyI$j&l>CZ{?&P-rGU@QKY&+0yWqu6#?|+fBj+w{ zVObFi^cuF{!4aKf2@GJml_E< z{?>SR#W*OjD5N6aSRb-I4bU{0cQmrYo*CCbLVO9hZ*xZR#*eU6ER`M^W{#K6NHCvo zoM6)!C)9nZO9Y2s!3nQObo`mbXH04k?#{2qrK<`!z1-2Hvvw`^Uz`TUbJ%=_-5n1* zo(4y(zjO8*HOYb5hX>i_Di1s`q3=6Po-m%O>KftB`k~~7z7i~8D&3{ps)O$4oP+yO zn0}PEzA=Tne%rxxhCN4gc1oM%wfdn$y%zA>XVW{=nad_64fHY%A#$xb{*BFtS*zQr zr;;0{w|rr_ej)$p+#=jMXB2U-@_^VT7o4fde51X|wCr~+{`~rwuYGeFM#gC6|3;}PkXL?;Srk2SD~;n9@0F|a9_-= zOUqHFlG;n{SW#a?_=w1&IZ9w9uPQiEQT5@G1N@x*zLFFI7jf;B9qlRLff`N%4W z^w`FgJeg0D)b9*t9j&(5V@#GT0UZgtsm%>z+UJnXVjM)&EXQ#zLHx|EDRkcQYMeN^ zfSY+Dj%(QNhvlttaCnmroyu5i&)Z5f zo|T*qabCKbF?NG6{X#5Xnl^?SF~*Dd%`2Sl;v%@+6pW#sX~3J$EiX!~$4K{C#7yN6 zENFJcw7@TLVs9vOAeymvLkYs=L~%92eT1l256!rMVbOZL?yv7A8 zzJ=iERhVV14O>4X(u?f9FR~&Hj*ZyCJ@LGS-nny#;VfNJIm#LJ*beKTw}KtEW55_? zRwsu;=~@ALPgEj#>x<~E>$SMC=rJF6NeP}gD4}xU=)t|}#|ITyb2)}FG%To>RtWRX zr@`(yyC9$Cgf-psp>+3IdTY5os|o$^ai0>uXfpGM#;~1&_Fl-~83)y3HVI$3h0ap1 z!^5hb{E&fAICk0=JN=EgaP?B=)GkNm`U8x;e233tcRezf(_p0ZNodJ%$9;|z^czmm zS@*1Q?}OKnIuiw2?0Ncd#U%1uwG%c-GX@=}O_qu1)7*+$EWY@dH;5leieLjKPjcfl zp6#NE7YP1+v=OX+KBucQH>36XHnwY?PLFN3#ti@0(0W-N%ubo2c)mDM3CW~GSP%a> zOPkb++!Y3le2%Un1N=+TXtH~60IF_q?{AQR@ zxeN2~?ESHfwfd5KWw9MiQ?hug^(+r#Q;mD)M01}THDQLSE;cpybN_mHK0Ac*gi{9R zGvT!kXckfc&kv}9L!c?@-?$H#_hr*{bJyb36crLHGM4A&TVnlZHivJC0Z+{hIQrfx ze*PK@dg(_M&i)z2iTsQJn|9_@vK$HYWFhU22|pf+1>B?!kRlWhYsEE6(Q*QY#O?w8jr^I!m-8#*tXsrn}6nl z(7Bzq+j*dr{6{G2;CcI7i1MdINzT+Iut?tzM^_n=k@csjNpm&2nGB;Izb-<;5?id2 zlHweVPtz^ag&6F*7sN(d3rBtGz#^Xd3hl$-V{x*c{`%5CF>1s!?<7Z zz9cA5elWW(?qY%CPO1&=Rl9!F;+rB-DmDB$Bxm~JnBR)rllo-3zU(3HU6~B@aVghf zYi$~sznSHvJxsJ&UoGQXHdxP_SUy&%whywfpQ~C!@aFkpB;!~)UCx}FiXYU-%*!c! zu^sbBrpEFYZfDa()qOZ{eF10oG)7n~&3GVH2OuO)fxJ%hMbWS**l4$ueyv)D3no@V zV%$#d`bqu{Bse zY9F_ly&G>+_hbH!{qRszhq*tN;3}meC|uCVz3nu?Ir8^mX+RC_q7E3jUz)6)k;i{b z5U^fIfwYx7!}T;aA85(topQ%egERH0H~j$jI<5p}2#Qhn?gNWkMAGgDYeA&~r;n@%6dkB)u(?%X!sD;>E8I`YaB;--q^2S9vkVQvSh~8kG1I z&4swVg3gvz`1B~-;V2~0u>nmeuJ;-4>eX}A4_WTlO^f&+)FxeDo$#YhAJl%bpyEd? zSg$gIpvD_+?F9iU98w^|V~eQjiCRo}AxD#rD8YH%9%3iDThJPJjyWqUP-o7T!THR- zDYvj~{#!`stOvtNb9|bf4M!fGrODeIaRT!$Hhxp)Eg3iULyX8E<0U4}2^Y@)LadqG| zHg8X-ZO^Q+WyBMBD2;++_wDeV`Y6)3xfyapSO)LiWRkKg`P*kcF9>s&GBoeY_K?kMfBwPl$W4Wg^jC~zM3oV@+3 z%O`#-rv(WSxOmn_!6{2QdOEWfGp%<(&zB1Lw3Y2fudIRl3CC#1TMty5Pz2@Ifp=#f zc~#dISTsBc41O;`*WsfFnO%v|h8S%zj`Zrqa_>?c@a5brUVS2^Z)Zf~0+DY5vz2G~ zo~CM45Zw+N?!AS}lIt+#KqT-t66h2?PyA|M1P6Mmjp!pYLnJasyplF!dq#FW*?CS%N)@ zEsz>NkM2*l$K^-z0OM7mwb>L6k{GjvXT5q4+mBmHl66mp@lDgL*}KDJk|T2vRDP{T zo!FAWnauMyRg90S&;9%_0-~kZbA038d-Rgi_`ZS4W^9$G*z7KmPTlw6#O~OFF1`~(O7n zCWQ6UQ)Hx}LSY>}BXb+qM!td5EE|7z`cyKya6e~u^91eR>xp^O`{CWn@ib_jC8{@x zku41@cVc3S*`|u*!+qwJd(eQWt3*vwwsHxst8njfX_(YJo6de!jr}4|p;|5xqNq6< zUC4y}C)%kFUdE%FInpPhKt-;YquypwB4XwWDmKfoz*e7>emg-YNZv+kLpAE8Py&@_ z*zZW67m%RS)PnV0v5Nk%@|=}$N^UEjy7msTm*|jX>E77R_ye;=qv`K$HVA(^!E#$L zck-JLIm7s)|K{!Pj3akJPmP%8{pJh$Yw>800<9hB0tG!kT>bg3pm|R+wal!>#-?o$ zAd}0D_OLc>v|EK{p&lkdW{k{KQ?t5f)wO%8b3H;eb2mqU;HRwKKD=b)uQXn5l$9=s3&Wipeb&#%DpzP<2WRGVhmuEg@&<)9Y!A7{tzaZ3K&h4*|7?ceT% z`YwzSYMIXu|H2sB29rq5J`dRScNe~m(a&na@~AouQWA6d6gIM|4a$xTBQH-CYt)W8u6kg)i4Z!+w<(uIyPL;bf%P!|I3`JhrD5$MJuoGREML3AA;<< zFHk$n3o9mG0jbb*8gkeZr|b1XO1qt4Or|gH_ZvItCz4?KpCY%ZByW}h-QZb+nyT9L zA0J>=;09EAoghdavzyM}QHS%dv75@L^FV^#C2dS`9Gtg{wrxShuQ%ZM{26qPlNI_O zy$5nhli{bW8Ct~-Ayb+%Y4lAib|0-us#|UgSjY>o#D}?_5Ov}rRre}Dl~1F|Y~!i)>0{>0&bSNL1rBhl*ae>+kRs37 zEptyLd#77JnT+1qAaMKBMdSw-4%T*EwuoAOH(ZdDEk`3)*W$$fWl&sP0nVnjD4Mnu z9;>BNO?yuqb>JdQk|4a#H-g)(Zi0tG5Nxq_!g0=$gPu?e#y!}_vc!*;$8vtGj>TUn z<%5?{dQ&12FMbaf)R$-RqdKZEeuxju%6$W(P40M4#vigSM$=|p4?LWeKbT$TB-!nA zXcxR@>Gc5m{O=AqKaptn&WPhs& z@9V)BYkS9&vbG3_@7jO~%Uk(M$%QmmP>nSAhG62VoHjAejGydKVwn^#&}?J<#!AgW)~+yMFV^`3V@g`B;KzJfa_07WJlG}%&9gSM=K{;_20nqU1C}7@n@WN@A_utv^{JkC z$^G?UZT}@}g6jMqC@z`|6SkVLT+>8yX6$LIKk7Cb&Yw@^yLNHXY)5v;csQI$)2H*7 z)Z;4s`(TxD7}RAgm?Jn1oVwa+-OnXx?f4Y_PA=u~u>g0^{{df4+d_@3H%304LH@ow zMo$;A{b1^BdT}>n0QuYDO5R3bA(u`MO%&qcC9d%Nm6cHK%q^6D`WU2hr;xRU-Way= z@?dS(-nkf?*K~lcS`fD&b1BhRmK&VCI44+RtAZ*~kr$yBF17fb`2fqEx?oJ`YUI-W z1O)>}s7`w=epd8!@t`8;3&(`x~i~8W-5O}!4a>%E#+eZbLeGZ72eUhA$X?QAXH{q@$ikSVR5bk zIjFrF!-IE0dj3jk?B|QY$ptX=Ss-T{Wk@FNt>(lYL{SUICz-cHoLo90PF=z{+}A#i zWSp1^Du;a0x2Try8+wF>cGTcPu3FG~CZ3yU@5gq9JK*OW9Xd4M6z6I*L%2*W9j=y# z@)^G5W2ht@y%O;LzVXB&)D=8hcj6M=$GpWzIl9lS8B6kS2_7~Gq4IbMzBR6cjpmW% zo6a`klZ9%e(?EnwyXlJkE-%KV6F(w1xu_Nv7v7G-KiDr?AGMfjgdBjTg2n5)n@=GPa1_ zC5?Crxkt^ZPmLYh!-|uog`c^VOPS-iY#g!pQbhZg)nUtqS@g$zWf1x);S5zpLHV<8 zI(6|rER|7!!a1WUXU2Mif~U~;^d>xCV1YW7X>elZIT~v3fZ-93A%3VbFEkb4qK)6- ztWOB&COG5t@0vvP(q>A->hOEaEczVx!f97KtUPZc_*qp-zj_E!@3br2J>SarrZ(gD zpHCpk{SS;}PL`7Emtf_WbZW=Ghd<(b;bn`1pk=-%Iy{pmV~;!lX~sjiAkZYsW*E`! zUCp>kc0RQ;mmww>)?#1%YC)mYc3L%1hwDmLfS&7ou(?j~skr^%TwT(B8=7pm0Zk?| z>D8UKSQq&Kth+Se(ic^{_WHj!NnjVawu? z#IHh4kdf<(xw4(`Cawm$HQlhbdL%j4Zc3$f7vl38c@oTh=Vp5aqT#_Wypm)T{jN}p zPp?cee(R_Wuhn&N*n>juUp7V}p7rYO6_EIB9u2s}z7LD!N&SgbNL*}&vkV*H`;Z*E ztSBEv#2Ld!!HZwl$g*2hmQ4Q{2DTqI;*F{A_>G?y((#Nv7+bGk?0z~D^qUsrYTLWq zF25q${G$XlO@#o9O8B3?x6tv0A`!OThT==E_(8rC7P=g#@!rhi_VX{Sa!(K(s$PhT z4HSsUvHL)pV$s-Dl3osK6K3tNL%gGC+;mljtX;Vt2l$ViO~ocUMezl0_UU0g#!}cc zS&KBwgmLSl(`bm`5>{u;Aq(Daq#pVlZkhiXx_wkYZLS%f-!*}BuSsV&`*e1Go9mT)Jy`4K7M)fclAvus*^9^Oqk3QLB5@fO%}~tnWk5>=IsSkvU$m z`3;+sUEq752L_+jBCEuY(qmrrxV>;8{XV+@RD$hrKqkwmQ#qa9nAR|^mm%X*ZnP(M=b4)5ahH<7tVa}h+n-TiH0<=`>!S?W6{P$&QO!Nl{c-0 zD>mA6;DssvY_13O*|l`;Fgu*^N|fBmJqRVSu5#far)=Jgx<82XDs==|R-yJbI=ST!Hu z`oj8&m{;+jZ*FX9IF?%trDw2!zc_|DNuMhiE4}K5QLomcg4rjoy!!~17*mIDTPBj& zbvne5bHXJ_58$6OblzAiG%FuM3Lp1#ft14>lQHD??5p&6XgwCLaiJY*Dlqm_5AkjD zt&mYXPy5oNutoGQ_u79HjayNLH8(4vP`MJeUb8@>SILkOc8>m8?SMK>ci|titNpJr z<1@d5bM?W%x42{Iq^TrnK_IQlszr_c&Q!1^6to}O;iDOkD)JYU(al~_xJ~po*C}~~ zecP z@2my%o$)hFwAn)UuT~^WbN%sot(Z`c@lWPVtHqDc3}JNkTxf|P7};e!m~RvWuERR9 zOYmf}CjI`3F|G?*;Ai(#n4H3RYyDqg!thM0(QAjTM41e)X%n{H&m-^781mO1Tf?O* z>v7FTS>eBYxTog1P?4KWiq&1AlJKO?z-%GT|_bT>I89|KSY0>w-HW>S~3DjP@ zLIKMy{5>#YuqRKcW^RSII>eyyk-%B*1=)Koh|hRkL3gf+z}(>uLIp)RTEk{v+WcHN z@}vT$UAMzGZx=!FwBt0;k7d=2GokG#@I5Q7@mpCVG|Z2LzE?|dF1v#`bZZ-RO+b{) zlp|ZT6S(N_4w!zuhZosP>GR>?n03ci*k_c%e{^g?wM-7Q<9@)8)>XL0*awm?#8JJr zBD60aPJ$Os7F=Rk$Bv2)$e3LV21zbB@uCLExOW`kwN z%eml$BI+n8#cYj2AYmnZk)R2WR8Jt8SuL<8#tnnoJHVprIIUyscl`7V^ji`IX3>lA zKgPAtGJgOk%A+yPV;l`=x+OFZu0qLOCxjlgQY5K=J@z->=eFQxnp-@|q+`4|nca2( z%A2N=iS;hrFRT-4SsGN;~ba%0WZuyDpt_trX=C=t6zHjnLrUBNVVB zSDBl$$nmefDCKbmX!kz4WH-y9HQ$0gQ-ZmzuD(RFWz^ujMQ`C^d`1<>a~}~pKkz1o z#4Mxo`mZ6w(-jpKP7`)V$I_boDtstC2fAmU;dZUFHmxi*Llu7ylN)|Z(REuk{EBm? zQy#KRwf0>&@T`}6&HNX~Z+?U&8Wr@~9>$x}QXr8}Q~7{IM^yIjsL4PLa@*5{ z)3@Ig_Pe)Wd=_-nV5Xt*PrTb88>B}EdrsF^FU;HoFo#A?yB zajkfLyduk9dcj_HkCPf*1>=_2QY8mF+^jm3xZXa?o3VSAGcVnmQD2> zCrUoo#c^Vz`-ydO;UJH(q%{IRsL4_H`a*uHUkyI`eNq@;{tC>l`Qzw<4sMs)5&AoV zajT-6V9A?iPUU*+4|c~?8clq{s*o3U_~gChU|SOEZSnp|Dd0I*o)dOPk%9Rv5z*#su3lvIrApM2NzkG+t-sO04_# z7_7~b!FQoEHryFXk};4*shOYk@2D^g}79oA3CJWYiIpgIgL&=;8NSEGcEG!#o(kAwvlV+?faXDF9xqdG_ z`l=SizH0LSm;f_vbW!o{!NHmN;j^XKrEw1OUd*SV?zOmUycCHKItJH%n6ZAFhw~e9 z=-NfL7(V(p%s)7k?>fX7$hW5xo9@$Kld=h?H_1`g1B>Wa_8rcv(&T^CM}dsC4Tdyl zb6WXD^wOC!Tq$)PHasom>lusV@B=Aw`fMW{+~bNZ7hB*T7hS!;8fBmVfKtc90+)K` zu-i74Ok8pw=I%IvAFpe&yPOu`zM?9eXR5*1yptl+3^!o>Qp(xHZK3n(MwytJh!DNU z2UsRpi=4QyaWKdD!&olJtp9Hr+z)nlX4cDkaf0Hl=dF_6C`EIye|PkBe7i`hLcf3&o4 z!jD^ciS5cAo2L*F4PQLI@$}&Rk>@5G{Pm$0{&CTV5Ah+L_2Pqb6|*=yJY=Lmmbee4 z-(wo_;q)EUWY#PAPu(5Gy^DqFmkv?^%aML9R)U`uXSmA>J~+ML6!=VYp=Ek2&{Fg< zYQ~TpzSbD0I)U7~n995MF@}7h2<3FnP}#m}w6dDYdoj02k6AU2 zJg)>5i^mc7DQj?T=n~i(>PN3v+{09UB5@b(<0O*|$d;l)&i8jDy*$+gZ+HwNhc}I) zMw1Ni*Fgy~G(ipe*002^%OvSP_uS&tI{fdT7XPU~fxB~I1s)EtgOks+Xztv57`k*K zSrp{MTq$O_---v9tXg{JiakCYB0?VAJI8C^aKqVhYQ!gLEBpxBi8oG7pbuWiQn&jx z*dnXRfBJqEs%Mws)68?w>KIkN{#-j&{+vJ*M~@(pMP8Uz)((-@;k2{V0pDbakog92 z+}82^Wb2H}gSqtV)6qD}Y6`t@s+iYTt;IdIntYb(Ysh`Q4qXZ>xY;L?=??c7n5oA6 z=JsqqJA>sS#uvd=#t7)JcgFIhX4ueAa- zEfYe;(x$+Fj1MrUIZ}A`N;eHpjldrPt=wMok<@2x6=sVUK>qkj(6(KOVbzDg>HRr+ z`?Ed%bZ;EYv1Amp+4!!ZWZcv^s8e*t6JE-LbMn2+aVgNgEG&OrMkAI+qik0P7pa-T zFO+XaK}|WlN%#$tN?weCe-d7prqc&AT=4pu+aR{VN-%cP5=;ypLaJxp0i&^Q_%T71 zTuN(94I3h2H#z&RaMqg%Bz|oH(%^#J8G1P_=A3y|By#M`lS8$0G@xg#8jc zdt(&cP+LhKrbXbIFWUUS{Q0n9jd-I#a`0}n?a4Zv(Ygq>C?!&r-67bolMg}8FN}+( z-$C~*Gcv^&NT#(5)-Mww8`_cDCJC@fZ6x`0>n*pz*bCi?QT()b=VBKCey$o;ao(5I#1=MtN2tJ*X57%o=U@Oazs0Ek8u$&zF(R4W;J~VWyPZ)XoC&Tkcs0WUKP=om&(}8 z_Vi%gc9Cayc0Cv1bi!V^bITo7=`EOb<^&zR$`;*izQKFFBLZ8IWq9SIIytiI6MWmn zdJq3#{$IcC=eH3>59M%AO1Dy{6Sr{%>uvLyyHi6(i|o(v8)UhxQuM`V`FCOYe0dr% z7f@HB8=5|=z|PmEC`(5V?l%Kj7ARtR7I#5%9u>2%##xVYVNGxXAyn~##6H!S(J!e~xOV2|6jit#V5 zrqfXiD9Ra&!bEu+;fD#$sJY-WG+fXi2F%Hot9lB;D`IIoG8bWO6)bTH-ckBK=P1o+^}tYgr()`f2VvJ8{f zwZTXKpWJQEgt?G<;OzAZ>ZW3ae=Wuk<*Z|T5@U3GRE(k~JI>ISQ#DvRE0j;1cvGlV zUX8CM#UVax9MSJxg+ZIlA=`K*y)`-nPjp>?jbgD}{P+3f^@j`GlZFU-GSL~&zhvIY z0ZD3Y%~*x}2$Ij7Hy%;-*svpv-*`NcI~&F_JOZ=9nf7?i5Y+p40qzYGg-bbR81uLU z&J@mc!7vdh`tm<6U-^fQV{2Du|>*^Vg{I?Kgti z-Q@-FEIAD=^8i|aC$3X1r8(PIMX)osYVg=J^c1--LNfZ zJuWzt#f>jGLY2B-;+$gU4z7K|*_{r?%||XU=kk4MW;w~9?Kh!K%!+EWi0%AaNPYK7J`7ZqD5?byOj#|zcTv)$29j#l7;#?+F zSKfe?XBVPUWh7kGJWub{*`rNBC1hDCF%K!AW^Wf{m4`y&2M3%zbOL$&cs&hTkwW%N zcH+}^A(!&d9(%(z`Eiq3rsz7G*>+@doleR8qK}PuIVlH@p7;SnL%s3fmn2A-l|iEq zxZ)=FT2M@~7Kk?a;Np&9BsifH#=i2z;-Sh!;Rm7GEl0>=Z72S)+#N1EX#<)JGvS}i z-Az9;r@%J3_uSt<`mjR}arjsz#sz&rrCitIqLAazGjl4n`r?R|_pU>bx;A9wnBp3v zS3qxPP{&qF?0P0cqNg+q4@MjzKa-sJ|2EAAG0*jw_`rm>J}#h<@2YV9*SDPN-vjW7 z?bPbeO@XTemuR9*2o|{Kg8bFD{4sYs+-b0#Iv$Q&hu>_OGd4DD5|!3MSk=}}AW3)!iJ49~Z1f`7J}Qb;yz#+;vuQA}q*;6L zn>w6Kmk_m8+GO5TOZ3Y61wDgx*iKmiqp$WP<7T%DrQE|7*PDB+7Hh!Cxij(f6hrC0 z+WBQ6&Qy(qrM(w3z16;W?^7B~NznoKSUo(eb_L4o_#H~i5M$5t%>Hf}I*rdTlh^ho z79T?(7E7@?DvS3z2f?V;mH30X3(pO%vahQPQRAW*rg#_7vPVAnGKDkco&4ac*c$ze zDj-2Ek)6F_fDeYfhZ&yHqWla)?7>;UuS8G4{)w3U-D*YCTU(0u&M3j!)SRFxFma>0fv$2iX-f}PlHgL_9-LWoa@ zFiFvlL_Cm%WlH``=h;g9sx*jv9Vg3rj*lak>#V4IR+g}}(-GGf=+k~@#H>d_37+g| z7P|KvUw!RS)-hVD!wVmBzTp}M1NXcZszY^fSXc{0ekx-9KJmXcREe|z-JzX zbM(4vjigDFcTjt`2p{GSAz_1^@W<(e&~Cel?cn)$*Uf2AdM;dOd^n#x%1sv*eF$Ka z->t!Vdkg#*=SE}u5S`A_o?EU$(b__+xGaV*BSH#KwQ*)mW*VHnkpyKXZWwF-5So4+WDQOB zIQhLCsmh2K#=Uq?lwM^@HCe|pj_ew5)C_?7R9cS)GArAW-K zENR8#cDX!9@JyJ^zrUvZ``fM0rK@-kzj6iKT5ZS%e9*_S3h&^TOuMkBp5I3Q_990M zuCf{P;z_IBW~n|uTQvp)qsP(izO2j#e)#!ffMC3~C+E3WVClbjIDV@H-sCRFuU7k| z`W*0iBMv%U1A{U(X)0$oBt<=u>T`CpDY}0iM7E^6vU$J6By8;_YX6G}JGSub$qfr? zpH|4~G(+%de2B37m6#ShE64iL@n9A44gStC!GY<4FqU^CWYt*k9X)~lDu ztP_)KgEv!ugV``8$qhsQ?xFR`0=vuqz7gB53u$fPFg(@}Wg|v#FIYB<9P5iy#w3H) zo_F-XS!1-nkp~}NT7jje6+U_03C~Z&vs91en55R1LY1~9$fCHU7XPdI5>0O9*qq2Jq)u=nV3_9w;%r&yl^_hMW6-`xWIr=ms@{l37z zQqG&R?F6-#ds)GG#Aye6lF%1X!rE3b@dX#ER@I9wEjfTqt7GXfhYXseUWpoZg@Vha zk8t7bW~_TK6$IHxwn*fQI;Fg)_fNC-%i#^!*2#NvR*T3i3ri#g-yt(bhgBT5Kw-*I zV!B)rF6zdShj(1)UFTEuHh*sooBV)&ve1BR$C;=yM^)E zRGowop*ry3p&m+VE$M2I1M0YWB20YQ!c{b{`=X3%6jxY za}0tv^3L;(T(?zMOK*!C7hlF?E1nmA=E>;KwP--Qxc_}Vc*HHmwLJgTy_fbl7Dx2g zZlR-I&J&&XaK-vH>!dpkr9M@-W}_Ga-o|jBt3Fmd_l7^|4_LK#4orIm`1#qI8->(Z$q+#=y^^Uo8UtoZizWhtpwNT<_V1p(*;XDKl=?j1Zf5q%r=!X zwRhx!@Ucx8cS8qrglBL^MZ!u$Io~9_KhZBwpy!jtWY&FWs`=y{RSpTlH&utJ-Mmmq zKPbh(t9b$^w~!9;R-DssCfq1@W)J0fUNz|?guM$FDgqai3zes(-oHKM0;)Y+Mv`Z5 zVxQHQ;L)FQWMH33;Bl2d+a1odwXvMenplm-51!Dns%W9-K1Wp1)r5?vQ<<-(FRJFB zgxg=_;i;g9S9CAHBee?l(~I*v3ctZe-3wGa+8VoWn?i~wxc(KB{?0CR+q_v+Y+r`$ zsSju>?*o6^UWmO;9|S+&kU}G#DTw`c66TCchKv$>49h8l)=z<~vdshsiQdD@l0(7( z&G+Q$&opUot#fo7u`=d`rn~DTzpG2R@ALtEcB~D~pW)wyo=G5TcnCv^Y*20D4LEzm zi0#W;iNDxe80Y_4P;?_$nAL;y)XHVgR>qO+78mMQ^g-n4HwIM(Pov#gO9lN9taREZ ztW;5EN3AL_aC|HzHD#?Yg#`G>@!vZ)dLJf7MoY1u;DFa%&UPuEjF0gJc8ua6SlEZOnwb=kI42a$Ah)% zI$9J_g?bLtNW*nGlB#ckdt5)j_BUSa74JSBxw!}Fb>xW9Yl)b&zu!YkwR$m?x-isT zdzFrSn?-B;m7{@rgiy=<#~;2pqo2xnDbuYz$`@N6#>3o&E!w@fS3f&$2KjYpG4b=~ ze$L8|(A`7svu-19XdFdusVYOeb{rX*=q=T1{~hHR6f4Kxq)*}f^D}X&;ZG4uYh_{1 zMcC-+4@vtLvjYBns=bPr?lhXFEyDz#OlY2#&MbedM^pD-K=b<1+OHxs(2^r=%LCwH zk(hXu@0DtGgE!x=9_qo4=7&M)R%4tvW{?mgxyqjIEX1N(KiCmoK%ZUr#oCT|h^Y31 z$s293BDoN@9pfyLI?n!H{Tg;%jT0>%Zh*f-dJ{kWM^M{8j`*2*Q!V}0B3<=zl-nrB zx*46P5BT88A9IB}A%1Mn;#w51J_LgwF9)mT>ZFIYzSQHFf9n!fei%*;FYshGj)u5$ zRWszZO@VmNrRbj7gJ{Vlv-Owx?7DuRbl#RrJ40fVo=DyrZU)(*Zuq)WL(plS&;Geq zVS-~gWKD~O+Ejh)VX_Tk=R9N@IhXLm?cror;wW}CN*9mCH$oHVMLOzR;YBi-?EMzY zl2?n#m!W&2j`BV?aR~mo3&NGv{Uw^G@8QatXlOa3Nvtg#(BCQq z%*_t4>@wbw<-nj$AxsD>up@78bqaZ={_L}0jPCY)AFn0LQuxyB_#tm@FUb;|L>n-1uumrEUVq*AW z4}EDolPVr9MPpl8HtO*e@H8&M4;%cUT@q5bo8Pl`)w~DQt3N?p!^a_lU9dXS%RiQgC zA7@yF=_cV|ce6zJ+f;!8n?6E*%~WDyVuKA)g&-bo#IpDu*3RH97!K|fE?N^TZImaz zJ#v{SD2|vP4WK(zKZ=a^G?PhMsx)G28hcR}fTtXW39mLQvCJ>!sLneo^j%8e-A;YH zxyA*QFJ&>Oxi%1ViK+rK>MyH!o(hC z_<83s3JZ#u%-{oPY&=3Z`zns^SK)J%=6|rh$7h%-n4tEVZJ>WCjtxs)hyV8F!cfr&TwNaX(%LR?$eK0Oz-8hrpfWG1ucysO`JQjT;lEnLvW#5?!E@puZ`WaNUk zkBlLwpS+jc9}q_-?+K(sX3v4?dT!Xk-^-@k3ryXm6#d6r2=)APzolk`bFRq4!%Nw0 z$dfz_+I<(2zfNU7`PJw#WD5Cl{4T^Cw!$Whc4%Vp?0hTN*ar%v|1Bm;c_k*JWrOMN z^u5fc+86hHzD~O{m68{LIb&@Q`l_Ek1LSYA!9q zP$Jb25O-Ol3${djOmsC?*q^ z2GNJPduaJ(-XV}UoY@71z@!FajQCYAIyNYmeK(R|yZkmtwJxI0^a;*s{w2gXMdXjEF}tPeDvpF9@PP@|%mqB_24i^P^~} zvM2j>NS!Q}fRq`rtm+chj2cW94E1Dd$1TU7nh)UuOa}cIOL6E@1(J%%tTbIrA}fOE zrdwK~rR&d-%v=8?F<&=9M4=lde0VSNby&dM|CZw%W6tke7Y%(s>!an@&0xRhA)7z; z5)O$RMC|*GV%|^n@KF7IShL*%4m(-luk{0@TJ1eMj-==W(=&O&f=Rq7W=&0|rPV3S z^kpEX$tei++m$8eBX8oC_kp~VM4e##I?Rdng?A~zEXt=Guezy{{NG=M9G?wj(u?mx zkL`gBP8j2Y`ragg>(t^bF-fToq63#?2~o1nc*8J_|B|N3dn;?C|3} zy=9?=m$%fT<$`wDXDCP3WY}TB&TC*ZJCF@0W_X&kLieq(V9m7sYSD^RF}RpY=xc%Q}X&?+wEk;~DTWH(0o{z5&(Dcn*E)Y|=Eu z7KvFd3}Qyi^PV{#Qhg1y=BKbfj^La1vgDy^F3a_aBNj3TrCQy0;TU{(IFNSV3io{v z#G(5OMg9rBnar4Stgdv0lZS7BT8cg{T4o3Nby@6!tt~DMxCC!Y)#!_X>oH;GCz$?Q z43_1bBmccG+2q5u+9i&RwmwKNr=l=(qZv-o&Y|UzMQmYJAU?6VDw?+_h8`#?L9<3@ z=yCKD=uPHar-qHN?5UUu5jH$Wp92zQ6VZ))3-rI=3TB#j;i--lE*PUi_O1~z!XLhzk)X>9L zz{Uda;=A=n)V&+2J!yn*$A1<)hvcxVS9y4NPPJ64^WAH3#K%b_K<^&hEU>}^o0p(f z6VF-?FU4)OvZQqb6LmF-$smUasaAWA55l#3U(uM3flT#9IqEn(5iL@dfXl2^Xm|dT z&}qW8S}zalwpT!Yzhr7&UX3w26G@w=Jh?e*HO|#*g6MHOS;A#R`73|nSXz`YvO!Fy ztcsBCMp_mI;@Orq+N1ImbzNM70c#$Lw94PWYtDmMdQeg7!QRu-X>MO$1FpA8>fPOx+HEwLlG1&n4Vh)fhsc(+?GvSe)&e3^Y1 z0~JEqa*xN7=Z*Z9IyOKQ-^YUu98!*Ye>Z_bHG*jV6!J=Sp%6dqBr95Q1&inPCu-kz zv7ApUFva&C+z8fyNq=;)>yZq>ZAq*-?kQ)a-eSw!f(5gHOtO97V7k583C>u%;T-=! zQSsmf{LWsE?J|yVz%&{vl~-U@jWyf~d&m?td5^B03YqnG6g%5%IriOp8!8ekA+LjT zMSm-kqQkMw^7DPHEUso9jto|RGsVGg@~HmMQ>-_?r=*W=6rCDnCMh?*gxE8O8&*xb*=^dgWw_7ik!Td25&o-pz!7PlP`1;OO&z%j--qPF5wqXIqH0|n z`KKPX)=1dpT2tKnQHiK@oS>fL%~7}a3MMx&gPDx0LB;p8*~VKpC6|wu;LoCmq7ig3 z*&OSNrK}g^XSlEd?>U!h#B-?Xcp)tQw}_Fn!-_JS1LBVzgA)#yKKPtmp#WyQ^XEk{y`8e-mr9?Z-}OR^kxLnQYATYcNrf zBA&AW&kqL*Z31p%*N`^wd#FJEjj+S){2YkC6~ONF<=u&`k3jeDL1AE5JF%-xfSqNp z*pmEET-xQw2AwOQcS6f?@$2a<;o>XE`{si4ll(>RzQ?eye@=HsKzIq zkD(}a8hK>A4kr%Ff#8OftYP3LbQ=2^j$c%Sjq-?wwSPdeEteTpyg=6GgLc#jpjZmVx|58_#^SK zNUP=uU7~ywF9mIbYur;f_~j}zG2aN|AH}ml{&qO6?6m@7oJFN$7B;coKF4o zOrf}!2lm@=i{{h=i|mGd0w7{94n_-E09193piYvIUPh&L`RqW>b6FV{8%5R8Tq5t7_$KUkG_01q|*EEO7Y>(4DIyVckrXx4Yi!RgjWxv zSx}z>eAlBGnvPBu>8Dj=_;&73__L7MN-Xgc=hk)ax~FkwP%jNdGRi~-j;3wH-oD$| zN3{T^%(LDF_RHD*;@Ft!4xURcV`O%8$h zohCS3VUG6CQ@O04!T~(>yDuCv4xtUQ^%#gp-5T;ka{I@F?{J+dt426AFDc+VH!r>)>h-f9S$=;9Zd<=f`?Kb5_TQ~C z9Dc+YI{i65IYpglDo&Tq%I_w9jHUS+KkF6v=8g%RXn4qu z&$*1-EPIm?Eu&aKzA+}9zsnis_R!#Eg}oN^A&c+CGWP-Z(fa*8_AZlqB3JQV%Ay8Z zv;Gvj&{=}!Q!=!-s+vjET5h7scxzZ)rcUlRJK+&a53ndd$fBd{aY+0*_(MYl0~I^s z#djX}ia8^@w+Tk8E0Pc1vh2HmGgjF&vxCoM$c;>AEN*C{Mh$UHrhhp`e9zQAIypmd zp1vO6ZgGb1*DaZ0a_(+#qJcQjDvp;vN{v21gsC`XdE0VtWF$K4Xq+1I^ii z;0&e|a0sVY^=8gqhb5c%PI6BF4DDRbfO#{VcgTlz2*=f3*!XAl*dBBbo_=l?@(**af7b|sHD{?3&#o$${)N@2 z)lMVD$VXJy^4pjV7&XCE2g-#MYSfK~2_Z}#WZ>z_YL-$}tm>lVv=YZkE z&O;xCAO=>pSdrZfgWkpp{yZgLl`yfFN@j@SBNv z+oucO{g=!1VjrQoQ!~qA(_yyS3$nM^op!T0({lqbEru11G*V(W&X)83Lj;8ZCGdFP z3RF6&59K@0@|}@2KK^nV#)hcU1v?DUAfgWD?mPg?bU5ERvm@2^x=i$#dr;Nya31OrQOacK1_#yjq6Y z3$!GGs`KEF4Pr`8zR>M6S&+L0J2p5&8HbqN3RZvyYhFu-TaUBi9JHJ4twCSp0e!rQo_8RRAQ{s3dz%L5wQ8U5$5HV2(30b z%sDt8E2rea1czzt_|sdsXa#40KYa}2He2Ai%Maj{VjT148HIJBUC^!VKh`PX=wJPr z{ae06Huk};+}_M}ZC}=IRfZNlLnI@Q7J^8IcL_G#5Pm&B&H`2Qu`u@vxSUL(HRB%P z6y6y7*+iKrzBR`gviBiL$&2lgGr(-+zi>BIEd1i#K@nE#*(jwFw(edaKK|Zcs_p4v z{GQ?+ELm##4z>{wj2PS`M4XFZcD4B!ZG9E~SWFh_j4MYwyFo;)PK(^n;N7Ri524Le zm+5f+!e;SrD5&ldPLFcOg~t1MMS>qY>QIGMZtGa%!fEiA&+4@!J`{D&>Oa$h&~aU- z0E^|BdTR+D)M9XYc^ur(TaIpvVj=KpI*a5TLAv*ELHc3^x>1EQ=}O;2mObC6uXe|k zVf)yBpO&%7jOTR1tXZG8!Jt2M6&^8DmRQfpV-MFKz+kW6!i0cBHlHN6@1<$3ra zBkl00RvH{LJ;`oJZ1D_d>S-t?iDFGx;m*HuMB~5bu_Ex-nW1M7%hX=dVS%#W%3*k=+!u2e5-W@(ks_n18?7{<|b0H&7o&A|@f?M?) z;A-(S@a1{QNjEy6dv0Ix{vn!uZDkiG1`3bIo+J7?BKp&RD-3(+ifbQ@my}(c&uDZh zTCP|C+d>b6YupO_Sh5s4H7-T*rWS__-N2viME5X26$q=X31e+Rk=({)5W-j;J*0 z4<#ZoYk66Q*PTKncjPmKwBeiZcB&nm_qS%Ly0>w+BkzdyaE1+gmg1R+Qt;8I?8lY4>2M+Hf|-3Alc^IJJP;IVKr*O{#} zxQ{)i-U2%MOWDZ1eTnWw_JV>8)Ro-yxVSS8hV@9#@N1 z42%sAVy0RvxevS!UY`sXB%|Mxh!JAxo?I&`3blf`Ib&EUbsNKb6;d~_VDTsDZ@C5k zP97)e?hpUy#Q6vl7Jy#|XQav8#AiKfU_i`lvc|;@!#&a<;*v4b5t-tf)wdvU;CErx zKF%;&{S`dV=dv9U&#=?s3!D9A7Nox&jWPrCsNd=~mb51b>7QiDNVPtE_gjWq3pBxj z+yME!709b+Va18F?AHKWeEcH`Zf{WIy)YXwsi_G({oN~G3yZ0TALs{1vWCcn}2*r-CT+nt0K-tnk+v>3L&O<`5joKbRCg*eV? zm&8|n!3T>Ki_3KnlZ}DyXgyJxb@x*xTJmRjk|O=s5f0bPR-*or3&NUHIc)dJe7rdL zJglEIjqMUDu>P+KsXKQQL^d|~rSd)mxF2KYLH4Mx-kW?_+9(K4xP{O9l@csn*@$5_QG+L2UijK>N z(&?e^z$D)V*N?g`T!X{Rt}Gv~c$@_*{mCLD!&=PUKad=ESWHxTuj!Euw;_t@u#PH2 zoN)ao7_Is(OuV@rO_W2J^Zfv3xwZ}`p4iPwQ)hxT*YJPs!IEwbA3Zq;$J#v-E?<-5 z{S3U@C*}$S4T*zEamz7iY!o~lbcUVQ;vF595BP6gAG&3{B?{IGL_9GDHbuMPmdk-m zY`u()v@b_8*Mn_2AIv|KRh*%jB)PmbkEx9a#p>4Qf`QEex@>tBE@$~rJh&Eq4CVaj zu#<3+a~W#aufd4odT{u9RJ3ocJzBXak#W(VVBvy;IMDhy)BblyVr1Eb;b%ga*|3RZ zP@4yS(a)3E&+uf^jCuCe?xq*TMtecy#v_Sq1APMvMpV}gENRbcvN z8svY_#q~o!L(zmJcJY22HsATnZg+(X{bMu9=zT^sv7a++PjSbKrn!>&0~WIC{iQf; z?L^q@#WnoJ3JhDh7_P5qWO{wB;DAxGWLC&%HcHDFtBN?|X^1_%pJ9ob8x_dXsu-3K z(1@8DpV{A=*FjffH4Z!Zm;M>R89FuxG4u0X$!v@mT2Ys`@<09HWQHlh30S+1n*8c;eG9Hq%m;Ea2Y1 z$EJN)w?{>jYq-MPVYFMr?=)}3B`eKfyskAH`t%+;*^D3-magC=S&GIX3^weh?1;n! zn@;?LQ|gIy$pp@ob8%zJKQdU}r*Pa6rq0ZoBPGvTZy>%JOf%a~TXi$Aa==P|* zecOyXoo|83{Vv{jzlhwv86?&4c|1cjk#h$7*$relOoTz+Z@_@6!YqAT+_c1#_1_!K z<||jDZt6~!*AOiL_wPLumk5K_&1C6aeRVz$lOtm!(VV5iI|ouDVUlYldov~*OLk}y zm%M(g?|z<5TlJB94A+9T=PsTp3uUs_{do^bCB~fE&TekI2D_IqeEn|>=wA;ld@;Nn z3mS4^=F=b0qPP)9)SLp{xM21r&In_tR=|YG;lh8%-xKp0(b8Rd)9G+*$m4pjRYD_G zTyRK?KQgoUy5sJ#GFe$MT*G|ZXs>Pb5V!AzUQA&osYfae4o11v|$TQIT zq6mL^O_UO6Q2u$8%Z?g-z|@fn#cTG7KyAbrJn1f>-QMq)vjTbFOQmFF9iPd$w;>{R z5(IC%0n0}lU}NB7F!^+r1;|`M>p`+)oz4N;(ANSlX3G|(n|90t=g z&S2I0N5@{5u(Kl%;iDnFEh$T_y%xyU`YThZb2AC}uXjzqn2;~qbL4>`A&P2u`^Z_#j? zd}ux#KZU6FJ4rb5UkeMqxC3Lq+eMEPWeVm2j`sBu5}9DZ;4^dGQaG8H(i&v2SJ@etgMU5RavGKC9|a#*jr zLR@Nc9xihR`g|K-)Hr_?{IY`JL9z{Qt-lA|ytWJO7TDGy+V# zcz0U<^&LDq@1SKaBqc$dZ2r*^kzu!|OWeslAki zYp%wKx<8nK!{MB9u-|i=hEIaKm z;Ey7y>-h;jW(4D}oCIbPS0kCh^DH`%%V~DwVZ{EGgk08?|U*b-x%udhZDKYPc^>vbzAaS;qw@Wd}02^v?hH zbzH0U6G~tc#h@Xa>Z%G{=v~%{2j2|o!;GYM$lTd2`yf6ZgsLXYcui19zhqN zy1ft7ep!lLY6XxMN15+eGn^Uz2j1;FN%sU>;F6ZT?3Gz2+qJ(0)2_Kv-?M|sVn=tp zV3s8W+iqoBC$?eaiEf%9o2Q6p$j%m#99Q*cJUfPs$eb-#g>X9?JC0su*_aMk)S_?hB)rF+o-Q0BxTYz>*&eh*hE;8m&79 zIoFMu_WSjCobQi&%vFFFpo0#(-$4KQc}!LIIS!5NQS3i!4oti_8rvQ>(ieT(*d((6 zbUUL+Cawj~lK7y9#FDLtC-@i1+DTZ)s9{1m!(Dk`j%fEpc3ZX$Wwd%1za2K7jORO5 zcgLgj$7wBi#p^Z`wt7l$mwf|VP;`vIt#4{RgjUL+bJMXUWQ|vzX zX)K8O3R^GSl6XXa~a+%P!$ZqsY`(PtW{5w)eBV;hf=x>JiD#wr$F(u%z;av= zewudo{%saaamFGaL0d6_4ZT)?shi><|K%y_kmrMk|8f3NOe%QXx5WkC)u52=%TngA z!W83g(9OrZdC>xW1_ZK8q?Fy}yVDPcQt3^@c4&X#h6Zb+1Xdc&u9_5LOjA4zJ*F<& z@9Kj?>eHc8?IoyAw!tUwD?!Cfk1ZOz3>SF4hJH%lh2LYgbGB>@`x_F#%6G<*WkW4# z+cg}6W(`X98}HM$A>F}Aj66yF^e4d}TZlN1z4)wnNU{~{PY_N20> zKWZd4YH>s}-GW-kJQ4=fxbxhE9^F1@C+oAfjQ5Fs5L!ndIPTIQ_Hn(W*~VD4t!TS3 z0q$yzXNkOf?fOXWvo)LrAy<~-t-6i~ZN8SE+T37!s;Hja!6+=@HC z3DC1Kg00WwIgXBWkh3{1OnhliZs^wu8pr+FYCfwFvp?Wm*n?H+y}+*rl#2Ts@Xk8b zYV3LF3@u7NE42S{!W$#BVa;ee=6lfxt$(INW>_C6U7&}$x39pVGRnepR^!i&U6A=`cHOAAHaywk!DXWhb>iWwu2#5zQWll%P%aJK?kn6)KV%asN*K&UIlCIrZ0$dl+KCPT7QIa86=@E`!m% zz6nt)bTFc`1)3-4F@rTv(S2&4;#;F;!7ouDj?MXxu6(A%P7mQ+*QN&HhgUIt?J~fA zGsl2++&Q*#pATMGd!pmxp@kE#5C6P?>xMeZ})y0&le<-<`> zx+|WfZQevDH1=enKf`d$*8_Bo#&J5Ng?rm#8ies9zrsy9Q{1|20(fyg-LyfzxEN1? z-a>bgxl=tVXe=VmZiZyxYAa0i{{fm6+N@crg?}b0#nCs$lEDYW}81O*S`gWjC#rBn;&rV)M3S@@{vSwvY61=4OATNK^@kVqS@Uts=qWGOm-UM@z1M; zTSqRjHQYb^CN2s#D$QU6B%FV@CI!-$1VQZvTiidW4F2ml#%_LDfveZP2IGGvq7-W- z)N-FG)#MWsNk+L3Wa&e0=#XE)_N-4x+$r145k-BIG&(fZ|mjvr{UqUGN^ZXlH z0*e#$*m<50RaAKeeg69)Z1`b^(VHUKbnorVp-&u{v(kya+9V?|)tUIqc%f9Q&3NCJ z%GUrvzg3=1uPni&iWuom->`KUu&WeO)ceqzjU088`WSl42f|&w z?Ko`karWxi3O1}$Ox{m-qLo?(LWsO6`h2yaTa~V{yD7nFvLH|x@;r!c*`loD>vNC$ zgjL9v$LlcN?ht(Zc7nO3SYp|622CRpMAvWM#er{n7VprUNG&8{(stL8uG!Hj?7OoQ z+YJ2ZqWODReIob#_r4*#U4-CdIhAC^$Ouz=C$T75Ck)kyhNYHc*o6 z4272G2KZ*;2(^Ie(cN6oSz`yY4{%maOD9Bo$1;QZCJbxu zSNt!w0%SGgI9J<=I`(-@Hw1-YbnapLV&5Rig%1^IU|K2+2pmuPT-b`Dw%Ks8J%Z^g z`=a@%WZutrTzE_D$t{O+VgGc0HgdQ%CS3RdGD^MJfcY=b@V1Inw=X7$iDHT)Z5Vum zUfB?eg~3tubb^yGpqDf1sLqsX_{L@*oXs=c7Zdt`hL0W&-FFdoe50(_*frRG{|oGz zlSIo5Ez!(3j3xHSV(+U0<^$#_b1TpQkJKnZY@6<7cwzqz3PAImYj3t08=eK2CM;h3X?! z?A=N3lg}GV@{jaqGbZYx-^Ca3SI!pH`A#E|C9*qSd~^(N!bEg)5tiQR{7y zfRSN^AF%?LIK{!CS-&9I)d8LUMo4ov6`A(bwN<~+k)X`UbNXPmId=U?Na*<;rG{KVZiws>?Jt{7RA%aou_uF zCKmx6O~$P68)F>*I1h}zein2%ThR99GpN{+$3k46VN&mY#WVlSg1ztKh$PdQR$Z`V zD>$=he@+x_+pfZf{VlI8wcv6c;&~%MI%DT0xnf4b9Ppf|!TxRK zIYG;0cu!f<(*DALwilB7cRz5}?eOApy&_3Nh?qR^bEHEx zw$a%kU@N?T|s1j$`y|I#>@IW+>l&Y!{Hg%9rimjqXgf*_SMIy=2e zL1X7}rkY`lN8;My$H7WbjGq#oSi3;F>!{5a6N{ML^xCD#G|-4MN`C*QgTjj7#wJtD zxII?7uNLd@toO43s4z{X4cflAdh{{ru0yV9EAMTqh9iatnC_xASn#$T^6C`z+%ur1Ly0Yd(1e>S*tT*|RfPk5ksD zIlKsRB9!Pkev7o(^$Z00P`?V`Hk|wFFHG7)pF0=`Ur+IyOMWn|IeLxx zdj;Ywx8;IqZU8mrzU95S;jm#;74)h%!7cjxVE3CC=3HuxY+exzHaa1?B)W%>H2W1- zgifUJKumg-?xtCsdo|0+729j$XvW!XY}&3m+;Trb&}q?!rTQAAYTi3h@~{)^A8f-B zI!B-^eiD1|qy{H#oJo{;PmtG9J=BVO0$%FL%&qhV-U}XD+;k>X_-Z01CaqplZ9jh4 z4b#Hosjz$jb2)Gqch5}`#Pbp%nln4@v?{{~hevGO7a!F8cvL!v4^LZ(S?{tTew-cr zeQ$v(pFYAmlNff=vk8~}8eAN;x&jL1<2Yk*5AE0ZijIAG7}q|zMn}1fl3dg%$5|`m zg!IAV$W^D!ILB-}6pssM6@I?BRqq&Ft2{1r-LWTY4;Kp`clk4gm)5w_?i`2q$6NAo!RSn(TI*J&h(UF z$%!LKg}f_P%Fh*MbUL#ue|fj+?n5vcp9nMeEF{_e?S)S#0$DxxPb#X7B&A6%OpA90 zCTh08u~oAm{+$gzONwUQy{xZPcrJdz9y)xUwaBOS3>i1)zN9_(Ak-?jVx+=cA*E&p zn>e)^&+A8k;|ep7^Va7Xy&X_^qlzu@xP(;!BZ%U<{!CJ$gX(ULP@uCGIu3YY^}5rn zaMA!aU|t-VYQKm2T7(NxJ|Vb8-bnB_B864=N^y2n7+f0O1wWM>@QddGcyvCHSzffq z``e0PR$ZK6VDW*}@Qxf;@|t}e7KS71bD5@JAr<$FBcbE?zghpHaAY^%vB<~JiIqoK z&d)MjIW@Wxzf{ICb}d{&CrcW)OCFSri228I}T zz6V^XJI8WNeQ`rrEEJ6p=#TBycxLBRLU;8bTSOM>g=IL1!vB_hP-}BaMzTxpSGs+9>-KRjq?je zK6wF04R1-}96w_AKh@&;?UBSWH! zNc|*JRK%oDTp-Q-twt*!a=z7(L2Q|3A&eYphN8RAMdqhCpXEs*sz+`IayymU>+` zC*6fRu4l10wP5DN=emajg6Nz6GQxEGnW)G!P2Ie+rQt!Ca93F<86eLNZZ1df5&uDX z@1yWocLi=8=nNG?2K!fTjaI#L;d8ta-Py1lgY6sPzg3}7Rql>?Z_-#+%5o;W5tG9f zLDE@W{yERKo1dU+x394gtsy+0-e1Tb6GA0?wlOCEN%j2jejD62%ok?OPGqCf*P(*@ zHO|jU5?!vlkDPE=JhpriUCMtWTK5J?_bO>It|(`nL*t%qW9M2q3ns@*sPZSUv`mA< z$To_)d$uk9N78xt)%5>yT$2!$j7YY~$o@**^EvN}Qb`)3T?my_2oddQXsM(@kxE4+ zH1ByI?QLZ%rD26^vVNcX{R18s_rA~jyxyci|3wzNdeRUs=)Z7s%#+?0NB$8E?BQK% z)gae=jF>2GAWF6CpwNFO`6E$}zO%2wdM!mZLQxKDDT`HsW(l7z-9q9_4}jy`Yz&l> z$L`QaZcvVPOFLa4kZq=<8gf`3q3EQ-k|8B-vAPjv!fdg-dfig<{cF zu-4gxQIq1C+E@1=U+V-}Q?!hgzHJMmWPC|+njzXz9p0rZmn^LP#uS^bh9N#JWN2$4 zzD#Nbv*9Yd@aQ5Ee~9M7wg+=>GA(dgPB8sEFF5ZEIehTE5)OJR4bEy6>hbex{KnY5 z&cW%rgz+eY=oJ3rs7SJ7QXJdr z5Hh%jrz=u#;ns)TF6$_+v7{1?{ZV9Ir+*|978%3Fra#Pu(0I&iECQ2zP2}P2%YqTp znxWiXmF<70$7=4k26_KpGQgM`V)hr#j$gs+iY;L;MbpfSNeH(_C7Bb8q~1%@*_he0 zg80#M^l8U%K|*vV3c{S={^yZ{Ii1@Rt3a>+35l~yCd%8j;cI)!;HUy^2RevOR`h znTG?t!^QML`J7JUb^>L-kxoV!J4w==kcw zq~X>icxNWop0R+^;#~4+j|}%;m@ZsCai6%k1{0}xSJ2V8On0_*xX+;t_SfCU>ymK< z42&Uj&UMarMKS&>rcCnXX@Y~_{kRTCnyGoWi>&LXdi{5*s~p)!EM6z0#7#>Wm61ob zbR`Q)>q8(buNI@O-4h93KL`Kicah1SPWwD|gYSz5uKlkYMrzhTxz!KBqIw}&)1k)3 zB-9GN96E>P!E{z<2Mx|@{hBH$`>n$6*_TGLAFYL&q&tJNdeh;zaEPe!H_nDLQm0+O zGOLkmGx-mPs@6m3kl%vW(J{oOL>~^TePEnMKgG?L3aKZmj->9Kf=N%CVC#`t?CiyD zL_uLQI6mtn>(-pYk4DddcuX7Ix6hfyu?J_ITD+AtY`M<7E%n25UY4*VC< z9G)?eVyjq`S@cIjmQ_A{Q7PLFQQO24kaB0!`XWIC5DPg!=9z5%LDaR*L%B{H)0PW%Zal z5`$gy|N$)nFPZ8)_4E*Z#Feromr@4|f4X_7;?FAqSnsSZz%s3yZER>0mBp9SiN zLrY6&*4s{P2QiZUPMoGW!X(PiQ=>j?)d}0+{K*?+?w@!jep)-*?%_fLmp;KsMj_BR zq!u61+UKE%JD~dVJv=FrU{8V*%x$RS27G<>epR6V-!}pC6`5(zTHwwLPZH(3oZUau z9(ukXAa3_I;=(E0VBM)3WXVNI;v7bArVDP7ZNCc9HmwuXV`uWAhRew}nq}ssP7dzX z9u7Vry}Xt4eJzd5)JE8H;IClTrdo2KM;{j0d|(86m(fkHh-w%0PIlWpFt%MP1o4aDf->#@bTTMpxvkUEG+T7b6-SCY?n0j{5QAKa@a37tV{{P4lO z+I4RwlpTFYN*^YX{g<>MczXAg&*!!3a?W`7D>KXpm`IQaCfY z!w8-$_;QNJ67kRwU(jtdWDeZ5xU8@itr}Zkv63vWwp|kKhR3lR6+E~z-383yH7-#9CW_`pqw&=N9%e`+ zGOk1B3v%Qepn-`bDFrK8rTeyU{=f;6-@Fc&ml#3}?cZy-{ErFM^ny0emzXg;7#}Tf zg>jb^_}xVUVo$ktPo8;jUj=LM+zcORN=)Xy9{R(bDXoU+(J9Qp+)g;B56KtgNW{lW z*iSXpwF?qRYPt$HcU3*e6fb1|c+0TeLk`jokr$Xa)(|bUJHh+vI9?_C3?Y3qul;gA zS36%4n|ngw+@mb6eo6?JURnh%aE{qFua=BQY+bLKyX%gyWgJ1J^h>WO7lAMNK(SI2YDdTKzf{VQj9 zcs1D@pvL~)BqJEm#)GJyW7ja3)E}6R20cf?wjqJUWf>Fs{+-sPCG;Ph|%}Bx3ic_cCA=oO7AIhfyCTqI^JVeTu^iTl=BC#(~$9X(#=cHbct4aJ)Ap0~b<#CcJ$gr*Aa1 z?EIuAFxUCbC0w4#zTf5s1xdgpCq?3E%1o$sjvxsWzcIS^ELc^?K&H^q3r}3hhoJ#V zto>ChyiUC?C671L$eA>|hO>r{p{KAzH4+uB#Im7B_H*Np91|F=cLncKmO0+C9k+jP zfFB)^B&67mG-R%W#_av1(%~jf3(W^N2PJk)jwCL=Z2_UpwbWm589g68fE)Wq@tZ?i zMJsm3vdu&HbB_W$8IOlbxzj7^ z=iM}W8^yWO4z@6d22j6qfmyiKgiJQkhjlJ;s4Yt zZwKl8;slcEWY4B~3Uh2`n}Au%(NdJ*Vwxtzg^yZhaD`E>jv|=Ukh*5^^HkvHU2RUlhifNi;#_u}|bk-B7lsf#!}+R+Dk#{81z4 zC*&zO@n)f^}%*9Hb2PF==breA;Vfv$urMcsshz`3j%ackmk(=CkS7_QC#A zn!RRyFuF629TMfsdAbj0On*>YXy|cnAYWOvem7VZjbpltRZ;0tH5l{+kf(uX$@A^& zV8knD662JH${Q?T+n+)*kgxnqeYS1!7jW-nn!Cw}WuNx?aP{&gOr)$a_*4w<+q52f-SuL?MFQI5>d0&9Q+LnNw51|L0X^;{F&f~ z)7SQ(=I4VTw9m#2OBx)Z^LBNgAE)#noEc7x>D-9t;;IvI)z=`nGj=lLx7e9`CRPnI zqJ7EL?0-Zf!U;;8PLRf>)IYu04zg@YiQ(ro=J7uZn7ZH=I*8Tb#^)!%ZMg_vTV`=} zKC$eELw?+N-2!H`*KTYc`jiUns+R zeD(k)=M}2!Zov8>&tce%iTvr3IC7D)$RrB=xJh!7IKwg+KBm=h-SH>54?_BWk>J3v zxius?!U)bzlOZ>r#bDv)A|SgTkg3xpnY{8Q+D9{wGGMLPn8_Vr^39YVsXm`Oq1Ov* zjc4$e#pbhO)8g2vlK$LWnKRsEs>2wpk;5_5h2%@t9Cn{^rIwUoG8WnFfvdkJkrThC zp~2%yV1IOxv$_|Ek3bv5u3Q|J^A6s{)pysxXl;3X z`#GA7^Vk3-8~OxIPg>FKOdu#eUPzWkyyW_dsi)NF71=cUA(64PhBN;tZ-e$Dcz)>v z!%y4z)ZB+;$A~RZZW2p#S{YdOHkLhq-;et}WLlZF)c&@B9iWGMp$_=fg$7(L&?+@H3ADCFqF z6w1O3k8H$ycWyvgdJ75LHwJT+>%dKM4qNT;oV1+ugYV+s@dr#q)oGou;EytIcjXRQ zyg3+_ovY!}oz|3U&|Zdq<6TUy`7aWb;|SufCy;KrV9c8Efz`gJGw9R)t{VZ#Cx`OZ znU!3`{4Nl?F_|}urQKe?;@Bw_{+ul!7w=F9zpWH-S8WBOVOIm^<#sWdJ#*Q=%N(I0 zVFGFG-;8c~O>mk0K;B$&B~g?WEcB*6nSx@h88<{|Eq9QQyt1Bn6e+`Wdm9|!!FtD0 z&UViU&dWuG<60VFjc5jzjjba${Wrkv?bifd4!QX3dKs9pjwE{XN$$tdMv&amL!5RE zWs476!+V+QBx}V%He7!e2qwqXK{JrNBEKN z$S+Hu%bp*z9}=Hj#&RzoZ2BF?j!_QbjzkP+MlTmar&BWbT8(D_{26`_F1eN;_1m9%7bEEa7g#=l3%BYVSj^8DERjW;GEx zOJkaU$>aF8M4Z0PAM*6d1fOfRbK5Mc!F{I-2^v0xZ8+%!ms)(uA+;b})@2KMjn{}n zb{g}IvLGJ4ypPqfb(r!d9C8wyu<=7aH}Y}^yokGlO`C_Z3M(8byRU*9{~-bmEGr;z z!bnE@)Ive#`3C4K-bcRE?AoOVcJTS-ArhXbi?8iW;9Y(edHP3;$b35jACG;-7O`Ml zlJXo3pH1cMUJ-KrU>y5Z6gs${|Mw;UPV}^K(nln4g7htLJ)p=eIewP(xUZ+4>Mu-U zOcs{xE`-^m8%WB~9bCYI7MQ(x9y@lf9Ba4sC|s%fhFAPev3p||h-=N{N7^J1_0@6g zf|H@#Ek8+gY6<|sjW*6(F@TGDUIigNvdq!-wM2RcWnG@@XTBBF{oK76>S?ZRYo{bL z>HICo%vNQy)NEL}&7Dx-Yt8F?UBGR;+Y7oDYP{0k`D|NUEIaF62qzT~&uwU_g>;8G z=;^eEtX)2beZ#tIX|^X}<#`u)xO@~*Jva^3qpDzb;S*B+@B(>js|}fpQ;42y3KmNI zhP7cH{FNDJm=){yK(V1U-k-b@CskC#>r1oIX<9Uyo3Q~bmc$5Vjc&tQ2m+hDspNjv zD{c(!3+`ChM!IAl5yy8{(6{p{xmOa04r8=|eX4Xog!?wVjszh8|pMkfmZb3^7 zk7i{yqRqqGpl0DJR5n<`KB0b<7Kuv&+p3cowW|hhW$hsYtg6yoR&3gk{fv$BF>JIc zfH#li*uqpBtRMddAD;K-f7vrxS@G!ybXz`C7CtETq0}S6F{GTQIPn zE8VLC|Ek@@pxc}jtkH!Dw{6J%7dKI2(KYJ-muJhvq|uB zAA6`>^fcr-q$J)#E4p(Ywc7(>9W~UB?~LzfSHbkHvW))2hs?`=n(PdT4#7Zo@R@v1 z7_uUSSTNJ^Q_0~YI&1mLkxgoiFPajghd}h@18*yQIA@D8@L~Ony97 z%Y6qNl{CZJUs34J(#|`64n}5HFl`^}Aud>+8Q(Xbos+N!I_pM}wV$lexTgtH`#Qj>_Xp@5@-_B0R07O zSo5rgG8AYJmrjg8kerMEy)J{T6SopeualhR=_Xilrjt}o8OFXFZ4I~l>HW0u09v2_ z2$Ni$`3RRJ@}z1DSiMigMgPh%MeGCwo%6ymi{m+4K^08iHVb_%KM`{!6Nue^%2CvJ3zGc7|5XOM+Y8syKO3EnGa~N=8MUBRavlAfaqa3=A$}^g#FSggJRFI5NM9q!${)5vGyK+s_n?Nsy`q6eu(s{NMu5H;z z9ykSHo4FmxKe{rwlTV;*{GxNBIva z?VRMxDE#-V5;C5d3e4WB3w{o}54&dXB=>WHbvtekdn8>*=K?)UmfH@JqI|Mr*+?Q- zcLbci{zB)gCvfbPPB5#Q%NzU<601k*P@uK|1>3rDosl=3OZmjHalg60_Vmx+Y$_PY z<3tv(2c_w4%$NEs+rN zO#4YINYe}{rjRl&x`$0;%OtH?6XPzp@?kswuy!Hme6|Gg=W>TYift31cLr*~h z8R%tryh%preJz*|?oVe_D?h>5gUk8G>*?$*st2CB;)MIvR$^2$p3L%7^H{6#&nQ68@R#4qJC$MH)klb6r-Za<+Web044fNxvht`4T6${cI z{*@V?VarC2aAst?edv2=0sJc)!RmP0;QG{8a26c-&r_w?(C=1oVctc|tfl@E*GCXE z<31KmC}LJVcZc&8;sROio%oceos3atWNp1U(RJ5_h1X2T1o3ioyj}o4vLjieS<=|D zf!^_Zo}pCz6-<{e#$j3%7Fr3jSDZj!%=ia7dZ zHMEIOVpHp$k1UL>HwzG zw_=NT6l!SH!?gJ)ytPM(65{SpYVtkr0 zLg<v2*90Y} zTEKDnm@ik^uxov{M`BMh4w@6QV-Ed$sbE-?##8R8;>6} zAX%0|`1QAz8@jy~wAVh|fUG<8kPIm|heSn7(sAT8ZlWBR>nRsW-NJi<%pb!*e$`1F zcd;9Nk~~1$pF^R#3}&R!J$zp~j(4X0oy$yMwQ)PwcRUHp&ijM*)8eup+Z{On+tom$ zZRFnunuVhs?mj^dMCX-1?m1)&OP*zr0FuV!saZjzSSMzg)ua3Mli>B>DVl`kac>T^ zLu=}5JewoU?)7kng=71al8W_1K=V#WB*#uGT{>I+bRsLpT57Lr+4s2Anw3Y@OdjZUrJ(9}K@ z|Ed1rX49Mg^dXFk--mu(HNbB$MdOgwWWDZ;hCqi{(rlT6LAQqr%Z7#VAD3QabiF@8&jc+#CnlXWO4|dz+YaI4 z11m9EwhjzKHsL|KEArWf@G~L0%y{;5)U^nLF*n7@lA2dszElH5_16*e{ZB}OuN~N5 z$Rv#X8GLu<9bEghpHKeULVis&hr2s6@q%e4j*JR}+6~d@DLY;?>vjhOJa9!_o8_$T zQrhSK_H^0xy}tOPvJ&dN3Hf~E1GCG`j-9A$JIMO3PcH!3PtvTg#RgyO>;czE7he92 z1WPKdphb|4-USh;dZ!)g|GmcZYmo8S;R5BSGs^7$ZN+@*6IgMNkfE~X!A1L*IC0lpR_W6| z*cK*+FJ8H!gFC%fZXF>SGUpL9Ph7w*{ZuFz(99nV_k?*B2Z=aN!wV0p;j|_FPTFUa z0xet6oZo}ohFH9y@)O=`0zbF(I-@bl1-8`u;s!F9FOOA$;_eZmNm>S^K6*V&m{7x{ zZEwPR`NiNZDk9^v#!^lW<(5>AWyMG<>Fe_a*M2GfXsHs$w{(E@JazuumD{8uwhmrT zG{ZBCB1?6CRDjWz;Ud$jZ=`;hJ1E7xVNy*`;>xss|M*8+hqDVpw}Hun-Ke`f65p(@rz{0CT$4*XX71O)RIgE@ zS%2oSJk>(ARC}0=4;Gl7GE#W<7tqp32C_BZm1b^4a3X_{+__fcr5|x|E z5Y~GL2YMVF+=Ae9OC%N?m&M)B=yNK|9vA6WkUd)r;n_J5RV(G;ilfJ2=g==qSf?JB z@}(J?%_$$~(=gVY*uhz|G;(3&VJzJC1>&52_!B$MlEw^kz$uq;!S@REZ#fP#Z$#s{ zvGE))(F}h+IN{k9f5=v66PVn-L3GRX3~IG;kb6gs44qpb2r#@2cjan`-uCtE5mjr5 zFHarZ!_STS3}frO`Gzhv_MgZDqHa~-hoin&`>qEf#`NQ<(WYcekPwu6+qhZDT`1+Y z8&14+7frjPiZUftF!hN#SstEDOy*HPd@4)+6<$Pz)mAX8F@?;xY!f;3N(ze< z>&t~C+^?BNqFLFC~Tf}MKopaK5ote+K>5UE?Io|FBwM}6l40f zkXPdZ@b;EkfX8yQ|78prA8iHm@?N8LQ$4}9$JfR~S(hg+ zAd@@-2RMWcq6!ER{~}U(yHIe&u?3d&Q@@WQuq!6Vp2#+}s1(@HH6wMB{jYv4!z zRv!YkPJ*x6f1G+3JD^>DIlt)`Jx!fbhiCCDj+xnwKa~C9z*{BE7m1<8&MFu__M2$= z+|$HhvjJRvk;e$uW}~th<-`2FOoG?a4wd-(kmoXyt?s9PhogS5gdNU%Xj`J1;!B9V zsliX*oORNPKLHRm zrJLF2(8FD#_oLsPBGME8m}pP8gSHXpNlryPmOUOKboM{NA60xwCS;kzsGnEx=-o^d zm%j@JdwOtgy}iiA_$8dJIgX9DHQ433yI|z7D3Ry)P%Ni;ipTP5#Q9hs^XBq4Ruwlf zv2*+}<9z`%juU64CfQ<0&MSD~cYv4ImSX#5Y(Y`K0Kcz_!gX(6LX*Q^w6myUhSDtR z%&JqO#ra#&ZZw^}{9GdTYYT~&(Ss8?0y5XT9FtZSz`|2vY+=3>_AI2{SF<;$nU;$i za-P7sT6KQzlMd1Ls5a=E`2{CajWl>Y)kqyiV~H;99Ji~2eIvh#ROGbS14GUa z?&R}ddO+`!9b|XT6zqCb0WR^ftQuw#W7;t^N&FpZ$4=SSO1@?K z!Veo6o*Ys_Po@K&$}Q*DuDDJ1?+Ay8d8&A&OutmlsS@-be-RmM`c8D!++gjCW+tLJ z3}>lUQC`4^^Y~;F%RwjF%Su%qrhSRlRdqC25*jsAy(X7TMsh#F0WRF-bP;D%EiJ z=)ev2NK#u_f?MqRLFs$|e`E7Hq8z3SvAIVEb(PuTUZA!z1UFog#5cu;aL&_L)U-Pf zJMlQoZ-33Ct<~qOCe^_5-V&n7NwAAtx5CBi7sw3{FZ`zS5w@gy^Xqpdk(#B{W41FF z4;`+=ADi#N*Or%9lHSWzhnj%OQ-9In-Dl8Ung7`~Ivo zl&wl3+DloyxKdoWL8L!i3%rNTSs^&1>^Y?G{yMmm&o>o9_O!0Soji}( z4fEJjBAqL$n4D1o7eeNcGd+pK+*=P6DQoLW|3wVdu>w!wxxu;Z@t=fHO)8YPdY{Aw z&)E+eYb)_z%Ni6s?1BT*zi?k*D)DYMfpzIWI5UGnynEM=`eQGM z_$Q)T%ne8#BFQ#RTEtk@4ujRrG3XT1jW>$?;qJ1h=s>CMYri~%1o59Z>vj_<%QS)f zF~czFRT8R^H&x+`Gzc_Xf9 zw7MXF+6zz&oJ-(@0h>kHalw|l-Ax5c(yx9G4%oix|Ij-4@TjMcG%dm ziZ}nnl71a^@Kx5sr?pC;a31~7C)0^?|xjiU9G zRqK&PaE~K5-}Wfnk)`@oZ#J>J;R!`8L;0SUMyRCF1tY5kyn|)gIdZGt5P^g`x6h(l4eSZ55vU&t`NaD zDYj$sOYqrqgilpl%ssmP57MhldEB>(EjzFmKGcPx|DJ<*c!VlDvHWV;nubIizrz)l z94ug_$4^Jw4CVS`J2>Ioaf{Rc8fr`Fh{*7${GpdMk7gK{#E@>s& zj@SslQ`EKpSe_+h-tE7I+6QU(y2TmD@#N~WE&Zv|S&M}YR zU7UMK|9A^%K6D-D|91)fj6&g7S_-K=Mq;l(;06JIerZ^JNn7=_Y{8_o7=dQ1YKL>$V!YT_HMZ?w6{Ku5;Rdvk<_IlT z%JQV(#iAh0*V|8-V4F!myb4OtY_;B#Typ%cIhpBc3zd^UV?;tMHV&c1LEBiF}2BX~?j#tHAfR29+f#UJx47_LMPtGEKw|Y>zFcO?y zC-X+5YPhLiUW0nJkbk^bhPCXVT4mlbw2}?O2*=ax*gPS}uRSF=zor&449z&nOKPmy z);)0O+EwOsx)qjWItUBO^w@)$QtUjMeNcW7LN3ddqHwpg(5*Oz|D(H^EHzbzh))4H zz>p=V$}3Dg3eW0&g^v_=9bX+(82q_1 zru|kY*K>^)Ma+joCa_sUfxBpT2G5S=f%!3nxU9V<==)AJ`Tw$si-Hb&VJ^M78^w|d z*9e*&6cav5jNq5ATERZ7-3Fg6%TcK5hVNEB2V(~*{_j`=vi6b?RE(r>^@A>awtF`m zRGG~U?96xFs=)Jr1Q~9SOyuwC0Yf_kq!*=Q$y+Z-+L=Z4=KT|SjaCq@(Kyd9y?=$h zeRV(ln|=rF9M+;)*K^QRmgWyDoh9Nae(>(_D(<7+C+;Wpmeh@qApT=+k+`w;@F+=( z?DI;(Q-{6a2!DyZb)f#ym%~8ee*EB`{D3mjD;-|oxS3;cYF``p)l2j8K`rEUt1l>v zt>vDZY~}9KPVgNb{me>}KSZ&4C%n2yh}!-D)OPg(H_A>~XI;!_FxFuF`x{P3Za~kY ziLk#)ihtI7lPm6f0e_dv@X^9yti=0j$a)dSsnskN%+ja5%A+8PcJ<1ZLs z9HLr<7uW=55{1Q+XvXXac#@I4dfy3Lr~d->=L&g4+AmqZTODpqHASh>-B|Lm0k-5N zaJdVTh}H|*vA)Tld7qz+mXv=rdTs*YPCIhTa=k$AP$v1YGn@R>Is&V;M)I0^CMX@z z1^=C2!|OCAkb@&OL%pOQ9)Bi6?aC^+KO~O3w6vD6jVADI;&J9H?Qrq-D20E&5@7`-AbBleuX<6o*#{4YY$+~)i|~` z)tGzXIfgm@U6mcv^tbF`W)iB)y1=^?r$K(RaVUx~e z`lfVoOE=%9B#0a`XGA;MXm1O<-^Y-kIq|sc(+FYdswDpOf4_)gpals2mEzOHOBnOx z9t@j1gpd8aO?0_DmfdV@#JObkG4g-*z^^sSxm}eJ*tWe1mPtvF$Ey8|jiEiOrL$^~ z6Qy771@!@$@X`vh^?#wgrLJs5HmhVr&r9Fup;70SAn zbE!rScv0m!JTw_a?9Y3UmACbv=CUf8GOq&n*ibf+Fq0gdRmOdyxApMj-|6!%4;|W` zL6juJPt)xZowE7~c9rA!S85D9C5if@{EWGTh8S)Q)f~ziV!00*kC>uOTI@Y-H^CRl zAQXPt2m1NCA9rMu`99`U3$g+Gm>=joBNi(|U&4%KI{fMJmzdKNsQ0hl zh~oonxVIN;!DLZ9w>M}bnHfO4YnA+&5xUJ-Ksg>~T@#4mfpK_=@|0{sGKu!oFw#rs zaPA&C{=aofD8BUth*b#rD^7Pv3C$k9l`!UtWj2>gr94%MA2Hm(-phvW2amsrOtpCg z#{NgWi&>Y*U6BmwwS2=Gu*!t{{sMWs2=E;}m2Wnz;>3S`1K!h=7k?qgo~JpEJC=bs zyekx?ZQ|HN^NcxhooK-pn#+5CE1s**o5wDl=L(l2eY~d7F~{SY_C36a0T2!{Z3Fu1&&g9+GHqKbB>@EV+YAPcfyJ zHo|woD$Y_XAEk{DtX!TjRm&r|_pMa(`ItoFo{F=wBW=O%QzS7zdI+;KhYR0ZCi7qZ z7LaKX7I1h3?J)mSi4VQ*L1~EuulTc6a2bg%&tL7z2 zV9xFJ5$q~xfSi9Ro|AuPQd%fARqW=~UJpZ%g9lqxaC@INo$kJKn$!Zd|=N}XoE zm)ml;Q5@sW`aw~z``~yV4BT=TZEGzeCwyl#k)oYR^gf6>~21|8cG&&z-)%NTAPehukle-P^hzcb)R0 zo~TsHzL-R8794|!jq-fa=@2~D*a2$B>v*FDLeiD54zl;H(cn-wN;}7~LanWw`zu9G z#iAgV|moZBzw9R_{r(fqBW z#(3sNC;X7qiUxvcpu_q*>EN1H17vITx6$;x#zK_t#ZI=Bjuy@85Z{ zut0}?_q<8m9olPFD=l0wIf1_iX-sDP9$1_bH@F*b{1L}i$Zg|3sM;`^XJ|j2w;m@u zza8~H1;fE>(TwH0_uQXNQbJw5W|C?(njJmK23%%`lUw98F8ClNw4Zr~FAVM@$39tr zB2$hbL$dI3U<+(llje^mY!_`#ie-05*>j2q`WTCot{@h+i+idZiRT5BA9C+5Q|I!L zk;5&lQMM{$5bKE=e)QiwF_p}tOz*eZ{cyxEf?roRni{mNVeN@ZwB8ws;oj{~RV>R_ zsUxEqw+ALC?c{vtY{$-jRWK*|E@S%LoS6R9gC2>=WV>Dko?A$HJ3CTI{g+bCO5O&9 zZ~mZid>(dRZiR@fHTxKlAz;NFDXfZy-s zL@m~0&71LP9_<2N97Pt)8IN+5_Y(hw z>Y|!qgpKwE9aTkMK2`}AXuO59S2praIgiOl%{X@NSNp*kevPs(?*8F8m+J52+Ohp$ zDelKC*%*O_J&hprrM=$1G9=^jYc?=^EYT$|aE=1)U@D!-->|Iav7c`Q$lFiYlJqQ6QrRPCkQ zn-*6RVXzLCE%70|b15e7qdI(2IA8NZha6^=LH1n8;9gy8;stv8=Wx<{>W`(F{S|NR zxr$S#7za%wkeRH{brt2~e>4@Ov@(vdIAFrfuD%cXHWx{_jVxQ}Zwst!1nmbmTt02{dE7)}N{g6CYL4XJ&RS3U-^8)kesATD>|Kn7<9EZFMGk{Ae7trgY%IIYytGUrMT|bg zXiO#}ebVtVohR4nJlXa7uSklO5MEJ;!}LjyG1Yr57HYLabc8JLu>CBN z@rz@h+ic~O4aIR`jUVW~I?BC>`^1g!p)+>J9cG?m6L}hB1gFPNC%-R5;WN6cOrkTk zfM&EdUmOO`Gg1ccjN6C!gXiN97@DYnX}{XxlZ7Im8TWw9+7!p`=-bOR{cYnuObGzv zx@68$cL(>cyc(*$r!(&~hOnBq++cR|d{TZg7|SJ(!mfJ>WKn)GQw@nX+DWmwH<>oTgLJ(!$Z+z>noU5X38&ot3wV{ zsRMIsC+<4mjh@>nuTN&*;5^UYd<%Xjedkmf&yql=4e;1u0h6kdgC+i@5Ec0*U;%8HPH9 z*;dAiw5iq_R`r&9*W3D=66#s;yTb9=RverrDD}|Nul|Z1b(M-D$}~k z6+UA!zMidtqK|Q`$Gd%l^SpSd5xh(B2P z6)Lp<_xK4itmia}rb-HbJWSwUIld!nCR>6@TrIv>l7(xl?!&TgBl%0>J4C0(#ImAS zZd^gy2c}5X6}C2ob6p(~sIaXI3Z5Y2C^v$9b+Tm_nM`Gpl6=so+Y5AfsvFUroZZ(C zBX36YR;8oaC1Y%0-uebqyAz3LqJM#R=Pdq~!2@RRSXb~Y59g9EZb#Ss_0TV$#k_lJ zLx$08%gdMYBs{(XW3GCEN@@c6sawW94zz)qZQ}fe5&0Nb)&^QH_4zm3dPF~=Pc?@(dSSgys+)T59P7iVZ_3Bu3j(ZPZ9WD40>nltwoh`T5?&a2++Hgy5SHTs{UasJb z0ZE#_0Uj-0z^L~&)69M;*tG=_J+tvxp>hrzry5OcKpiC zon$3tNx7@+<>nnVD+#z>2iITpaRtNw60g^L!D!Tarp7KD4_&JRM=p|lHXBM@|Gi>o zo*G5&2X$Zp7Xd3h=J1Z<)!e@L*D&(YCO&+I4C_m%=D*?;24|hbr?iK9e=yDBrAG@y zb=1$0CXNpeu43JUuJG{pI>y4;8WV3dg4oY!V!d_`NqDyop7eMS%P*y9Quzml%AV#$ z{`y2$TN&IxL=9@uE)ywhrTjV;Sjl1)&C86Lca)1VImKunH-amsVcgii`S?5_5LSn1 zFpAH0IH&eTaEJ<}{H~#_)>S*m-X2K$79FNsP)Xt3Gs(QuoowQ^$r6T6Z^GzDRru}j z3GlQo#vq9^Tr$l*m~K7B$z>NYd9kKY6B)r}EKfig>nf<|4PwNW6bq(X+=9fMFcP~~ zpIvgn7VP&0kfuC9A4y4}dPp)qal$J0>xLtcy8SJh& z+>Nfqcy7pU_;fXea|u<&qKDM0eAS=H8j?gp&+3C`v<&6aq~ol;bY3C7`5gTxic%UY zoIT?z?@)G?wVdn$!oF@S|GE|<9D0DCG?~A4?>w=g^EP6c57)Ou9OoN^g2QU$B>oe_ z*wlBpZ$dt$5a;5^UK2!Y;j6!=67=`zLNi6M-pYNec zbi*Q1Y`qP9bdlnNIvY{#cQnoX4(D5s7jnV2UEnM+nU~O#VIyhxdWNkpryx_z&0Spw z*;%8oy=$r9?*!UA|L-7^SGIz6vfByY$0?Ctvkmdy9&d;@QsR#|hvLhS9{3t<&j076 zO&SiW!!{jvT(qGZpPi+i>KT6A%DH2?D1~&al@Z&yp#fsc1GfF*89=A*1CR4+W;dqM}qrWc}uQimxnEReoqZ-O6`W*p$5KSC3 zrPGZhDIUygPPF?^SokDz33%{^Pa5zd%J z3covEp~&+%h*Z_NBiCAl_zSEz+x0lv#5i8>S$|P%tPi=t#p29yBgHa*Z_$)N1NjZi z^B?}H0+%~nMw{%Xke@u9=8bcdWV0OZ>%U&YHl;33cDO5;97q?2)`j7LZ|v4-wU1k* z{h7P{)tcYnH=LVo?1hI1XEHA26Y@CC9{+muKze61b+jMKuh6%Kugt$Xbl_=J8vPQq z?8ngfF#^|+?gp8$mxWUr+i~Q%LU{1mg9|xtL7EbDAt`epQK`*C)sXw($a2av56Yp< zTWi=}CPO#5-$X@c#y2V7L^rQ|BXQ7VbK60krmWZGOY)=mhugh{cXE*ebQQoc14VSB zb)3;8E&juwcCCLtZS4;SApQ0fVtPysSDw!Yo%mLAXkI#*_Qo16m&(vK-zcn|^Z_Q6 z*wCL=SGnldQM{Iqci-GDTT=nAmMWvi4pSm=-2i!!e?)F9lV&$b0+p){5%*Q2G0eOO z1{J&^Y1Iv6$~`ZzKR%YK-5-r!|N8=Wa<|h#F3n`vt|;Diw6~DhWsInUGpydD%;haSfrr|Q;phinvZQz**(dj&cdTIh_>R|T^yoCmNYA52oyEf3`yFs& zpEaGlN1iuj-kZzCF(|Dbg4G%9tv%1DZ*F@Yc?R68v1q+~1@Euv3Oz@M_h~75HARrO z#Fs=fu2AM|Z8+Yxi@a9L#iP@{gE%#sN*k^vg2Q--J`~-jrR?5&1Yq7R9LF+H16DtU z&JPq9Csq^B|2D#H!ig)_73qqTG$hLA$cu5W>?Yc+VCE5x1d!4OrGhdrwjgugFX7xd~tp*|stDSfC%(_`F=~WO(<}#sS{c!PHjXPB1(hdH6;2{`1@iSiAt%LOet?=@v zI!#`6o_M)L^JbZWeS5ge+r#ixr9`-QD?un_#i=Wv`*L43MxAb7ewDUVCQlgqQA zZscP!%5)L;r&1P9Pff%9v)b_Y0w35qu@~3X3`6%%?QrqWRH|nAf^12P=BJ(s7AnJD z3X>Cp;7DDQ@XxdD=T-$BZzppfSjSgjjuVXAHiX2?3&4YCts$UXmTuK8$34v#z>8O- z>y}mu%Y0g3QMEeFeIUzcGJS0Gvmn8KL6*?V7lW?J6#UeGktls@2_#rgS`&%%8FFof);>rw^sn3N$h1-aotCP^|Rt9sp7Sa$X&r4_cKvkYkW?BP4)iH|uLcE@9?4dRi(0nDFy0Cyhq7Y??R!=SG-kUvyKJ|r2zf5{g_ zuZ~8cT#^Ld-gO{psxF zcpbYc4`H}(3$z%m5xCT_zOOYG$gY>` zp=PZO`F=hbkA*6VZG;S(5PF5X{dTDM#)}a8@oW*FQ|}7am#*MeVL8fT1N5qtqO13L zLLP2}k?I*jxMve?_xA-CmnzXApH{)Fy9m}ScPD#Vo|4#ZTkw@X)aUD4+4~!`JQL{I zfEE(Ux>*jKeS$}yUdAO3wa`9oEUjpDl&tyo0ZKbrAE7DXb&{Q6!Muk;qWwwS@H`(T zRgC5S`T8=CS@Y5b?AEH_g_DNdhyBrIWMth|Jo>u_JnQ3WUEWZBfvgSOEU&|aFy`Sm zcnP~6PofLV1up853y8kv34LUP>mM zmBly(8;BYzN3UGCiPyis0`uz@G_&Q6!+ zHwEvdJ?FMrYwLIsyAs)WFoc|r*3aVDQqSi}R zXwE!lM+H}+IeREty>;B($rTynw>U9?*uEM1*$Qr<`m%wqWQq7!{H+;Nl(*xBU?TRS8CoYy=D#qOVm{=}8Owe4DI(l14AiKSsOtxRhU3?)6x}8_B(uU1&mbcAy8bHr#E91$ACQ!LPoqjo6OEjOGz|1Lz zSbh5}p0^GHt@D3`^G95Tc#C{kqN1_I8l|_J_NebsUS?O-e;sk*Yi_$I!VK z;E?oGI?bsYTj5~+r!?GilL}s5GDX2dRTa;C)6*+-m(qC+-=}pg-v;0r_Jh<=c zgAq-wIPHlaoCY8Eu9e17zYAfN(=r_B8cPnP8o+nmQKBN%tN8MvKQwlZAb)Pn5OU(m z;X-&l`J=7Cp9}VZL%%1}QpROcvE#^=nlZ*rM5#{CvfdMpcq#k4L5NzsfYIJ8r(g{gba8(ga3QzjO1T`;E-}> zFi_PH{mV-ZmM;STA6v-9{8UmrP8+fx8R(Px_xvp z|4qag7GrN?=BpKG@T&#VnqS~O=B*DNYy>*j9|~0!O}IxR5N@cg5zVdX5FSpohwp~2 zB(p9Kf8Xx``*COK3-4yKRLc@3NjG5Lx+^$PsUCu-sL|PUr({E7Cp2rlLFG2W-y7`; zPH`{#^ppFnQ*^t2m`G;CC$8+f9ltW?r|9uOA6(M^KFq)WkUYrRibop$!m~T)sOqrc zyn#LAWX*hu8TF@Gj4ti9g>#e9dO5gF5Mcqh%Z>o zH1;}2>`E2O?IVZY-~$m^h&#HYavX1-GEo8dKkyC7-_dlkHFB%@`+Aad~u z^lH+}S+t`N7PTxz`spXpZQKbl>t>4nW!~dizPl{Yl3aQ!L-LY4`QZV-xqm(rf42y@ zvSc}p-&HD9?tTMj=I@{r&&u*Ama)F>o>b(ggksO17r+m#!wb{uxW?Ph;KD5(Y;#+| z?_A&lpLb}86n9zT&~dDvKiix%DQ+WrQQBZ+WI{@ubFuXDH~6$Xkp`=;B||jFL+XdK zeKVXt;0M=+mG;f>C`m1tKdr}|)BYoWXB)wpq1A#;^ez1L$`8`j#%OgrtQVBs%b(3lz1=3z>Gf3D^gJHtbQHkElyO=acd|s&-wYOKV>t1W58=}`*};!E2l7d3 z6;6HLUo3fhfu@-*Cz%Ud^olhGCSwepU;iRZX+=~)mwveZ@fm0AZM7Y z+$FrYIs*sk=Y#h4w3Yw#aGz*BDEm~!?fKs&Y*)#G?;~@GhsO$`uyTNy7+s>jha~b+ z6A!`w|39efu8qg)UPJoec{IH#nPgO$z<}$U@yPlttXKAe!7~P+?&S}HEMp>=INGjI zyii6a&tcxnYt7uDfeF}hI}7H`%O$7jLazO-EX;U&9j8aN;odMG2vi?PtG6g)h-^FT zm0d_rCpVD)Z8U|j1WP&plA_hdf&A3Lmb0;B*oK z@uHCpto0m1zs{_{hcTyNVdO~KA#+dgsCf;&#`Ed@^K!hyXcrhgavvrvioo~LC7@@! z5wo;3MXVPDT%rSVJ$EeTZ%uWE{ii!PGm$Z#56T10uX&7<>q-i=yudDR3Uyu*g0Jo5 z#KluWscxYYajjr^$%6rS{#z@`4e^KRe}Zs9tu$W$R16t+4AHwgj(7|-gphSgx%%!` zadN)^kRCgbfEmZ3da zH)#fcKk=I6UtaRYWGB{7tC~BOjzC{u9%1qy71doEB3EoSavGl-k zpb-mm|LH2;zboK+fTrfqg0D_wQa{qa=yI6*0#gbC4`({4M>D~vY8~4f7`Ety+Y6GoBL#V>uTi6iS z0wbU7q~EGKB&DJ6;fVGUx`uV17A$jt-Anf2$i&_FdVdKFBpdNTMg!;Zh36d=q;eA1 z1>x9o52&8q&3%735pz@X;oZ;z;y65=c-q=R!jz%(uMmyv+I~W-wHMvfb&uO3=K_f` z`*36Ge6*D+hM5urtoUj`g8Z2uzDqH;SX_leWRJt$83Rbon`*&l!6OjPvDrE;)|Gr<+1{rSfsJHa$@V(x&Z zK+I;IuH*#f<=-Jg7AbY{;?rH+HMKXmS2YT>;t9R~yj<8nvK>b6bf&9b58^ZItzb^v zWzhU8F1l|14i=ipbWiD8^4o4aybno17t=Nj3G{`V6CR^pvjW?zYayHE{6w8K zL^;g}`j2}j^h)2xLMuP`vvj?rAbFkOIid)TYA+=rp;CN?l>=yaS&^;Nk70YkZ#dtP zN}ooh5^H%YFg?J6aW4kwpBPTr3Xe>rc!Ci0)ESlLom!;iYA2n zVi3n}Veb~v+NB$byQ3IFv<>@wgTfwX=vXC#-1!;!nK5+!zDt!j*`FcBy?QX#Et~T! zzl8mDvzYF5lblOjA-JX-1b1aA8v0cmr)j={ej3Z@5W`gBG2E2t(hm6HWEL(`@q+Eg zhBDs!2O(*65eVuxB!4n0$+iAQpj#v1E;O9R5p#23;QZU(m%@7M5w@H_NQRF+i1Ez_KrZqTiJVLDQ!`c z=e1V4KtEk?tlJoYjV#k~`}Phjc%doU@U{>h`qfCb2%7w+Z+qaq-V^Srzd4qqDT?EV zvo18}406ui3kIE^K^J(0U=pt+4pobyswel7^rQ2jd2UGGP1CUM03<2}piJsF!Qp2K zytLebYacSt-#SCcIBX@kn06J7e+EEz&PQ(k+*v|-K?N*5mq*UXDDq$Qd_Z~HY?}0a z3tqSQ3|cRb(Xhl+GSP4|tc$*i3Tr5?abWtAdK8+x3lyN^5lq^<6K4jMlS9jl;d6$a zWFPZ|44Z+l>G%w?m35pQw5)*BT6yHEvL#=+FB8T1;10@ z;=xrJc;!nyWR96jhcxe!Y*1=s48%`NmsrUA{bGBmryR>EhGESjb_dU|mOS13iA&P8 z<-cYXh}Oz^V~}4Ktnj-|E_pei4QXd1kf5W}F2XQKAP50e86iSNW*9Hw&8gUMJ&Z3gT6wvM zOIC1!Sqr?;^~QYWM=yaxw;XYf(?*iqZU9Q7tR$CHt1z^{7ZOLky7!{Z$f z$*A2emtji!WK*!u{hf{LPAl7n@hn(N5*U)X+cBY2(irVI%qRB{tCT;1*6@ zc@oE+c?F$i-MFFj83$Hwa6JB)B;CmxQzkP%bIBa?-y#PRIYEc8;wQu)+#(Zm!y=t%>74YGkr{K8eE!H^HkZIqI;M1MYf`-m*oK+DF zLlPn+%L)wyf%)*aT%AK?<_+Mr8y&&QdJ9ST>V?B@{RRCGm#B{KMWVCG3L>t&#Ww?r zv0U^F)Q#uTXHs7UkJ@HXVGMUZMS(BPH-S@~U;AeD_3(U{C-+!VyXU^BJVjo-)YXG* zt_|Q#lD4v*eCEmjyc!)x^fC?VB6TcY$WOX>6ec(iq*t%`WA(*m_@uCymfkQVn_0f5 zq0@ELU#FTD=-*>XPuVW(6Ha-W;{&$o73Do31-joIF1DSaEP#b0$dqeOtMY?RlF!Vjp z1V8t$prcqu{zr)^JYTR6!8-}JZ3uw$vRP>HbGNW5I3Lb#WFs@Ym$WWm-iAr{xs<>_ z91>mu@(r29&_RXh+1tXTs8KY;t`ZF&g~Op~lj#3$WD1@a+kvoH^+6W}eki&?ouLu=>w^&PLu0HI7ul>Qh-H%kLO*T=dm65R9_ZyT1)`EDUL^ZC&o?+FoX+=Ws-g`SvPmN zKO_cLa{n}wA7=_+NXvEd>X8h;-03(}Y@1Jy_FCb+%Fj@H?l{fwcY#E8Zicrj?qFUs z#nOgq*m|!E=g+AY?u{~rcEf!`Jpzmw-tY}-%#SwDkT$R%=7&K}@7WU z7NKNwD_njvfI9Z35oyCsFwaH?SBhG2j?8foH2Vpk+M9)nN0o4=dlEUa>?IjF%O0Zi zv`Og0I9#-Iu-I%0(h*ku`0xlTs94#BzfWdh=htU&d&FXzqv#|VXY~>!J%3R7;UZrC zqAQ#O6`ZyD6iygX0Pc0XkoTMUPbzHr2Z~oknH#-vSq#gZ&bvVJf*r7MUk^N@Y4mXM zQ2sh&>OHOR#$$>R80zsBwhaTS0Y%*7)_q{MXdL6-@5b8q1>lzff=&ZVJI~XHu1|^F zMXrGL05CS9`9)GQQ~_Tl*}`676b1d;=;hi5x1JuP>OVUrrt>-=;+U8wlr7?G=DCBu zRxm1Gbj3zv5nsM4t8Wh5eB1}K4JDkF=On!6$7V>yb<+AUo$Q=%2kw(psH$fS$~S!j z^Cx~(zV!}g+r;MZ=0Kceu>em_XW6A|rIPopRk-zq4_rJ@!WG0-3*VR?a`M(~@~;E% z?i_EpWjCj9_D8 zy8J*CpDF;^5u=Hor!@KA_L1?lo^bzo!H47{q2ktB+Ap?DczU=OKI{yl35!PZQtNDC zDVmqc6A9G|nSQG42AkA7B>q;`DE^xdyHZsMNIQ@l zaXPSLlP1v?OVH@AtoW}>HeK#%NrJ|+yX2G%+&sMvt=xQJ@w=CO`*S$0hY_p#(NXK4 zl8YV3VW{JDq2Hl3LgC|ln7>$#tdSeQOF!KK9uL=&iyq!MdRIU3q^@gJ*nNrAL|Z|3 z+82~zp}WwU=P+W*3i{>KH^Hp38Fsysq3f?I@cfArKo@8Vv0XkQjTolo_8(8w`&;oZ zb~^xFw2COXtws4;zoC|W|1aKL$Qv{tgbG!8>aoTbea5zd((G0AbU$Nqey$k$*E{s- z9$)KApeWK;Xev2JW@hVy`NU9ewrv`=ndg9X(^<0ojFuqPeFRebDblF_^l;VC*AVy+ z=#68^D6|M|MU}&W@MeDsJ~JJJYeg}9!V?2wlSU6pk7>wtou^|W91B7SDLJCv_Fje}L# zPAiIL?0^lzw&YY%euaoHS~Exzs2G5%-2Xs2?79EMPgW_!NP)&XSVGij30^Oo4KArj2Z5{YNWG3<4D8YyKd%;@!20gb{j|`Jz*%_}JeRK6U z>&z)lZNssL6;Q>q3C2%Wprblp5S5d@uwc(tVWsO@;mYxR7_HpKnbq{?M||1=lPi{! zEY`oFI96J`<6$O!XPiNfXjp@Pat|JnE5U0W4e(|II~lD0A;<(YgY9@lIy+c_&uow8 z!xwH5HjjTUWX2c5qxcM=&?;M0eY6>VZSD6&@)}I(_zizlZqSae z3wcAIgD~tM>-L}Qi&MrmgJ{-TTHs(v(iezfaDiLjep_{j^%d{lB4|7@5uUNmmhnE< zg`xkQC09H3;o4CrZcbntc6DaMjvE-FDZe+mbt>(XG{3B7tY|(<;`8KG{$dx zDULh_{#!qYW#=_QXq#FM|^_SciN*vOnr7qK~99p5*H^EUcH=d4R;A(BQb zqiFuEgN>lMe>*q#t07E3vq~7xUBlH(e~3RB$$gwWOHkcj3BRn8Nt=}-FQe)Wn4?LH ztu63qeGlxs6-Ltyu8^s97Eo>e0KJ|*K*S5*H+{De;_ta8e#dP)l_POo1`}PJ>zhVpl{D|{5Qr*TQtx{aLBzQd~9Hu;^kSw z*l%5&x|I!IE$boLcEAhYj?9HgX5mEc#10&`dWbmHznJ=HOyw(Y+JdxZKl*RiO_}ktVn*EK1koRCSvP@BhC6us;~S`N_ob@kpCtOW@8JG00~&6)h)=$M2o}yy#CgjP;AG}Cs<>h; z6f@?~+WricSH4g(_e}sQv)t(#$8G^oel`zTtF+NicfX46$j+)gA?>oz& zk!4Q~U2P_boHv|q)1<0j$Dr!!Cy;wbhGu<;&6yL-_#O8d^E6+=Rqu0$t{?V-FySQb zXWfIgN_8BDOB4T%&HT1eH@KtMo?-0YNVpSXNE>EW2->6voGrqr-JlWtL@QgEy}S^e zADl$zLqFm6j`7r0vzu$3&b+46Y=j{y{m2of4N9bJgt-ST@$-j#u$x}XWwvi4wY@qp zzH0)Rdy;h~l=gyI;!T=pt4HR39tX$2-0bt?onu`MLtEaUH|sZfe1Ul_Y8B~$sV~S& z?Py+mvyBjZ@~97#Q=2|{FPGpNlUOgCn-H!|Db@~^YGbn=3MWku*I&`q_g+H5a(ogI=u($UZ%pamm)uRJY zp}ieM&3g3SLle@iB!*<8z4))ADUW?Oax<)jn)k-S#bn0fRK737rko+LaRZFmX~!+B zOT!WBIj|${G%>f(5(aJcfj1>1sH4s%tU1*NuW##8Fi#=H#2kDg0&r$*4t_rw&Hq3f z!L3k1*vzuhM(SCDgFyvp{jmw|Mmusz^CR#kL-pMWj3gfumU2fQ$byDN9@hV5EQ3&Q z*b$&Y!y<;^@1ft|r-dzDy1Rqu+%kjfI-z)D!#R{;S*@Q-T!ov_J`!WkQaJyyL-^ks zDPDm)05O6Y7j`8S1231sx8ewb9V1DJg&n;6qDp%%RiRn+1-RG^G`X@;xHIn~yZu?v zG_|387@OPXzNb;wHwdSiMe{?%Zi3nIfm$p3)x+WB9%1H^HT+sdXZS6(fpZ^bjF)PQ zV7>k+@}+#=~cvW1jvVY+d168fivQQKTlOOjLHY~`pewh zOXtbQP93-ys7&mKrC^AsjQHRsfp&$Za6UHs;q>`eIBhk-8BCkP$lQ2)XiJ(*zWt2D=VY{4=14sqd{~bE zFWegJXAPk1Vy>dqoJRN@u0zQqSILaS?_vBK*5~iZ@p0)<{9O%K!E@~$VOn4T$P8{3 ztiroEwF$PoL7`amuPfEbJOCctuH<#a>uRQ^n>EiChwqT3+?_ucI; zHVJT|j+b9>>Fj&>XQ?amorVe9YgmW;$u{91%iyPI1B~VtafQnYvHrhonES?`IDVGL z`EvGfXpb5__TUb#h<*=NmcjJ>y{{6Ps1B$uHKny1H2DT;H`unEF(Pg{<4(q)Tz|$@ zxU@M{Bv6jeSYRb#hIKTV!S$=j`IM54_!oFp}>d^i?8|Nevp zn&DJuZzd;w!4(pIox%4*7UBmnV{fUs3CiZz%6$dZl*uRkAg3l_W7lhi2%$xx=*hZXcPCxpOzot}fGy3uwtGt74FB>x8qOUvqhDVzK7BFs&XEY} zv3mqRh_Rnmjx57T2T$UK;Z1PEbvWH~=s71&isI*wcNKaK{&M}VmWzzacf(suH67M{jPd~9c@#}NrV8^@reOZ{;`MzNI?kjo~E8wr+ zufX?zDzqx<1$ogM#fP3fB-Bm%E13TZ0yFtL!nKGE!pz)4=y(>!?O7+q>qvHi?l)B; zareQ}sl5a?ch)rmL-taNBbiE>lI*^ zr8lWaS<2<>$+9;{VV~|HH`yEFvd2=VdBa#IT@S3iLT}7o5TMw0t1WAp^r=y zzqt0O&^^dU@?S_XjJY9?v$pr=4Ru)$YKIEvzSbYLZe%;ZwJrTPoc&w zRj8;F0l|mnQ^#xfg);ZIAir-59g?HSFVeArLnmUfcvUbSo)^vA@A49cY#*pa=DmdJ zW@B+zoen?ktqXMXW4X#K6O3#xg5@*)$d9KUq%p!125i@)|2+x735tKAur!ulcd{e_ zGv|Tg<8LQW!0#_tG#HQdtSavEK z4N0Joe=(Z3t@7&I!QgYjdibUQ&@6m0nHpzn}m zeTVWBiLlPGpZHvT9F^Im#pnHRA7~Y|;l-H4=x*8$KN&l zJ7f#XB7Gj@)i=XcKLtYKc8QR+_=C_ZVm$8KM>)->HN?!v9tJj#B4sUcI9YzI`1avf z)Nq~xzoE?BH;Z;pYs=PdGd>O}O>7$kP<&8Hvb#`A#(nZ7Y%5G}qN zf!~(*6E7aQhx#vj&h6R}#hZH_6HX2d6BeZxK;jKqT#~q%Ecf037mZ~&1J6RNV%^I_ zvlfyT?;=5JjXi95IfeQRzKdfcJK(KaC|z9oMPhpMCv48%MQ!I1-sALsNOMm^W8MS3 z%A@&XpS*+|;|rqocL+Zs+*k5_cOc4E9fku@>YS`-GVXX#0sqSiBHj@<$=d>ZSi$^Y zcI~m4G_)6lgcv%YEQ`B;+ZAdaq~OdM3-P99G%tVJt8e%Iy=NmleR@jp*Q!Q7$`2MC z)8KsGKNYgxF($&(<3z6h88Kbz1C4ni+O=UEe(fA7j=ON1hPx^7W$S9;j`DCiW`BIn zB=(snPkHs}&nO8&Q6s3)iv+k*SLX{AK$GPD*m<(fRr$u45eZ&y@7}H*!As zz=NJ&c-vbZHy&+*Kn=$Koz_TZsW6s$nV+!G?5}YBdIr(A@DLzC#2&TK*JN-GR@ zR->(~_b|L7iZ}i4CtOah7sA=ivGUdv;pjRa(Zub|zz11zYp4|uraNJgt}@BLsf{M) z1H_vPDOImn#*c6Dg8$}EpmAA&cztC%EY-HAbL~t>?kF*I-U#gTZ*1Hi&9}bu@6${! zlohg`#+3PdXm)A5aEE)-4PO&CY5siHpz;v8qcrW%Kx#7wr zSj`^B%FUq5Qy=5}$Z&|NT13~hWHRmdGhCjtn_BKy=9lfU0=MId7(Fuxt=}^(!YfFi zBL`{y(5quT%yY0Vel=gg?t@!CKN3lLOwmuDW!U?G&FaHJj zg!$YW&B=prbK#9kdSBnj(;9!stU%OzCWFD2b#QfJ0cL)>KpN&5L3M4KP_KU-d0>5s z*ItNbEuA7M%Ofu3M&&xceo-19f`qNZA>>VXcPs+{#EI90?c2VdN4iaYFw*8oK5KImP^Pr^m}tNB?WMQK|{{w{50{ihCuao8E)l z(HXR*jpL`=yTXjo7HGQS6uQ1H1{Yg3JbC*IH)etzzhbPQ^>H8T7JlIc=T=Q1{b3Te zoF63K6{uky*dD1QF&$yN;&hS#n9MdLl#bK=TFgAZ; z-#mAoY5*TTToa`XFG5?nTo4^}AbZOdP|AzVbAuVwf6HCQ)9nDe^QUOl^ska51|OkQ zaHMqxOL_Hb#sqY^iZ1bc@bJ-RFl=ZM_C|l?7WU)#)N`?t{mTOImmll4B2PpQZ%)Qj zx|PuM^9Xq?b&DvgZH3>3GpH;Vhi_ebA#iU3oijU|Yq`K!nHpDc)VqbKn%e@#hb!@+ zyfYbpawD{uqzTiks&N7O!Hm~UBKx_u!Z^mMIr3{Sc_RCQ^v?7F7k8j1%*SDC*KbIg znm`LJJ4nd8TF{6ZL%Y7k=kz{*1!)asSW>RUk7YT><|08b)jEM%bMoQH<*6L+B}L|R zH1n(W2Xme?pX2zmu`v6wJyi;?5fV1`!e`qAs&aTFAFN^vlLyrI=_>Jm8=>m#MEW$c zp4+zkCs+(=L6uBnemZf18TKd`1zKXsK-N_iJe7M?vz6SmU_IVje{v5b0#5Mw3o~jY zbj#QcL|S@0%-@E1+>h-dNj|W=_c!Wm%A;Li6X-gr(hW-*$#O*#s2C&0jaqkc;a49B za;O%ZMy(ct1{6Z+lIh%z(gFN-X=lhv8cHl~9LJ)-UQpVeOQ&UCAYMmppm?MlwTO6x z+b3Uwre|vO;qY7`D*ZJqxTsF;dlmUiYZLgoO^pBjiN`%v-k=#)B`mtWS0s7a09X80 zaK5JIeE1w^sJlOuoawKRyUzC)e@dhDam`YGgO@irzL-dr9D>keaXaj5v+0}Xij&2# zUL_dy-oD0Tna;2$!W`%Qoq-Py7J|F$Bpf^CEV(}002X&&6Gix?|<^ zYSeYazM7*Rq&(>67qk4hv5G29E8m3ExAnp$yM6R-&TYaqGq%o}c+@jsnWH>^*b=r6 z4_p2c>Wa!h!D|XWx$=Z8@-c>m`)-TYpNK%U-iNT@t1~&XcO{pcC<`NgSKz|M?f5~( z8{7t~(;S^)s6Mv~_BpuH(ZkzF$X9b{a5;y`+mewc1u?#)A0ArGbP8SejtkaAyjfWg* z$V5fnG}0PMqEm6i+aUaHQ3cn$N^ohw3eo!HI(WNsEiQV$n$OMI14_V)GDPM$>~R5j zuirw-m%5WWJ5LznxRM@h4?yw5?@;BFK>xEaB|UptZoTOmmM(6??aTc@dr$$M(3fU8 z^Jh?ar3QbtT_Ry2Mqq!13N}gCQJH!0rh|d#p44Q);A9zmr}iY%Ql5V__&8XcT1y9L zvW|TVmZ#27q#7ny$n<`eV7C5w-#jlLR|mD_ljy<1TEV&Bb2wa9gJz=|$z(-Sc-xpK zeCdh7PNO0?;D1&mcWf{>?_CAhT00Q6otAu~(N8%0GM7$8Uf9EO>uO==X|O8WX$KvJ zkVU;XcfAjet9S_&N2k(oVGCKNJCm=-nk>XufKTRoqQU(Gl|pb+6NWtU$K1_!G10+(5*3p{>#WbEZGDh)p|Iq zw*@u79fuB|PeMe}Yhhwo9&`mHh<-{}ldBRtc%k)+%h?o%g}Voct>X%)<)04H5pM%` zH!ISa8Q0L~X$wppy_I%r?w71P_Yoc}SU^|K0bX&w3xrv0$2~!eAD2-ABSV&9YsObj zlxEGVk6fVjFZ1Z;>IE(~gUR9B6YCMX4_EuNfA^xEWrT^mPF0W0M52e5e12h(8v2ZEtmw59O$7gkO zhr}X&;{2T&oTCElsS4W#!s^xZBA zd+Yfhz9>3ls7SJ^oB5xvhq)~I=Xgga2CSDk(A$lV1!wyna41Ra(^Yy6Y#}1@B@X|3 z5?8jrf*TvAQAeNWT%*bl_|^FlN0x5lCnvi?(Yoh?KI>xJ@wfz5`J5BI3*ALtc1?;~ z2mR~vLT^9bA@CLxKZM!0FzTl?i+#hO0k>u#UB4b<7HGxw$N4 z8ddl0>^c0hvHx|}_CeX-zqAxtw|M+U|WBlo}A!yK07*>JrYV~syT+QB%QyM7d& zN@ScDRTuisQIU_&vxb2;7~^YLFkbOz{{PY^=#aQlWI5{@T&}dnGp1|#sD;i@bx1eo z-dtn+`X~=hh*pyu_gu;9^!?yLI65>o0Hr^EgQuI%(mHBFs;cI~$1k_~c5;JJelWJX z6k)M6K2>gqe#IRqqkogk{AmPY&syQ|pX>N(*KwG9&@N}^t|`K(h$3hnw4T`f8pwMl zG0lM*(Gew%xaL+5+;vQ*^_Q-YoJWjNCDV+?jD?|}SO*V&PNhRO*9p2>^{_tu1@1L# zAa|dz{OQ(bf@XaTzCT+5FUZZDb@zsI-tOffywfMu)fW8U@Skx0D5Y{kK?w7c6;B;~ zoem9M&)2pvo>Z?4l{NIoNQV|ct+{lOnGNX}GlReAKU?_c&bgl4)!Qs-lFrZ@6Q#=YDgOm zvs6Ue==aI*59o%+z3=-zulMWqdR}yVKz^Bavd^_0K)pbf$V|>g`)ZnjGW8&5H|-Mb z#5Q<&eil*DVz{gGX!pnnKMa``hlJ*#a^5Y+uEg&QpXkJ`b>eUHD}!;(gnh88pqt5_ zpoydC3}2N}N;XqouVtJQJY1?qMrWKr&B|X;pL39m=&WJ5H$D)0&mTMQyP@l=Qt%wM z3^RH*usaf0Lfg<8g=#_fP+J@ZuBviu*z-~$rNo&&SQ(P7$v06&z7w|2I!%(Ax#7gr%!|zN{=8ZbQNpxy@|csdI;ia2byWscr=pg zf$pSp4zj+&yy=q)bjSm!m|1LDojlmsemGnK6T{!Er z0{d)j6F0Edl{w*Chj*P5;j6kQX$XHJw6^~NwYIaQ(s&3Ld&>c=Rhsd};v;BDKEMpk znZ$W+BcreT6Q)h;!P^R}x!;c|KSlbtu;7j(y2?L+Px3bkhw=Vw8f7sAa#hTe5r{k5 zyJ2olF}anpjMa_SgjvqiJ4!u%5f4Hj%ubO6QclTii$++iHItki{f^a@vW7%`Cp@fs z6DM|t!0B~^u>8M8!me4R@GNMb=%26mi1Ke*@ zBk`MP|Fhl+C`r*Etsm2bCFV_FH)j@k6fl5WNV6wS&z&$U@ifl=h#FAtfApZ4cv z7H9>5qPZUBU#L-SupMHS?M;hFYt4SialXG^nK(?ylU6gI_J-cKx7wg1e(=W&Ij- zNq++~^%k?An+n&K9m>ivps zYF`Wa9-YFbj+0ohqKxvR1<{y~s!XnX6=;8$!$ycVaME-~vWYAq%89&CnjlBxl{uuo zdJ)HT?g5{D(&V^BAl@3$0Ogx!5j~wv?BGF@xaS{c_0RL)zr0|_6FIznbqr3@en=Un z#iH)@S?tw&7I0?6O(uVPD$d`ylRt72#8x|ovnRFofzt>X^3rwzP8-ogS$?xgRSX5p|3Wuqq+iqfvturp1ZAl1K&S$XahHu}xuw|pHW z&d|{1UM+WkoB@N$*Ui~j8Qu(mk=x0-HG4$zi$1~XTw}5^k>TEYdV_IYAXeMN;ki|n za45tbvpRoKHh>dnQg3}{-;Q9M6uS=u$+wKPlO|S{O7Jm`<)lGrD3{kqH5OXzJ807h z41fLy27C)4J>}1s;g5EJr4i-zq;H{2Tlx&B>V(a=Y}uUORAc$OP*h)k59>-pp>Fpl zX3549L1L;4+_RWTI#u&gQ?(16)}JB6w0lLv^g|%Q{Skg08H^Umw0|S^3-tkZF^kNN zxj*x2L?&ygH{QnwVu-V7e61!vqglf16Q;9gN;6rHBQ9WdY9{#+oP?TlWcW`Tu8*#Wh$;B4I#l5dn!SSQ&4+wH%h1gFX^ z3-W~rPZW?n7lS{h)4rWMg`$6c!o62II9V%eX7Z+1T(~q5x>tMm&+zyaJrJI1iJ=&L9;b+7@_w8HX6+*vIPxHMbmb;pQ4ENtqypIYWP=n7m6mxy0INp;k#LK zlNl0%Xsg%@e``v~uviOL?t&%^Qm^dS#$WsnfykFiMB}kCPVA+*-DUI0?utfM2(X5I z&2Gph+(b7L1zq#Bac}iX!EnPp_*`>G)N)0d8{xVg4!(TO#GDI9z3x7kY zX$Ro@m4k_jL?zJ%-6SJ2`z_VW+OvPXYK`n^o zHTMk@e{^o)iY$ZS#hc0G{;SnklhOqWx`D)6?g~4~X#?Ede+4g9i10SO-<8Y0cziY&EfAeRr{W?|@|nVx85lF46ck|lotO9|yBQtm&pBUqO203~$-f5-T_VYc zNu89zwjP9~d1zvO9%qe@ae)9s8@L|`lplZq2Dz(UTd%lN7Y!1AI|W` zdk$%8euAg7PC-HQa-uv(ESw$P2a?MU5&6iG++%A;DB5@ni;JRhlXMNt*6G0YUrbHU zhWNk{hdNQJt_@yRrpytak?e+n# zwqT|lcjM1t*pcQ)CI@+A-rXKJVVyx!zr6yv#X7);m!tGTsoQd;LR?B!Wr|0BQI2$ZCB`Ctv8y@k+bCryt*NNZW&3s z%L~hgNb&jRSIP1fEH`0!Agnv5M1GcrV1Yy<+&E%P)(&@Icb4mNG|Ddg%c1w77fkv) z82|aVhs~z%x5e`Wsnm;XB(ofxpPXT=9;DLTq7;9_)%9 zhT~vLB>!ZvVKmFrJj(}H>}tfCu5ef^Jqc^xe-OH|AHpF$R!CHN!%m#;1S`koF!K{m zq3#*FSHF2mm_?oJ!72yJh#W>LnzK>j(FeG3em_|%aX_?J=MxZ9o-B=KxO?sNIrk0q zn&!k|QGyd^edN)df4j8nkpnP(M+x(_MH!4#{H!`E$*%+18VBjE)lHZ?T!|M=GyVEIBoKPc_lY3BbSd%?PYT2sK zw4-U08<}HlfHy3AV75{QDO}#hhV!o>c;hS*cPypwu6+Zn6HAbn!K$1Oy~PaApDox~ z%dmBWJ2>|)BW6cQ3${Ky1=pwTB(@b#g)wp65FUAnNR$rYPU%s`*2ZuB^LAXwM~L~z z(ffE4lUmsY8LCR;`odM5e*w*c_0ASlD_vP|T@F!S&oHzS5=XW4fMi)EiMwjS{`S!hqwMeptyYKg65#B@*W&B-~@e;xvl0%Q%D*^CkIDj7)LKjfYWU7^S+cTm>?vQo?!vOw9Qd z3NCjFnDLpiLcBBZ6J@l;NCQA#s<0Zf7j#2gQWQCII`{vKhT8>{LnYvJ zs%iV~I*aV~USYxz>Z4n{M6kb_%qZ(wL&P%$;mfrXcqFzMuI-m+Pt}<)iwr4iro9fs zHCj;WN+85&P9s(m)o{jNIX?1wJTakt0!vnIfQjT5KKbuFjx7v>3BUfs5jk6gHtM~6 z)wWDnr&h#d8Eye>4;>*-Jq+FGZY+IUnq6~*-Ue!2z+s;e8P`yQHtCnZquPx;GpG>` zw$V}WE7(Fkt&TLhf&^FktZ5=2xqsA4V5y4=D|gnt=x=@18L{L z-gnr1R~p^t*1<8lTbk5nuot6g2dtN=@YrUGuy;IVHSU*Ye=L*bM(vG-nY7<#*1YYQ zezXsU%(_aBe7wSj3ija9@*Rf^E5TVNwGiuUOnhh53Od{i_!S{RmIS_Lcf7n0PgWcf z#wV&WA)BjU?Oz4i>|q+Ak7Tm@D$)rb2@9=A4n|K4^7UCft-DY`y#z zZck=ONwXardU+Bj1T7IBh*D6yyd3P#M+xlxboNciayX%Oh{=??h|1%o`Rbcb$$I~D z%t+eNdeTps40*KxTRdsk^ah?Re{zXUNnZ`Fr}kkA^?wJ?e*#HvaYE;-_bicdf;B<{ z^T+QLK6*BnA6Pk5tbA`G$67eT5(5pA=8}URc^{zlL{R@Momuh`62*(jkuXzEw#ps? zYeLYdEDQ&qp&jX)EQE2#^G%t?jhwH;2vMhDAkLh35H`eQFqIP8*zsu&e_+5+v8B`+ z?(=U4=;|6tG~OP^_}$;(yk;bEbE#&m(|u_M{0N5Sx#OX230#!6gcDnb99C}0Xj53`A8smjM$(nfZXDNi{$@K5Eg;lPg${7>U(bKqn zsVuMUd6O7#EM}Hm^Me;N9$|pd9Q2Q@hn590q@%%|ji(-XuW>U3-!qQ|eYGkWQlh|m zoPN)KY&!zaqdbVhIs+V|ro_Mbeut<&mEiVQ)q?&TV`3uuuki1M_t1P@j?@oR4tqo=g>1jSz-`>bw~+WwskU>m+T1pr~koU z%5ms9x(#NlE+I};O^l7wSNOC*mE`RWXOZ>EOCSyFD+8{ zsuDXr)8Ku*G1($66pj>sfTZwcWTEFEZiK20$P5U@D_+TX^&FiihU&I?4f(acz*xlPgedMOx4+Q?+DD57I+C<0fF8OeE;i zZjW~PUcrhoaZc=CC#Wn*W-2FI!-lK#`sZyN)f@Y&-Z4tm#?1H@c^I|r9R`&*;}q&Q z-s?V#{LEKFJ9#Nys`)s{&-u;X@7Vx!4aet(7jRlJ&E@US!H9}oLZKA(d9Jk+)I?&2 z-1Y^7g|>ptw?la8SqUg+zh)Lx3}RP`U7k_3a2r zRUgUiI_Ct1#`o}e=3(RpJO$kp8PY({M6dM|xQwHA{quH|DSmF+O)_yO$5o~60g3Jbq>1)9Pn!B3 z?4Owtm0cUz&F#9}CsoUSoneGcJg2wbR(K@6OnCdH7=EA275;G*uTUvR;81uoLY`v7pdeZL1EDS-_(T$i@70+48+X;7G zN(x_;Dj>(8K={X4+&a}6*oFHUKa(U}d2}9sdhkf`-&kGl`5{NhJE2YVa&mA(a4Q%Y zhmw@1RPS?Wqg?nEBxoqZJ#*LyD?FnxNIx9isNZ#%l)Yf;nQv-Y<;!W3Bhx7 zD1R{FFr&Ij3->;s&yOCfAs!WN!(E^22rF&1NxaSpbdLKC@Fj+fd>1U= zo=Gwe_K7Zhl;9_wKSq3&%(!cb5pa0(7gSB9y{6gkVESGavY`4WbHj$=W|k=nmT?h? zbv|%&-v+^Jq836+G0eF5im~at#IC#G2G&biqQEBOd5OOuo}5c2elKKZU8S7dKhH5r zVJ`YN(9WVeO60KBW_Bq3JDicU7Z&Ob$FWN&t9t#`{#hNUSOP}08$+|;C0m~u3-=>hbsJ!;%K+lJLzPpRpTH?zv=dAg^H-$>d$`kZ}L7n~F~5sQJpnCMSGp~F&xylh_0IZ+Sim(R9>-}NYAt#BX8hTRl8R&QY+)-MO6 zBp2o?WpVAw{0nBvHDvavm294FvSLJXNTj|7s=?jF@dXp zZ6_$3#+baG^cMIv6++oDTdwEwR!DRYVV3(@;I-3p`R2tV#CBWd-BubKX5rEmQ1$GWxI84;b;ay)hhye-3f=d!gSnv z>5rh9Mg8YBw*7P4_m4I35(@-wQ9S-3Pk{oSnBAL}Gmi!+P)})7zkg%)+#qNjF^?pC zQNtrwq-Z~OA_*JV&35jwg*(qm@l^5!d{hugxkA^_SIJxGm>18LD0>PfgfO#={NWON zNPzFrlxo@H71L|LQCBin()You|g_B*&TMxEq; zz06*qc^S{~Uj1|1KQt81tvw-VJf0wQQI_jiqg*C?k{q}6=TSOucak-MyV3Ko6tDF6 z7CD}f%T8Fo5u$fWlHHF=FjhYURxTJxyccE&dTumhYpG7cS{qrXbMf5L98bz5tr5)6 zl>y|w6JjP0V&dwg`1857B*I{s@YPd=A3W$jS^j&uWlNKGd%dpSc&$g?{qvpW9XM=>6iq zdLiS#r)<{FHDFlHFtH|a7`0>`@8qH>PW8~`&MP>@sOt`9A9=Fv*DXBf@f~(Pxk@C5 zNeJVAO7I(}CXiRN&A8`d{6S@CJzhMx106=cg>whg$U}o4jG`jTY5ENlw1z~Y`&(a# z+Y}+pd8CCZQ!1cn?@ear#;a_5nLFt1SU~oVO~La$GQ7iX5xG98nCX4)4{EpTQD**J zTy~oF0|X5sy~8%M*J3G;=9s5Yw{RF9JQD>*`lp3?1K$XZG#|$#piBaWj)akzAv{m>#Do2oYD}n6qwf%a<_>j+> zpXF0idZj>%r%9lFB$(J{Jr@$4|ANMs8$@fxaPCEkBS`v7lg_1aC_h`0kJR=ccBF^d z7t#e=29F}|3|Dcze({{Gho{iGD@xFGD+TKz^@3xH8|$}v1<0+O&$Rm!tb3{fj|1NH z=U=XL1Od54pM8EQqG82HII6I|U#~dnXans?Z;40pQCUBp3x4b`1f19;iek%QOYvVp z;XhgK0qszoMf>s(Lnz)T`U^+QUXcd_FR_2dI>EtBbx;N$7S;Eif;ljqiESz8z4!=e%WMaGI1f0+EUVF!hXFqS@0xW~z z{(NJysKyH4zmw(z5|YWtl0sI3w}pdA6}Y)cz>1hKSm&09FHZat`VLaAQ2lP9V?r{M zJi!KRE=CKSdpz!@Y`aSDSmyOyhWS)153|3t_WLwy+Guv~r3uliR>vijakD5eg={G5 zW#^>YLeI=9?5MneMy~YEMGElup>2W@&10S^+b?`RCT1E`{a{1=1;J%G)q$;wVTFGv zb23Yny+_~Ae{0Oh+`%tUx9B8vCD;*%g(y5U>Vrw?C&~B5kz7~zCP?KUW5}3joVnx$ zJlU&GB7cBs&!zjS}OSCHMm zL($S-f-fkzP5v|7#Og~Jg7y7J*h+i0r&ol+x6!})eH!|T@8Qc(>hsUL!mdeA;6@l6 z6zq<53rs>3+!}dXSh;nIaLl0?-X9EQq>5xX@r7v6I!3)%tzP(MsT^-K<1T4!ds3<;Q6ii0kvgL|45`SmniFr!}9-AhLhr>%5WuaD=lf6=UyMU9}RUk2%F^7v0r z4!-ps;(sMFryPAbeFaH=(xy7{a?cXs=`u+^qN9*hBr}}exgeODu0a&s!_dU11@_Nh zM|vJQv(hUjaoWF~g@4`D$Mxblxl8*5yXWS@Uvt{`zDovQ@)y`)Iy6hArp);6rrw>B zwfsbfx#G6B(yYt!J&=2I2$9~(W6#wV(DYkJnzv=Kv7c506LF+}ZaW3UbLI2)3sUDK zg%QSOut7^6jV8TdH3m9Cd+3OM4J3NZJl?ZQTP*3W%UyMGg1kfH$@OEDz0%MI$~O;_ z0T>|4Z2k%_{yLINfeW~Z^i80==Oo^gj=*y?V{&8bLE+Q;d{g%&&fKD;L{VE|Fy=hi z3r6$wm{0W@c&<^4{}L}JE~Xr6{h3aX?>e4L>pFoWm&@=Io~Mu*qZ^nVHGbgz=px#5 zc;Ms$nzc#XFG$EuU_OOfLf_@X!Zp`2)S^DFP}=qQ)V@>*Fy9Ow3l@_e*+PsM^b3lX zUMFV{OA7VW6H=CZiYWCh;?6Ghhevu%I2(81n$kDW5;L4=)_!MH2b*%E19XIcUONLn z%COshP7pV1A}4tlULFl$^wy`dT-9bcp0}7R?nuGi8>RT$0V1O9Ntocw-SEP)6{9Ja z=gY=7@OJTVGUwZ7cIgMo>2BLEkhEbqLp2a`e`E>P>JNlBH1Any7RE%euUM(3qp*1S zUb0}QA%1t2;*+C9B({$5$;pNdBVFK+8 zS)nY8|89I`<{!8Yw-nQ)$?vejCJ8>eh7z|4&jr=bvb3`0ZY$tyUD zoeL!Rx0&7~PO6((cKtI*^o}M67BAzbJ&Naa#QTL?)ltGSn&*1iCWF_;xUsFzSHQVg zWyZdppna_ds7N;czmNJ=Fzk;SMe?MSQDtKb#Cg!qepVy9q`?MM^b+uuaslOk$8)Va zL;82@GAxG2F6y|yPm;SMfy0g_|2EVDYGRT<#$s_-6ClbVBh; zd^dD1AE2ruj!p{Z461|SNe@SKf}$~c+Ao-KBY_P1>&j;Q1n6FS3y*E1yprQSz|pR| zRyTcgr#c?%9M-Rm_?BD34B!8R{2N)=)Eff5Z)BOlc`}088kR4ynxg?c;szMVVZa$;~C2^iskY!w*6DT7Cn^>hMPlx1TGnjm$iFfVBab7W?Ls4KF|*0 ztDj)9IUA$O z4tu>B@+U4Mzl>jEB=x16mh2+-Wwb+lOCS7pIZf(^YH(z&1JrapN7c>In2=Nl$1Sx; zc7>T~wqZRqzqyBbv(33H6MbPz-5ufdeH(mopcrh|O=tcw1w7yRK+i-g@^x?+UZ|Dl z&%2kAZXNfSodHiP0p%8DBDkZ10jJfNp^slv zzPuSDE$hMMqZCg=ZY1q3$Bq6G2&z%q=ML7nU*QuXl~+U{+GT{TBYuXljRL-#Y}E_NZ01eTk2 zz#g8NB%>RK;hfpDLvL9z9vmdgW=ptm#z%8S@smPO;@kmXJ~o>Ey91u!wfMx<3gV0B zW^%aN7ut0{YQ}Hqyk0Pp?zh4`1I_m?bes_eEa#}cH@LiBmo5sv? zr{41aJfI}Ug4COzL7$umUTfk~v7Xx!c6#JaNL}$6ufLy*+LCWUReBV0&ECQun6wru z2#c27GrUwC0=xD-5dPf+wFTPCacnyC$o?f8^6Mld#fK7;kU99wl1H@PoW6vKj2XWBbJodsG z4T!kkh~JExP~mY9?1>-MuW$2CT~KG{LGn*@u%T1ef%m~gRJ1I>!*dVAr$zfQcCMA+ zU{?(D%SK|UNRpc{aw}XL{?v5Xun^SW;S3oGlgMHAAwFe3!?V^n;yyqQe|~BOGTVXl z3?0PvT=@xa*kSU*)Uaa(s(+os z3rRZS^Wnif4QZyd=`4g7=pCl^PuI%D!fV88x@!*msOpWz{nK?9%NayzM z#urekbr%yAuCND`tUx9(RT$Kkh0|pYLHe4Xriw&Sxa=^8FV@l#FI-i}4NVG$U8jLm z3|)%{gL**DIEgH+&to&T*ukpFH8|-nV)^t4SXd}v<*jbvvcg+%IaG#b13$98=WU?v z-6i3JI3C9>D}{nzGnlIf8OAnS9s+K4^v~_%^z(bMYY~|;dkFS;_P{mjfzN&2$?jQf z2WJ<*LPd{MY##g^2A60PgK2k!n9_IPC4P>v&1&57L0(X*S0gm8iNMqTbndC;na15! zW!HFkz|OBL$+p+8kbjs4aT@!{!r*G5wWAxv`%}o5tPxzTmIG)EsmGSp(fI1dOW2X8 zLyYYgm=3z}1I84!q17=5PS=ZmSL#z%hOP}}P+xS5f3E5IL~r)><=r4UX-Di1974IE zURXx0x7k5o^YCcqV5aGC zEew+{Gksa%!5K?i^D|$VipK<}3FfCH`TV-O{r-)@`XDH`8%r9?DN9K9GhD6rAU%Ow z*kPmfxDcJ)!apYCqx5ZHH^>FIuN{jev~$?!=yVL3lgh4WS^;e*OicFvuX9$y&?O+Wg(=iw=558SfJ z3O1SD5n{P=)UFSKYG)tQSzqr8Z(n(W^E^wEHdR1r@(V8hDkN5erG&bx5`6R9v*g7v zGcMZgAZ#AqgSFBJP<-qScuR~Y`sLr5ick~oJM~mPvI|G^^*%5~h=dY(uK7#b8+3Yx1i`Zp6u${!Y(|s z7Uqw)z?!0GST#Kq6#x4qjK5nWJWIR_2bScTmW+78roW;A3jHCF?LW0j&bdbz8?`8%J z_zW%$Q^+>j^YAW&_VWF9!hgMdf!|BPnf9PevT|p=ELOtDP7~9V^a8ll@Ihh%(O98`Cpw#!e3yPMexFC~LjlIUjE3o= zC~UuDDFn3_!}=o(nv9p?T)uh0rj4gf{&j{74t55U`BTaM$cOkorX8xsCz8$k=jLmt2#f}804GDwGCS_Rm`KK^=*ee)6?G>*1 z+`w)qw*kkkH9~7cJf_q9=ARp4rI}XGzoQ5uDa|2Wa2f*uQW0 z2EBuiCHlnC%iPp?-&Y7;{tdC#meapPJ*Z1)-?)499*ac9V0U`Rf{%*8LcUtwu< z64`7LBAT)5D;(9?N%p%f;QX%A%;|p_crPX#6QCAMYU(j*qZ~US*M)m(+ALz@L$G4N zUf3ad#3;p81GSE7@+TLoh=*#<=EP3Upf-x;ZsZbh?n71nc}qSqTJn?WHfn;Mtu1)_ z(SFvU&W8`KbMGIScjDjn*bK1ay$cT&PSLn%IB zAML6QS;9pv4*(r)DWWBJ5M!>IawScy@Gna~DT&_JO}Ye!94(BCEr)5@Ek+L?UtzOO zd&3Xab;SD1dEE8hk=Ob$Ma;$H{(6%r5lim$y?dgL#-hsejTn` z^c?FAg1}xy3e!G46ikasLD{CkC^g|VJN9!t1W%73!>wmwMde>mktiX*Pqwo=V&22l zPi~}Q;f2B%XFFhv`CKw#+6dZp>I1)PwqxD5!}xe=1=z(}pv(dVR!R0NSN=@V=-;f? zayk!MUdPDHx9^1mm! zT)7qZg60stw{6E!(>9`w;eE(Gv=rx+Y-UUUt^}dg%jkqe5iZbn6pH?~9ApxxxryHD(*h3jFDeg@umy@eC%Vqi1PVO*|S zBRo{1T}g?n@xgp4ZYO1ssd{zZ+5I92Bet*RNj4|`Yp2Ymd~$}&E7Qq6V_Et(24KOC~NE#NBqI9^exh80qmJ{w#Y8gBxDsw*@7p?dI>O7jXwVmDzDc z@?N0mD=YeT+XADnQa{q^iDKuJV6KJ@f*E;BiTcPWH2nAzbS2LbHElPxAst}3X&FY^ zQjX+EKR8GPTsvec3Y9OQ<#_{Ysa|1sJ+y*7cNzts#LKukpaiDN`iOoVHWOkW&EjJf zCy1vsyyooMC?BeREm5r6gvqKsQ1JEwxm%sbrZ2IFJqwz#u!nMm1H+*sp}PMTY321C zSjh$)J>wla;Nv>*I`&Cu%uc{E;|CBN87?v(WyW;q%Y)tFpZ(pc+U7Cf8DdY44joPJ z*UEgl-A&@LUyfU(Xb)fb7F@1#5ufzEgv|~5#HLOV>I)m8`eYZ*eLI+Iq>PLxS$T{( z6orfaRKTv#4AIvGL)qwqzCgyJk~4zq*zW*) z-+aX6tI_x^q81qXU9TW#W-4;*gtdbt$@$xM+@*m#;0!O1rm^c$YXs%LoJ|!qY}w9| z(1Y+~;1+U=aTwHpgb9wP|HC7~Ht6FH_Uj~Vt<-PkWRJ%)QmH>-C75{{h#)!*vo<^MSN1O# zU#wGN#rYg>sywjdoiL~N08xIC$6jw;4bO+AWAuYYtebNf za;@U=y=|8eKE52zcRS#^c`sSHeKt@yc&5m0(J?eSIg0;2S52IEW)L@iqYJpp%p}(n z@=!eK8{F|ZLyo70itI=y7o=URg&_+I9_%r6aLwMjd@FXv68h<=7`vT(|*0 zdPNT`LhyCc9=PSbQuJz+1|C+`9ea1Ux z+n4R|>M)}7mMv%lEnu|x2kzAfVE6s7f`ZDALIcej_uY;J%>~Y)kCQ8e;og4mvU(Gd zbuU3Zt{Vcr6%*Z9X`%MIB#&+xr1;%p&a*HWF5FWf(qn`17QLyZjh#>OCrGmK4_I#N zLJOhhZY1hj_<;W{S^T$qKTRtK2aijl`sOR_sk=Kt^}8c+`;?BAu{(J*1Mx|(Ic(0n zeel6kn#?$BjDKnyU}4rwa-hSD4LxlQ(T817|HX5Rc@zQ;H`H;?j2hwE#8P;BIaM^g z?G>9A^&j{e93|rC40>10<>Lkq64&ttT*}y1$bYk)47E=$)H>A!yA)@W>AV_OWata- zUNj$+8G~Vz2dx(6j47iOS*el^u5bALJO45)YbRd-%gyoR^SDM@Wh%!z+^Qy?r8?XX zM;BN#ZYUAf9mA6yKVjSTAaYrzi}4viKd0Xok@-KZxlI;+kT5hDC&xLVf&D#bZLmk% z=QQ6jdKJ|DFc5Xn?#iR~4t((T<>Cz|ZnEBqBVqr84xDXff+cI%*$JN&{v+dlD&XCWUTCF$k}ulYoNv*3sLad4$ZP+hg7^uX4t|HB zqwkq!&hrAz35zIB!vZ&l&EXTq==SR*rx%1kdc|_G)a)?ozxzp_ZT~;FU5n^{b*mhc zgPL$rs~_ZPiqS4>Drzly2mUSXm|jDDXnj`j{^>_y2f2(tMioO>&w0^{$%};Q+jIB; zD_yZaSI;?rjfQV-wq#zZ3+j~jz=6RRiMsuD_C~QiD9X3uHZL(wzZVYEqiaxWdbcqB z)(hBN)r_}~yl3UV*+9yM4xvRh0UJkDz~r(^qT!kgnCTnkA)}$YUndEgeF!>7*pdTB zHSuU?4_tk4iL?}VvCG8v@ZYL0=yvBKKCgZWr<$gdFSI-6WaC>Hqtk<%z0|lfA89V2 zcnD4{h{Ckr_aJS%f$+duolTqR4?o7Z5Yf&iTsi&}C`b8`yBEd6(mlNpKPiJuc|DT* zMxTY7Uw0v)9qb$FuChgYJ_$Ru%yjP7FEH?;ENL}Z&mC*q0k<88qK54T?7Ln9pAJkG zu734pLq;Ej67Q{qeR>!@9qHZ5`3dnUa$_GnoeCzlAJDL@8RbTV!jkU;NMD6CP8-(* z1I8JXwv9RLxNFuBknMx#ee>{aPc#_p)JM?*LqVE83rFsrBy3ZY;R;qAhUtfcNp-h3 zTAKAim2?GZPomoRY6ob&K9uy%yN_#6q(Lp6U0E9Gg4l?%DPNe7=VoneR-84AjP}92 zj6{s5+^$2>yV1x%jp;a92Rg%9Vax|luF2nqpSN>~SYG}T^-|B}vkTS59v>sP-RVK# zJYY({PLgQ;8}z@0k;!fTY^=g0F30##|6OwB*KLr|9!B{@V{y@km5^+nCwkqShDW3v z_y~_x;(>)qZ1yjXZ&1?^kBydtq8OS7;ii&xh8DQ@X)nmTMiK+#JM58?)nM`Ma=%Uz zQW*xP{>Ee6;#MKM!Um=ezb$&W{}`%TjO3@C9Vouls?1&g?gHnk=8(cE*HPh47i3>L zPm~XYii!nEezbQq@iwsH%Df%G*diZKUys1d*>6GKwj0}?E3n7bxpV8T4iGMn3&WCO zdqAP;nW(2~BsyCR=f@VSh%L8F<939(fRx`H+BunkbNrR~;Hm<$bln%mc1$pgi>*Os z;$G|!>Y@GSZ}cklXEg?`hE2RAPV6biXKX064r>&dgcJ+!+xJ56t}VpkaXDJK_kr%H z3bNKhR`@wYl7G4MGP$X+n7egt55()s5&g{FDE+w^z9pIv>(PD8g!3lclijNYAu=4p zhTn%RhYbYt8(Hiu>jMy-=SjLFFXQnlN8WSEtbT1oXx;f+T=2Hck$EpS45 z4+$NcUU1*wa@mu%pi-?>1iFoGzNV<@+c_H}#ETV&c-=JAdmxG;s@@lDrplj3|K*PV8- z4RJtc!&NXiB2T0}wFoPdMnd_NU;X>@#Ua6PmU23pk1656RXsp6?L_(0Z}!+5+9}a~ z18bCT%s}#s*>ED;H2unNK1OALGo7 zE|5~aNG>QUp}kHweDyv=Ze(h5Ib%1#z@0a7_MkI(>30px81oY|Z10=C8FZ4nS-Vg$ z8ajksamx#iTu~NWt!W2A;9NdcY#^TD5yCy>Lm=CK4Vg&2f6BJ*kr)}MO|xv5g5&NYuMQ7?goz0@-^#!QG*n9D!dZXll7S_n~@|pJ268~LNxniphkWV%#rh532-bby zuy;@z77cj~Cp71iYh5S|&TD{!a&lzX;=$a9t@q$wRIu=`Tj?rG=W3Zd8IjwBBNp|7 ze`6JqVn*YHSrYvE%B$qSZB4F#W`vcF{-!9zOuDqpw5t9K;3*ZtURclB zOez7`u?aP)EuQFAEa}=qqvU@o^BA7D-$V>_XYHK6tG2 zkQffhW{rv*Kyv;_B6s^fzFd6~7>7Az!{>{F^U+=y$6Avj6-h3ZzUFTFnlsxIakBYI z&fC~rU;E?W=ohMf)H7`03sKkSmQtZNQG_Vy6*Qr8Hs?{pA!-<(F~ zJPE^D%AMdA7)HLl+r}0z*5&?M$MoL{yVSkGx8N|IEFO!JHxjr3eoKX{_&rSJ`c>fT zq#*3%)A8!%jr?doE3uJ`68lq!9AUi`nnfo%-%tJq71P;yPIA0fNJTizHnw!kzhxE$7OqVkYP@b@cj0_keBh0 z1a!y>_4_6GAj52;YGTI4EZPeON=oFW?H)9o-U9P%7LY%|eN0cY5jR+ldXi~g+dm?K z)1SLk2(wxsETtOGNfIjjq+R#Dw}arsJbyx7=3u?{MqcyiEOF7X@$AA4d*RejCDJ?5 z7|mnfQ=O0{Q-!VUmv`3S_&<`)!>`Bp3*!w9MB1e!QbdJ}O7(f3^F%fYm1t^FH1Q45 zR%vRNQ1&iLNYA++l0A}9A|)kTWR>c7>-P_M_0p&FIrnw0>wW#)j>Biwqe?H$_&lD^ z7wdels;1n2?~Vw*H=}{kzFq{g-{g{gL#@$opBcACMOAROF=8(a`T}N8qDja0Q*U2+O*ye}72#Z)6Kj^{1u;9dh@A~(fM4x`SN(Bhh0a&ez2To>?zs8nSIj zYNg-`DK|V$J*%6T`8?=M76qr;0_DZ{>f?>dF(Gd&2V>vX zekij^CHcm^%t%8gdegsxjV_mQNlq**A6JZ566f)LQQ7P$-4%R*^bOHo*a*F;B7XmZ z7+goZ;ER?Oi5>q4i^u-}+1%qK@z)S^)%*)~X~|^1lNMY2(1~i5RXB6sew-%v1ny^x z6W^^jtxCpcvn#f);4Nn=F%CC2!2G8yALqH4X4Xb><0_Q|#V}{K%#L=sR@#%&gxz?* zqZf>xoF(aM{>;-zfa^I81H0}@nNS$Fx(+9s8l(En7qC5FnyjRImx%Ho7XESKZ?#JC zHfA%qA{S$!ShtDQD@+5w@Qq}6vp;IZ^g%{I3F&%M&RiPl0#8SD2 zJ^2gGxW(xWBAaHtW_&xdSlz~z{LXa``4074@GJ8uKV=$-TBKy4E?=DdW0vmvk_sng zY$VJEUEI^s2a5isd)|df=oGuyK2Jz#$BvQ z&{i0_(s;lx?SD#!dm5KVVt&Ok+LUp3^ijq@kHEOu0g#)Vfx|k-qTbnTcJ6$qf%&X- z+!nHDnDTAWwC{ZOTFzb1Nht4@V_xlJITg>*!pd-Iu$7F2|MpHJUnLjdkANN+YMnw% ziZ3(Llx=I@c@cv;X@~UMU10zB2uc`y;D7GUW|yiu@!y^miL%q}q0q~chZD5Rn9<;B z)s=+5YI1B@q&Hlt5|M>R%W+|E7pzG*L1wRrt(xW}&Yg0l+Gf=D{EpXLrC`mC7V?xhlu^XN^@<;pR(M>iA zbR0eTGz)=$k{1KZQg@Jb=bz%8Ch9S>c|xSEWcY(^H1iU2o-F-q!{%m&f$Gd*B>47! z`0e6P$lB;Y-anUNa*mj@&fT7Tc32GB7H6|(XFBn}wp;V&KGhHwe2SMzImXN}i-j=U zN%XIlV`-@iC)k(?@!EP!_AS~2wPG02e>4l@N?${8=NwY?$DdiG>;QTPV{qxVdVEQ} zzLr_5c>gz@Rd;FDpylc*zTUfmX>K_Kt6v@^RWi#lc8VFNv|e5K&}YbcTWw zs=U%^+IvXcxrnr{P-d_C1cMRvYDI;o;0etfc3ZpCz}&8G`OFsZwN=u4+A-YfEG(FD zjF=tx!OxoMz*VZ42o94YSf?s4c=};9`5l&lx|CJEenBG1@Ax7L*7*zupO%tS+Kbpm z?I3VGmx(uTx}v*HHXBvCiXZ#fSR~8aLhoEt{?di37@4U7!lXWIk!!=5~qRCU_%q z;LmEui==pSDN}Cb>B+*7@vm63W9c9!A4Kf-ZA6P5 z{V=+rl(-gNVDz(TH%D_1O88yHIhSI<;^tedFZ#uI%eKNn2|1z=`-$nMpY6#{9r>rj zAM(SK??P+dd0r)Uwy0G`28s$K$-iv4`}iCPp`UX{oP-VU`oM5hISJML$$U<80WA&c zi^w{HtHWQy$m4U#gBe%(+a0e#VyPl|Ua!b1Jj!GZ7+>C6?gSrrw+4p&dCm{pslc3| zzl*xh8_B%C^t(9yBq;osMs}`i;BO71yK6)l$=p7Ym7`3&ONS+i`Hp1VXiRmCS)OG1 z>9tnl)V{!3gOMb^YZc{nWwBh-I{wqlIR3Babr`*&fse}xVjg(!qFME5GB_j~#nr^P z`xVbf{#94zS+y~UJN`!BQE&0e3hHlkQYXwTN%UUQ51r$@iR6`P#-qmp=2-8>u_wy# z%;PMUJX*(JJ!Mg)lv)Fu%b)Y~@WZOiOM^T6lZdXz7QDV#j2o<6PsFlIm}$N4Fe^=m zj8VLeK_iaBmOinFZ<&P+yXW+6H-8)kt%-8~g_5`O~&0*cJ1G zpSfZKTbt^}r8PMTU8!gJU6Q8UNzIYMx`Vsemc&O>ahaNS=T zp1IO&!c$XntZV^FX$|6xxI8k#teRQcupAarZv4OdV5v$xybnK1`A#4C?={)%<3)Z0 zJN7Zkp1qPE##hwmp##z8^e>MTjx!3ZmJRLH;5nk~c>#a%zhP}<3F!#kRh3*V#tH6O z#HP)b4XE%2kM0Nf{Mc@kH)y6T_YtJ&gDgW|5p4g7Y5eUyF*vAV3z%+*=g<97$M$zB zoct(7p~7M^EC1G;GQBynv^f_E{h6;^t|a15T1BHihQi^SFHr21AD&qJ3U2k#Omx;} z#@Hu|eK~#|Kbpwn?uGH-s*}xEB;DrcXYGO@y%-`<(TJNgCAf@HjpRYGEFaQBXSi+! z8Kp9pt#pWl2su@=!+!g22B-fK^V)9J4m?b+RIGBGuh34Nhvf0B{>v^L(j(6~) z9NMBrzGciwreb6Qh!w?>)uxp=W`i47*KH}d#OX8BCvAo2nhIppGz&Z=-VTxWOUd~7 zK&B_#0pcZgqweqqv{{_ZcBZW7M{9hm8fip5b!!`WIh7ZTro&M%);LIZX)HivRWt6J zgr*QAZNwV<`~#}JX=GYjS*5<#d)PL3`M?a%mv^PTpQ(6rd^B#{Lo<5a>-muyx2-hp zy=F~n|5WvSc#dA7rSPQd6v_Sin~&YNf-`9`5tKyX?34sAa8%JHhXOM2{I~BgHX@k} zPN)6CM?XQng*|b*vyc^w2!f3j1$f284HejIcIDRf12cS?)iN*+^XB!ZTtnGyHr%7t z*1{p(VkSOD1AbkSApg91=6O-DQrdFhZm7Fdk~?=TpBQrzZ237SSUB+(j`(#M^EBeY zdV3kZ_glo@Qp#pekJ-da#MX#bG=;+BL%ICg?p=6AN}nr@*A-R^jm)QAK5%^b91@}S znD$Big7ve`k>74|xO&oGaKDvFLXxytTZh%4uW%bZbPizLpC+iCpiGLt)LJ=PWV2_? zH}k6YN=#k(Mu^qT=C_+I!S=}-oSwLvVES`4oBt#X?r5$g%HLv9VO}q&mtG*d@A@$l z(*Rma-eC2;HsozLLzi_cTK}Dly;M5UyvOnYtRpqkSF^e|y^>GjQ)w;J}kswBUhd?y;jx@}1l^WR3?{}ud zx1n1}>UTX%4-w}i&Qy}!qq>>&$1WhYaS-uuI)Vick3yf67Wr>_25*tu4ib|ziKmSU z>vSiRT}LxG|K>Tnqy~6bN!lev`K3!XLBd6C=)elcV%kn+Md0#!>?%fY7#$6(- zd^B166Ki4LVi_V5Pr=ibeUSIWpZqoOvZ^`y1)fnKXrpj8 zT`u@3JeY}c+zqRn6UgVE`S>o^7`~0^9oWguCPf2wXp$desK*{t{+#9VM$r6|Cp_Ojgv*yCXE`nZYhb8olMD zxyS05d%&h%T{7PHHfle52cv!_5>KfQeD~`w@Lk50=x^#`hOT#jp6_W`xG@ih*k#jR zGc($QG52ExbGWQ*^k5;pAtI6Fdh?gYuh57`x1p>^QU#RSN!swoW#wFR5e>Ut12_ zURMvy^U*8gY5uwbAASDFH&C|2{R`U$cJkUB4;Vj+&PF=V_oi!e>1|qqFkOLF4D*G0 zy}9Jae-)T@?-v*ppC=kJyQ;3D7#A#?M>>Anvau7~V7>1{4CHs=gR~~-xTZoP|H?2` z#=h*iNgSV27K>A_Z2>RcL;QV74ZQtEg_~%rESRjB%0 zj?w#W!CvazJ}}Q;Q=RIC;&y)hQEPs8P&ItfmB4@fjJqc$!`9QgNzx~Rvu~{A)W(_$ zEmhi#HSKZGc2g#v?`NT0VLR0M+7k!sAm+mj2hg9Ej$TU}@MCcn``czKU#QSo<>`A9 z*y=%Oyy+!#pynJ5c~e3X)g2L(%(zh{qlEZzM(k|5lN*U=5u@qlmBG&Mfp1$yHYY2y z?(;*ywfrDnQB9@q^K5o?;CBAS-rH8|j=yFfOi<;m?mfqkr!K&KEF-V2#BhoGD6Y0v zTIeMf?5J^G&^1zjKud|x-Z|+DS2JEPk1BnkE^|H!aD0M0tbV{^r82T?&QO%m?u8jQa*3qrD7N?9Y8bNQ zA)198z*MU)XnZ(>zj>0IHURsQ16>8ko5;bAAj1yb) zJP3ADe_hPgNIdcTFD&_TiO3xFV~*?sh-iO@_ox@q?+ayTrFLU`o+YXcroQNjn#551 zJkxlBYE2!{1N(XI$=#s&?mqu8M2?^OU^-X(Zn|*y&kI)mWfD|u2qhv*AN=9q3iEYj z$PTA#80!-YLofH@Wy3#w?3xxR_SPbcyFM^Kw`H-L7DV%rEf4tMYqwx+hAP@NgGgz= zG)&fzA^-RxgI#k#x+a?35*gyBWOFWN*kB>jc^WHc;0jttWr*aoqd3#<7{p4AA)RFz z{PI8T5SKfK=%%T#Ms1m_Mo7I(F^~X2y1;!twQKWZ|R(m}2S7ea~S9`&fawkZcV8pTx+& zoqYW9C`fD2CV3?iI5p)hY^DB|r+dyZ(XSjqtTG4VqRUa9X0fGb#SZM`Q@pC7=!Yr} zy*G$`Zl489o3hAUQ3TGPu41jxDt@*2$URo~hzB(Lj3-my-NvX9A0VSOg`}_j$cGMj z3&B#(L@wb2qqExq8t-PKb9x>Y2Ia6p<&>ZEvfeV9_CXsjF+w$sKz6Rb4F@`Ng>`ES z_?<^gxr47p3*t-TS!c>3JNq8UX3CiRyQ&*D8|RYHj4jN>;t8y{UD1HoI%RJV)C@k3 z#iz$1M}L`T<8I*NmzNkDk7d-~et`e1a|{BKSg>8B2KwUPcT_71v2ST zl<&uqpt?mkZq{G0x631y5tWRI{0jI;eG@X_Z8&7uE{OYm1*@*Vr#ZM5c=h8ZI*Wg2 z5(6FKx$_bJ!p}XZC>p~pe>g^{sZnA--CYN7cP%6mM=zpS&Mydib%EIS#Z?*Ph;g%4 z?j?t7ZP~*|-662)8S0e9W3$i%ZS|VOdz>tD`-C^U&1f-i(HKL0!<*rKPSt=O?(;{9 z+rLv;=mH~l9J3C><{{D|Q_U&-VAtSH+5a+5Dmy~@WMB*UKL$z%f6Y}J)kauVU@!gVz_ep#|OSL}x5 zzVkfROeq?ooko)bjZqkAJd7JAzl%ILuE`|UTCv{uVg|A^U)uvIgV7$BOSC2DR_5nVY_y`^M>ragAZjp9yL$O;CJ zmDp0BZn!%$mkd@YuUzKx9$cook=DJ+?7U7YPe?0r7-2KPC|IQ5hKWNrvOu!$fMo6w}i2 z2?}%8k`%*5?6VsoFgxW0z6tWcxS&^%MrzP_XcV(}Fy*oa74cy|uA!=`4R`gHjqtv| zh?(f30X3XJ{WohuL+4DJK-wo z?y%(x3!7obog2vIDzhhsZ-CaB7x=kHqwz}Q9Ij=$jj*s$f_=JrJ=hLfM0pNRF?`-1 zI6C?wQOq5N*L->)^ieL+HPT{leq0TcX_hdh_yBq=c?BjGS|oM(BP+YePq2rpL%SYd zc2O$zW4l!F=2}Z|Qi%%JX{su?891;97jA`jt*eN;Eqx=;?1dKTN|N;6kC9pi@J{N( zfZh`Ay#-#M{D^(^Q}DfA3uGP|McfR^7#p9JVE@Pp+14}2G7+$6{B{2NFEQTquokyy z+9+Y_R%CyBr@`xW+eotV27F;E#+mz8k@5o-O#N$D7^W^u<~3ZyzvZ!@P}h(7)qi;J zmu>L6R)=Vx{mP8!bO1YL7T=D~M!$Er;lnRYEbQS#mTA%;He~R?es0#81Iat$h@6ZO z);WrCYnBK^cj0elTY)P)(H=@__8-Mfo=53zWgM~U+QU~Y>VRf>1Jb@lm36-n1bqdb zxNk-xPLI6-{PD@yI$V*N%x!`t*TabY89Lj?p9J-Y9AfXHG%w%;{vFrw8jkC;%e*-Lcu&9`C)n0a1S@WBZv< zCRr;J#yrg?d3}fQ-eXtpo{o)h@+PkWnGyR??nyb$WRoE`B^FOfPvv)iuZD}>M(8?4ihcWEJ_Onpl2epn;`h}9 zblNA9l*M;Y<|Fm49LXdny{PBLy$kk~2a=ywe;A9!jxf)!5WkJj$K?w35W46tPP#Hu z%Gp_&`nw_RpjS%t2k>yf~&`5g_8*KEknv+?L>LOoRT_mTs<|6?jy19n^a zk%4Zn3qyn9)c6uime#{I=>|A5{T}+hJkNYOvkYAJUgXz!9K)8AU7VHSA0c94F0+gk zabZ3a1gBY2u>D{Zd=qAqRK>-pN$>lwyZ4gECn^~=>gB7r_z<)F+AxOhvD$P$pJMuf zFNu8xuN>>}?v}62hCWA7l|w$*DFg3j=yGP+`a-CjDm!SgA3U3DOKQ6>VQ=6cm|R~; z{M6#BzEYk1*^dJQ{*dFd+~8H?3&gfvcz=Hrh@{4n4I^cl`gTutP=F&}@-iB)4%z|^ z+Zy<+=tf#NXbFF?dtN9m z+us7U)5eiJ=P)LNTM3Pa=HrYd_fY$NG+55-;4i3D^CR9T0Uw!49(;X+3rbgV4&$u^ z%lB@)5G~H-jJQU80_U-d2S>x|VY=jeYZQLG`2kK@`4ZP563n`*R;=;J#DN*!yC?`| zPw>Ql-t5aZH$i8`6gu-xG9M3SL78VRX=}WTxl>&^`?NViUbh}2EkXMVua6;_O&tFG z_5qZAd`aEVEsWd=M|g6k5dBv?$9D;FaMN!GiaoC9byn7Z)IMXho7Tt}pDP9RUuDE| zf&=rvzz%iLdS2MZ@(;$5H`Wh^y7N`v+V zEN{c}H|nBxUg4Bww7aFfp_fp|@)oxo1?379E! zuO|27e=);{xq)H+aFQT*42K>(3fiv>NP$HLe@eLxIwl#BfQ`zmMN0rwbAf0yJ^`1_ zyaAVw&%y8Y3e2g3P}qap$$vKOxa9015TBAs_AIOAi?&E|?1Nh*aG?$>fs_~5HGjH2Gi zbrX~DivMJO*VXIr#B4S`Ln*eysQ@;{9UzH^W2tv)Iag3A5`HXJWb4+gh1$e$ zP)qeIe7c`YQqOntN{Mg5{J?rLiuuSqSnUY!k`JO5laF66*TT#Zk1%YOswimROJLeo zWBE{jcAe==F6O7Mpd7l3)zXcH&8~}x)87Pqy#6n!9Xmi?w1zR>sT0|dC#U#b_6P9h zju2Rx22!U;4nhiZL%)4hN#1;#r!*O?Qfcz>zoc*{pW{{?U49 z@2^MOG4GhYsm>7pw2@!=Up6+K*5_WD8wzh_G+5`$8{o~mmBg3sOJi)iVa{kmoR7s< z+5eK^?kk-pa|b)KYv;JbIGZm)O#As_6;4v>>ZkFge4a32B~;m%5J=8jP$NCb`}rLEFgYsdohb zj|cH|)^q$EkO-#75;0@KE8arm4s^uK$J61>jN+RrsGU(w490ll)5jXzE59MaZ7BtI z9Q__Ves$k~2Ht$QgK8jtMCphUdnr5^)RtD@ZjyqgN{z6s8`XEpODB-2@T)nlNx(B(w369aI|E@^>#+qvU6G%FG!`{@pQmHSLCp z4y#DpF%?W$CB`LPKTM3K^fS_1*TAuDtr&mr3i{hOK(x&SqUnE-Ul7#-)~fHZZng?5 zkrV*N>izs|%3FQ~dYtw)L%|}dk%>4L0KfH|NRrhHG!H%jFOp(N+#iAGrKzWG)**6! zur@0@+8Jik%-xl9MYz7K8J;XOCa>%2ti->5fvPKiaD9XydrvM1c1Ve1=rUWpmZHEp z$*2n~y}9SLMZn?v>xpG?BJQ3$h#T|y9@+9`Gqd|A3(so);E_zKdsjq(kw}K#4J~l) zi5B>=dNP@qTgLP>tb}lyU!1r4EWX@G=WWz*te+{x`{ZhJod?DW2Tt=$JK@U4ZKS~cGP9y;6->Nx0;ASn zz-hmdz)?L5zwlG|Z&f1 z2|2R$E}q)+1AJ=tld;af_)PK^lKg_mtMre|x_n2Ft3Qr1Vfk1h-UxlgZ!xw*OXMJD z%DFc&!oA8=KKt}cZk;^!)xX`ver=3_qB~28|Lp{PLVF~;tcr-T-zFyE)daTx{n-I8 z%7V%eC>w>?JWn5gzHA2<<1U=)hm7|w>f7Jg!KZ5+#~gRy3>u~g--~2`oQempYb#0X z6MNj_)(=ljj*!(8cqW+c)#3O8KkaYBqU>GpwfHe6fBC?pVFIOsf*)h-F4+)EeY@{VB0#vTaUUrmD7Bvfq~Hkj-4I7j~bV242A}%q1p<@p3j+DKJ8*ZJ7A`t)1J-)2K_%aljQ-61p!fO+5nKHn znT2i~qrF&|C_kR5UmXb!t`o>HEe?A`pJCDD|49GIFoqky3U=6>z_ee_@z?wWcsxBF z16IG}#S0MfpWYZE1Q#e5Ps&5x*j$4U*mROdWi<~praT|-{`Yvs zGm^RU(GKdGI`|0<)fg|K0VSV?4(J{>^~vDh;7k@gP{RxMGTgiIB_uVS=F5aN;P_enw_$YR7yfXyXP*#vsF<#8+1p7cMvi5qb zRe;`SSklsi8?LTn%^gBu#R_ROSYn40tQ9zAYjq)E%`$e%g-D1MZ5Z$hPDt+uuf`k1 zCTk;;G#TJ;aL<5_Jx_5P+`KM9-jq#4rLfm9J8LT03+2q56SSvh=vq83TY_*e0g83i z(R1GrUT>@xXLw9kaB)WVz@B8#_%D(~b^GFkkA2|mbb~DDxWN1>cY{(ZMbi1E8p9>2 zZ!mT+$@%b;UsBr+UcJ*v;rmWT+G`cWfA&IC>l}=&y9G1qT<}gmh(-oWL&xLcq-p6} zJkz`nc1LFry;U>lz157Hm7yp+k2YaVUb#WFuL}9ya14jk9fC3XQ;5o&G=6pPH#na^ zn=CaM#X3F+f1@RXgsSeFWs(^2z;Ub^P3B zY3|91r)2BNaqPNc>QmaIPPXhz#q0AFxvNzFe9;nZmFL?Jv7?rfwAt&}JC8%4If!tfQhS@2oe5c^fp9TN-UCoDAK~E9aVWZks0x#U=5SD;o_7ua=RK4e?mDbO<;3 zP6d%yPGGbz8nBDq%lTC$`_ZyB7%YEQ+0){@I1Y;8Yp9d(@Y zL#A>CVV1(F;Fltk{UYwc-zmcJyHe1So(z-i+{vd?F8Hmp7n&~}Bh^!@m?E+q#x8!1 z+fv%_xmO(Q``v&No$q+@v8}Y@<}c<(cQKjKPEczx2*U$1@$85R+_EGSVN&KuR-v5U z-|KzI`?~A+>Pio^thh;5>`SQ9qwt)QjTK~$kvn^Q$$Dt<>Bg;7Q}E>bUbz2uFNF4tPsc+(T*hQwc##4K?JHIBhd6!SxC?+=4}9#R9ddho**NFHTM$fGbOm9vL{!5cBp=RR6?#DVc#UA&ohlOMi52__n5 zk^d+cZFk|pWen_+#xAuvm@K8RLouf|u;mw9bd14fPvXkO|Y)c_!pu}vu zE@BPO=MT*4ZM26gF*O#CSZHC5!y)*cbB1W;wBYjqS1vzvsjw_bpV3Z>fVWR4k~dO- z82T0D!y|~c#&#y;$SP3SS%RL4bl?3--%a;u51x2EUpnI)*eFCQZJPM)tEqD=F-=i-RTXdU*6e<-Y*QG*$OQ!#kR8+hp0i^=91%-C+~ z4mL|4n9pNtrf`q%S_tj)!_fPw8fVxoC!{=?!Ag32L4EQ}IukN*c&G%|v+6YYFIJ41 zwL+Zhota3?TwJK1Dhe_e)}ha;VBAyH1kRg&p#nxSzP`)h&C7m1%kDakTQr616}J-1 zZ>BM(L>;!zmnZ+c+(Kz8%wF$9N`GjeOm#1W{5e51Q~omK_ZoO%`4xGuDzqE)9NyiY zP9ldM;vYR|hvoi*NOprd>-uprH>k=|=v05tygITK4lMB_BTv$Iedb^2NWViKzn8~h z#XXeOe4ON6(qhNa9uO1HPRyX+-7(XFFQYvYdR#TSLw3?vFtXA+; zw4xb=a)v9jhl2DixKg(SE1s%zLDR+wzD1R+Mt3@RKmt)u55%XQeQ?729{GkBn3Y=Y zFloFxc^GsZ*Kddg>mmj6Pk)Y8eGArmS+aT6H%5`Z<-_c@VauuK)jBvnG|H zYV5qkK$t|kYT>#V$)6;F6($E85t02wV2NHrNIlyiYRB+du<3DmPw(!YA19&mCbsY&gI7>nu(4c zJ_;B2mXT{4EAi7!Bbfb2ZeRzlXJf!8aT?isWDt7j^@3khB3XXy8uLBD3ATDv;L@2D zm{A`K&NKI-bo+Q-%`KbFd}PDF+j>WI%;Fd<7nKuV?R1QJ?FmaM^VU1>9u|jnL4N09 z;+^o5f9d%RHvf(xA;*3(^K(~0Y0d?Vn_qzM^Bduuz8G1vZj|UJ<-;2su;DL{&|&5- zp3Jp1S_*;f34HO-nVj_=L*e6!cviA623E#9kb|QVu{p38Qe{q&Q7g7F?~DxC>4ldD zydV2oLLl+TT?~oP$8wFApd>9$Tzo4SrA3puyyupJ@}NeM_i#(D+jXh{nuFlwh!o1W z^Cs8!x}x<^MNY@MhFDZlc1Oi>FrU{kumj7Vr_AROuTdiTJ-=XV3mkHjB)b0Jn2ZKv zPULDS=>FDWvo#{1<8Tler+Wu2R`<`5I??Y1rtk#B$#ezzSr18>xr$nsOvs92PA>jq8xIx_YHpk z?8YsdutHe8V*}rM+Ke+hq9R;gkjk!E7zs*olgXCANYp&r3%?C^lO_W>=1h+jJI;SU zZ``p9{b@gVG3^KnXw$+crP=H;(Omwsf23&HBbtXge2$EN(u!gWT)5if%Y-j=dQ3-5 z1f2NKm`ExDRt5Zl|DME?_}VBYUD63EIxk?(-$uOQvkPow_hF#_b3T&hP4*9;%YXat zh^X(@6*#c=4mrHu3uoAld^az0t zi@W&IKNWX>eg(r%OOO>2s!T_gG3TgiDO7IUj3wvPxG&1`!tIAM*v>0nu*6^%nI+0Z z%U!aZy5l8sH%pp1Z!6C2YfdIZLtNPPN>OlS@pG&k7L0l0n&459IGMUJl8Li6=ClH> zgy~EwbEZk1cF!r0jHotD^+^Rz+mEPS)j+2y{ScLRme`N(V~)8v!}Q-jG4OE}|4Bp`xzd?LyCcQ91;Zbc=;$COqLYQ~L#0Ul_cnCc9tMNshEfln3C68# zg~&{6GG+7yrclNKHcLdIQ%DIurGM{9}balZkW*TdI${lL` zwTRErW2 z2(&83k|NV~s;`{^i@c-cmC7srs+<`oS*s?Dk#=YGMcz=7Gn%5+(lBuAA6V#{MDCAq zw^FG30gV1iQjzDz+I|dzx4$wlamXsvp}CmHryck{b2AaU^fZJmts)z~33w*V2!^Q3 zlYd-}m9a5Uc)^sM>8JhR5^`K$ZXxN9uV+4&J3)C_6&~}iz@8CtK>81&gxLiC_a^GO zwYTTn=iC-8v^oPjm-A#+P&OXfXv3XT6$u}_2eWn0yx@1X71>&FAD>?S4)4DnBPT!q z;1^Io_WQG`L^@o84XIuQY%9%VZ7IO0voAqEM}~eLv_+Sx7gWRCf!F^$npwZbh--AV z5{^d1^OcXZIbA(cG*-ggNNp_twWsnLyld%>rx}GV5yZLSyeBZ{(<3~8%%}h z&(h%Um=2$B1P~d@P)qsLOTD`#q|K*_QM|Vt&ic@f(Z_8#`)VvK9nygx`#bnF-4=Lx zelR%~{*AdAM!k-A9C-g7clkYShTM=BmV&?CXx2KL`bjjmli|-EqQ)Qzu0H%J$#F`l zl9dwYlwX`9vF3Jc5bf$x&g;d1#&~>g*aoX_+K_}*a*Rrm2>tK3 zz@it{!-=f*78c%+`r&vkV5kEb=VPK*Ft9bb#!%&!yCOXLF$GK z@wZfA%4Blbo@__nw<8_>3Jp2)WJ{sEB?NoNsd5h=%L{8pPG`Rqdqb2+L>_<2#NlRx zx$ovYdFm*`ymu4ljEd4p<_Q;8llI658@J%igF%=jYJy{*Wk^qKBvUmmhuudUdDBtD zu)^Mu>t!qj;|s}5&NX!~bxAg54B^A6L`w#5BwRQcFwY-$HJm_Q2>AQf=@NTq= z=W+dtCa|k#$tl;PJX*BE!=52zZM-Twg?bTfvhDdrc1QTPZIig_Y7614R2$PmwnEj6 zz=0Y5*0TWK8%2_Ri{;`x!nEU{_q?fD+CUsH$pnVrB-wC`+&0!xNO?cr0NzlVHBJCYit z&er{LfggubaMgmHIMFYQbrARA-M&1x`dJ?Wof5mq4mxA?qD$e~$x~!o!fQTS-;C?d z94Uk^b!XWRG%MkuOR~6rzT(d&fvm9$GG+=o9LWGWhe z`#fA%y+M|H-a^^uHXOeJg!%8!FtgVg!K8ErqEpt6_3|-rqj?sI**6Fa(tF^?#B^d% zbd}j{NBb87s!>~l_Uo;F0{g;c$&c1pzNaLMox8z@pS8V>~1c*pA`X2KMKIb(iFUs`rCvx5%Cg1AF!J^B#~_D?$G0$+Gv} zK+VTRKJMwV#;5OH{<5c0TQgn(s3(&#wng(Pu!;R0X2V#*Pb$w>ibYB6a zAZ%||;bLzq2w`8Qv6at!;9eo^1*^@%>KF;Gy!0YbuN7m?b&7M}e`OI1;>u>nZHENI z*Vr)D53^o3fm-%(a`1B`vobe}HJt0ie<~S@GvX$4gLjGqm!Kr3t5O|G2dh#BDc!^U zbKuJE2=Y2-EOzFJac9F6X z9CeYDZ_r^|X!nQJ840r9=pdF*|MRO%A2R&iXRDzxf1xZ&pFA}9kNrkJdsC!B_-!7M z{Cr-Xi@&2IaO$?KOf}Vt6LyjE8<}|F4GXK%hL9hIl;IX02G@!eiDZunUfM(RdPi3i z7bU{HD{uhattlukU5X!QmfU+?=)epg^KB#-6l5eEzQ(iPPo~30|5W05G7yKX@PH%y zSfbWkgNIFG!Q`42SzrE#$DD64zuJX-D(hoL4RV4zu4(wHB?nK_f3uU>G_Z%?S||;v zm8#_Zm$&%A>pYkkl+rsm^?v`Q@5i1|g8BVv?22~UEB!#1Y`k>>FRnWZA%EwPvd|3P z@xeQAmUbkGb!x0cMF`kkE5?&4yRl|MHmm*XKYpnE3#$X~Lm=jLJURQW9Zmd8;pU99 zekNzhwbbYc&mz59&l+#oRiHmGx9!96wQ0o~&^ z<-Xn-&yo(xI3tq>aeJ5VrTWZW#-ngG)OFm(;^h~So%RG4dkiPpk7N1yC$d;Cz5fPg zxP|j&SZ7#EKARQcH%)!+@ZfR6=8f%)_E{h3dNGGAOn->MkA6V(f2AaA)o)(0U5qme z%q7xolC17aCzxh>8)IE*C$d#DJQY;PiI+MeRo`q@#Vw3)U8%#AW=!PFLK&eaJ&r#> z)VW{vszRZuC%bkpWiPlpliId8+-TAZ33o1#@k!elzcZ8A^RjpNdC!ZmZqruS>-!cT zO__utx3naFM3$OxkHC!)&v92fSI5nLY2LU%$s z%*g(a=wy1~%y<1TR=7wywUH^jup9#1x(8;s`~Fxceg6~r&JMooeKQozP$g^Deq$o3 zH-7A^&HRq_w|SqKiQI^_jL^Pu6zlCn^G7EV$h`e8ahjby*Dh-++!y;$wW3Rmb2Yh4 zYTWEt__GdPuNp$e%t^tXy?xLo@*|CMT8!OSAKDL?&)=wzMQOV%n&02T_a8Fj8+Au= zYsHO(q4Ztv`)W5d=_HbGXD*|L-bzl8nJFBSHD~ncZ8zi3NU~vhIMyv{hp9JLkVwOw z%(x~8aGsckKMWtDp=TDWSGr|jCy$g(g29G`1DeU1P#aFW$68pRV8xeYai!QFD6`BU(zl|RTQ;lV zVeV}l6Y~;v>S$l8Z~+_Nyx?!BXR|pk{u|iIMdv1R(b){mVmw5vQd91M_YA>A+L-P5 zA4lim&(;6Mahs;>6&Yz5h0+l2J#VX|BvD30g9;5Tl#snEqO_B!sI<(_dEerjBwAD| zl+~h0lk&Si|3LNd$hqhJIkn6@_=Y}k`sf|@sJn0sH3{CAb%9ILkBbAJWWoFvDciJiszzVe5) zZ)~Yc<`FcL6Co!b@!7YXLd-mAVbXp&n=V}G#mYS037VSiST?i{J9Jv1L|lQ+(TL)? zwLAyFWRGBB!x#)Yrbo_A1#ac}WG1v!88Ypa>HnG4=PzVI!$1_>`$HRDeT9j&WhDg# zVfOkZFDNY+r>5qJj!A9ck?l+ca|;B))4M?|M}v-IRajp~zWZ!Wq@Z|Ip5R2N9*Lg} z+~Tr!Cf+j??3zO8x*6S=6;S|f`wr2NQcke{j1VbzuAr@_G}-hC-XNf^ zk~N9f+}8D5807qcBMt_%!($hlb0d?j`5ig3lh0TyP5w*O=1$Z&vh|{=aN9>`$Fv0p4EWfac9@D(XEV5h$u75J{ zZuT`?Y;c5K^Ds)V)kLZC+Z849LEeD7^reiwG;|t5+E3FjD!i|kRj^7l6~0q4;W-<2 z$`|tIPoX!+J+yBTYjBBov;MG#MH^twNl)I3T5`H@mi>Jm`WuyF5zm~&tUu` zmA)DENRS@+5#pD6)A=iv*^JI$xGX5Z-`A6PUvC!Mn;#>{_j+Ryc!IyNrXA&`R{CDjjE-?55w!EkMhN`cH$BN&e5)eqY zPhH1~E9`;Q`Iqqx=YF@luP`Ia&~mc7yH6|HuAfvK-}Z#>UGU%ax2F|0O( zd3}nsD7G8ttmkjg7R%@Z{qb0LXb6G_vgw1IyUc~39^kd>F=BBER$Od?rVR=-r8ZVz zyzwo3+jkFV9#>{lyg9f!@QMZnU%)N4Q^@U$Q@G;SU5vuAjZjozPZf=yAU1!8h|xFc z_QYR;qFA2Q)^?mK<%qGb>^$IC{UhE-a~$X2cnkIl>a^;ImZi?q9taJ6f*TI)W3S%P zAvbNzxB;g~!Ka-{#G2QgUWECwg|!FZ>%h8^{ru^pA-JbkHllAIysXC>->w(j9OC(9 zJaf;u=Li0AG)BXRZLn|0M4ES{jQMAu$*$4lGa%!>3X1vPue9-m+x(}|vQm+d+9blg zsF#A|mSj*b+d++dyzo$gD0$V*QU97M#wyVn#;FO>lFm-N*AfeF1BK}Sebmo*zlz*q zEo%7eH?uY}lRdC3TA;P?fna&I9%&v!IGF-<)_+|Zyemtiy3;#Q*u|B6F)-saj6YQ_ z$QB_>Tqun*a$zTk`oX=HmA~y1S8aO+o(>F^f&WLa!GCSsTYs2O8jKw~$b9jeN-Q>8a#r)|&?;4f zwD)Lmjw=<}l%??!X0e2N77xmPB$A0rbW{to+-D5@5G6FQ$g>39cEq$dqe$LNxC47|CNf( zhmcTBT01&ikY@b}NTm){{j0`?mG6LkS*!54LOjx3Ju<99xG$m|%$LMa7^NLX1^lja zvil0OKFFr)74Hj5JH&~&aW&m+HkEbt_l6dGN&30v9RB2Q*(YkZ(e=GwEOOMpLHMlc zbTywf_ATE6nR+X5fsZ4KdPx&^IUR0ky(4=nk}FTH9tPUn$7EJ*f?cYs(m%|UpkFu zHsSa==mjKSet`NHG#HuGU`X*urmH2p@z}L_#Ikh(H{K}#$MfHdTUSPNTas9|@Ztst zG%}=5>e8{!@i#Ol9-}VXeJu8#{|RH7w$t33zU-Lx9gyUF4Vwl$Fr@brG>W&NXHGiv zN$5YgGpB(VqLy>VYYhB2GM*+ttX6Dz*kMdoj$;NXhMBx2fBuDx$3-w_`LaCZZB*NexznSbG( zvVhKc9meG0G`3~-;}MNT+9wnwqrc-gJAJfW)COh#+O%_788b)11s3gIhzlJq;nI_O zBr?yMyKUNJ`Mk`6T>8gyyPCzp%s&&Xe;%NvqXJM`O_ZEzt)hSAsu=$iXK2?JrKhC2 zuze^7PWg(`|7$Eo)8E4UF*>xkuAe!&*&WQ2mSBEN20mD*P7D{Caw?HB?14LJ@N~f; zdZ51pWiGf9+iVNYuJlu-pN0rATX&cCC$C^3Vm)YDji*J$Ntm-oh$MXrqjfpz%->b( z+268xfl7q6<+iHRt@R z<}+6o9)RFG+Eh_G9Hj@p!3&Em)Y>kN5!$~Ba;uJG>ib8yVr)F9OGfaS+FHTE(j-tG z!~4nkEX+)SDR~#G$*Cozur;~~!1gbpePsz4ttCaOtMcia21RDo%sK3)^TmSIN1{;V zb1)Q~zKTEZXkf;}R-S|O1a*8VvwJ8P3a1IEb8S10HyR)h*8bvp`ff3yvIn5@3Ga`J zvBAh+|dF{>0|7<{DZ0OnMQ`M z6E16EJub>JCFJ%z?vjfE8@Xc$ypt>Gx6`-FJ=Ooh%C6&dp|uw4xG)&fQ+v@jFAa~- z7Fgq;MO8j4Fv$V@PMDe^*b;aUEne!8ppVvEpv!iQl$Il&SqhxJs4@F}NdQbNSw;iL z9K~G;BIKV~6}=-b%t)ORA@bkP(DubXY(?u%P*v$eoB8YUIr|R08g=Ln(P%~_$AxE* zEkf_Z_i&&>k5ufo4BIoY&@3@zP9o7oy}yNq%A~FKE6Z!g@oAR znciR-FqXnQ#2Y&dT^#FMs5aq$B_6E|xL*W~KR7L3ko-goH^FE_N7S0&|cqq%2lifsM)wIDlp29>&U31znRfw9I>x=5%|a6ITEl*9(m z#R1Cf!DTz(bM0;HmQ2P!HEm$0-G=TBlbMhS!Jzpug^JX5Vc+VxWCm-&89m#C{o(US zLV+%)zuA|qzsvKxjv7(z@9B6v@Hf=YI7vG%`&cwh_z8_RA+*@mm;I-|1N^Vt#z{3x#J(f_ zaOop6t=1D{?zW&#aw%r;-M$$&w5e}LoIvvOYw(rgIiI@}*lRETLb0hlmq}iu&BFi~ zIK6_3U2Mdtrr!`?f>f((NN{oCSmNA!je7hi&BpxkfJ1$6(B10FJ@;wCzbfXYqccQ{NQ~^;nm>3> z-84yh{@Dk?($yVc@IaqFTk(UD+v*Mq^=?>^p27D8=#let?YOH$>TK!JG+1hyL3=to zFgu#pI!YMsNB+mkSrdebO=2~*{kfc#UA-CntrX~zRcYAlH4FhyBdFi4iOlK!8`xzFiTo+e(wEOQ&*sBB!%ohqIyl{Ry6aT8FsRmzX*)=6WP-7&Ff( zp53QQU;6LGE&B!`xndu^5Rt@`^sa(~#^>11$m7nRO@mqn$tg!B7TYv{Tj_g7cy+~T27D@ zoPdwk2ZOWfZ7kZOfk$68ft7g^o-Z$9Zl28rQ-)I4gmxU({YI92`@=0;af_LjkpRyR zEvHGl9C3-m5R~)Tnd-7=Mn~Hdl2ux;wx9*a`ou%N(L+@6c`dMvc?&`7rE~~?UW!XU>c9dRiy;VMa>_6Zpo}p^rwAc*|!8`;1J5H5I z#{h|Ua9&D}CK)I*CwjlISIoZ%zKFcXf*CrbD%p}NzUGIL2C}5$wIcVQiV^#PpN&hd zyHfMPW7ujeMi#l$(!=#4OjU*mX*_kFK3nd?9^Jba{#E|Nf_(%(!t3q-7II>fQyA$8WoT{Dpl(yU@S#->tm{msMP^g+QnfJgmAOyv zlnS$-DBrKmbG>$jQWP`HgPWy#RQP_VK%}P=`VEa~*kNT>KXWS_y|4%0zl^~KUWfe5 z|M|tq9gNcB5YU+yHKK>-9=Z&t%8pa*Yt@4DO`_!O&N>=3FqyTrT?3h+6KECY;=-?d z-};3EG;&hEMX>1~*gqYp-0WR!^|>H;zHB%CpY@j@Cry4APvf+HII_JN{n{etg%Gpabr=ayw9(}Vj8e^QaN$dqV?!PS`nWGceLChRuy6I;PUb`9% z{jT~{b@6XO$+m9Ls|upaH+^IJ0^GoPcmBxSKHv8WA`LomYlXArq{reg!Cr$N;e83~ zUn2Otsi6nKi-MxW(cOw{mp5GhHcF~7R-*bTnB!Jgr+7;nPkKD+DX4BoL58~EWzu|z?S$fgP*P_5!gm{dLqdPN$*roEjp`(#!?Z|qe z-;6H41E?P#^Z!q(epZ9L!ABbSrUe_87=r9H4SIT8H-1~40fxSQ)F@N|PZ4>taWSO< z;$6&Klht4r%ySlhm7+@FOE7JpPE{Vo3udl=3*A0F2*t|m5xIY`#zv9Lx$>It|1~8} zI+omlCqqn@{5EhF@ubehFEMEEAJAQXm%b_eD~Pm^Brg6}Xm8PI*3rZhsyB9^P4)@o zesqBhnN7!c=~_-o?g9H5fAGnceXOvgJ{i5#o}0ZVPM}pPODs;RaK?WS zS!W+CP```|Z}a=lmqnatb(3Yq9!oMMz>eE_QUaz1WJ0wkpMwYrz@f9E1nnQv)7sU{ zZg2*1p;7ezH_hhrF_3h2G&NcKL4XU}AY{x;S})Sii1Xf_BG(P5Ta$r9{JT}Tc@dX6 zQ-fW*Cyn<~9vPY87JO&ZxSuSidhmT^udXmL-*}%gj5GUM%pc@-D^lgPDY#{{5J`U= zO{M3lGmhz-S(TT!1&$Nr@%`8B5cPUL`mIpJhpE!!e#3Nbt*9PbGVA+1YXX^T6taOWm1IekV zmvUd=6OjZvMbFc{qdReCiYe(T(&cXFq_CRNF`zns8J%kti(!}lfPDH{Iv_lT`P6F3 z+74F>xG(W|a9c3!8?MCnDH_-|$or0JKcHNt`6*VXvM|T6JWGT6BgWlBe>B27CL|QV4dC{W&kzG6FwVa zTU>?FM`sg#MGLO)x<0#h=OEb1SJ9ukx67sC{=$omxzz8b7VE?JEzTJC8CCbj;*doL zSZSNk$G24&ACWKYj*>w^g?=}Ft)4>aZEQH*QGxi)T9K5jQ0HQ2nXb<#u4J|WVsc%N$b2(glU zcW1Gk484F9&s@!gSB-k~PsSdBm){Tgyp*NIaXRdxb=#oMEFAyOecH?4Uf;f7#HIh& z!5se=0%KdF=qKKHai1v!8?}@4$btU^3oFFP7U2dOI&liSv~Ud=-r#-CvgdIIuT7O* zkD_uxy%y~Ud!T3Ie7d%FBm3Pi82Sw&Q104tbbKpKe2n!tiJ4ApfZAzDI&*<~rxl_N z&t^Q=;J}%6KVeqquwZATNYz8S@buRR*la$P76#160FgepArwm64s*=eGB>F1DZpl- z>v+{T1te}{;4nL05VBdGD5THi4o2K&+g6-`@(=m+U{wr0*gJ{LPL|=e_;xW#H`W2` zYC`R!@1t6EG^ouspqKXi7W_A_AI_36I#~UW$xCp9q-uOd8SnN&1Kx3^A(yLPtnKw zp9!Wn4Z=&&SZef6hh_A4!r2eisD2_D{~m4uPri?-!Agfo5ekM%X;A%-}hvhMBAIUu>a*n z!ILjfkoIoEz~nbjuJav3-o`QKPgaBaiO+P|wHCY>Voc0k%(=N=k29eU4fvfzb0miz z%YO$u8`jW@hvQL#lOwkZ?o!6HlL-r54U0-Xp@)4L&o^m?#e5EEr*VSdsdgJ&6#9h+ z+mzUx2Y;dYixO9x{~9}%7?YYQ{5yTzPbPEaZip~kPq)Uj;!pk!JM2OM)`gI5kmEcH-6;=(gQW!#5>iP3#b8udAUmZiF!g5=QJkl@Ed>o_T(j_xam& ziqSA>eOwv#4xT=pL+za_7^Q`-utX&gX9Qfvfa`ih)7OF9{G-Y8{RK<%-pQUDcq73x zrBY!2qbRDA?u~1Hi;^un9#hfkYDU}I8T{Ujp)#sn*d!JM`woqxpVz(@RNwvyzQ62v zpPM+_v)KdK``b}-NhTiP-^e0?4xDeG1}o#A1`~KzmGW>0x-DBl>PxJ-f5jgvZA*kn zY}-RBy?g~*DX|e6?N#YNxm5Ic$@4|ON7Iu#RT!;Vfh-M0L9QTqVA-L&CFTCp6N8NTs zGxo>bAo}7Jd|~tiGiJoVxYdWTarJ+Kro&0FR^tM7UDt_j&yC1X{sQirn7N?DaW;7- zGnGrlWH#x0G~|gn)9HNQ@$@n&k|2GPij*obX)adma7Tk+lSwkV2L{8HNPgC4Yv5Y5 z7f`@{!IXcc%(nHse$rSqGSBx67?JjSym!4vjH&QR1<~I=H1Dq~?wCB9EctSaIz%00 z4BvUeOrBvCak3Qy*jRXiFYv9xOM&Umb~su%i1RuJ8LcQ?lAyo>R#jqb8ko0UGl>t>|_lwW0 zkCZ6>p8+M;uSX^qI&fEJ2cy2R90@kz^GfH9S-*Mvpn>nP{p*v9K^KKdO6@}$7b3)j z^Y_jB>}5LR`Wp7!u@JcRRE+)*-iZBEup{1=(3W0E^nVvB8FziqRmk~LgbfneWN=WnG+#!9b-mjyJti( zcr3U;h3o4CGN0y?)Bpu8tJj}3dAFx8d+)L-Pn};^QuRJq4y!Iff z@wt1a?rZer${-7gQVFtZ?qTYzwwra~efaI$n$dpxX59UT_f4e;)8>+R#y`6nB(uLz z=xV_~{xeDcU2~3u9OjIYA$0U;kK8eL*rh|h!A7c|DuWMF{({r5Wt;ginI?7jrSUHw45}rRe`P@Os~N@cL~*C+b!*4N0zGv?T;j6kf)= zn{>#W}8As0Uv<9m(Ck;Z> zkB#i)WsiJFbm|Ij!`)w%X0ye}ll(?nl(348jO6c_ITPvq1u3Y!Ly}a9X3*+AQov^W-x0;Py)MhUeDRbslm zS@zwWCju*-M80ck2au_CxRgx7#gkg$`E_CX;ukV==I6p+&3hyBT%V^&FC1^qZCEeL zs7j^6qr~;J=(sD2HHnj-vN!3p@hMFFs?}iM+J`HQ+ptYC4jNCt9m(|!+qJ>+H6nD) z)?dt$kVz!h3%Kz3yZFRu21&?Tz)hE$!hQ-9A@kopp|4j6$~6xUg4N86BlFyy-3iNv z#i@hrLCoCU0XaO%w)nRSvt0ZOd#`UahS_)Hn}2#lYo#OS7axqHy9`OP&I0a*>~i*9 zbR^7p7EHe`&d2EzYsh^GQ%-r37qi=6gcR~!E%|;v?7-p>&^DE#DbM^-2Ey5K*)F98>6x-BELiqJ$zhQ+5NJWak4a5vp`z)p=B&BSmg`X3cR+4wt4L#L{9X47jXE9#${o?4RvnbFD8yscIRWpizcq%UBTi zROfwSUAW^!1boltJEtt?qXD0H`yGCkDtCTlp8LDQh1xPqFTai}2Vww)&Y;y;NrB&E zIg-*doBL#Yn@t$L1dn+h;IUt+cy5C&(d#$o{vDTQXNzwD4bz%_(Y)g?Kcfz#ox(vr%5+vKR?Lxe74Y~3*>l@x){09 zb&G!a@{rjp=>;aIe&L3mGSpcA29n-e(ul=Lf|Iqp2jJZ(noCvK>5_k8yoDOKa67M$ z&oU(C&E}l!y*|cBeLoz&8BB#f^4*!?!*G7+F+E%$j2ADABF~2_snUjV?7k2_Z_DrY zFH2A2$GyU2=Q3})XO5X=xJNJ4ew;uX!ot~Kx!NS`kR3N+exv}4q{+XF6S=*jtJucV zeD=q2KfTnHgzH}ngRAWm`owcTGbm@s?&#Zou|gW8i5?%B;VW|2kl>@P+~SKrE44Dkh~<};^v@DEHp#~yc6)15$(JeE zT{QqbqZ8=)P(|kL-9Xk%;-MfqHUZ=KH?Q;1VGJ)-MD?{3$aZ~W?m)CYyEU%>_6(NL z))(yjwW=dI20pq^n*fs96i?>%Sh$B!*Egswz)k;1EWMRmdeM{&kqIL)RN%s z)r%u@JL;+dd9~P_d-!#(pr%=kXtv99NjHMo+$(XgV3ap4E{VtLNGW2pse;O1P-48l z1H0bnrJ&k12|oqxg5v$pQ1ueuTYdgD$WM`=tJ*6W7mZwq^|?>Ou^pdP8W10M{<|O~ z!dST-goU4iXic>T2A2MVp4uz4XK5^x+PWITw*SIC&)QHsHV#}$Kj3DER|2OQJa?#D ziZc6uGe;$PBgcMw?qPB*&R=CfvOg{0+#DvecwCscjccT1j4I3Zcm4sbmzPKKmhId}(d+vnEeA7nCUK3*eHHr|=BRA+h8(+2~Ed;ts$55}C8&PO`2ec1a z)7t15rl`*q@{6MI`S|-7^^u=}B~F~)qZB6Zj}pANr8_dWAD=7Y`@iz2b+$Pc|2LPs z8m+_yY0hI~Hu!*1sv1?cx`PTu`5^VqoZk5sE=ZjI5js9DqRc@xw#k1RG*ur$)y+I3 zgWvO?o^|3xiaMFQP9Y%L6F0JlJ4#!TKdxpRO0B`h*K^4@btUd-+6Gpt*9UHWQlkrP z^N>sb4L)T_w0iqzi}Z+o_@w4UBRhiF`NrEoBKHt>d|rm{&NZc||Og zxt>GCEs}!gVRB^Jui4y-u3Kzed@;yhxG4WpGWS)EN&LgW;dAoLBb}W{X<14IQAWEqzdV##V-Xqc7H*5 z(?J?IUYB)k-U$}{%_uZI1s5HE14=)}(!oM)MmK=ZL}VVJYu9w+sy2NR|JQ=koU|It z4HU`GLK)6()O@zAbOV_GWk+7x8NZ!eIg%Z!MXm(V&0XVFjxNzhc#1n(-nOG@ux?^L|p$R-TO)u&2laRPSX1TwI95*I$nja{Y^2QuRi z&6vOaS(d4Qs~EGKh)YRPX04)rP=N^ zjHHb-+=V|v@eg@%n%W13KFq3BP4%Z$f;^UkQl%slNzSauP z>Z=B;H9ZXuGbgEpWhZ*fT1T#Wt>&K94OWgxoI}*FD07b2GubUm{K2q5hc>@U!6hBP zz`Zk-wkoPH_kFjpZ8IAM($R_7J##0_{+@$*ElOB7bpnx6n#DN=>a#EQ7C@$3`N-T} zDi;X~t)_I^$ zGqg|I>XOoHbGV&zj0Ep@s*$txik$l5U^X&54sKoarD3Pz@j$&WY2m-`LyIRciyjl! z^LndbpF}d+z1a;4D$O?j4hfw4(#}S-KYe_UaM29p>DbB5ig>qzKVj-c0|U7L*^HFa(=3uhAe~E!N}r zRyfUj@7EQkVqSYE)R#F>ld)=yfAkl&&rKOkI=V5wO_NM}W5>Ncx*kinO(1m_Cvo2& z&0uA-`97e?XzF(F8m7G#BIbvl)3qJLmc?&G$gg!J)N7Y7JC^S+?sk`^A2x5qmX)16 zFT#OZDaSIet5-q{lYlGR@8e8<-`@V&h0Fb$!nB-Ff@ZntBc5=@<2T^K*Q=B)v%>j` z^U39d6S;E*^VyZ2KES-yq&We1@NjS*T%SW|L~WShO5sNsSn5KSI_&?83AT{xu|oeU=x0_(peQl)dG3;okiwcxch1hA3u-uJyYXGEBUbwCcbc; z*A@nH^N@D`0rS*D)bCS|h26kc2zU3O3bBD~E$@f?x$-m)bUWjZ9A2OK=)%d`hOnnZ zN+3S;AzkZMgHOKL5Gzx{m6et;hm={czo$)&_^e{SZ6x^j&!g4>X84_-Q4N8|=*ff6 znBAHl@V)jP+U?@?l-tjs_5K(-`;e>P(qmcj&SV~kLATiZ_e#Jaw4Sc&IEv!sy2P+t zn=5qr$^=*XL42Y$J>6P|@w-zXFw35L+liwyGYIPHhiOBQ7~9$64jWtUVRK(LUXgnT z58lbsnIGLOU7v_S+L);$InA^e;(VN;s>VEHq=G>5YB8Fgq!>u^Z#7dC@T@N$^Iz) zX}g8JH)}Us(`mp+a&YN*>Z8S+f>%_0Dycb3M!m)-B_9FBgNrl?TCWavJS> zzX2n^EeFedrICI6er5~^%~BunqFCJOhJW2F==ab+jBBbp1W!MRjx8DZ!FnQj5O2-R zJSoE$S*AhmveR_d%1%6*Z%ZEJS#dAdzN*w{GbO?`s+^p4ChH;P4^tmap|cuNaFnMQ zxzFWLllR)pHl;u|@a0Q^tYrdD@7V!RcovsaC7i`clk5kxIawWj_Kkf3EGep_i|X4k z)8Cd*KP&E3h#}+6cdl&|E0ym{2kR5$K78V<9bd&yxjbVCGN;fawF|2-XIy01?r@{=7o|0A_H`k)@UqsDOcAGO)G3K8->riK1i!}6_Bf1!!J zMK9@Vvq#xLIG8<##wPKa+r~j?68593&P-?GXMJHGwrb$byl#9Mp-IGFFXEOvtw(cy zhQ~B%aW4jEu;UVvA=E#SMohSkcWh}d~)=j`*{`**;vx>8aF6IY6!>>P0rrX|hqsAdy(s#;+^UYd^cc;!JY65l6Tx$bs zmFf#w({<@7(F>>-&g<1_C+W!zgBG)RZTWWET52!9h284D1$wTW!~e6j>u&1tzPMG~ z^x_a!ahU+jeV7F-VK(gnp`IEnAMs6z|tbZh~N%o>8< zidnQ~(gVgZ$phZ`*5j|X8#s6Jb2u6#N7Loq1ULDcSCNq!&&9pP7D*s*E-&a$hVS0~ zt4ro=*X5!=ePvvvHv%(Z5iK>YM?>pacs7OipicQKxac|v9rOszPZneMPxk&t?x_9K=psx)&Dw>ctM5wJ0sq3W-6g^!LAb#^PudthN0!qNUvB^NA}i z0rxT?i&1)F0Mn}s=yyJg`iRdFEWL4nzW$^dYLxcaPTn+r~d?9 zIPhu$N!|5~X2>b9jmL!;I`ZZQgoE(Y+Jaoh8?L;@FJBi{g{aZL*B%(1Gp8^ZA{6ine1mzA>QY59*^Wj z!gQO7w0Eot`Z@95&h&M(WAuIIXy;0Jx;qoA2MTd(r4AX`#xoKf8Z65q%}Dw^XU-%| z4DyeigOHSSbedcgn)fY-UDs6U(rsPX`ZyXyl{D#v|#c`|@!r%rZDjU-A3xZ`PI!8`*L{v|d%_Im{u$57oKm(oFW; zb$R-DbaG<*XyL<7OiBh0jlQ zU2VXM+0Rf$CI(!Y64c-IpTM#+5v(3xr6S>-==4m7gh`rlGel??#6sA=!ErPv#FTf5B-h*fJm)UhwmC$}`&ViTK${Ll){v<=Lb&@Q5 zYLP3s5I&!Os!yyicp*-nEUlsk-1OO+r+yH4YYbKJOTa9?&!tm6h(5kHow+Rhg+01k z7k|d_zju0k!(+*6j!_T6R}K?Mdb7^R41e2{4yF&%X-;DWD(Se8;{Efu-(Q>=`|HA_ z$xJ{s%GR(3SEIl-MxCZ-@4#A@_b_R^Cms40$87Xp1?!$<;@+dR=#oB>*f`p8r&dHU zd-9cFv#9~?wB+yO<8Oeo&<%RAk6^#BIgz#s8QNoym;axTv(Sv zy$)X!XpZ>^D=)9+J=<#RNel)_nvY6NaX3(;Ms_&aa;r3+Ff!SD;JHr9h<;L^KaYGq zI*)5TvjQcysFSO9Qk?cH8#YI7Eo_aQLbZY}@VS@YAgpqPim&)=k(Jp8)sNQE`8Gl9 zy0mRzXnp}@0-W$eqb3PJ2hPoDGw&IzgHxBgY2l_8yfR=z$~$bhe|=?)>u45Em`|ZL z)jYRa%PUQQJw5;2P0U4XYkoKH@Zf4ERLt5 zM$n>N5cTqPqOwy#0V&0Zv@5DfMjz0hHdyk6zy};eunycMW zjf3f0MDC*wcXpcw+byygG+UR_YRh8m&m4qWtqPhf(kfUO$=~v7a_GE<$?OaHU^u1G zgASERI33W^7pFyXM_K=SSsP9iiG#Q2w%KQ zqgkU*YYudZfg~dPF}VhT*W| zO9Z|6stZqb-iExkGjx|}xgd|{>RdaFbovKTw)=$_jNdzo-W_!s<3j&}q}6V^Gi8qD zooC-*&83+%YgrT<@l=|;*sIIs%ek>(Du;nH&!kIsAHx?O3RdYMqIZ~>O!nFYBepPK z6idfkK(~t#u>6h&JyvUk6^FW^y2FP$2y@Il+f~r{CExdg_)N}`EL}K;_GA;vbf2H8|Np@9)6Yzu`6@w{k5IAFnBik z{#=9mq6Bf5U zL(xC+Fzi*0x*m0c`e%u-vz2FU<#uACfev|v3%I>|X9yCK6-jP|GG{(7fW0jh2NTKz zsn(u&-1%69JU)MyUMiMhj#I+sEcrU(IeGjl3N|m~-&2 z=*h^w9aYQcqz+hfH%19F8KaKCe%a`eS$%f)Uua)hNgJNWF!HOt;poFrbWZ&{bfa+~ z8X!hn#a;_mxx9svmD(ek$&9P2&XF z8(O^!m-Dxk3Cndkb^jUcn~xdLEuTgGm)}8KUj-|({i1h-^X1uBg~H@!AIJ09*RXuw zFuZuCMca<<#0!IcuwrZg-I<@l_~x&I6H3R?r?VEvE>a^ZXBKh$BO{soZ%R6j{faNrZ@?mJBTHWmw(n0$nz zRsMAHJ2lpi_XGwEp2wo3P+VWCLXu1DIK7Gn#(vWtcx0ANc|{*Hm3dxz!2)jb6lc6| zHZpTeaT*If7n1-y&Yq|@Tu1&exRiOwXRJ2B%no7yT$idLv_5zAg< zkmod#(O|&Q+5yJOG5`Wgm(!ao9^+y2G`JM+M*qx~L{;;#gtfd%4Q1uoS(iP)&-xXg z{W^*hdRigQdkUR8dX=TbelcJ<1A3^e8<+F5$mydk$DOFgYZcn0A!aHkR56L&B@+lZ zbp>tcyN=@Czo5~nlA15&S!z@N0zN!NyO-;-53cNh@KfJWsWcg|vT?*@E6D^hipF zE!WhM#WbxjfSDVNY39yq+uKmLBfqIC!88tGW-TH1pX;oT8^yWY$j9)1{012>$;Z#bH?+9grzuXdKp9(;mt(MI&L#$I;c$MMAf*c9&3 zr5d+fmb#2@ko9II0R|arZyw&In@I<;)AG{_J2%E<|??P za~3;J7U9ghs$~8BMV!Q%D$7Od)kw({Q!dx_4g25Yvv45i0yQX##ASxd$!H~Wu6dCL z`#y0w=C`Uyli*HpH|%rurxgeOFthi2K(13R)|}78{6%+&+w#Ah z>4lr@Kz%AWhUU>pM>_F}*<2!blGhmD)mCO&%_gIlYjJuDGuSP>KhXY^F*U!IiaQ$r zK#uE4+LWWpOk5bqrWo~(%;yb7!LTRb7G`QFVTy}1dGyX~WIm^T&4-I$tEiD^2iAoQ z5OQ&lTjqKi&ctThH_O;;zDoBpGYnpc=XcTad>@&?xjHeye5Je=KLhwAqq z2z+iNLfp$6)SYK2nKft=vj-MjmCX!6^a(}cGe(Vj9Ut&NlCC=*%kO`iA(cX8WF)(k z2!-c9=Ln(F-a;ycv_wOFjAYBIv_plaQl#{p_o1|>4KQ|Rb8V!B_dXeTtY!>+J+heAe(A+7H2}(Y z4O?d7JoeGCmS%TGX!xnXO^yJnmygo|}CY2`9?S+cO$0`w~9CHvH zUUZ^655`I6>iss{pZLLt9saw4rc_#xcPj2|ZKOByy0Q=N;kyalo405*T1u)ndotx& z{=!e5r|SRsI$Z4YMYcy(n8^`kOYtwCzej!UxP+WjVY|f*(-goKZpIW5J z(v#&UMF~#pG;#b#Yl*+Ie0LQ-H1sZ<5Y47dTeV2`#s17_wKjUNG5~AM7y~!XU#FWc zbz-fG960sqqWDYR2RuK14Lo$#MZ==P@E*&nbo`P8n!RWf{?wBJiXClKrkv;1G&wWP z)|pi2iycu7H)b1_u0U_j2H@G}$G|4bLb_A48%K;g3KLI!a*j=tC-37EpyO363R@S0 zKd9fLc1xDh*qavQ><&Msox24s9(Nc2Q|N-7!(URhYynrT8ZF^KX1XNeOG>lh)p|Gj zJC1vKR4>EgU2Vdt_{CV7y`dLBUZPJ`8gNmvDdagW7Qf;CyXI#C8zNtd29?N?mHl*B zty3c%V>O=mCpfVoPh?T3;~G4-d_GtjJ)yHl@4}fp?I{cjlWDAeVi$Cy!|<1t^PyH^goJ+_j}&#P?>$s>`76~4Ygg*B#R(-kY06gd)= zzgmO0$Sj1$@uf6F;ScwbF{n{!5?7w(IXQdsVFxotmvc5^k=b85by_M-oyR-q2U^4W z*QP>3#yV_6j)2CqHu~S+5yWXBVg^@c($~L-5STrTEjVV2rg1&$zT$;YxaC z&RwJbgyVSnTno6gVY+ydScU+2!pXhXC}dDKE^8Rc+@`*uIfpIC=tUmvU3QmX+kZPg zlDY#H8MV=53r{lonmv1^H;smSN|Eh4H(~ZShl{5|a6u0K{pHFibe)%T5|{OMSF`uu0SOM4THzj;e|Znpqm4=JS2tj^I; zDQ&WUkQbYNq)KG4S(~U$wPUKzjp%Q1K8{E_2`5}*=!_qH{GUlE{IKj6!p<(jF>_B+U493CE^R=r{h7(cJU1Zt6xT5O z7D_Pu!4z9^s>z6%gk&SH;+6Psx-CFf8eMs+8+RVdg@!%ag2LwztVOLqWO>$$Bl25t_n>ibuDMUp!`h@dz>CFZ zi)jp>ZPxgBu(?N!(CP`Z$c5hmE3DV92pTR=jB;uKQwy}UB@jPJ9140T6Div?fZXH! z#Lfg$wblG@<1h;cm3?n`o;4XZ-tS1dM!^B5dY;SVfyTMjp6J zcLWS2JN`^!Eym%B;;m8!4R%z`3W! z!Vlj0v2*)pJZk6xKr>3kC-^?AhWB%c#HQ$$UpNLOO4o-b()V6E{G()4y{qwg4QCQ>8^Io=~za#JBlxzQw;rnh2c-1s32x4^SF;hiXzb(d!>>Yh{YCn~iZ^cIzj)PjMC8C~ja=2pASjmj-c-4S(8z6Qx?g|yf znvyl%*6dm7NHjh+9EY9^0OP=`)a*zPR&K9`H(OtcOGp007snKWNsS50^jeEI?&y>B z+NgKG!?(uSL(EB2;f&5YeEZQ+$U4dIGA4#(N-kpi)2GuptJTQO0lG~8pdG549f1`> zmVw{FgY@(2UL2i#6OMH)cYY(^kI0`dhRWyRX!IQ3?`$yuY9EHu4eoDo+|%*UX`C$d zA6120tz?+D&P#fi@11M^da>C~Il=`#V=Jt(aN>o4xR(8>8Z1-#LVXaEPVW3xEHnn zM~lx=x3%YZcC9*DpX|m8T(60uowZ2*D0`-MsR7As%g0{^oPj6nVraYAkc{&m%BD(x z7xo3r#I4>Y5`KG|Mm!E4HV%BWK8e2?zsJd6!(mlsuOQ9ugY$--ryBG2(8D%HWLwz+ z7S=foJw29&Rbx&<#H|)O)Rm`8b|SXY>drMg)$zn-qA43SdN44`yJ*1= zMKU7&A}IDV7e4O}L5KHrOLmki9m4Q@be-Nz)uelK3;9mrHe4UrOxL7ZlkZ)Q%;uAh zaBW2#9@Rb*9>~YgHNE|bno}7#DIXAaSo+{2(h$;y+uH@K`a= zaeCH5|BW^zW+xHrc{NHrFGQV`Xb)!v(W}rf%>=CIyA>w9NTd#7vPAC513q`D3f~5} zqR3`xdTeMK-_vZvKRx@wj~Zj@$i5am0!{8OoG}k{7TgMK8SKnTWPuP9Ln`NEh z({33ww@sZSA9G_RR+s5ZzAwukG=;gpGD7Lo{K#@MZ+0MaWQAp_J*gWugst5lj3#IY z;~PAK@!aubT0HX?R_KX=%@a+9h6|l&O|2lo@aezRiS<=C28wfOXR!)NsT6K_~!C&BPH*qU^3ysEkcbn-1N@_V}q z%lM;>3e1+_Uomzd&F}RGE5G919(j;G{<3%s&pp@`6Ay0>nWDa5k+|UF1L`w2m5!$B zqJ8QgP#)04SS3mF|1khucc|JA3cG06Tp! zS=>dn-D4=A`LZqMq)=hOLxB zcO$prgATzUH4F3CKZb;g36IW&!3H2*AEW^Thzhb2g6^5)X>*j0Q24s5+7 zF2~X&MyD2*hsz_;YVHv>(*)^+TuQbMAQpFW;PpjMQQ5|iSnh=jRLDi5vs}{{=N8C{ z{1U~Fk}OEuhG}fmglIIN<^;AMR01RKoTG0YZ4mJoOyy%v()h$E{L^?ejFz#cL18>I z?MWh_!;giDl?!mW;U#)ke2)4x3?m)9kA^I5K#nSfxNpTp*kZqv#_(Lzaq1J|ps(y9H}=rlD>|f~PQ$%!r{Q~K3;lL(4AI}~#Ez&`UCSM>Pa^ntq1ZJRU04!?+fO-xQ_U_qZmlB8 zzf%T*Tg-&5NBx{7 zTOLA+*AOB1E^B+KMW{yfY8O+ZXWLpqaK* zj3kJdSe|8xH|N; z_~P)N*zEEY_tF{}Inhy)%tnGZ~3C$}A&EY1>Pz4!fl-{)cwwl{x9dG$JLUIH4c<;-MV$d ziMy)6>Xsn1`9%>{oKp%?>tE825laXPna(n)kI?->me@>r0s#}3qXN#|wRn%_TETTR zU;isMJrxU@eW}7mBkqA(e~J31-J^OYnt0V_2Qa+XN<{?>KdpQynZ3;tw1~^jAuOU^ z8@1>y$8HBFg4&*Hs_y(1HwPUDnT|5?^%XqRwO<;napqc3=SaM7T^&9AG=-|`RFT7F za+R`ccA#MCO}O9MyElxWsUH8S|eZOHhigQg$!!S<>@Y0aDiwC}kT>9t%8?mst) za;M7S>Vvl6v9X=%aJ_`5+6=aMel>Lw%t(X2Ju{-lNa`{_x1tD`lFD~KzJ2)2rdo&) zy%ldB*Mm3RI}Jv`{9OGA$2T4*!7$G>x>u?hTWL;$h#HRD^6PLp&sB3bY^P>VEJ#=2 z3|61!L))(oCXNZind3nlG;@6n*3a7n%A1bU$-I;F=HNPL#-YyF8>Gqlf(tNj!y07R zyBQCTQsz12{xqeq8Rr&o4P!XMAn(t#o>rf%bpb1jeq*qom(uDkyQxBu{l zJu60{OU7JhF1BE^O&jTTu7|01p1~HZ`z$1k--b)>CBm70dE>MeU&Bva4vElaHBR)0_me6-oC1-5x1-!~!%4se#LBmXqA5A2@w69LVbtJK zD&A#-2AiwVn$IU`cV`qH5Ma&wudV4wOJ(9S^8ieaZWm^bS%}XZze=~77SnBpqlx^2 z5cd0gqv*P$7MWk?$mGmlp!O?g`2Oe`%zK?gE1$V>oq#jzn5co8O=sdR$59gfc9KB? zJ~`PDCfRn0d#?3ht*t3=B2p1G{925+^cPdr#yxarXeHTODp%=zv=muRPQyo6orNjq zTB!Qf(d0hwZqQR@*L*tkNPL(k`#mxinSWn}Usnjw!87g-21}FJK^MTOU0+z5y&ApC zlB56AkQ^(B#rMMA(yARs6qpWi%AL*LwM|3|4i@6pb2VTZ(@dA}uAu-_K!7Lnj zIt5mU{phT3eOQlod$l|8oWs%nSgBPTB0O8Dg?a+cex(Wi1DeE_$F$;szg=Nf^*`a) zxPhdAA+~YwIjYV1*v@$~*q+HFk!;E`a+k}WajL~~^z)7B58C1HcfQ#EVWDvU*H%g$i! z@(PIect>;2DZ041$W%_Aknij%4G3GVNU8_aG;3h2nK75Ju+Gd!t3Nu#R% z;bWiAfkyNo4%D zZK6Thqlo%5NA{#CUsw?>;Qi5d5N+Q^ZOt=rW9Ay3moke=tyUmKGp@jr_6A`w*PkaW z`b{nB%cw~}Bi@_j3>WK`h~NHJB@^-|Gfn-==wql1S^iF+g)}r!7(0p_2;%SQ%pPI( zoM`+ZCLCgZwa~q1Gx7G-YeC^ff9igwA9?Fh4y8$h(1>A6@bXu`XhiV=I{)Gq-1EvC zp2x2eIoitMxk+{s9bl5aIrllvU?bmMr~20|$!eZiI>^r)Y3RmbnMYAj_x28bze$RW znpp>l7n;Rk*SXjGK{0qVk3`omN8q-qflzQSjV|Uo!1K>1bH3U{aNE8XUsE^%oh@y2 zpV)vLh;nBp7pK#6zLsRamNN@`H5>iqT}4B$MZ+fRlk}yW3@K}U4nLNxcJ`5yC*BXP zz_%3}k;%XLm|^MAd=g;AamJ}*U}`x$;%D9={wG|@Wl@7w=n7JK+8M^Jcf ziI*LAmf-fD%@?q1`Dw_>9#02F$`d&I5jpuvebbg0D{&E(RF8?gNZi~b|3CR-vgeJR_gTpa#%QB1zrAk5}AKY#BQ2Y3+rrckOj}&T2+3MF5~_b z<~1HJ{IsSagLKLKLl+<_L{bK$O8Q}CG41I;kQ^2h)+BvV6g*Umr1d$oM5`Cb z`eX?%5UN4Cau-cM<3i^6@}K`yL$3{HVjtHrP;k7J3Nl%^bL%vyaF(W@M)lyg*LH!e zpolb<`CyBp>-384UOH-dCCRYuSNY$AQj|6}4U^5q68@y+q$SzQ=c1QC#MfR|YLPWH z>MW>d8~UsmgstsdBy+g_QE3u9q!jwFfl&E$CHgLsr#&Q|rq77Qm#4g^H_eS`;bR># z#cUqCVdsd-rWN9pceU_jUNiNbY)M}Kb7ED`HG~%$iFoXVWl+}|M_(OQCX02h!!Ct` z!u1{>yg;>&c0@g+Iem%vkJ%5ZKCMRV?v;dlzly&5uTffr@h|+HQ~uLtVfD`v3v#zqQSy}dj$QtuPDKG^JUR^&MBeG_C_Y-9q1ICt%B2x{&mzN&Kz!Bk!Z10d6v~$a47r!sFCfh1*%$Rc%4Wf1kxJ zZybrdI+qce>cfit%_>Gsa3D8|w3x>45OiAr|cGDDFxhj%q(!SxbzRE;;|+P*h*wp%j&F{hF&ov2W`YT^!*wkZOqw(OV8$QB{=n|G+3EmrmyZc;f!(*a1Qbl53Nxn z-knp~-}G{{)Rp_K+>O{h=@<0LHVYCwTEzCa{tg*1eJKR}C)b>gi{7r>RPD?~p#WU;q{0~}b`PFb26LAPeH zMeD9p?;x&c-Y;UeY|YSV-9-H0@=h3R@sLj3CQY>Oz5w?#t>T{VJy<&HA~@<9qZtR* zJ;M2!sdM~IA@70|R=Qdaf`XRYEC82Wz+xU2rJH5;<<82g6+B97x7<<^Kfs!J)Lhifw+zx z&UAVPqpTTAv6jsUaJ_{HY!ZZ-tc)}ltUp55GOL;WgOO8AodjPyf z3!-lWdB4L!Kk)L3MMHX(iT!35wo2qLj?3jdYQS7pekmFyJiE+GZfoG^qAI$tauP|M zjoA&2Y9ZtBIMl@RKmNyuyK|p-l;s3iI$<1L%b#DspZ~?VNw88_gwxn9+Vs1amfTY& zYW6NnDgT0K${uY}Fp)6dtR}Q(%N6XNSqmi#chi7ad+y)2Wj$~DquBQ|aEZw{39qut zIuqBX%z)$jrD#ZX4^BUw1t!N7QT0?GocipJ1kcZ}s3aX%6e>?Cl_6x1hSM@HfJ0{s zeRO&x@gL*Bv=*0LQ}Gx^w&o6H=9OE~0o`DHDbXEnXQtEDSxRL8xEtVXZ6T-{grL&x z{ptTaJB`a?aZ1x?YCqG6?lvvNN8BDm(9&jlFyDfxyb!V9AsT}A{RF(+b|ri)i=(Np zdvTrPCAhvcRTzDA3BH^q13R3abB$;szBQnimge6VuQW*FcncB?AI$x&8;a*Lmq89< zuM9nMXrVP*5wr!BkgHjd_BHFjy*td_x zwA(vm|Mf?aMTL(7F(TB=qg>p777M3*g*S&j5~&(W51rm)>RnJ(NcM|P|@ z0A<^41f$YUWO8qz#A|u>`2aHc%p~SE+l$ssR3Qg`*sx!QW6oe1K)uHP#sf1m;6YV}a4%vJzGZfs)+^P} z{_P{lgvWtwX+e_ESgwH$uZtvnxGLu>_9r8@WbqZ6f5m{PFVbgQVn-lyKalHP-Jp8j zZF)H12lo4W9^Rk0BDVe|OB@Ctf;Kc3mHyp`qmOeRSQOuB{xc#^&a7Y^p|6B4lL&m~ zzk|Sg3}{W0A?ZA7$JV@Yq*wEXl1CBhOxD*KrH8G=j@#T}49{>o%`sfNn!>&}JcW6*K}dSTi}ywf%nDxYPGi}roR+utq&n-Rt+?f4%YX+BnxRW<28|3+)_ zyX}%M!uC^541oq^>e|k*DU4%w9`{Sp*BjHqc9{p6_ z%{vYEzzLqrqG0s}2PX%>zDdz&?R*XLL{ng450{~T+JIvZ)kENfyR^EW8#%MsmC487 z6wW8uqK?Zt)YADh&3h7!wF{h~-vk@#bxD>KtMdHJC5?i6>>^CGAJAi==c!TxpG!YZ zV(X(Wh+NAUPFVW_D!mTS{bFO{IM$fus`Uu1GBdH9$#{_BT}bmBGjZ6#IUrjmMOBY= z<6$fJK#8UzGM(&$<8Rc`2f|+Z+O?8w)ljOOVpxVuyHoL}u!|C`&gD7MAL_ZMqv_H$ z@4=cRHBE!%eA$fpUkJkI*LuR1;B*Sh`8{seRcPtd6ZRdrg|1ieet7Tqba^E2G`Igr z-SG&z?{NWs?fn#DM>kU?-W_&jF=i(YX$X$Z3HYsPh-BW@(e1;!`^rJyJWbg9WC^}i zCJ$$mp3~Y#iC9BX2Cj{-5nmpjg!^?=LSPQptMfDVfuFHz|3YOA(Zl`NEQ`vgj`VABA>IV!4OU@O%v|a`Ko93rkT)0~WfG)8|}SzzEffyVvZ< z;-kZvTwpMg-x-9PJuRW`ax#s(+lysO_CnHpOF`M76CE$|lkg|Y;*`nJwn;4Jga^&4 z=0!`J#pr0O-W<5dAXE!yY^?yo$31hb5s zD^x{xB(VxNV)}25QE~7pY(38d{O{kPQrCaurt_D;+~u11+>IXmZs=YZW?_b^N;cw> z2W@of;zWAq;0Q8%`*Nmmv`N^4A}|;pf*EVtX%oML%nIXCqLbZdQiD1Tz^8{;m=Ynv)mMW<@!&@D;%K z+NVO?BwzfsTOQtBy-dfyeS>>+=fL!$W#S_xYGmAo>Fm&ja&$CbhFnuNVcXkY(1BbF zx?lljg-`zoYr3QG3El@9#J?Hy`*Lt1?@Z|$IfNS7Ns%KSS0(r?)w%>vtdxfhkq7Db zoPYR?@jA$Hju0uH;xl%$qlEXqB4b9*8_s7H6R*?SBNin2g$t{#Fhj|88F*!E79=;k zq^s`Bb5GMv@Y*{DT^+swoB9lexXbD3Pd*YdEd?Q}X$`h8J|)5AqZ%rtNf^nx z(Ks~yUj{zGXSQRH%IUtzb4m6uN9Lk*-T796GeU|jaYm`)ey?uR@1*S?KnKb zAC61y5>Dm;_E@jPWbZXn(Gzr00k&5#&0e@_iQ zWb_G?sv2l-iW_NqGMO1W-V&l7j6<|uSHhDlj^e#qD+pA(*iwzAMcA|GDHZOVr#{<8 zkhWKW%+at`bQ$$0?=I-E?{AxEmXrypXy^L;;vT{O$_%{cw>{{TwbHRav#`c0zVDbR zLz_eS-dW=Sgc>QKm;V;ymsNE%U2iYd3a=!5YN~8cC_{ersd)I7Qh3naLO&-Nk&G*j z%zH!WwQn0VNPrc;N1JR$>vsg<$z@X|m~7J1i`7?GK+1`csRjh;){T>L8I(fKh zRvQ>_erCt>d_4Ecaq#foLU;1w=R2BaP~+Q59SgbKRJ(+aMfEn=n#B~~kFFv;dudm7UhO{EF;90eP zn;e9!ex2yBcc27sKNKsGy^)hxDsrbvt}3K!ssqd3H3n@te;Ow`R)dZ3j;fg25yxBl zth4Pfvam_P`t{SfuRNA+DeJ}=iu+;xiY!6BaS`?|d`dTF*3hgdL-L>AN+x5NAe_?C z#D7{{U}Rq#b>Mrbj2o`Z;@%aSAU%?7+HA_a^-R#XsloX8vFUK`{5={``y2l*yb7D5 zu8BLA_TkPGhheRX1?uOz8D~BDNiS|lrvB1~WOPCx8{PUs_$eQO*E$@9(?#v{-y%bT zIw!J(laBOefGV-e8OrMROh89|1Y_qFGvJNKIad3!^FWAYjA$CnvtwE3Y8#^%X_`SkI2R`DaxWEIB z`=gzA<4Y+!AV6jTbw4Rftp8R+*~X`W)KOm?$umYi*p$=aoo{f+4_|1FSSB7Hra|I! z<}>Nt*HFO*8B!c#&ZhB>meE|#w(q+uTjty?OfQYX#g}6xJjSNaIhcNphc?e4w8ut@ zm~$Uf)i6bLCCV4Sc&QB4Du-x{XD=SxvIUk+3=`R1lf@N7M9}l9oqB&aA%hkyU{md@ zs7;myDe!k=?_Zdqdoy^~72XFSetg${Xcp-xcVgGxJJBgMa%9=*+i+*O6_U>j#Rudy zz~^})l{S(lhfJg4W`sy6OkacdJUlJIThCw>vgw`)%XvPImn`qWr@Z%rLIS0|e22J- z_rx8uS&O7gW3lN0V<<=nrA7r`aMihWFhgdyASDeL#q?*>7Bte!X4>R>@nlw%o+RW4 zSz_D8?%)~PPRZsQ_~@BC@N=IB4YD&N3#(OF(Dz>9>8t?!X8$O-+5z;DZzulyVmI9X zvPXQp{|79s76c*d^wBljKUksKMv}Q5Rj)E*%HXZVXhC~1)ZM|W1Yb`^T!`4B6v`UV;GP4v#Q@hE)M2>QRS1o4z4Y%Vtw63qoV z=SL5=U2zz)WF8BFKlt4H_XUmqa-JH!G9a~DD;Z3$5xMj!61Q3U%t51(O1(8Dm#2+l z@2dKQ|6m4QG}sX~d~BsHD|X@Bss&J0-7B^WkRq#A=fcTMW%POZVqCMjQKJ2roL)(O zEF4g|v#|{26{g~F2tlwz}V&f!Su`(Ry%#EixH+i=*kGJ{X44jeUi+5!VfCoG3sp*YGtae8U z{>M4rXiUUDZPn1ua|2X(US-~1&Xp}N6?aZmBWQ*tQ<}bthYRK4_RR;ue&GQ+Vc1fV zoX_?A`?d+2ZxJ-GMU4&~luEyCi^7V#3}M$%Ga6>!iGK*8&>>SJ6#mS`!_K^i+ab-g z|4wa!EIiooo{yr~Zzu4V1*f3R{Xe>^kn>l(yJSri&r2jp_)^_y2}dzXqYa1X1;Xs( zQYa#~KQWb^%szIUrZ@ThV(t50wx<0m8j)s4hCUd|{3xUC!AN>s?qsEKSM9fN+CoW>Jh+=9{D-cjGj z59d?EF32pQUzvJhuo6LRqV(tLECtOy*CXpjsos z(!X4xFt&}FMC`^Bzw897m<6=;h%70oxC4_Cp9-zDzF0+91@?uPQ}}xVFUqihXpyi5Qu~{u^GkN)p$P||v#^;CoH32u=;z2z&f;A>Tjj_)x%=ENZ-wRt z2I1Z^4Y1x4Pao(j5Yz4?Fb;4RzOP+_KOa5|cc-?~^dfDtyTXet`{+SYx(eAf(wxPO zw?XY)`?2QiTu@HCLAzvU6J(9pa+gZy@@C#EEpr=cL)W4<`xtDx(G*O722-=xZ}?o; z7HD+XBZQYw{P(^xD{^n7!}$HKuhNqh#Uu&0{#oFt2oDLLd=6FNgVXLpdaOJBP^wSV zZw+Qj_q&DnjRAO}_gEMk!|2DxPdM;P4otteM?8A749T+I32*DIQSZIqc-H#yY+-gI z?be9ISE91vBJZOd&^?}1Z*^wVzfYut&TA3Bnab?g4t=EJ5`ev*kAdBu$7n0}E2&&4 zhAG`{qB`CYJkuc#e)mg8(fsd!^P4-nddf$f@R4V2nfkLA(J^SA<3s!{<|mBi9$5Dh z-aAq{Qi92)vWd7`VK!LBI@5hR14zTDi!h?*gK%oF`^7!cm z`0ApG^v^EFe}BKFD-`$A`^PKE@b3dFqeopvm(o)4#Lb-7QfQ^>>0H0(>{45&AgRrSdMGz!4s7fu^SL6enTJqAf5uHJ(0O#PtkH z*Wr&`nqXD$i{m?0;K18@>e-rzo1Y8>&Am0^@WMoV^42X-<@r3S4%$TB)QhcnVIpqj zc{qPMCo_MWc%+hl2s5K&Fs1q^omSvS^iO!PQ&y3}p?xms+sl&x<2rV&P-A%Z z!HixClp@kYc0khDmqPoXJe=g)0owJ=bomHvva`PzdtUHSq#Ig<=W}nGNgh$9}i;^iw>LuHy2isqVI$JdB$H#<(_ ze&~~1r8Ak(qK)j1+mYA|WA^V+FpB#egooW85AC89+7zrr)?F@!H+v@v(Z=!Z{($QySj_8@5t>f3%A_f5PD&)2`BlV$A4!@nb$rNR-E&huvX z{h0v{H~yp1uN6qYinFli%Mn52&|)0X_Lhzae?YGt)FXBC16ke2IKg{|2HxxD2JM_v zP5Z#JBbIou2$QQcS=yA0ZW+xQ7Mr6p)7SG0_#!wi_n2Bd>c(xVl>jzWywL0~?yk;* zEk5SxRNp47%ljJshtF*`dgK#b!R%H)7fQ>*v0+pmkjw4V-Pn+%y>OPy$(6Z7$eDai zX7}6y#p;IP91kB@AAgCan)G0s*_99`|Jk{I66YdLo`&V);?U9mwqUhKQgCJDLfV&W zL^huaWuhnRQI75{TykHQZTr$lZ}1)QaOA<{P4b1+Lj-L8%?;|`w$Z@B**L^uC&v-2#^J4ZG0bhrpf3u3;=A)>fDE=1 zPWZ0Dc@f1hGO?Y?Dh(yNd7NLpN9e(eD#T{HCEJi`gHF6Xf}5JSmt?>_y2*bgF}aV~ z+>hY=*FlcFTVD(I@54~u>KN=5VF~q{L+HM2?#KDI19V&u2#c3ftg1DT$=dNbk85K8 zCb}^f+nqwpBMThV;3dK53APTzB$cqpk=gRtaMC@c%E`*4(`*% z3rw|1T-a20^K3Bs{G=8yvik$V!zLP-XH6OoIi1 znvpS;)-3(yKjGG*8CatcNqA$KvUI#_0NkZy(ZYteJ0M&O~iLQ?f~Z47|uOM6-#**fuo^#5znQu+vCNW{o|2_I1evh{M|4aPwh_q{qfB;t-`wh&eRO8oI` zJ68L&5eiR8qoZlEWXNyKtmBT+fy*n2N3wL~=8Y9-&RT2oJJ6Ah87Es&I8~Ea`ztfM zSQpe8AB-m!PJk!pd9Po_Ao4BbDhxP}g>dywB;;S6%tJC)3o{K#Loa4(pNlEF zWk#OyyJvWiB})Ff2^Z}Qgdo*=Dr(``Q}h=2I)YfIr5E2>SqPf*%~4by&)gf(4|YCF zrqLU9$$wM$9dLV{a4<3)uZubk2fwz{;<+Z|KKI%@Rwfju3?@rewV5ZiM~A0v!HIuX z!ax5jG&F^Cwyw3{{NRuCRufsWy74SLnh=B3ytm*Fdw7N$$L-JDTTKntGqaWJ(X(|o zv8Yd;%{j(ru!lSoAGkExopKj{dX$=*cPI0x>LBerLsz(u+d5#GxN z@}ps4+bYWDf5yrr1_lOZ3vaY24xKrO`HXC&k);;6W$ZLC7}HK;+s2Zk3wfS^<|Ufh z>_BwdN3o;JhoBMDmgD*F?cr!2&rUD?hBKq`!82pO*twq!N$g4i=@r&UBj7il+Up?6 z+#6|nofMeMRrdNPqqF&2am}y25`H8581JQ0b!PqVkEidqX_D)w1~S*J!;vw^|L)oL zAdWarlkJCaEmI|2i=Qcq9Ux5_UME9peiC}Aq)Zxzc{2#`7q3w?A*{leZ86x6p5R)1 zF|h{%RyWazvN2@LP~MgH?7VOaPe2yJXnK(E?`q0Y@TbfE5YR&C7NM$57);Uv=6S_ntmDiOiIP$ zeZI(b$Q5Q5{VTsa;M5NevrNIX9&lVW|Rqss9^^zHS)*77VcExEH7? zm~yV*s8=-HtBR*LvgAm25kDJGvW2>Re%Sbe22?aQP^un}&jhJLS;`&pu)svDU33q! zpYwe0YzyM2IE}SN#Up$DLag(>1RhqOq9n&184op(VDebsD6H->3YLKx_2ymxAEN}Y zj;|NWqH=Lr+GqHh*G%<|PvUUBQs}=XhIT*p$1C;6OK`Y6ITL%Im;^Ufy2Sr+KDlRD zqy&c}PsoxY%}MN8-7)%%YX~iRXRrz>V#>t(`md$u@;_YyrZ3C z#}KPHN2ZO(3Uin06T5*!*_tiM=)uDTJY>@%2senPkD>;Uok)~zME4tj{|42Fyf2_a%jhiK8lo64cT~@O1_c_N(8X6)hq>QAcMa!scSw%#YB$Biv z_c=#JeM(z}G;Asj?a=Rh@83VrqsNWc{W{m{x}Mi4tVwDn0}+&8()<_N&Z{H~uNVN& zo+#+UpFn<3OvNRJQ&HiIP=Y^Qb9@uVlC-LP_+95QxPqnkch zgR)gIa0P!0u~~}o*G(eGu=^=VZTju_0*NArrVFGXEDnTeM#Cs+Npe)l7fV0YMl*J9 zr8ZGpfZvKHcxU%`YVnY1znE!drk-?u%1N%Zg$FZ27Z4FPA6m^bAl{TnN|r6g7g&~g zLdA0uTk@RSU>*n`?N=e=KGfp&_hm3)j}55~G32K@iJ%+oY>oqSGfq4 z8@W-n+xGZNqa9kYe+osPw}CHm>)`QFO~LFP_w_fF5KAF@&)9Gqgg3&P-iu`4t$w^^ znlUnfVRXif04y^$1xabx(|?&9h+I+$KYeAlQR#MUG~Wib>{X&?-dBLMTQP9TUNf?_ zE)17?NTPw3qeQx+g4WS1kEQ3yF59(Ahu6xJA#_LbbE@L?P!U)=?dXT}Rn{%{`xg{e%!wQ$9p?A29_h zG=9OYH|=QEW2Uu*HXxxGv4+qE$v`807wlyJ2bm)*3y?h%ZHRWHvtC-_plQk|FIARx z!7#3)@mjb+n=Jq$WjI@T9P(h?n2?S#F>7x&?utw4h)am0u zJM_fB;1{HPL3QX6=L0G$k{IV~> zOI(Fe-JZuJBV2=9i9`~jO%`?EvjxxA%YnMRN zh`4Kn3OYUMw<2ZEw=@~1UWh0CAQ8VX`v+?SACbOghd51%Kv-n0N;ZVG@Wksc3Y>k@`#T0H3m|U{cTxk{@4#FD`Kb*R`~;p8Fx(az6%c zNirj*>kP4Fv^rM!06n5~x=7l|;sMWB19`uttnezAZb5qh~v#&8zL`&aB6r za$O+wUSdPKS%>LQrEJ)j?@rv6Kl7hyF#d353bB@v2EiXi(dT?uIuv{gKikxRZX6J6 zxcun`FkLhQ%}{fo?SVo!Oh=TE>Uvok6UJC0J?r7!&5#6NO2fBIC!i@3Hw4;6>d_%k zaA`m8-_ws(i-b@J^EP~%Z;$n4&ca(8p9tn~^^_T?{k1(kv~VW(XvP$@K3$G3opS&< zvfJqEUVq}cD;6)e6h+sbUL;bN^10KKR>9tJKe3L+W30AK7VY}sO}%GCat3)y@Tcp1 zGJi!sE>t!~_Gl4x{!oW~niP<6v=*(Js|*ZR#={kvQDi6Mg!ftegP}o>$n?(*{M~MU z;htG%$-1=$U{zEU{6HiHJ8*@KEZgzCspYv_+nXA(~UN#`)O+0K)j3%x}Z{e@ZpZsQa3#pa<<5>NH>AG7klAkJZV1I8EEE$y~ zvpy`xPb_3nO_nz`U*rX(l$+qE^W&*mHe)5RF3YV7i|CT3liZO39-LsckSKcfir+UZ3*D=X=GG%(*rqf2EZ(j0%KG2UN+GnRVD~RvDc0&W6NZFyQmtL{P$Eb86B2 z3OBW~-_IYO^z*U5oMb=@l=5OK1KUY>pbDPKDkU~L({apkYc%eQA~o9W1SYBlLN^yx zqL^8PH>&M^XrIC6aq=WNqa4YNk;O)1d;umLus-@@Qi*XG^t>PUnzsYXRbyH}3 zN(Cr~v2ek=S){#T9e$=X48NaACa)cjaQ|faP$Wl=CLd_W%L5wFg)#Al_*zqNGQkK2 z%~&G1@lA}x@Wh!X8WZ^7%6R ze!|Vptb-}-6?R+MfDVs{H?(a^2CAXE;I4`SQhT8f^LLn_iblo-dSQ-@la$e=nUiSO zU3Fk89}H!!Ia1zKh994tf?V@k$e#3-yjBNcbZ1jG5&Dx1*7^yfPxqavJ-3)&)xmr< z+2Qo*qPA9&(#;a?VK(S$lg4r7uYmAOvWxa2; zBEWmjB6z&Zo#-rOeSAh)@Z8TW*|hp+1sBQp|Pz?=<;*8UNTA!-S{<)!i-Jer{O_(Y<(b@6Y@ABKk@aR=+ zt>p^tR_fx{zYgKb{8;#Ur4?D2ZG_L2%cH9%Wn|I*5iadvF?2uuP2fY`dYs)%Rhbv} zh7h+~^)hsJYa$XVDfrw)XT&G0C&=XqcYSjpjAV~-r^$Wzoo6;2(_26$6ny5tIrs<4 z_ouVo6DeTu^dDT1k7#C2F`mFO8s0MF8p=%Tft!^vdLG1d;CG{SzdV&tlCV5Yx{QFY z(Rz4fjx+livHPQqB=U@)q(a?+^W=X7iwhG38pYDNVkpSTov!Eyc;`?hBm>U`y2N1x zWAuu1pzk-EaPumZ(U}F4XvUZQV4Oq}{MZykUc|-XYyRU=%cgp=@7i$=xvhdf50B#U z;g4~Tt}Ht3Zm9AaH1cZNgE^Y1738M)eXFH!W2~5WFW|Ne~5^O`O-1O zq_GEARtqC;d>eVbqLClSID4mApX^r?mJM7R1vh5Nk*Wc9?-Oc<^Oe=9jY1k1d3PJE zZK@#t(+02)^L1zkdQs7jZn!U;?a7NAX#`vjLW2`vme_vcHT^$)SwRGqy=x;vk-r_M z%oIgD>srRgU@VTBIQZwXGFhv=2A_=8K(>ds(p19@ApKY)v{jI#(s8fw5@BQXy4H)T zPA}!AKj*>oI!lRTNk2~0%wjhhmeYy%!f>BBl79M@crI<_%s&Le>H8U5lGfqF?E~;> zPXalR6~V7E6hS`~t>|jS4qVP=rhAMRZR`8X5!V=KU6W2G%KMpS>WuI^YD)9 zZIa;Mi5qrVA){R?)FiE(d6;9NRJ1L*E4Cg_njnU@ugxb_b5C+FaXq}zF3`@m_V4?gNd}k9cR`PB zg+z|_;eiU4*;&D($@*qEVfR!tGf4hZgBFnsNzi5QMujSD&RK?vL-44dT-;6Ev zKjO5%nJ{W_JGpy&F7})(j&{oM$%(UXxE&FzV2HE`xv}LE-uX!eec}7j?KiIRzI>EG zODc@%x>X&xm}R39mhot%r3lz&w+Oln%_9?buv>H35!e>8mqbnz#}0qTAk3a z;gzePx~K?oO3lMqvl)(7sng=+H@O}?<~M$Hi{vt2++OyU44b};9{+~xl~^x%wz?)w zLmR<6ma{v{GQSVzR$__PM(}AYO`t!F{}%&KzfdCgMm6!tv@$5~&@Y(1^SjyYe)c?C z|3QwsKAHjx)LAb6VG>@;?t?BCt;BUl1}EPc2rcJpk*DnMXzRW-sI+}Lk>CA{UojyG zHdj3n?7bhaO-E6aL#UbGEPhTK+a)ZPQE!7pV0H64JZ|xjSorXeI zqzhPiQctiCS2e~$V;@`cKaRA5ofx`R#D2$odN`x#V%87%gXk)C<9a=5M8lov)T9@@ z^{I6**X%L*YMOy>pLIrgCji|T{)Af^5(vAF^8~xG&dw~j({vGey6O{uS@j>-nVChj zhNZypwSUkmi*>=*7URgk29&>le1nr$J-E*DWpiiqXqx6|-6lIlL<}cU{&om{HLr(e z&U47+HkM~e6+-uqTqW~lOgXEukHB1yeGf1;f^4o3lC5!}({I{ibh;9rv3NmZ6S}Yx zd)q1m^62c@CS3O=Wn_}8K>5ndi#sj}Hr)&%sYhe+gFFfJOYtW0bt>V6!&ku{k|G43 zevIY2WYAlwmGqT#B&Q{(1V_pilLqD&&6;40rU?1aiZwUz=Z!|_St&<7$PAFNI38a4 zFIF&zQ*}iU40%n$Et~ka_m9D-;j85Lb0ZM#8U?4mn=F{aF(S=yN%=II;grU>WZU5C zy=O_9{Q%y>b`_C9Zz?xq4n8Fzhvv#@)5UkK!J&{8*1ecS>^&Y~@5Nqd=7!lc?%X_{ z0n;dMzpp3DPQ`(}nNiTvUO})M`wD5I-Ay~_r&$|;bMI}KC?iEXf3@Svp=n6$`y6U; zHIEZF;lbC_mXVJV{rGcWIrOhABct})@m5b;WLY?kjvH123U;eu&@&x!d)f`G-!}wx z<2NYVPjnCBS7mqFAuu~XZ ze9MqzdL-ba&L8l8O*Tm?tT_@Et1Gq&|645+FB~z_%_YPTf;F}f2HnTw8 z{`2sBSQFXo)rkWh9OB%U5ZLwj>L>#0W2qTXAeR}?di(e^cEMvyj)6}H% zmyB^QYeHeP*c{Tdxe@Og9){5=HKcTE0Y6Y%49QL@B3DahfkUl7;Hwf&urnvT)j5qBHtH~XRfKB%R&e(m2#s(1D^bX9wVgtd=o7SjR(^@AHdgUqLk}r zK5EwAG`|hd%^RvXkh>FP{oRgzI*0J|FPU%>^Dc^BnTuZxilLgFl-y5#!+nTd1-Ge* zld+?h@a>CA=)vDGsy*%|Pdq^ajp)swn!`*tJI^@VPXWE@D+1Kdd&2$877`zsKD=ss z9`v0UPp*z1kGD0j_iuO|X-Sm^H5XRF6Sm@{r8N)tFKmV{R%_7njf@5KIu#b|ZzSA- zUOf7N?J!L~bn+ZhA5$ZXGL~vnuWK8D|7+I!Hk?Z4zN*ISYF8kx&XEdlOX7-Z8^N!V z48g3%y)p2aEn~6`YvSU#GMIgOkepy|F_C}T=)$!Hbg8jCx78yZKJZT?8Rn^&_l;%Z zL|zd+g$ypke>L1gbcumR2fh@Y3RM&g$f(Rye#5Io*t++bU{>?>q>!JAGu=?A%%8&; zT*;=^l(#h)II`T3<=s|t^4e{@Nz4_+-EgM1{{Gy~3TLoP+7R2QAHuWt$3dw-tP6g` z7(W^}4psUU6QRTXoVI>3G%WumVE(_T(Ls-@gXx&W2ye)~0jfl_6Cc)>qyF6mxwG7y z;?JktpRoWK7z_ozi~j6vnDvn5LzjHv5C8fD@97*Nk7r1OPn*Wz!GkVzzE&|7PHsT; zlP5G7U9Ja%lXcMpKU+HQ_Hf-4eMO{Xra+AjLNF_GJ#685kUz{Hax{Mw4rN{=EANxJ=v_?eF!W z>Jf9WXr>YJIS**_rRBh^JQ-#*BoP_=hj@|dGUPSEhFV0==QVbTqC3AaIXo{O6rPQP z9X@KLoVNxSp3p#{Z9C}p`VGMF{B79eAw|U>v|~kCbtGx-Mn%3K;iNb4V85m}(FpCw zjVH_C!$YUYg!)KaRA7xhJW;1Bk0=6*n$@uHuP)hcR>N+s>ExPvF>bT} z11m2aCVsM!yupnkkXJO1oc_~~#o3!k_`5S*uX_>)?Nvde<6Y=p2NkfjA_x95t03nU zdoYP|MIW{2&>KD$SWeFx&6%o67k6w11{1czf0|ar;Y1ofY(4_t@60FN7wotjeBNH;uB->vjm|rL#qoQi z6Cz&;-NAp*B>ot2#WTTElkf2Td_a4B+i{MUHd0$0LSHHMbEz%S@bqXgQDp4#{rOtx zh>$JiPt(UqiHxz|qDK2yXoK1J!{GGQ^N45r8EjcT2DL@&iK3w`uR25ojp5@&W=kp% zaTP(aE9TMcoTdENpIOh#;Yd1=9}hemAHcO}Z-8myf);Q4}SykMEs2yNSN))~& zHiSLa9D#{D;|X7S5!M`FzQlRA1^aWyw^eXmh6K4Sdl`2x6-G{-b7^_rY2NQ-2~_K1 zO4DpQ7;lR0x?7#-tNkKi)+0}N@X%tCyS5L%%E*HX{s)M!?RZ>oB809v^GT49G)NKm zhbQtSNT~i%+&`}w&Ka*owIptF!z2}6&b&j`74_ot$7Ipl5M3JcWFuH@oCV|7u#C_0 z%ecOJCBpY0O)yC2S{0js=&fvwy87`Ec6YuLuTCDH(8MKPWzbjrBbj}_8~1L`f<=|t z<~fJ1niIfH75xy(pht8od*&S-;Z~#uX(~%w+V*U4c&j%>$!i5zxSLA?Yzo$6jYf;SU$qLo{T( zZY0&^v3Oe%V`H*Rjo$7fT;*zic=o9T(Yf;kC#NZ(_qprnvw%I^H*Y2Q^|m*;;5LAD z^ORA%gsDK6pzO1{wDo{sAC|cziYBNulC?VKKnm`JH7iv~)9w@;f1nwbtk9+(h0?hy z(QVM_eYIc*o^)RZb^X<)^Rs4yy^cBXj(9E!WEmyVe*q|O%$2In_TinJ#O`Rdjl`-r z9vm)BIm{W|bA;m~ z`~-WiP~b_ZnOR1rFWZRM?$Jb%vNF{BqX>9v8U$Y}8k1PVdc5)SdpOdYMTDMi76|szp z_%}$8c5qIj+zpdP-zuk zegMl*3n^@;m(Ik4W78i%gHCabV3A_ZuW#8?p^{f#GQ&f__-#5jIJAxuO|qhcX18GZI?87zQZ3LnIuhgQ;uS1 zi)N^ruT81tE$&N2Dy%&7ADMBh7e~j-qO9$DRJ(U0P!B!=GrNxxubZ`au5l338+4~y z)oC2v*$DVEjtF+zgmp1+>4+xTy&swmv9jC6zG$~VU3y}@g2^C}aTw9O{D0quP83yDyy^d;G{uManFmPDtwxzSJ?W&U%< z$&?ycN#Eoof|=k26g&Hy{GQc;{~mP)clk2~IzzKU3e1RJOibdeaa{gixbSizd7s?I zEs8!4=i(7!oYRG07HFd2H6fHS#dzoYBF z!~EPSLg?7xV&cuof=+EA6gt_1rd=<=;U^l<*ICjHzg+m>-8~&Nf7Fq_c|Kg%#(JW~ z?3Ji~3lE4)-VC)}ml3ra8Mw|!1_|l0jNvcHRgZoIe@zYx=I5`AqA0G`lZq%pEV{B1 zrW|`Mn4ha(v3I(uEA{O$;bMiAP|+S0TK72~oZFiMH~ii~lGK+}=KbN7IbZ*H|}tf6Yv=Rz4mc2uu*{ zsASo4l)^btg{yklG+GS(`u!h~Ft-4)`Fr5>#ahHQD;-aYZHDtibg7G3I#|QU6?r{cm=MQTTJS`8tawsHCZ2nj8UWUHB0JPg>0ngCe9=V*Br76#9!M&n* zc>Sb4Sz#ZH_3VvN-StFTbT9_|S9A-`Y?h%ptJ<+erwZz4eFxGjbGX){j&RE4Rf1U> zvGfewpkGZIU3cQLFB<5>ds({jun1UqGzi+ApGlHR>hTk^kBrZgOGI{T=HF#Gta||t zw85bR^TcAHs^k$;cZ2b%RA!^4`y6Qh#&h`lZWUB$D@og@>Vj(fAh~N{v24f{~S?U z+=E50*q~g((Z#NMjBhp@9i2R#o-W@E!k0zD8D;jwZCx7H?Dzo}x)hOr!?U@lwg?y= z!gd=rOJ!MSR>CAegT~KfS!r3+2OOw6doO&SdLE{Ien1-bbYjzmR;c-*4jt+#2M&xA zzU18!qRKL%*?<1POZ~;f=3oJ*Hc|(l?oy%)a@+8eKn)b48%l-$WN`VphH%5sD#1-n zI#LUjUST}C;4%yX7>lOVh`ya50*n`IfaMFk+0J|qcQc(iP@NFrD@FWuQ6o_QbqP7w zY689_e1Qrq>%Fh$C7va!f%5W0=&^w=PAD!K_MIvv5v)H^)?N#>Zgr#wC+Xvp%eB$J zBm-)G#}Fi6+W>E#^Cn#vtFSVg|5+WBY?iR*g;$Fpm#ovIp*IzHWr`!qmtNH6kS|}U zQ3nkqZJ@Is?gmpXHp5Jd@l-YF6_#UsAtmPVOZ-vAIZ5mQ@wPF7U3As;95~+pAlW%_ zA%4F`99^tyCWCk0a($=$q2n4^BKPbvuDCo2rFX8QyGr>y-a-lFG1HQ&`E=koHn-g` z&7m^SML-4ggyI%Hf>~-iwE$Y_q>_#2C*aOBA;foXBtrSpz-7Q6>ZQw)cSA?9YTJDn zKB7ZsPrt=YJ&+1LEANwrN4+?PWyh>FJ!oC{xq8tqSrpG$(?@S@0!kALp!JVpQphsk zqFYv@_}qE)l{eGtOq)RK(W3%(M9ke7XsI)uh)mMLTz~uN6l2>ySPZ|w^lOCB8X`MIt707}Gi7Zp5{EGiPDiIpRvB}ExoQ%` zTbGa>;#T+i?47%4tqKrQB+WSyQ3$gh54 zgI*jT1hi-&QzITdXZWSga?vED(xXiAavreXyamQf`H_Q_nRw<5VH9E4L}souo6DS62LSQS>o6F6l+OOLRwG5Xi!!ZH*Sd%lpgjaZKnos#2!U-Io6rJ zb327MRI%J#`W*T-XC|nWiHD~qCX)T5jQyLp3}tje`uwymo}DCu%$D3G8plmR1-qwr z%~T=Zd=6sS@MgGe)Bn#{{(oCxw95s-jNP_h6(y*9(47~o@VaJMr1i&u9#OFYvIBY0 zqrQmD)$PH9kNi=9^;}xv;mvz-%mLMIk*5=MZUDug{ji4^l9FQ~cr?x!{qabmQg>p2 zPQoo1p&?6!m$l<5=2Ovjp?S2g;xJdrcGrAye}SK&z@-vOG}n;1Gk4*9v8m{`j5J+g zGRkGhu7O^!O^LlUA18SX!7q(@WY_U6d=KW0Y%6dO+|DBZQ$v}m3+U?&{oJPa`%GYf^JuIyc?60{ zog#Y(8d_KR6zBS$teC?ZIK(GW&WL+nc zOoyLk=s~ktF^<3U4lr9KPT*(gcFut-$0ri&>;+gqm+in;9uq!#$E{r#0RIk6BCaV{ z@V^Syvmoa~13y;rV*DhKFtDQf6&-k1E%P3*ol2!&1YBjitE`V7yWjQUm*Iu5dwmAk z-ztSKB?_Udjdw|Ur8L;%7XWQ~CXvF$`B+P_8Jd&n^l|Ymu6|!Cj3W=odD%W(C#i@Q zv7YPA>&ojL6J^npS|d6Zx(Td5c^pQJoFNeTPp?l-<$gpqg1TD;0xy}# zju<#*V?cDNCQgVw1y$091vzDVSw%EY+m&*@;@s>1is53*Gb~qFgm2pipa<9H)0H-( z+_;1_@VUPw5qbCqhdjuF?v8-ONp|pC7AL|uzgL2t_MnU;iZbw^O~%UnxzUWnS+Rhs z&x`_r-Y;O~Bq3_d@4yeRIRa8F+hXm`8NV+E3r=L?`1gZ2-76W+G+a)MZqCLpXDgxW z7jKcdMIzwPw<5T7rx2}*?7}7G>Zn^Nl$s3>^KOjDG5)y;Ju2}Q-^wya?d^6n^dX-+ zzl!a;FXs#9@ba5E&?7O7IQI_oTmLa0=80>>w^bd;cmIJ3jdN*rLlItH-GI*WWE=L} zOhQn&TC9NOePh1SG40J&W|VfoJ>VjgxF?`;x7?uP%7piib;Yr#jb zG^+p``S)YfIC(UGRycL)^TOj)D`DG)E^?Q3xTvxWrojRa`eNP;&M|*7(pWr|E|7@> z6{pxO@>?w7qS8Y1HxHZ~J@LcpN z^6A+CUOA$GI+NV!>hY(rP6o>?WX_`sbSBu}5eJJ|HuirrxoN}$J(=Q2_gz)P502O& zJ8PyhFWdz}R<48ZOQw?M-gta$Ml0FA}R@kR?ne=WOz+67#rSs>}D|dWB zy=fi{x>3TIy50DX`eG#g3DJG4=koGC*`d9~3iSHfT2Pu44~4pBl49>*{BnUYO5T@3 zJ3hsLRFzw>D^gxChv$4$Kt1Q(XjT6qPQu#}76b$d{Jlr!R>4q@Yvgy*UVQn-H1scb zGMzml46;(zK+(5W#Q7{A?@AwrzZ6f9EjBy(8E=HpbvKR*9e9N$9w?x!Qa5@}vV(i+ zvJVOe93_GKd-3=db95d$((2O{Sa;7<jiuh~XN%q45Y`a+) z*(I@?FEGYI`ReHYr~kdF-GKDlY8dzSDVbc>iN(jvP(Zf>ZLK-!D89^!=}U&R+w=^u zV*AO(S$@PyCmP?_B*a)WmE@z}aZZ65)js1XjA7M=wO6R2?^&TV<8V6n$k`CyJ02wP zGhAaH)H9Fg(-)i0W1&N4s4K#OI((D@ZkM8AZ%r6^Sn?e22^oPin(mUhq9uH%&qk7hDow{@~Vy}X)J-xt69^;!VY}1 z(+J({m`{+#u%ZAA@gbJ=X9|1%_+EP zTn$M}e1OFan?Tv@<9KD>05)9{1E)ST7R+Q|athu)_g#>uNN0J;(RFjE*dB3Cl-B977Xcw;2Rzum2q4aLw7v4WH zc@%$XCSAPfEmlr9MVI~TY0sk@oGA!^&Jz|1^oLJ-GGT5}C`q|E#J6adK%ca)lEQf^ z0ISNQr335f>E5gO+vNtN^-!*1k~{`y2iQBPcRr1_`d8xVmDZKHyw+SpOUi_SpTHxG)KmlF4mZk*d4h=O~T((iOR z&-sKM`ZYzFeu$|BlZ#{E?8`GryMG`qnP-gjx>9MNdMvoJ@+MrgeG+YDn&ehXN7$g6+dXM4dm!_gM50=nCFEudwFB>jM zyF|X)_TVkLrpO}Mk)|n6!wH9#7^6&v-Ysx{-u6{25myq?Xu6&*h?~ zM8I9UZwmHdF+~ydAl-?UFE+vd@~WYO&2#cRp%ZUyorxrE9qF=;635b{S*Y`?5xW_c zgXc9#FiAgv=&ap^Q-p+&@XvFkw!esL-%|^h-&CPVH(T-aPE~Y`WoMMvr*V^p4dBx! zYXx^PO9M?LvD%3yWuL+ZAv2LrJ?p(%E(x+<#K4XJB1zxfS6C)z3{J6rNDAUl@MDcf zpq|fJ((uUyyk^Xn&0);zRrnld=c=N@kWgx{{xx^*YZPn|svy%M7>DhwCgMb$siTNK zPS?^ym3J-aFRPgVl*GV8d66XkWF5|3EQ&<$v=eX<#+ksswW9~AqZ$RN;IJq*7 z$o%JtC%myive8P^UQrE9eHj2vDpiQ>)T>x>qBwdV>_-(bimNqrZIf{l)z@S=D7g>4uD1tD&*$J ze7s{xGrT+3kcO1<=rQ`+<4kb6D0dLX)<2V9SOX=$WJg9g=h5yhKWX>b5*Q zf8%@X^(GxIIUGuo#2s4vC6IhZOPal^G)jDZ#j>F5a$(6K5H2KSVbZ{ND{B{4fRB}|zf`FI`p z7{|hmhs?{+JSfHza6Skb6L`O>6@R`&G)UjBsA=|D{-iXUY*pjFGn8Un9o06+76j8jw~(1g3`4788^j+G6S;emz9DA84xW|(V(i67TO zTRnSH(RTv3s;VFvx5s4i?8Cg455jP-zYhr#AH+tiH&BD;PA?@F;x3N{bgn|YVUOoc zux2b9nmo8dR&4LVuQX<`-#tgVI9v@&@));d31cr;%maDJ;jn(X6VZ1{!l&+y!Y0)k z;(O46tFKuPLzQono|*xC`l%SIYIdiCW@cD9u^MVUc}euocVd;>Cdf0xkwz&OJBC;> zPs^%F^fxaZWM?Enx357YcG)g`a}(=Z0T;-z(?wjaR4u$bs7mwFTk(LDEaRm!#_!!Y z&gY{6+!YZjxUXfi9rD5i*2nRL<`&J!t>n8X$RZH9oc{Q?5>!vT52XU7>6Mf1*y*u4%Kwb0_wEwTa&QMYBbo5!~V7a_3PdxpXH%cF}pvpUE1BKu~*z2xNOe(Kp^9kbU8tZ*H)>_4D?Hi9= z$Lwh1l@5H8W$R4km(cYaMZxCx3*i#2HG&=Zdi`0Lsa{3`pQ~W$A2#SeM->{_HWw7R z1;SIa)QOjU0gfBr40l~O63k(*S1EAw9`?BnuzuJzQpoZ@j`qnH)qCc!o8YCz^uWSH zAi3>4^p|QN?#Ex@Und&DlB`mJ4m_UEvYAzuq;s_vcF!$^QgVL;-FZLwtdqAnn407( zaoKZfpz8hxa<{P>gFmh)+J~c;!8OPxT)C~4aYdp=Mqlbw~%5m z2=Z|b`*iIL4#O+@JBU}b3!Z1ocnH(@By7n?Zc>&#_QLfUeAc;joH zwxv9(^tGgpli%TSTa1w_%dF+|uW^ST`@zoUho{lEciN6@#Z9H1Pt)A37 zP62PiL{Keb9h)_r!cD0U;N3noy3hI^XU{sgze~)azDvK>9lj@r&c2>TE94wO=f#82 zJ}H*WU2_7PycR;LNiF1bgc+yT{1GI7ImLS8`|*lCd362n78(%hjsKNjL+@Or8$Lz! zf|KbLu(Wbepc~8mW<9)SOX#Hj8QkhvSroWcomS`X0g}w8*WQvy!q+EYfA)9rGxizD znw`guyATL__NtSf>K6RrwKNJ+T~DJtw{SleC_I5FJSk3X!x4BJ)jlJ&eUttnAMK5e<8xXkU?FH{Q3^80F05QEA~*c(t?| zieikoR|oXLB%u)aZZaZ&-=4(hE1BMSqMm#Xi{q8|3qzA=UlQguh!+4+v@VYEe>{)j z_(csU*m8VBM%GQhjby_^ve(Jo3q5!-^Kz)HBw7}UA8~azo9}C)veQhWHNQ}_y zK}X636gi$guZpHgDbwNV3^3Hl7_FY6q@{lsc4qf|m0mv4$tmM}GMRr~QjI?IY{fe5 zGU&h(Kfz4iaK`{zyk7VJT5&(~7P4$h)1(^wBg+WYUv;EInd8BCn}hI+OgzzB+l$Rh zh0)HuHd04V@vByi!h?)kew=v`?d=9(B=gZdI`I_qWSileFm;;MpUt6XQSkngD)N}| zKi`ixMho6~(Od%yY{-0u^_LxK)+|f#;d}y=+Pj}*xHMw<>ZM3yp(ULhRKPpG&k>2S z4iT+^``}XDIOLeSn#xUB#ouYJflh{QrM*jcfYJx|V0`mL!Ay2!Uf<7`z36qBYL4sL z20qm%3hs1fl9IAly~1NeVt(#r2WWDBNm2b$@u3 z_t7U06S_u+Ck6WWk*o4frhg>{!aCwD{ou-^$uWH|`vvEagbRmNF$ z2=$^m35P&R^Cf6C56RK5M8-8iqrqy2*&Vf{P67nery*D4=C7>7gMzH zdh=396h}y8R~HWZtcO<252Z@7O5F9@t8nM?`=s0Z3O@PL1)Z4*sh{Cn&M-9uMzH=S zzpySGV3Pw6Xe}Wl7vJ#hJ|w_^+-~Bj*N-EmM38;C8?Br!%O4anM$X?OsC0D_konaD ztL}=^X)YaDIhVZ`ZaC6!FCaIoy%=nhE5vpM@A2lYOn7W`8%dc9aZrpbdKh}26dC;C zc5N+$Z-T|BOhG61_#%UnxB1a~-miJx=JLoP%Zk2O_zs&fowEr$(s0phoPLQv%=YsY z%;!II*bE7ZAuCt^;R`JokM7hF(%+&CekY2eC9_x3(-Eg}lw~tKcR-z9F!+yajn_sK z?L8Q)dARQ4m@I11*QA-24q)Y#WC%AWkdc+A@qgk&z~kT7k+TqA z{dWbWM@u(Yo#_S-Q3bsI;RD$w+KuH|W^He;7p*s*$$6{Fp=?)8`nqo~*j11YJ9sH% z)$;_r-ChXU+Powy7UXd!#{wbxu1Th=KF5_uq);iho^snaagDZ$jByt%xaDnh(?eyG z!>Eh=bzJ+4>7x10v}cbduvr!dS3712G>RvDYqa~c8kI8N$$ECS!Gsud;@*^uCv1;| zJaj{_50@O2L6zNZbmW==mj23^$!S)!a*Zue>&%7O2^D1P<8B=Bz!goL$$Fo)0B`7k z9Xe*9L38fc0+XRwIQ61EK?-ZI&vs+<$sv>0H^+hz;|8c_t3+Ftw&6{l)6w0(A+$NJ znCt9vfRaHQ1bMggvO2i%*%NZYI~gwyv__rER`g4x5;*iQ1fKcjLUw(lxTE45Z0$Wy z48BM4f&3r1DihKg#TWR1G3!3?ln~5emHfT1nii9>-d9N2Q($26rWGmK!>W; z>Ftfifd4cErt7jsX1jnK?;K3QCnf?Yx+ zkeYoXQR|({iSAqvh5x%ljv5T&TPnh6soNZCf7uvYuCIpPa<9oNNyejQ9B<$Ys9kuG z95 z(MpwM?%N3in71H;#5eTgX+Mq7n{XeRwxkAA#xtA>0o6J;9*8;}gqIZ$5XCdSxc|5a z`Xu+3%-1>1uNfMJn)|PjlpQm{XkjlDed0tT&pl#&$IUQosRs32k;4VsM!^x^YNE}& zZ6C&r5Z=bRJQi6n9}eS&%>Wd+TY?{bDR8VRnOGIv$Ky_Vpia6v8MO@`6SYBanBQCZ;#4rq{$9eZbxGjrYj{*g3iZxiPcN*v z!ZU~&j}BJxsBLZsp2j-zL{nX;_0i8U}U};_WS9Qu8GI6@0%3pI{K0%r}bg)$GWI{D1`3ytE(T+c+riijQJV28CaHI zg8xU-dH7@fy?w3MOFWJ-gne@YETGH%9&Wvz`5kk0-bmb1(W&0WY|-)}10_$UtR=e}W2W^~eicK`6WUMJ8vr&N~V{v4Oc%EF|^ zMtbp>IXUQoz5D_V-YEWgR7{HKNvJys+a)(5~Sy8?P@dllZddKhF~zb9s#rMffnTb&V>-;VJQ@5s+0VYCUCnu0=+Qi zeCg(WZ2HD{I&`cQncUpKa+VwsHtt@D?;kZ`22ev~_;0IapdW1h7$}^P*TQ2buaoS+ z8y6~&HF*TaE2h)^Cv*wgK|poXP!zm43TuBp#1<>Qq2BwQNp-a&h;?=8@mMQzY26UG z`7I3H-?<6<44KHj4c5L;-Rth4dXG?yE8^TM!VwCG0g`0QTGtcj>dlwv_p<_pKU!Mv5 z^O8f)R{G%47SovRta7^k;7`0a^9oDu-Cou(?H4ZQ{V!v~Yv>{FC$#x2Cw6yBM9W_6 zz|Uvqu)r}LbUWuTuR4w3`q>lIC_uPHwE!-gIg#uAqnr2E9D##?n`MlBB4Fj z5OjGEU4BW6)TU~KzL5*+`V@o}W^x|>@V!)>`wZP>OBi`(Cp6mnIHwQHmo=lwoU2xUrHLW?R@xmnoD>vJg~*mv`(8I4@@ev5;3-U` z)|-HTUJYjIr?*k1wm*2o$PzZ^Po{9J=mw5oJ`_@a*3mkV7O{Wt0|osOgb{m3;U&+4 zSk}8vS|Mja_73-i6-V;vMb6=T%9&0LHL@s7CKhKrkL6ii-ifo?om}Z}%Q?pKbV9Za zF;%|9=9O5XPev`cwF$$yo(FX8t}5K6W&}TS4+}r;hhx|N`7D&b%T)2_C-LX6+CPEX z@Ht#Y3GZy0hzdduV)^-r%qjROZGXRvOxZ*rdT6f5PH-TfE~~-k)lbpqu?ocPt3S+H zx4LX&upw#OycME&Pmsx|`}kUd8t89npwfHw$+_t+Aba_k&^Txlda;k+G`I(NtI1`o zFeRV$p4>#0dJM@KFD01cD2GLmRnmFI3JR~SM~7{%;InO2Z1v7&N=G}B*yS!jpM?v4L3hw4or{ut-0j#_} zfwXL%V>luQTl*TRBQ+;kDh?2^jtE+tvXN_0jzkkyEl+Y_s>g}xEAsNWZc zWtx-B4gw*8UPvkC5Ki+>V()bF>Ez!_$*CL+rEW(AQCbg5)3_|T!OeRoPdp<00msdt z<^_dh?K35DoJlhpQgjv{jrb&)y=Qq=*K4;4D7)_D46Z{s@>&uz8N8P+l;Jr7yHV`T z!dj|sB~K=t@&~3GAoyO>#F_EFk{O#aLV@@u@nCiXos;p*_rJROTSX#`s)pN zPbTk)>+YgEyp72w@CK(MMAvcVKuEa_yuD%$WSREXH7r6y_@^xg1hN+3t7_paRKbj$)Owk z#U$XaqImu4TSy$tcLR0GveMhBC-*VJ1Y7W}97Ip7(;^4_21DRGXXHL_19qV9lFXWR za3AhXC}YumwnAo&AFfm8849azy0lH2>{u`tep`>HGrcYmUGqM8H1ahnHoAmAeraL4 zX00@|Z8!-(Y!BU`N9@B}xu)?!7cT7BhZe~0#jaz+*~%Fa^jPj6tha$OxA&PsHok$Q z{fEKRn{_njtp>R{)E932h!duIkHW&p4eVk+?sZ8sCm!xj5Yi`$?B!x{aY?*n*WI~i z87Z=Ig5VStD$8@kTf*+Lg8P%v^O|O?yv_l(e&t;)NmaP%k}(`dLs(y*(dQobpOo5 zJrMQCW04}Rt5xt)%LvrH;@Ly6- zuYJ%ZUfWzC;YE+&^8P<;zBEWOSLbv7e8MRkFwZ(pOaAB*93}^YSDB&Ta;xyBr50?- z^P|-4z#iP)(#Wo#>Yzr!Mx@8k8=iiyN@*zhtF`gKe$zG2)CwykcZd%6sXkJma$M)>%pS9sxlDNsE9l4ehE zArGylgOYQL5R>DJvwLQ-L0{j{xf#iLZruv@#k!>|J0cE`-P+COhjh}!av5^_+B}%~ zT%)Y)N(#b|0b93o>owu}VQ!4&! z6U)pDUFocO{mHkITP!%MRd}6p6wl(ULiNQh^lya*>Fn@ zH_VCJ7AHu#cthB-%?pqCw~CG2*g>T~r{P!r@%-NUr|bvmN1hv%Gv)c}=;AJUGVW&p zBvoIc%28EV_qZ|acD^q}oiZnv);NJ%z8CuMQwp~Dlg2KmUZXXKdeFT&g_4~%uuhH` zKJB9w^ErcdL(V^H1Mw;A~ekAJM-NU;DUFc zeO{?JH-P6x_aCILMyvSmodr9ZTuVc>cbN+x!WCaSH8ik*}O=VX8Z)o`{Yx1+r9=ak_C>~=)%r#74=vZa({J+fGH(Y{-qlBO&fr5jv-mfQMh4!~Q6(r~CI=5SfT%DB2K(+RGU}e_au(46W&DgzTRh&uEIUFxtWFvmjopE-I-X+b zt{pVN)|jYf^IKBcQMx-ypM2hFDA97AY65Wk{sqk1?kqJR{qW)^D_HsNZd&nFgM3@! z4~P5b)5=ip19w*zFS>9G)s9TUK0kOrrf)mFu*8Tw7Bln9{#YoU9zuE zI5nL7xFbO3$|Lqu*J=~b3;K{{wh!H|-;3?;ZfDJ=k+kUYAAHr6GdvMti7INs?ix@m@&u-SWk7uktEFm{# zU7+ZkGCjeww?6_a*vKUlQNz{OxYgGIp3J{bmBXv>HU|?p+b>!0$q2`m1y>}R?MYdE zGJM8#*fYtPnxvQ$vrZSd^L`?FxgZTMx|YS>Jma2EUk}31WN@G%Q#94vnOx2u3- zQBSojad!!T*bytr26L~=t55NudM^eQ484avItRhrHr`udrAJh4-Jt$_mhfTACN$3f zAdQLtK5Wx`(JFGNU08)LRa>%a`6 zH@opifbA7^RK4Oqe0}Z)wk@9Dn|NPX?`}IVe|MZdnyF7ZIuxP#yE!@=wF)arkLBHY znY4N99$X{ynyI|#pzllMNc?SQc;5eL>F-<>@>j_gcKi!Q3B#`7v06_h`ar*(chJM? z0y>c2WKGi&@VA0_?4R5iYI%ltM#%Svyxtc2ee*D~oOka|R#6kqLO$NF+r_$eRG>xf zuW*TTf4CL*k``|8#lI%blg!T_b5rm{mvwB>#@4ci@Ho8X;ybpG@qD@i=lNW4hxaL( zW$(j{d49wnY&J%t;+$vrtgoU(D_HZC=dJi`+15maf*IMU;O$9?9$U@xDNVgG?9K@% zdh)OgN!(S%ayE7e&ZdCx=;*WZI|WKt`~!@Z7gkSb1+1wzeJ1J}j=If}SiHE9Vb4 zT73l7N=-bx{eLsIDNKO`xVpkUnobXTib?LPzp$~m0`0Sm;!NWsk{N4!hjU=8L~vk` z3N>jlAS351!;$s#(MIh}IQl<(CTF~d_T>#E4`%p5dRvJwJaYq1{RR@A*G>mZPvO5u!-14uL#rRf<2~EvvO(v9Y0ni4 za^_Dmtjdf+!P6Li$~lVnM!ldNPll5CrnRu(X}ZwhWQRYu{%^*bBW|VQF`EBwnH*+muMK0C(``JHznC#&O?h_uQGs=>3h+nvc0&y zK0-2YCrkgq;WO{BDUd0Qh`EmU)$sSMm^%7ro;sOP@eJ4NH*|E22l+JH3F>Dm(BQ4MB=h4SxH%#c zoeq7CC#pDsgU@~1)1wz9!jSN6gY9KKjluZ><3}J8DieV%^}N z$t1+)X5c?sxy<-$D=pu!oNV1b6Gms85RL0}Ais9&!oJvNsP^VS^6XduSYGxjGn;Nf zF3#T#YktL`S?eqDy8fE*gm*N|(9j}M51io3e%|Tawh6sTI7ACAKT@&!c^sNm$U4RZ z(5zOaow~Yre>L>;S?o1h6NqmU=i1AtmQ$ zgY1DXf@RKs__NDKiB7BFW<@kZ5cF!Dpg!9Aq^D0A_BNWM)o)kfe>oFa_vuVJjqJe< zZ<|>7gAO{tM1ffUbAy4^nWgfV%}HQTs$$K#WSg%__Sl2_ z_TjTFOPRdU1iBU-$DXnSU}7=9lfE57GSs}m@wtkiv#t18h@rB^uh-T*KP ze@SOd^u;6m+*xqj8`^(P3Z8b%kJYE~IXo#2%Z0sX7fyB3E%W-3H%+tQ=RDQ20mZzx zH!T?SPVPb<-aN(Hhm}CnvysMf7Js4pCFZx#JHqD+*VY@zaNBb6yNCt4TX;Ic-M z@X>_(7N+~MO)(wR?L`*e9GJ*%X$_!0HBw~k*Gl$8Q5|(Yk|jIhgE$H#k2aDjEK@!L zT+{9g{RV20WjFbI(6*-HBpo%9t7rjQj`k=gG#kflKErl|h^eO6a67@wivj}te;Jy<@JjubWooCsnYM!H6?LbDgPJnw~JB8&1tMM26iR|Z+7j(rV8A3t> zAl%+tC<)fYIdj%ac3tTi(qzCL2N-XDnBKDEey5s#;2fRva|lg~eIzr^?%8$j3f^h%PJ^eoo$ib9-+wo{FNU zx&J@rv;bSi>(O1c{PrEc8Xh<;MPykj9x?qY8#b<;w$+R$Cj6aZYR+iUvEoVO?mSZn zE4YfR<9Fi|-#yveUm^59=dWt{AAyA(QAj?Y;^#m0A#&ggI$-1wvhsm9*d(M0Jw|qz zJ=`kM6Ec=?|Lw#{;QRO$4O=mu?6Hyt?={6c5G99R_+Hlhut6S#jwOk$0mM{_Vd;vIDPNtj;?)0-z@$kCt;jQsP!M z@q35c=s&F_e1y+i#oBhd@|!Vnf9n9395kug2z6qTs0ZnHF}e}68Rrb~W}n6$qS48H z_+@q_Teihcc+30BC%mtg+|E+(sS&d&{!r0@={5QDBuDu#>Y4u!cV_aKMFz4((jiV3=r^unmWIKSl{JDijyd}_IdV;&kq zKZ81IGDwXG@_ul?Zi0Id1Gv`ll31yL#61E(xwQIk|9R-C2{v zucZlY<3myTy+e{anx5Wed?LP>nQjiFwtMu*>~dAmaTHR1kXM2J^Ed~a z=S?Pu%!J*G9E1b?veD7i=OjDx36hO-HIte2>;+WglngoU^_+ca?-C4lWZ=_&3gB4P zOe=d;$%s~8=>M=;6lJYKPIro+YwRofOB*7tu7MIt9s!hy91aG*JP>(=3vA7 z$&CDwrizJHq%wXG9IN^d)fUT=ooCm>hy{7{UPKjskZlT=3?B$Hwpx%EW7mTGtbQd% z8+FJ*ohk5UgbSKBmovSG=Ce;_mGt109#rO8N?(L@(TRM%9pj&+lO`_oQ$8;dJJc)L zjemkFx%PZCG(FvkO37)wXlMbuX`W3tUUwk86AT>VyM%*gYjDi_DNOwJ1+A-)CNmoX zAn);7;gW?WUOGL5ZGP891D8q@Pky8P7kHQ+KBG@`V&=k5VuUj5BXQcgOvxN}G#p1R zIoX5m4msKssY|jP)gXKJZ1grF0Gm7)*u20w?%@(b6NrxAV66y#5Y}<{)dWO>WJZ z0yed;sG-7G@_MNqWUWv`O{qKZkdr}7e?Sd2TJjf<=iN+c8=}h8j=#qXCp&`Mw};d{ zRG-Xi@rIKXU4qe)?fBHO^OAj7h4W!{i5&pj9OXUireyp_?qAwD36&q(iMK*9n>GC! zz2!K7^c;J}R-BCxeLW+EZEe;`X0OphHL~*v@2xY+qrds=ZIT@%?iYI-`TabE`yIN= zCUdsi%o@(f`a275AJM0CoYaX%lL7GBJhVYS0&}kum@u}*E?Aog=;lT52_=cMa99daM!}ujv%GwX+ zevcL+x0zzQ^;;#kGt1%J*SFFeo?I`W?>KiW{nacGpOHhiAqH!#KgjE>I%u|)2f67r z9d<8JpvR6(B|T?#VCnS;^r(M5@8EEN#6frIz-?8y!PN}8Vj;w(msASk3}7)D)6IBZFp}|Psf^WfL?;1QmY$|i@%A(zkyLtaSf?2FGVm&ZKiX!aAxv* zeltD(SoHlnzl*7eAnR>CJ;3kRQG;gl?yw>O)i1+)P6tb7?`Po@ZqdzT9=`JYJ&yOw z^wR>Fy#LT_u1)RG426kT^QaWh8aM=)!LGyy!bi>{QY^NF_zpWXpZ5es|1DyBhCHVF z7Cq?tEk;uhb@AMmG|4FE8h)M=6^%KA4{hmVFDJE9mmV`>#`6yA*I5ef3suR9SW9@l zbSF9@2%e&e?@tb8d-c0%$nF6o zjBD2gNl7$zy_n3CmKJNqRw9>&kyu6{OEPa~>R6J1f3{HkZ6Lk5OqUqER|Cg!v(cS` zU_3e3f%D$uDJ&U4qBXf6Sf@yMcw#+P)x68Tnsn1TMSU{ymN(Q(+0ejgsaSE`4avM+ z`gaV8XtRYudS;^Fk;BO9)!H!KA{$-#mw@%>FK1RHgc`rLAYH-fV7Mq6?c?YJgUv%= z=e;_*n{)7D(>&l!!d`)8+Tz9K|C_g8qxr6jtU%i1HBCHjNMggrz}q-!)FB;>XJ>`6 z+S!ftS^htK;OQfF*EG6p?2~u6Th9TsH&oG5H&t?ds0U>4trdF4Y{#hmJlkd4LCf= z4GSSt$qE^d$ip#XKd>S)#;Win*9A9%<`3+E4*;>lBYus7VtD8Jf_G@kZ` zCcS*B$i2Z+cFu)ukLA$o8!`Bn_aXLe9Os<3d62ggWs=k;K+kQ;c2{9nY0hxyN*2EE48w82S+xpXbVKPVqFlZX2CW!R_i%Pi!-2Ul_U$CJ zeNYDeTyd5iw`rqwpS;M6ckb{l_k_r2rHHsj58<5Bhsceyop0&}!n4nd%eF7GAls7n zgTc{QR57Lkr#9$7UiS-H$hG&l-7?~716)z=0p2rOmLl;gWDdN7P4#cHpPRPR8UL(^ zWy(0oyw&bogVUTvY2rH-pYLHX`p&=t1(g@#y2fHMr7M#2f>U(d4tcabM{h$-E6f zQasPdy&u|1rN=qLM0L~x7=I%g{c|qFv--beahIE^+M>~9XrUeaOI{=#zkCPDUM{0a z{ohit>wc`X-jC%3PNa#pIXHOaKzQQZLKFFC?;!u|sdn@e{$0z*SG2!McHMvrjo3{_ z4h$YN(sRp36QRfsmR-3e7+&_l7o3+%wBqE%Be*$a8!Ot`QFb6b7WbKdWl@El6l?b< z&%+nOk$Y-okGBmY?!D{b%C$)JPy7UrFI5Bc&kgiNt2tSGelCo-?I28kat!tB%cG<2 zzNPo~7vS=x=b4RaAf4f9L)Ip41Za}~bu%^Wf=JrL$wD-n%U1iyYhE#9?Gn-E_c&>riIz8=lTt((Mb;fq>& z{@*(^O7oUv4m;QmAitFYVdWY}`tjXqeB+MI8D$bB!);wBhPT?G+0pnq` zd<3$zDZrojy)Uuv9L=b3Ch~VhurRqtprLDVz&R0Hx0Cn6#P=tgrUZiNu~ov~Nt)Ps zQaGzT(@l?l?N3sara^%{XJl}XliTKjV)yz=^zd9HemgveCFZ`NiwBG*#sfs4bwGyZ za~9>}5rd%e(+qTeQ4n6?HjRBOkE7?fhstVi0C+sUE<`G=#|u93nZswY(=I7u8sG@a z^L6P)kpa2%-$IDfo{k>$OU2vn6iepwom&<}>9svPnQSUD($FO)J2XMtIUU7F@5X1x ztz%NDAvChkg1oIh3NH^wqmqy^-k~rIw(qZ_Zv|B{MAZ}4MC}!7V{CCpQzQ%5=%OFZ zbcmcb*K&)R=l~r<@>g>_ILwqr*(+nQ%cdxH@V^%7Si(6Q&uZB@+g)Wvf4lJ#H7Af> z^MLlZslvnl8Gvk2y5RX?8y-9D68jd}L63dp`{a}PATN80I(Zp$f7(PSE*^_kb;sgN zjc7Kcl2NH8%gF&dJ6LVqDDs~rg>knp3p&|N9bYPw!Zm^LLHj)Km#@Nag&}b5aka1@ z>k#%oe_yf>D~EEgJDmkn-|Nu&LRIo~$1o^Zi;$l-?=d_P%}(cK(Y4$D;p>BIS%$J8 z{8jeFGNeW_pCkS%k;NbU;d`z^7EaV4>y(ToEYaJKyn?s)@-Ud5F zY@b-o_e{=AK9CuQz8D_F6GQj15rw;`wx<+nF|1?3(b!JIrKyxb_(C zMONQl1Yep|seh<7@#D;>{dGG~;JR8obF358%)U*xBvj!$1*5^yFhy`y4#SSCOC?&d z%0Cq{Ki3&9?$o9mxn?*(cLBI6O-5tCrsFHW&oe8hHmY5{oD^z$f`;EoQLDc|?wT3F zFI0`vt^1Q#KKwI(a8cQSjTXdO?I4&o#Uicyckxv-U07ZDg0}1tlZ;`qVvj|xsB?NK z+7@y|GM~GRu3?>#_gIm81pRY^{+RKdE%&cPvw|9N_yKvzd^X^I@_xKuMqDEn!uI)K*|b&c>VOWq zRwfN6Jd0qr7I&7dUJ{GV{(h5a$TpV^N%pc$;QBHOnW#L$W7^fhU~>b#-rs_R1TBEa zLmh>o`;MVLt$c|V5&HQu-X3&;g&X+OlY6bnBQJfJRAYpacBW(7KxL@#Yo?h7N<3`koMoNH|X|=T_m_yGDc6^9O>1#Yj@~bS=<`-^J^;sgdOQlOQBj zgbe;($H%5TV51+urn+aGNl+>V6O{xZc7G4rAXPz?rgzg#BYDrxv_ROY?Ldt$oW>s$ zq+qfk_xC!DAajz}z)v}IVF33+oPRk1p49I|kb47%zkk4VX6IAAnU17-x&XVXyM^xB zby#h@1AE=uNEL(ok;=7!&^l>J+AAy z2AFIsz|>hIMN$1Y@A0xW$hfDYtpy1<{=6^Ko)kip`Fsv`%!00a(P&9$DK088gax>c zKC9w;7+wOXp{1x_MjU2n$GPQMutqA2-H~`Ma%GKD#fwb zPj6`93EtIM^NQVci!EDxu>+qR>j#_#j#?v8@or3bH~J#)JJf!%7kLybf=JXL`a53=n;Hf%L$$Zm zjQ0wi8xsiLJU?TvU4`Rc4uv``x;;3mD}hAv)=U>Fe zQeP!AIpv@s@osd35#cHJ{{mFW??pziYGoWU$Vd+wxIRp z3N9aQ3b)48Qb9qHppSmAN+(kIu55}E*F{S1cgHslBMbX22RFmh^v@^*a(B8D$XE3W zI$kl@T|PykQ7D~tCZYsKkdl_7*IrnWk6}Zg|HK{W)~Fgx8k`_~`z^XcBMkEh4YPFY zqV?-lNU+{CXx7!HB};V43o(YA2gc~!?Q|SwkSE!b-^4nTjq4nteBvR|vk8c-%;NrS z;V}}M_9I7527_-*cBRql3$4hrm6PGm zb2n6S+8Y}!x>}wcSJv_G(l-`(?+20BFBfXKU%jYzE&FNQ zL9;5-@Z#&yEb>xUnN>p!c3tp8l5wjUYCzInt%q$nJ5cxj$9TYa4bC@ipt|qPN%vO| zm?Ux(Qe2LqB+Ej{{Z8DRkDvEmVl4*(XyLCZWY7%*n2}_N?k`Qpv6(6oUEs_LA^S%LikpJ<`sUxyRvxog3{ zWt0G1J6e5h61e8>L<{FoJj$k)6?I&vapz3Q!PopAU0flQ?Dob^qg|NSBhJs?Bt;%C z3xJ^!%LRo88hH7GE$rH6z8lZxY~kSPP|%e`>%GLJB34d(#PS|G8X1XuvvMV~_uy5| zUQ<92bwiqt%+w|?rL@5E#|$*nAQ(S9J(C$Ph^G_z@A#DK{;Eq!jOO^VNZL-GD3!DNOl z#`~jL^hkc+Y0@I!cprL?!E2h&|NS%hzh4^h-R4a^-VzkYc2&Ni23{?=M-73L=r+xV zD!h<)xQtq!Aq?!H%F)IiIAWDezM9v1s1?e@J;ppkyDOdQg!JH41`7)o1A1*;Uv$-w>1zKNiea9Kt_( z9c-cUQvRt?|27$!|Opor^NeHp`HMl3>w$p^4_%t5yO>lr%n=MoaP9l^-$Ck5?z zAN*g*3wFA`o37$_oLQ*>a8K2izRbHqWPFvy@8@@-$@4GbkCVT%E8kma5cjBTJ+~On z_+{JASjsh-;Nj358iz{iIR9tkVRq3oo@!3NitA*}p!Gv7E&d=+wtM(PCyo%@>`ie% zTNJb9tUM`81!6MI5jIOD(qA9-NrA5m*xl?EmfFYgUc6Mvyk+suM2fTMFDXjVWM?aq ze0mr}9NCUo%QGCl%^CLQmeVbR!|=wR4nYNu zL+a9Zu}!%?Jc)flNu)7(@q8^DNjoFVm>7z5OnAOf_XG9YWI|F+M!*nPCG=vo4;E%m zXVqntCh~s9(wIQlL(YlXjegXAtGz=Q1k3-ExK6p<0boPvMnZ8ZijhBCX$4tj}Qc>$aZ0`L3{DGv> z#s(8oGsYKug7zZE+5)_^u#KH>Zl(|UGoSNk{vEbZcvX0t_om;Wm)CdG&}k`nKz9^N z`Cw05z8}Li3i5D&J7?w;4J4!5=EAR2-$ZZK@^R0u-x4h%|4IYCv_%Q_^KMh)1LkDI zdIBpZmkR-FeDIMazLLA!+X-pdiT5M?_}N)@vL^&OsN%vnrIQUz)EOebd z8AU=M`{8!vWB(X0IjRZXqZ+7`{V}vT;i_cU-M;rS-sqCga{K(K`5P;8WP&05j5I=l z+UeN!oGQ5NZKj7op7?N|&${dvqJ_(3$dL{9&_C-jwK<_r_Q|=xz=vmr$J3YL=lze}TgvJ8k~kR0S`k4LOZn*4Vn43@q>PrdlxcR{?LY&drTb9$0MGk*TT!4m?(-QkLm zd^i{{Ui(NgR|ihyIV^oYus4~=8I_kvWaV$TbGRKHDM-Oi)?&$AU38b{o|ZX6?ah&* z^SrNft+5`|W~HIpjeD?m_C_{8Zxii&$i1DDbD+y@7jn2-if0@f4wKH*(ITozUheXR zwrz)mOA~Fe$DbH>g|o-4L6aPLCP3)RmsB>FGv(YJAvZu7-HD3FXLjsnJ2$_fQm+?~ z#hjgPZqZmasmq=GD653CB}({Bdo%vb{b^|7ZCcKG6vO3>p(H9pIJ|Qk9{=zX zy7Da5L_TN!DA*wD3rV<$XHWF^Kc$MF7LY}})3#yb6H!gcKlCv&n1z1prmNEw$*Gm= zVYKd9`hI*BK4@VK-8UZ#Nxp}0n+5M=4}C*VUsoYsoD5i%E1;y+N!Uy)h1DOvNc-HD zl36btK(YR$(4_2xAC7L2?6jV1riqxTKn!+STj z2in5(<2_{_lcx}UVg!COx1rqE&#>KuX%P9ooI;Eoxvu69w`Nrc?rocJ#jtYLdaa8l zdCC(53n#!j>Qw9FU=m*K1P=?1k^jMT>=jVJRxN3xz6w?(@2?TqC*4K6&Hm!E1A`!J z!Gf}0?g{Uma~R6@#Gz{IJD8p^0QpaKv{T23{AbU(UJFhO6U;)9Vn-%5n)89KE9Cbt zPivqz_-=EDXJqII$p5Z@TDAS~P}SLN9k*%(-u;8uoC}0Eqt1#>Wqil(ZwOq8dqA~v z#AMB7Me&YbsYre0Of2(smqbrcddL0SZ>PeSo_s6O^{Z4_D8a%_imK zQr}6t@v2|%+0Ip+RNG6Fl*RaRZp``8<5LXDr(bJ;<;EkFSAbU=bg-Ron|bFNXJBeO z!PDgnh4wMGk;dH$$$jmM=3#8bSs89_w)F3nW4K&H0jxrr=}A>hGDgl93P;HbaZ>qs zhQ?nuV}B)zp4xyN?jb@#<$~u#AN)8pKr&g!28V;<%rD)p2KP%T(+uFkDR+33V(#{Xyw^zd`7GVxsU2;_bEN1&UrO$ zAIA&t>a$SzitCabvA^tPeBZv1P2cWE<6{g-u9^zW)Ko@;%F}RTx|&2=FiVvqkGbEt zL8nf1f0s0QXDtFzTs3_%K#vTY?83RDX9V4W%kb%u5o}>c2VJ~q3K1^aK=YDR+Im%= zWIU9I;Bn(nhPo87Y6%8;)l;-s--z5N>%gh_YjMvrbF%r{60p=-iGD;C;X$S~?9tp7 zI_}&%q!jvCvd0cl{)>Cw21562fky8?g-0D908TM2w5igN%-}pCg@Gf5eL*Tj(bgK) z4%>;ed)u(Gxirj;Z=^Ho{c(2I9CjPGP*GbSZm+XCukW|IH zgO2YJnzmI;ZXQ+=Pxx{VS$IX_q?|KM*RX@;MH!J#a&{1L?|0dl7IpIUs}`L6?Tq|9 z!*PN6GL|xZADue957%Y$T>=*ho1KHPl+k16cbnhe6=jG*)jY8JF^uLI<&oT`-|%~V zE83dEJ6qS@Vn*Eiy8GR5qV!V)@)He3^tuj_Qa1pVpfofL@56`QZDTW)w$MutEXcs~ z$KhMVF4QI}#qaO&Omt`+y}ww4L=^hM{n?3v!i%Z+#N;@Z?bSuiGBt=^E`kD|MvD3S z(c30x__13V-SmvdWZ7P3#&aUEjSI;9V*+^0Z!CLl=uR%y+=H}GB^=b%gwsDc!0WrW z=sEW)yzc05n0+!s7&L4f*4lH8CAM`?Lq~HGHh&q&=$)c+3H-f@d(S?(*`UOm(y3h&kBwiDNPSX?7w}5|W*xC&e4I!^wjC$-1H}Zh78@TB|SMG532}SX~Q^J*P)BgWW*eKhfR_sS>9IQ;C-QF(?f?$7Hcx z;(c`K94&|4?gPaQuEnT&{1qH4WdW*lYH4zUEZKk5A3E-D6Ue=hc!zn6WRF!}t3aS` z8aSjR(o4EAcna@%-y`C_=n5;cjO&&)n|sRkcvz8+&nBF^wF52ad4?0!+@NFTEs7V( z63c1+Ak}t9kUqZ&H+{Utzt>%KRD?Xy-{S)1{_6DYWHE7_@E7LSJwzws(($C5SJ?I4 zZS?8xDdfgf6L`XV8}uUjaBNl(bh^$jtJrBl6bh2T{AwI3Zn%vP{~Q7ub^KPCFpLb2 zT?fN@P706Ch9GOsV*UT!bt~U9LncoJMMr+Onmv-FJ+S~|0~PclHvnIKuz*d9E2ker zeq#mxdA{9pTJ!*a!&|ByU`YObYUDJ*;ril8@wDZN_+ZFPygW3P`AzGj#xsnF_X#^l zjZUQL^9{(BC?goUb`0uU6o`|8-I-U-NqV5J7pL%h&5`QwLiOJSEZy-@GH=WJX^`$x zUpQHEw)C&AA<6RahLzXjQRs~V-2Yt{8#1+pYE+sN!%`PGc7CC7{_Aa&6#anSANiK1 z9!tX0s&}!$4O6M6_c7cxToII)HPfZh1Ie{}?y&3KH_;y6g=(cG1wU~m`u?;Y`%UIu z0H%%9^Sn9nN_PRJ8|A`=AwGC-O)!gG(ZRh#8CY}JUM4fCr%Zlq3|@7&k8RQIq>T$? z2_~Fa86K>NoFKi_4cS+9yD`)y_F zB`oW6mE9ZSM{AsilAbjx@O_FR3JXcY>yN3!F!yE}A|?9mzvd}K{gWN&eM+VJ)Ah;YYl?8Lek@w5Dn(u^hk(o6Q`DdT-5k@vRi;6ky95SFS!T#ru$i~OBvbZ{HCNS1+IyGB~R)X`zwYd7)B zD{oQq*C716*@M}yZKtZ|dhy1l0Jx*IM5yu7z%IEF>{V?yUAaq>%;LWB<{zi2_?(#R zL&{=5+xzJ6ghtRqjIf0neN=(aN&<-G+PyRKlvBKFhz zBfZ$DIsj^g0^$1QU_4Og3A;M&Ew$&Y(V}_2a5Z`yJ-qe;=@{1wrcTXBIWYx?4!X_0 zSGH44{(s{4fq&PAnu-?sat33d0W7gdL$c%cmzjDb+RF|0ze=H#E^$6g7VlQuVT0C`9mRJ(NY-&AK>b zE6T!lbtjqSf;?4*}$`qpG~(4+xZ-ZU9l{L zGkNyxQy>!@rc3r-dkfy*y3YwX;9D535`(wrWU`r@wRJgS3K{4mK)c+#vi~FLJRE9# z|2N(q(oza-rF>d;q&m-i-z_O4BfIQKo9vN>%1CGsk&F-}D@o^m-YKOaqM@QeLs{8Q z)bIYD-#>7W)BAZp*ZaC&SCg>~Nj+!^*Hd>R@5e7O7P^b|+r-IoWJytyf?Lf`Am2ME2krA%rKweQ5b&cGNN6+x)RjkYC>h&VLsU!&0w`K|s&-jMh zm@o0)!g6ZuGQsh#LPU}I;~`kWYZfm46~oWn)J=a4HzIfH1n_-wKuMrRz3RQSf%Cw0?Gmc6q2yA&#apD8rmZA|j( zf*_&n5IR5W7Ct`u13&La8(q!b4L8r52|L>tb2T0%$f)$G_@5zHR6yoH5g#M-uxxz6*Qj-qdFdO z8uvHgZylS(9VfWJ7joBp0HNAhm_!|E4W!mVp8$bjuZ zD2zFb-t<@FjYmg-TV^9oHXTkrvi{$n5|*5#?m6VX?;({j_&}#G%E5acW4G_DrheRH9s;{wT%d_6`oyx;7Y^U~ zQt-57IC-+f1@>NZK?bAqaqs*l@eZuoJ%O}to(>O=Y~>)N7d5%o({tMIX^^4_`}qgK zj~;vKaQPBeJ|znadfMpWGCdNs!xusp8go*Nu~s_E0a9j%qY}+`ICGRdc%Jbk{HQdEzq1gu()HyNIS^>j!cCVcYlg)m&xbU11L`dtXrd%Pg~_ z=K(iclu@rmEN-<=;A;5U+_f?1D^M9LgvZo_3dox|X znz64%rm#@|4EOl)E_~Vb0WW3IP2aLyRl2Jy_!b|d&)D7B%i04}gtqAZinBQ8bteC8 z&s+K*_z=!^4y0!^3*KyHv-(w-Sc@2SU7kqzgn-sa#tfat?rYX&pm(u``_Xd@Us=__ z&pzBqf4|ct&ih=U`MCmZ9;!wP8!Vw(j-VaU=kem)EM8D3q!#8YiMQiiaQD5!?fB-4 zH;!!OpH=kG-3oGK$Cf|{?V3Uh=4X=-X_cbzb!{l&br$~9G{BFxYNtop=ilG!3Tr$M zJ1j9!CA7c->>tOV;~OsE*SBu)7r7KVO?xGIG+{27J{pQXFdx+XDOMoyrH(eulO>BL z1i;_G9o)2ernq)bjCf~0;w(el7*p%izC(0Kz9!k|7J3Pg7EHnPR?pf1VROfs~!GhfEYH(D*lnjMw}R7Ii*G z$x}txj)uUKVe^I8(^+>w)=6-m9*fS{l;Am63_*vodwQZS*)(ATTyeUI@bG1(<)4a!|pP`=|X zToJsHZyTAzINl;W@G1mO82;kk9E`)ox4w&Sa26wE$&ZG`;I5Ne=&EZ>RlT-#tV%JqFN)`zb=XW!2wCwQeLZnRg=X5%^bq@I54b&{my!E1uRn#YaZz}VvIP8(1DrfXmN@!_Y2CEt+jz2nggrc% zae~fUrbE=c)ZqK%@hHEpAA8Q-4Eb6YY3&XrV)1e|L}$M&kT=pN#c$@rfdNl6g3HI# zT;K4Cx7z8Sh2zP!U^_5L-NHrNen9uOHPHm+9(vqggaf{YFwMk)y7^tg?|3=!tiH2E zmyBxk1r^oNTt<-!ad728-#r|)?|+MZ_9}ouMH8LgGLD3NoeoxeUvM5Qt2^cLO8z>_ zv)4F_@Q+EG!TSDkuD4_uZdev6-m5Dl)QRPj0BApbkwP-#E6z|a>a4FoHcI=k+2m|~ zGt2D?SjKHc&TOzrlBK7osgp6KI`HS53yLe>gQKSg@-GV#=o|K3J(s*09?0M3*3%&D zomI!XFY2YiF;c{EtQX8Vtw%Kiu8?6F{SZ{&jINGL#^;;M`E4INX#FJvlIe&cb-%7) z;fxVv>o#L}ACQVB+8xH{A4Kv2wcF|A_ZB2!awe=H(Ww4n0iHNwtaz_hJ)%mY7=LMo zc|13B_jH`G>JZ=b{5?IFuR=z2u-s^4Eq%oH>TeCRAyrQW)lH1WS7#j;-{4-gcoEE) z6|G&bg>q9Dko>(*;ccf9ewy2imsB`I%wM4L%s2Jw@mMI`a)#?zvkQOvSHOSJ?WW6i zjv@H54>%2+r`L1TNT|;^2)?C#j0Z)jdA*^BMXi=N4|TvWDW6IvVF7LzH#}fPBR^ zZl#GSw!R(9&v?&zSbQYOU>Ancv$6CV>#mag;s!U~f8m-xMq$;M^SlG=-1)U?9MMpA zfaTmSMaOTbiJDe{g(Q#2r5uhBHQ#i*<}bTS?NN zjp5uRMf&BX4pEvqAI=^&MTLJ);R3w^{s?0sUUwfyhW=okN>BC+%35s5oRgN&Ctrqo zc8Ty@^DSU_WxjCHH4D;joC^NiW0BsTVr-LT1a72(jxg0B32_@B=JvCw$J& z3C8P`()Sa_I=X4^E|Qay!F3fLIJEpA|7J-y{c_uoRJu5VXW%h9>x2%myKM$v6|Kx-xo1Q;sVQy`JA2uI)O{LROJ$+zVRhBdeB49tvHV_xu4`W2tDZ7$!GBy zWfds7(@L{nsSuZ8n_#E0G&iXu2Y-4dEuO=FYF^;@XFd<49I z9Y$N8KgFy5je_cbujuw`OzWQK3k5FD9KL!MU8~^5d5s-S_wYUD&Gw28qu@T8tg{>m z+z3^~?>vc>Gc?6>xLaO^6pms!bc-56_h|{HMIdnUtDswd77;%~nWFDK3(=&REAXGt z1N_Vp-E>}yHQ^ZhedbN3BVA%X0V@@-lC(fl4gENMPZ*SVU!;b|B#0B6=ial53vz$l z#|QXUz9FfdUYTM|Ry?tT-qsM#!0ZDWY<)v#TlUb6S4H@$7wb}C`o?M1OE|1r9;Bd+ z9%Q-E^Pd+%*MZ^OZ`P4<>l_?9u2^qQS2IdQ`airVbZSCotoGJa{LZYSN5uTNICAUJqg zN3dRQ1likS4FB1rqWcdMuxx59PeQ|~j)^4+uFM33z0t@hvH+)hj}`CCIld|+$IB0L zHIJ~4yy;lI{t*9XNDn0;L&>;h0&w3~LsRp0$*K^hS8ta>QEU#stUk^+)^*b3m0lz- ze*Llh-^H@67k* zO~}Lf-e8)RPLD~e5vM_G@EO!aKNQa5A4{(Brp|Baz{oX3*UJm8o3#oI#topP<{f;^ z&R#krTb_)55yoz9muMgB(YvzI92CdD;7;cs!@{%8{Ii#xw0+cnB>Ju|$niRqAE`_3 zePz0L?mX1!cmsRe7xKydm9)BJJ-+yx^%U%9n%He=Vw@HT`fiixgT8AdT%=s&fAKXN zgIT!YmLznjv{So5RdzR-0RP%!(ae!KSkr;>&sJp6Uh`Xcmhm{S@~opLS>NTJjRB13 zAI5#qGQ~5##)-8HoFYwx(_CRUjj`k>eQ4v1Bp0WG6BHYA6aYXSW@u zEzfk(A-SIfF#S|Bjfk}*MM3tk@RtU%dlHFPvdqGUqpxU3nh3Wq-3scVR|FYqA6d^P z^D7RPP}4c8B=F~Acy8CmKLK6Ph4VNJ$OwxF_bpI)?o9qs}aSXeeO0yf23q&NA6{tnuBdXdW zsOtNQ^zYrr8b)vV+=zBssbfjx{@B3;s~~RAuU>Rgs$D#j-<)}hH;rVyKW}wuLf%Cj z_EZ6GvV5PryDB;PWij0B(&QE`VxCwn2*J>_^UV;LY=J^if8>M$L{5d_hI*8 zMr74hSLodMSNNV+C6*iXVNt&mYRihoF?09x>32`k%YH$4f=462p|F=4+bNUf)BNG2 zlm&HCVZFUpOQBoE9>si2!V`v7^S{(OY2tqdg!gj>%VoNP2+$_QUS=@SIu(VEO2Bg> z5Almt!|87+OY&s$HP9@JMmDb>;LBm=5W2daPF7YXri%V>X82)l$E@jik4ZeQJfVj| zoDxZXiD2}x=d^F7F4;DmfW#&#H1jLtNJ}M)cVH`z8HBB`U^%{8sOs-YGUrx9b@UMY zudp8HzjK1BsX{8Tp6#n&EWozn45##ZCpHbI{0Q4_`f>bdBJa2o(3o>n?}sWeDV+$a zc6z9=FbzvtW%JK%-_kF4e8`;li{YT*Yr(1Le`x#0UE+QC{w;ZO#bi5lbzGuRj#YS` zxg}^Pz2Lr{J%$D4Z+Nvoo%Ft+3W-?Z3@_(P)8x^5r0kp{Z1G%x7NFZ0Z+pz&cX~<7 zv({tQ1TWr)PqJ>xIiCaJn%P7u>b!=f9!kODvNr0r*o-*7_l2M2ti$F1vF;~Ng4VyW zD1Ox)ygRRyZ}QKi`6pZ$(+|U};UX?7Di_ZkG9KK!YUy)nDPqnCfbPmI+@yjr_^sq2 z-fQ4Jy)h_FetdO2C8~v(bKKPxUtMceB%opP$4TymWt=_VxJJCg)+r@vP|?yvd@46r$vqQ zPqjIjZ{Ps2=ZB%i%VMzYrAYq9#TL3RMuZDPw!?}WR|Exly?EnYXGj`bLh*i<0i3J{ zU+GiK>;PNO^)hZ~E;bNC>VC0#K-5cxH=uzv0+a!;G(Qq!YQ$*NpzSo4FguWzIB zYz{xWy8y~NmT;Xp#mK$nm3SXkU6qOdE6?E9-d{l5glV{Ix|&#*_~$>A97)&&dajb( zi0~Y|70JQ>*ghe(4cLj(0_5LB^VyF5_0|H|{H>TfDDuS<{n;Ig?Zbb4a`A_V>wLml zd3vfd5+_wj!B)l{s`x8O=G_hei?(6Hjfsq#^!_N^*?k19C}mkB)@hQqtVH%O^+gpoEi43k)%l6_WLze~^YnJY z*O}hj%ss>Kf5HR&#ofJBZ%~=|=LLb=+w)8_slp8=`mnaIp3^G~#}@Z*^B2x^(Os-_ z#4W`Orj3@PK}o9Q_ew)J^2G_I#>e42ofw|XNTaT$BD`qYPQWAYaB91S|(_7kh-*d|u%9od3P3lS=0p66InyD3R3{U~6r%K{OU_ z3s0eq!N;)0k9gj1*?ubf*MdyAkp+eW(P;P12e={I0t#l-)3kgglA`MmQNIszL+z&H zX^BU93%?$^^!^a?{te6cr#z#vW#(i|q8FGatDv8sV{q?~lYH|)C;egMO1`u?!o{&q zh4EH(c%O?in41*RoI5+Q_Zr}rGT+hl7(-&Ub0zz|OQYf1BT3OVBxV9zb)@0g`!{)$ zthaR0OBdo);0PXfiUpTq{-J;Adw9#6z4X<68PeCc1q`Ay=)dE~@KohCe$SLHigv4z z&#deD<6&u9c2bRa*x7(#iX%E&myd_XKjVF7G}9tY7t)sK2%kKXI9uoSSg^cPJcs2E zNRpBvL2#vgJk?)$4KKYV4GC+QXCQeDQBmIjKcAd&@DETUnKCvo@njs*kSxGjub=aE zg*Rwnl_}}CWdbL-8gBK4n^@`Yc&M?drDMKHklcR84SN*IolPBswH*(O_u({iNpdEK znY%v6(t~pt)A&DyqDNQK&`PEmdMae{FYb3yp7AHuLs*yn)z`wbcGjKIuL-;L=ONu~ zW!Ur(>*u}ofZn_zLBg5tVcjg`nya?p>x-)S_d|QA(mn~Y;<5`I`l&!=3VUyYXEW2m(t0@{H4QZSJo{bV z!?HGKhoRSx4&qbNtSfnY2lYH6Vl2Cz;Q#lE;AvzhUhm)t6SaXpsHnpJ8U`@UEQ4FW z#{+M5KgvtK?53C6%}L4fMR3XZH1%WN8=ci0+?gss#TO6Zt8H=opz|ZDnJdD^#HCx)@S|DkVvQno ztP(MOunCGhB)Bj7Ie7I7dDv_F1lcWUz#b{uaLcNR{(Z*uXO~3~VOYY24f^6js|emV zp^Iv>Y})FpIlRA#0xge^#C@lw#Tvz|r|dhE7XV{Q)rGxBnJzT@7yPnW6vVRd8OjrcyfvmZ+=_LUz{6G&(EAj+<#4ht?x#oqD?8d zW2ZI@q_xujo=Fg+f&e%u^;B@aDPUhQk95($BZ?&_V zmbRG_=MoN*i{okEGfgs?G5ww`{tx*vy*D&^CxFXEx@_MVV&CTr5;es{y<)zRFHO{n@vOEcaiFIDlq-E6jO$7Rcw^SP>Z;X`SB={R?YF$S8TP|4 z>N~*8+4NGST9$!&;}1FE=cwj_D*WZ1K5SKN;D+RcgpkUdZ9?{1%z;UHMgrbIlc?L7f?akplGIAZ<`WWmw*%4C4_T57&+D+3 z96*Kr53tc8OR)Z4Pu~fL5DocFFk$FHZf%P#{&W4PSc`xh#zszH?A()8v{6f!=;k@W z-KA0}tSbilME(D~%|GozOh!4uz?CXtY`-Q67?K22!%L8gavfd}?F>V-3t4t)C!UrI zywk#N+G@nS_p&}<>vM*_V0(_onnkd$dpa^=v)5)~F2Cd6TRMBL3%OqH2=k^F3rsHk zL$*Kn@rR~-pvn0%tXp;)%gJWYnV!e+&VTLvJiRW;iH4Au-<`l|y9E6euSSmgP6H=! zM7%WXh|y`_(^wY(Iqyuqs=2^`Rub33ufy7nU1FxC&ru2TG$aU;8^_TVzpml|p$ur7 zwb3oT#^fdI`RZMN+Trdpb@I^P7Pe#@M9F6WUzpg;SF7Bio|l}7^l%sW2{FG5F}VBm91c9-1K`O{~v*fcvmR^jlyNQGcvh^zB<3 z8nHYIch+AKYY}fU%n4B^5Zw1#_^LsRjI`EjK?n&-T(_C_3a#}Y=}e8O^a~J5L3|oSVt%L z3@3NyZG@=OGu-0f5cFI#OMILA_JH+JyD}ZDp^kQX8jw8`r@$!%MYQ|nLEJa`5I>}} zgGSvGVJ33J__bFBL3i45Z5xJAYatEjs=_Ou8N!CJ3@%jP1It`U;B|AmX%h1e)oUz; zUZ2y<^J7k$H3-~2AV9eBC_ZA5z=tk;Ld~;9*z@;p7<1|mw{LPR{*(QWztGV|8{R4s z^TthZ?OA$Z(2-HZ%P#~1#z&*TFZ9{~mb`7C^FNIyBfD5u!rp<)9&r{Oz5Yb(qv*eH!ty?LuuJ9*y>Zc) zjFmKj&Bba+?{6|TT`>ZrSG3aRq(S^qIuN$qtrRS|(S)b9*g<*eWAsGn54MgV5HV0f z4+V}Uk`vcMm&R>wt@;YQR^kY++T2Y~v)dxEB+yzKPc^MH$@6ecsC_gRwVx5;*3RAF zfAb=}{!@Z9hq!_Kw~~Ueb2rKU*&^8Vy%$}ccpoqM-NSD>*G_BL>{XsXfd3P~rS9rQ zIT9blv-k0Z3;5huCGqSXHG4RbnYIxIAM0>I)R^&MHbAgKBHHcOj?*`)!CI!V?_zs` znF)al=qdMPNC=iZ5hC7u_q2$x*~z_7W9GyCmL7&bm&JHQhFeCF0 z7w8#?Q3FjIw|*u`b&IKaO}J>EI;X>tD-fjP0bjL6sQkkAdIE zkE25yQ}92}Q+#~a0s2hCl6)%7hKRTW=;Q1Mc+*X5@O)BFvqKb#O@%+`>Be#Uui0XK zqvO2Mq8^%kPM+jeVek&Fq!$uKlAG65XSZrBX4{rQlZ{n~+-)D?^8tx~2E$;fhrk#TXffNcl6Sak`hGWWH7Yh|Megr!@eFJ{L6J+ zbj&41(q`ujzsm=N&UVairtb=Sv^>#*ib8Ce-^kBodHF_f7cv1D+qpD}3yoTbucW^h z=QWyd58xTggJAq_YdYc1ReZEt7NqssXuR!cvT_T17XLlv@aVJ(`K>z*w9I4CwzLn} zc##5lIyciF{bnTP73<#BdC6E?H?gP1B=N3$F8LpxJ~t4i?+W6qqQ>Bk-gv&Q;D7uj zY2sWx8)W7jqMeb9Yr0&iX!g{zD0giXuKsY1FZ$a>x8)fVKFc0D&1!}74{4DK-I4H4 zY96B9C3xr-HyHWrK3)IwFV4&l0BrM+`!RkCwri>pYYsa<3}ACJHxSq<(D(a_NX-(Z zqB^7JDB#Q~=KXujdl+@lb8LSYR_Fw0WEcxnN1t?68A96i8|eNe5v~}$4~)|n3L9Cj zCpPRnjJzI)ycLV^+QVir#GsxA>uQpNg&SdB)@e?lszp)@Fqj(EQFE4mm(6to{_8N5 zm~;?7|9Y6uJ>Eeps@Y9>);<_kbXBl=d^;|i;|PfgLR$Q`3R`a-4RKi+T;(DUJk|F& zf6M+o9qMUGa<_TI;U{Nk63ZYjxyiE9RDf2lO~j!elKILv)%0a8^V-ed2Xzxf+{z)b zczo_4|7@U(9vGoWx{LflWSCx<#k}9LT3cZK_Gsi8b`vMQ`YY}m>e;J9X7e*3>!%C1 z)wUQ-8Qm_Px0ATrSa$Y3{`9)F)H}Y8{9CuQXu=%@e5UjamiN+tnPIKevs{7H+xbJ< z-@gLQ@NB#}SCMsYK0&cb_4wbGQQ~=PGHw*9R&j-83vO{I?)%~?(b4=Y=6SHcW<&n6 z*^A^4Q-$vlc$J4Nd|BK@R~fRNl(qnPaz|D8_=E+?F-wH6dhzHz>rs`eHiC}CSM=gC zBeK@U7fLVMaS~6{kbgmic)t~$H6}4f?coLAOih60h(is*BU=fLIh>5=2}XjPZYxzE z{EI6g09OAh7yNnGgcr9uK%z@2+HvnEj=fG`*M?&Hu#)+%H!{w{zFcl-&2sE?C|*2! z16+(qaFZ>pm5QOdts3ORIxVm~J{H-fi?EH}K5+VXk$UaaB>A3x&~NjuK&CvKxQB`0 zTE%;Gq%#k@_b)BwGI12wZ(~d%TQ-9OEbF^i#X#+IaS*-hB?;sDyPE+2dNjROzXk6GlTK(yrpAl4+73uv>&v6UzI z;LkmD!Zlg4Ul)UM;S>7kaSWa#eU?AEv5Qto&m}9`7lQVOdZETlO)~9Y3Y?EGLH+O& zE3b2dS5F_(I*=ze$RDc1pK;%A?7%hYkHwlpM$8aW%dvdWsaSetp(^QnJ{{(BdT75x z8V=B9&nDlubbn(%@|(GzH(l9FAAA|aYww0a`1Uj!IN}&yH@{0fdu75D$$$~-#CbFz z?C#YeI(OZ{`|Nxqol%I_Y&K}YlYlK_#)JcoC7OV|(N2W0)_-7U4cz?N1SG)A%3dS%IIu>v%YBuBfM_-C( zY?ZqN={V>ChI19^>8K*|xnpP%=l2{X+n&Nx$CZh7U2Ap&N(*8AYk_+OS3UKK?n+~j zSIb7jjx#^x`EZcyTPU2~WI+mkXTX>*ap<^T5gxbaKL~tNPoaDmsgw5u{e7vN;P!a* zx_=+N;gmxMWQUXfTmq}#y`;7*FLoZeLW-sa@|%4S+vmsgj-DMflf9!g3B%cY(>1~U zRjs)Aj3Y=@J)~LnRoF+%1THsaaA6PJaqY1aVm;x(PIEHyfj3;5d79d?J^Y!ME1Z(# zP|dfKcuidz@36U!MzVYNYY2y~vm);J?HHVxBLV;8v|mzGAT8qqVEX8Dg<(z>B>g}v zjF(`6*v~mQvvq*iXU|Zp(W8jAj~m<$apvwFd4yEwy`$S__0TH^a&WoPU0$onht@r> zBVF;!i$G5iJ1;qdWt=qO>6BI~n=DUUeEs2palc^U;%uBP8UnFnpP-?m>v8%^9T-~H zNSnWoBrZm7u#nv1MksE;R$(#xpnErcu+oOKPqK%ePlu@d(+GUTLk>dsbJCIK}>%OWj&hsaOO{ z=46j9H;eFyvT!&Ue2KnpyH37t7Qy7WE~LFV5367QEY2xEdB?a?F|H7JHIQrQ>p@ka zU&Xh!Z+#-H@FE<%><}Fc&%l~l%CL7@D=j-OOR|SDmR+?H_c>9Ytb4c)9^F5RPUp7a zoq-zQcc+Pp^3BPzg|6`Q)>E#dKNwHXW^8RXV~3fs%*dy3nB3>XeK?`c^u~jH!Yp

    9Au?f=q?MqdQ);p6xS1ewDx_O#=jJ3fdlf9v-hfhe z7UCH{TKGPe@i#xb7Ng@I#M(mRSrPtpn=vH>mh`{gD_G~dJeX#;(yGx0jE}T|@tIQ` z=4Gjn$UXKDcYyh?tUlnx6H4OQE43#FPrEz?W_s4rBujQXaAA7BYyj8t%LF&+9}~}8 z+x}t1 zxJO5aityODAQ;y7fQ!7i882K=$Ddr#L%SYIkt?C|pjdY(9doLP4Em`QnZR@8v-}iJ zODpG5{FvGA>B6I|BTrBG!|8xO3~HE-Q*?*IP{SwabW0u1!g}J_`_@T^C>YOz&i>n67V|V_ zl*aOtK6O#|h$+O4?U}z;AEL_-MBuGD?D@{#(JpQk;T=bUU~Q&~(DIfA`Kp)#GcLrV zP3;wU-v|@%?`8c>>{;3Kz!$QPPUHHr(@^sKXY}jL5A=P2Az60L0n%F==%P`kB&Ns; z$`>$iNnsL}8)UhIoEDm#Ai{2!gJABpCxV6{O?b&o1aGuUQR3h?oU)2BlOGq+x>tH+ z-B4dRa6Oxwd3-r8y>pEB)MJ_1P$TlIMj)QO>Log4?zhoU*ERuN%M;=KMf>4c`XxH& zpDantUIerDKP@Pf$sz&sL?Gwcfvzg%;g2`V}sk0Ru9n*w~ zmQ6H`X&_A%Zeq`aVqP$QP`!(vq0Y1s^L}iV7Xdn{E4kaV)NyCoA+hGr$=LEsU4vmy z_i6e?y9(bnHH9VSuejf);rMOGLw?`CE^0euIEmlj0+9y2LbKi}59rT);h8Ly#<`PU5~;g4UEoBy~9*#}{1XzegTr-7A(va_wyx zyCeoJ)?mI7!35|R)X^t@WXX#)0g#RkaB*{Ov8!t`@7v67ZQjzPs{zBr;>YyMK274^ z>kO4k|8S1;VsP#5^Zdb)U3BrvspJRK@iycLg&$sPkcB#_VlASXyukY-+(BFWA)R_q zmfU*a50mayaq1g);OJ%L{I8O38p*hDeWSghvLKO~7Zefc2Faplx^;+#q+v~|hkT{k zJ33@mKN@NkDW1uReS_F#U@PqXn?@5G5*Tl=m*+Cr@1_y!i&tgO{ZF5T)7kf7o%dQ; zwtfQ&LWQ_Kpd;U8lh7V&tH<6oyhA{DoF$zXdj-o& zD+26lrQ-|q$Yr06kT4_J!Dx>Pk=ZJM`iNLGq`H^=|0;v`xMte3eFC{W%N`_dwsMWX zv)RnCfdd+~w0waGKR6Kr&c_0{g)dETp3iaq-LoEQy<44>9rg!#kJGgOPb7Y^;U>R$ zNH_g9Xh@a{5xhe+!p5I!tUr}%q-NR&rAu88ovcOkIAuYmJ$+RS>` z8^p8Pg?Zby{a6TdN0=elEEtwG zl5{Bz67pe2T_?T;42p_U>>TcXC|tVkE|=_p7lwt z>$MfSaxR=@fUeUU)0K%tsXa`zDW`u*%*o9V576JKfvz!rb@ry?y!O-%npGsiHSZ!I zApM%a%uI@Wo3smdu;=xuJ+JX=rZaebd_WJdJ^9TdGv;@?z^Nv>04Gv--IolVb3(9a8YWzKo0M zvgGjs)@4?9rqFKzyDz&Pf?r{Y=%H~AzLOvc<1$<6!=C@?X0GskJjc2IeT0ss_fQ%4 zUdFq~#oyB(@`j_=(3}gW@#2YE;`toEPL|ZNd-t3dzXa`dH*olTW$}ETJ*5ukZqo-} z*4G^QNt4_j<_bsau5*2>eX-L1gZxOnZmP6*0@0dp55WPkG=W6mzklV$T7(np0=p~> zfx;dY;RfDA?J-rcxJy2D5tite~Sn&mkI@Qt8#(*qegt#iGaN$GR<)rj52yw@Ll^VSusuoujE*wujd|a-S?d@QEjL8EsR&p z`X=t{265P}2c1p&EoM!ORO!bPhekrq0HSU!=NS`H6&hq(slo+WqVBc?ZciM_xi^d? z7tgJM^2dkJ)v#79l-7dsfkyh6Wh*3NJRk;FbH00nF>kR?JfC|;_2b)>k)ZNpB^N27 zj@^Zad7X8=^wvpva%fg4{QGyB^@&vCF%QgO-_loHtx`B%|5(Udvb_1V*P7(d?iu3w zEE}v!78+ZD^e1Q3DRl|Q=iKD?W*1Tira50Ph=e`b_qfgAk0ZJ|#QN|}XIb)w1cHl( zF)enuL26zo7pZ?{&nep^d^hwBfAL=@eaZa)DaGvbBQ*ps)(#_UpN|KZ(j+9Kbs6{l z$mPo-66unOmgHa09VkqRLBfgvqt=gRSwx9-yTA`YhxZvU}?&FW7s25i-{+#J#Q^ymJh@%M_0zZOlWJGa;Iz zC9Dhk*=I3N_}r*4F;a!C%Ki3+jyMxeBX z>Bbv+@q{}n@MK6cRfrwOx&;|CJm?K)_Vos4{vP;j^O6pa6k+%Gn*o~ya^r5A;Fxsw zp5EU>4OoxTgwg;Ae4I*c3L^1e!&_p1+FD{nPDVI__p=&dh>|)PP}2qVVeZKL9*=uE zXM*(lyR?aAJk4M;_=Fd5+unxaw)|J(S$&jgET5RCUFt@oI9jm#4W8s!$zFK zDl*l4CCl&UOceE;{XK_7!OmHWgfBi=kkRWhVb6_& z===!4$F;5C%&K}i_apPG-}i$^l@zX`$qH2t?x%&LZqO-*RS2UvLA6&UYrWSchlUDZ zQ=~jv@-q$_geLNfy*p^BVn2Rw76qM#S%SH(k|d&gH>`~*L4KyMa9}2ZtiyTq@4qVi z(BwZbxpIN48SRdh-=*+N72ea|uS|$$k2lC=CsV;=rfDe6fq#tMRP!JMuN#rW&nbOJ zqa_&Q!Z-?I&Hi#vdJf?H<*W}bwTo_yks&iqF-`B`=|a1C7Ub^r!!YMsB9gw7jklkd zg0-t#>5=n``l6W5ADT@_lJ)<|L zR&HE~KAAECLCS?Xn$$Rw>^(FFEbc3y>&i(Of7XTg9WC?&yD_P#v#dd2xj?YF5tlx9 zgm#Nk)E@X5+od|ew(FEJB1RFZo4)Y0EsL8oxD3B3Oynh$-&2chL(=h-z%kVrik_$w z+t<1oTqDmLyvjErh90$_hTt&m^nuL~!+MD^d)+hmCT6iaD0m zzZjd>bq>Vs3*uU5_n_Chf5qCx1;6u{=Bh#5!xlQ@r3z6w>IZfzTHKw@s-%i#YU;xy z&_VN79C%b4Y=5yn*$>R4IDHPRJ6_FMYzfAV%lGro1>LmXzaOhDkAmH6R&n2ltK(UY zNBI1#UaI<4o-EJb3^#Y4p{{mSxH)Ppls|aI&7K&JgYQvZf%!cO1KDS8T@MPE`oq7(D9-fbG@R1#|Fbvaiv-id8Dn$9BbqmPIMFY1 zgT>tKUd#B;o~*R5%xAsnq9^W4kcEc{ zm{xoij%B{4V+9*QcW?u`%y_mjth@7nv-eD*6>;!!0OPBX+ylckINZFC|F))wI*b$H zI}iqEpIg#TWtrH?LcNoEnW%qO5#BI&HjJ~+ zqc0Dz-(~Hsp!dCi8>|S$McGZf+nFA^FhPY>ZDw5h;E_~fj4BzrWHH!uj6xICPGMN~ zoX<<|praEF$fj;bkj)Ad+<&f3;?9o&6qAV_EA-opj-0X>yzKf{I_H7JgwpP0Nkr!R>1zigwS&4fmuWz^s*q zW&cNRYi)oXE0%IQX%Pw@{#mRozm0r=AML7Oe62tl^CcC>OdJ7@*O{+kD(m424S>eD z?*ftGvHmHRp)If{;tEyp>R%wRR^ZPA#m zN(@pK!`^#l+&n=V+RnHp|MLthvfN^%4}#(QU()D(>>f1U9fUWZl0z}g10V)8Kcf|n-rI0zg@}v zaqstx*Jn;vHF|=m_9!)Xu_WGKneW2Y8PPXPPaYo)A1_>{5&NZx#+Jp9I{2iZTAOt= zJ1=JWP=qep+`~1~|A^=FZ0378*5V1D3WB(;zuu#*Xi)4QzSJSYMU$dobrPmWzsWjg zCPo&G)V9W%KhkkqhC0|WZnNB9GgoJx zy04|4FtxCnJ2@&CJN=0e>&)@4{aDrb0Qi1g#c7wT;Sowl`AT+oOM5R*76xsDnXk^! z3ygEVz|aB|l^VH=-}m8GzKFlW7$*Cj#*z!ozF;s(mNvGk5>vH_fPcCmh3hx*w{1my z-1Z7;@sqJHy(krId$ZSoOBFo+FXqzw* zJMU=c$24}*2EDQ5Pnj*J>pHLoukWUTM{e1`>@YC z7JYbh56{0p84gz0Qim)l@>(YleB&dz1^hI8e{m`wKem@fO&P#hY=53Q45*|x^MtF( z6|F43fa-_E;BcS+Bk4N)vF!dZQf5dhD}7nv;&<*m{`P)pqkyxMvJT)uyVcI-KYkN*71f0XK= zjyjTL>WsPI`udA-dpGNtV%W85>2~zvX)zAY?&1ZRtgkhgZT;k0!70l?&idj;eBwN_4@ROIX=N5#m~#=)U2~q$F$=oT(4D@*v9O1nUwvFNr|&KX>6| zNmbBPeM3iVW4$^tR#1Poj$1YO8rHX&33-h*G||2SyLc`DQf9+lu`|F1G70?Xaotp1 zNr~L~>TA0&}gLQjFDGk>^V z=K~tXzMEBU%OF!h4LQAyz$r(P_=c-(^!g9xZF3EUvH95o#{@|-#{DSh-n)<9FRsNq zj?abBo&|JHWjXd;Z3Zj*Gr7>o4p_lFm4C@PKLgpO;oE_=U~w~+_Dy8m(qbxnGt@`2 zBhKM2lE-g%Y^ABA`|zcmp>T5AU(Vk&6bpY!gRM5(?^q*6k~G=g$F<}V=bfg+GcF1W zrpBYOlGm}{TWPpIyqW#X#}m$c8+2JYbE|wyk;U(CbhdXlHLDO}cbOW#bN?QC@pKB# zv(y01#3s6NloV-B@r0t9Z-U#(*YNJoDiA&D5#m<7z`7swA%4|ss?E02KKl<5x$fPF zHsh^$_MIr+tFVJMFukSVuoZkz38q_S2jFMxna}nKyBP)dV#esf=(4gf_aVCjHm8A0 zY83MR@QC>{jUi-MEz5nYlVS4PA^zzUPDbf8nmo5ojN4j<+Jx1EgHL}Aea*U&Ycl76 zT>U5%vN{fjykXjlbrUsX|Gu9x4?xPICxYiub(p_y3ub@IP|E3UELt)bG)zk9$1h6c z?~+v@k~qt~y6=j;rIWPLtmO12_~7GJY$MWx;VtgNZd1abZs|r&CQAh$7=4Owk^4Y@lt`1a zk9UK*M>5^7{}gxrGKG+hb=;JoBe>l4o|t1lK59sIyk~m>KL$~~r)uQIqFEr@>xkra z3-HqkEYmuwhPtu;_tj=$u*AB6>-@9>*BNw)vHHs=Nit2yZuCXEbou4Wr zbfh#6OW$kd`^?@`mjjAqGg!m!7zIH!^JARcGz}8&$D%}^0<3)PDW7@xJj)N7k^L!! z(CrCY4W`-A&)O_ha>w1j3f^bi^(Z znR-e_bbRo6G+QYQe_nKje}CpZ{T<7C3-<`1RX$gkUaLwT&N?H;>K=z0yz%}Lc(SF0 zX)KZ?J(ayTtsioK&KuMT+EG+Ci!yfQAjE;rpyBQg44N)ekixVIcx= z8<8bIF}=ugW*Faj_XEw$?!)FR}UXmM4 zn&Q|F)Y%otA+i|fsej~?PPNc(maVv_#X<480FF3r#OdgVm}3hU^U!wdv{B-`l=hX zTtLiKTuo*{d~OY$5Y>zKt@DLhZr+^FC$6 zx5hJ%`u$?gKVTP5-`2$UE3y0$+sa94VBWA zKvQ=V@mpXF$5bz&ya9HfYRCra6NzRYpjfbZ62wNoq?;BhkRw5C>!Bf*<9C^&TXTYG z(zY%^;E~}~LD@1%GHy-) zoMIjA|FU0UjhnV`b9@2qhWWU3V;X-ru#?U@r%Uu^tb+v47}w$#aD5Pl&Y9Zf8F*RUwl3mPF=5~=RC%d&rVz6 z%v+w5X>-Fy=Fz-KN(Y_EvSZEDIf%XyM1OQ0#TD%BW_6*RPG`4iUoT(y@LgFrlzC%( zmz;s@w^69T{}JmmHvzLwcB|DGMLwu8kM8`*+_np8C{MOttUtSq)FS3A2e-MjnqEG~ zI&ay;#SLY3q@ovxzc=Z^9H%B4`mGlii+rK<#uLFruR8p~$xf_woI2NzpMNKi>QPAB zN=A~kY-9aV>m}~WURRvymCO@%tF>0qWBUd65cE5gN+z@1jSkxr10X_qp~?=1J>T0%R~ zn+hrZzrG;NJ3`!9>j(iihg0RL>G)v$aF{!)i9Xa)AlS?uHkPS!U9wsvZ@f3WNj!m4 zN*Zxfp%yqezoru3Oo*Uo1-O%E+{nQ`_|wi%KKxJzH8>^2kFGhwuY0E4fmjv%dH?@0 z`BJ1Tsf#}Z6FW}Rvt$2~m_N%!4_^<#7sel9di6d2Ch4G)t;UgLb|*EK8bncQ3BI=d zIe+;4Yx-cK5I>mf2pe0DamtN5@UomPUWfht`j3_*I&G|zvs{O+u)9Q_x(yXA8s3Bw ztK+a=OdG$5=?^Q-70F>qrr$185U2;J5K=H5-mi{BW($SbYU&H#B`=H0#xWeWxeJqS zg`!CG;o}P5(}{Bo$lAXa!0*czK42Z81)I)*a{hf}lkfmzpLrnsl}qPi z39@;i2cX6>ZsLpsctK?qzg4l5N-`hFj`<6qGb4!pc?{%*pNwew*q2C>`9hK5eX-`O z#j;%!#&b|{)0$w7#|(-fqtw1gV)v{f-lEYsrHp9ynD`1v1g;OK#Ewg{>dr6 zKZGS^rX=$1E~p*qj=n1wW0eh``73i;s0;gc{ABe$d3*q8Ub+Ft=&1zP-4~ z*AKco%<0+Ui+JZEC777o#C(I2M9$A1g1_&#O1P*;){fr<63T{__hmX+SzpL=8RBa$TM&uV@OY&GJ*@o0U7f^R<7T!CiOwRq*hp$EU$YNMAmbkG1 zHm}H~V~Tq5ief(~P%Yu$-%dPxpjphHU$wK%GUj7fHylYVQjZR)PgZP7qBDger1oWb*cFKno&~jv_B!6YF5jV(7hN&54%rgCTo+5N?XuMl|k;p2)uq%8b70@jV69A z!8L_W@YE+zU^z;X?A8qg`Rn)5xL+@@6zjMi`Y)gUO`ebUx1Q!VUFf8j{){H=YuCZ` z5z+JsyYnU`-ibS$2|ssSs!WHPkmzV?gk=(kaNm&!+UCC_@~U91PniSF<*DbgCMGrcoe67SAe_z zYzHB=msP_0f$~%pVbV)ef=bWAAhL|KefrTsZ$_aN)b)F7>l3g=z+Ub6Wuk?izl-@PP5umL4HRq zj?7~I)jJ7vg81oZxlPaN79gEIyg1CdOy?Pjck$ z9(TA-hj9msSzng+_!Fc(_;>xCC`SuUw>74$yyK%Zw`3r1;_%u4ZH@6oXS=INFKxaY&m5j52sZ)0O_=y&{Gik^!91 z!4e7{;C8I6U#r_TdyJcAQwmn#ha;doi(@CVfAT;$pH|y|z{JQBmzj&a7epQqv{viwD zZcGrBPDsP;R*(37>s#r+9VSFS(i+?sWeLW<{*6qJhx3zJ{^zYKyVu+J!`YvyRA&?0 zf*jk!Uvhj;ji(JJn@Sf0?EfQ_W%#TYzZVi#x}$WJVk|%Jo7hw5dBlW-8rm?QVE}i; zaszfY?%|VJFLCGAUUuK{hc6}*sIA*YT*5!UI-HHacX%+>J2e zP7-Pw+l6OVjTGzB_Aw@8<{TTyo?OS7re$NvWh}G5xQ5!5_Tu9`{xHqQhfBLU7VkQh z%-e15rXKSZ$ZRzqDCvu*mx9Xitg10!t#^f+qZ@=T?JMH7rgqT093}GB*Z{PJc8Gcw z;ZZjo0jcKF*Ni6{_xi&QpAzm8^Ut4je9M17(M8v0$&oShJYksJ2)b`q629=gjvrdt zM(;l!OTI}i1zvWaU|5bSu`D$L<0I#gVq*!OzGe|TI%*)CHPVb!{k{&jC6A-(!4yxK zITenwKAl^gvP7xR9pWLH+pS}QGQWk;!GT#+o^|*~HxXD6eUJLw(ID$&Z9zS4FiN=_ zfg^S^fBOiAITAuVF=!FnWC;}5)iDmh{1w5M@1y9uFK}C^9XP1prcQaXtgG1_TAsY- z#w?wW7df33hm4l^Yd)v++;Q#{&w`6}M>O$MT7H_<~SV@Ug) ztx#gPm`f=Xp`-P^V*VT~8b@^V1Tg;Jb9(ViGVYtK4GNA;RO#_w+^Nm>EB}5J6h~df z*0jxyB0t~;<*$pmQlT4m%ZTH9dOGMF_BYr?M@c=;-oMBtY=b1DA~(&j8z%1ZO=GJX$#4mq43_3l5 zyX}{T9PT!Wb&Q3Enxu<)wD$d|qIb`*{gL@Lu-Qc&4PF_GV{^tpLQf+Vjq1ZYS$^kj z$WuXRd@a7k`hP;?A0Xr1ZMd~~E+h;tr1w4#C-m1gsI$1h{n+D*Q<~HG5iOnc4cq%( zaDO$V)SRLLY?rE^Z3%s_v_a!n3vu%MMSvgr(}Pvj#BtRM(Z}FA)Tk&&vMfAc`q~#o zKbGo}A@6+womq)4N#^4TnAHOsL9O@cra)~UFyWtN1ZmDofcWRNl5BI>#RVUHcrw#b%2_5MCSx1xQn4iao zec#oJxxy@OJg6apf0x`rwYT))gd4{olWyV;)hc5*wOHQyTQ?m!S%N(5*$L|J;^>Co zedPAhRifLaL$Lb+f83w@NUUl6)zTos2euG;X&H+6&SF~fExf&;nLZQrVXZ62;NA8+ z9BSCkyr7@O9h-4${^G^6Sl_}CZMx-VCg~WYBnmUBN6sE`*mhete<<-ir5nePUxC|T z>UTYXg0Tweo;w?!?ukRs+<#!N)}c^P!}{k}o3So6A;fSI=vBZie4x-00y3Y|tB?Az z-D58}J?tnq;gJO%2tCVZICaxaJ-_hw@7ACmS4d(K$8S04DYGi|q2VB=tpm7PNc~=)<(VHJ)ADw_2B}buP%>=4Ye*xDxsetjsCVKy$BUIxrHFAj zXtW%0W|;y(LoB_>cyiQc=8>3th1;hUggpXFc=`PubX1cPNeDB9fywr$y`UJYRWAa& z^Lezpp%;J2JPP`CCETK3A3V~qmH&B%d30lC$(<}u05vsg{&I-5M$igT`&(7qzBLJ7 zb$G-7l5M9`@->NEjy+Ud+$NY7H=JN;=CQnxiJaI?E$_=QFp^j$%pAo$mi{;4DLIa` zB7}J5=4oOb!>Uk*b;o&tTmC6-T(&Wa{uN5o=V#F%3mKxb+Zvn%rSu}(2y+i&9e3>mUg+5=>_ z*KvD3+T+V-)5V&`aCt3athpWngePg3ep=fQ(bDg%TX@=5AXAGt83%;0={)gv4_sS`xGvgt~Qzrm9`ijmTKAarx+YZ)t=G^7_G&Hv8 zEe%=nk&aVTBW6+<%$pw3Q+PCa>0kjLPb#9GuQ6;_S|6;RHqvvdefT%a^=LLd6`aSl zc!h8QOd0k7Ioy7ag{k)NNw0{#2USV#&h1dCd7e{!y9zIz%rcM2hkD;0I-VFeR4%Y59T9 znbeOhOT9onB8KkM=_7mmSBbW77=pF-`{U_59*b{$#q|m#(`Y`7O>Pwan4wO37>0lJ zUy7zz0}knG;m4XaQ~lR$6ZZLMe*d0sYHHt)YhHW7^$sn1`dB7ef}8h#BaQpV`1lte=m67rukQ)C0vzw9IqdEUz#4t`IUS1{c>Z4umi@Ld=q zYfc{3`oWVdPn5j82q)|I@Hg~Y=mhpn-+#=WaiKsiYu|bt<V*KyC6TcQZt7O+<2@op|>z4S3gBPs7y&b<8v0We|ZPA-xgi?{wr^5^A#@kcOd?@f%56W9n{TTljz)XfKbmTLf?bRD;F$c4}M!4@amc-x&_G-RC&iL3U6rhlq*N!JkTJ=M;l4d%n~7?mWfF|AR| zjh9Z*BsJR{;P<#~f+u0BWTvz^s9ZdUE*LqJi$-7Jv1GCEj-eSTQO$*dsN*P4Q;4^u zO$U3QmvnX95R&cb0WMltX7Z`z4 z*PP>vCNdn}Awl-O2o`I|leAwj(~ASlW;vR+JwsSt*aJqqdByqMvS+;I9RDS@lV(kj zC#SmY!Rfv~wQ`(}YJ!c!YwE7;n$} z^kRg(p)tK%U^G1!ABfNfKJ6J=?@@!}-Wh{$Lmibns6*aGvu(IrgiI@8TEuBoG+88LV# z^EY}yBki~7!-k&%Kyr1tp!wk|{Mx_?j{Yh`r&AkoVT3jOR=h=pn}!k5rR^}M<{USs zb`@@GJZG2iAMG1;TJ~+fn7>7ec(8Pgs?st+0rH4!C{@q zAX$$8FGKCXapcaL7w~9KJe^kbf@~hKMwH^Bh~09|u$$c|kl58od)$YRd_xa7aYKn4 z8qRd}7ZK1MavH6RX~09@jR9l(*Yx7J5hQ`KEzXeJoT{HUZryl-f7sSR6N;2^mrp#e zllXzo-!8$7m;1mWJ)R!FGP3K!@9lr&q^Oy^-q%;1ZI+kKowDQY&|j?8;70Gedenf&#c|0L-v|%hn(#? z0#DYT%%&P(+s9bc-u@j6rwoIOPwVODoo3{tKfv;rEElYuhx0eEEwkbp8o!-o$?y7r z#z}upDZv6yUw)2n;Mp75?+4ylI~PQgi)e39DE|6BmnW=aVQ|YBviJ>RyR=t?=TpZK z@Ag7aG;U#iab-AQ)IyMWmq+(A@1>>QPKaQ8G{%GXV?OjXZ~ zLrTfYi^`%=k7|*HV;U}yc*g4%wbFXlv9OnMp`XmZdbP0!O><%2xE&wp>zTdS<3J!d zzD=Vx9w%|fzJ76U{Ms~@9qV2SHD`Vb`-}{T#Hw8|2sWUMuDf{9(m(vRre=CB-Grol za)9tffm}q&I(&V5pP1{uV*Z3pmjgk~aw1LAyMX0fRUx9Wkruy`BAV-#L5+`})$G^0 z z@a7=vyzJ$oL9dmu%g7{5!kT$~y>_arK7!;o*+SOs^@0QSs^n(KL{K)%M4$GqAiZP0 z!tUm~!jTiqNcf37D6Kh;#%Gk^Ww&O4E6WzOhYu!4^F2VN{3Lfv#ROgLiJ()Avgsb< zL8S5=2K6^3G}l&*xIUZ0`To`U_ujN7C#uiOS^d9(K|a`;mk+t$`=EkI}S=8MyKSFUDIxu9CD4-Y)v9rtOL0lv7tDTaV3!>P?U7U6wZ=P+9;BI@Qs%6 z^HO9B*;oDOewG8u&|Coh9X9CQehs2<@+$bmSJ35Ws>sBoRU%ifI`sU~V6yCk2OJ$- zRkT2R3W@YT#q`NtC_f|*_XJ5pwqrAml^sETKemOGv?bhG-3~OXK%W0^1A6Xw0ohUh z0$MJ|Q5lOD#L0QBC>|+dSak+3j!_4xrHxd=g>6-@_kd!4C?_3nN^++}Lc@d8$j|N# z-j|{eujkd#MwXS6ZM20i7jJVNYrXMj=5sTU?xZ(!l(EmX1m5=N2daIt50{tihPLt; zx;E)Bu40|T|6#A(0R>XNVj(;(XcUfGI)a$rw1ZsDMabqWV9$b1{#I8r)m7b&w;cT; z&W1EB@5L|jc7fz(E&Ag}EUu;u;EY}(>czIlz{FB4*by*xLfBGHE z45*5EZ)u1baWyT4EYoA?c4aOe&E7$0?$ywNQ!KY7yBiD)j&QQ7412d_^0yh^w#)mB ztv|57-^T^C+%**YKD;Hy-VJ~C2tfo!4ZR{XojQ(~|GEpa6kE_glQL|fvIum;@@Nn1 z{&F3^8%%ZYahv-0;n=7*e8tC3`maTWc>MB!BBN+(q+Lp0kYS?1#&yV1CJjGVuI6=< zTWPY&SR&J612yTH0>Ato^kvI&u}4Ch-Off71i{ET(x}v-I+@OA5>02|M0<0(Jh7;^R9>|3ZU5CqS`}sEJrMa5Zi(Q@v!Nt=PsqC}! zIDXG?*zmZKMl6;h`q9h5KlhMTnw17wp0ycjPRAj>uKtLI#`Mm=*@o3 zscpN0Kgl96wWy}i%!?TNI|z(c?c#E8>*K9vXT*5B@{SBS{CXE$8xl*`hL>Z-9Y&C@ zmc@CV55&1&MPj_IV0aif*&ZIexhMSTr%Xm&HwWSM`Dm*_8E#Bn4^p>E=t`EUcasbT z?yr#RtM$hD<2!lB2VJyIZ7_Mr-omNhROmp3ly%YC6{7G_%6P$>M68?omXB0xrw7>n zh(5aoU!D*kaDJjnqOY^w`?;BDiT^SZ+Wdv(tP6!!)69sLc0QD9o;4DfnOA-TL3`af|Q6nogGFr|KZhA?g%=rbyK9trW0(lulYG=w9_8{RAw83-JMh+SDFl# zvSpi(d#UbnZ8G%d64ui`8GRd`fn$D)#P>M!J3N`bZB2zPmb?nGDN2X{=x zH#qr7Ez+W~4W8b;&0VS5f_;@!`B`l1O{&m@7+-LLuwdpdkvxo}*&U(sODoOmVDF%> zET?v5m~fAp8Nu@|f!dL1G*a~e9-=h`^0-&jX}U70y14`1dKz;^B znG!jog5YO~h`ugn{+ugLuw%Fe`tm*+PuemLb{=h{E3NzRcfDYkr&l2u%k-R-o<(Bp zZD6^ZC3XZxo8DwuMJ19pV+Uj&N$1x7bHUFpoa3h*>7*5r24tuFT3D46Nh4V9COqE> zjCJRt0?InR46nhe!4*`->lryZ-Bt7_u@-$eBuxxdJfSbJvgpR2$z=PBXy}`?3r*ON zhf7`z2Dcr}wD4dD(#us8-{2ai%^|VQFCfe_mgfF^P7MC66U|(yh~w%{<3GDKV7){m z-9As6Ow9Fwwik+AJ=&x)`uT8>|x!EvGnqeKCRa80RHbif?dxKT43S zjR2!sgSx^2H{dS5CA68EPOl_q-|i5#DkY<78@6H5mLK99+?Z7? zi@Ihvy!F+heZp8AulG%?@qRs|MO+3kZ)CofKw3?ixTs>-*%pgd%lyFFH;2Qy8E>e( z(2V?iRtnsXV`#clF0K!q4YD>h^wbNs8}ec|Tn{CGebH|tB-vUQSdUKQ7w)NtXZM&h) z`yQuIybph(Z}?-So%HDv6>=lk172pHq6c%8$xV+H5Z0@U)(uU=v*W7y$2VG8E=ivp zcwqwxGcpB7miC~5B`3t1gC~0ra?gTcb<$~itNR4o{gHr^H{0pavxA9-$r|7!`-N{d z-o?^826)d>_Wfo1zjn(OgZu43PUYlU+_qwXSI+FDzgU0N@V~*JKQNJIZ#$124yr+a zVk321B}L+Rmebesvua>@ir}{^Ayq08O)7hjwI=GoVAXnhn0Ypg#x8~_n_hE;{g<(d zE{0s~YC5}*_2+1Wz__Yi+}b<(*d*aBpWV|K~C z1F`G3dwlQR4q8#ox}N4ug2n3`&>cI9amp%KdbEHV4)4Rq3`1b=ddi)$@y7j^yTrK< z+Bb;QZ}5Vdy~@-jQObJnIA;-7R>r3*6S494R(_vTJJpv}CE5K`Kt1^!@^)ED;=;ee z^0qrdLo1dKx^Wu{H=jVGCY9i=kuxFfz)N~&;UMzM#1rnmInG%%tgvEzOaFY}N;nR^}U|M+} znaz5Ef9ouUf93_$jrG^j8y>L4rG`_VVUNcIU*t3TJE@tBG;tX{4~$&*&`F?0NXjzS zCpigy{hW@I@O{2IxRti&1mS(x6`*f8xtS|GV6>f>FrB_xkia-L}eBp z?>ZD*H#O2VdzHzKRn8!tGmCSvW^tGHLHvK+nANlONX=#&IP#-{sx=GARsB_>UswL1 zsXd8!|AaAO%^@nX7jL+;7Yg2g5VSZI;Mim1KotE7#Yk4;4NuIWXi**QU%~b!%$#Au z>C0TY-xj?8Y?_$&4sX>X3RCC8O*vnx6yS%w>{P_qyIH;uw~Yyb;Zmx?rR>)E_5Nj; z!bhW5*=4NzeJc2ke?_m!E0O6M?y!5l5m!2SD$3FgqjD&m!g@tA>NE!p4m>qsy!5Tp zVmM)=fd;RQ#!vJNp+~2Yo?g?3Wt~D`c4CF#{Jod>RmKvr|3NgS4o@3t0}niJQnzbE zNwxnDc(wd2N4QnkE#^Egqsnvu^|567*|qTN>@hm5)PyWtuo$Wq%|+c~)ya~^Yj7jA zoQ}45MlQZuEz-JQi=5UCA`a}%+d8VE=qa5{0ySd6diE}K2XgU*Cqtn9V-t1pF(%S> zTg6^ti*xVMupdLkyf@BdHi>R~0kQ96=pX$W((q-SXx$bC>{WCcSLJBJkZFx{j`|?- zxy%D*JW=2j&zceS7%2Bw#Z@oBc~*&#Vsjo&ooa_ ztji=^<`9d|9Qw)k?`B>#H3@6}LEtA`T5AipwiZx#L&nWgT)_P2ckV%N z2tK##ju?lJePLdUID4@_t>(D_aZV}$t(`5%B&Gz*d(LOO6<6uZjr*{_aWg+my^HP$ zW_wj^&mw$k6rJ>2iKy;$f$NdFNVzf&xxM42J{$7Za zS4)6lU^9KrI0@IV6gE`^a?StNV7~MpzbT}XX0QyYnQ|x?qDjO~KhCiz{&r#Oc?{ z_=>X~^kL3Wg4xbUYj}}xP_zd56fJ;}8(k2eDZtU995!Es4!|#@c!p#cG8OV6! zm?Iy=d^n(9iU>}4LGB+V`gWR>^}6#eBClE{{3bIItBiinE39g#qcX>nNj_V_FY2(s zVx%e&+E0hn7w6Ez{zc@#{V#BDa)GdSp&9XTx&u)KCr~^s#Dcnv1M%H0bVU%Z^;LvS=7rn3r2<>cSO8uh_mw!Z zJ-+G#X&~@PL|3A+@U-JfVtjU3q)b+OFy9fK#XY;uqv2A6#ae{&fDXCgI2Uqa%BkuS zAvt8@D*EO92N}jBVhLS+=)TiP%~<~8P{V#0ZvRoBJh71RE|$I3d5yf%o?%^=3E(xc zmO7Xylbusm!S#&G+^38!I4kH3FSD23n^^``Iy|Yep-d9}k;>HX7UcQr>XN(~~4Ay~NWCZOfR3`(WR&YV>5-nWM)WyPVth78pGB@qy@HWtOrHcHJ|?>WmbvtE0kcoz zh-fY5-EE+zBc;gEah~AtMV|YYV@m4%qrf=&4B9PGkMrLd!uy6=x`yqNj94*5)NJjI z!aBY1ajQ5nJ}-Ktgl9x0^Ha(`(3QD;_}Ly`XgwcGyNmvil@eP-eB}_lrp^zq&wkFw z{OX{4A4?F4jJaTRs6sgEmkIe%>Io0Ey^(f5j}LA8D(1--C2GjF1A9c#x6)8ULGi`i96`B$GIad9`A(LS~QnX4kn;f>{5vf%!ir1U~k| zh^Ej8)t8vBxK;KcY*dUyAK%=>rE8c!C!?B1vVJi6%7c)(`Y5O2 zKLZata*6M#`EOI>Gj^!4hnUnmbP2mFwWo~+U-cW@nyL`YExs$p?Yy@pByPwGSUdQZ zu=#`mX{`{#lHeBf&ZQJ5uVVR*UpZ8dXZN*N2SJUE24v;!#UZC#_;j{ynl(*{=tO(N z5A`T|@ud>640DB|G+mTil8Q5a)$%(3T4}y7+awxo59d#02wF$~LLIC__`h6Ujl&7t z+9wG^x3$wgqrpV`-g<~?=o7NCC?b^-3{6U2Xisb*t~enHp-Y?TN8W@q1+9RUzXQ29 zwrjBY5eb+wn|)`id$GSw7&P5rxE-B|za1C}y2g#PVd7wNw{ktGO$e}BtZU?p=uP?^!uPiT|8Mp!t4yxy5>@MT0JFTH*R4$XD>PyDijNX+}EU7D9;R zNz};hn^k?YKwIktJz^+H{+;oJE&a#16+y;mxk{ASOFU`x0A6<88V+=aZjtBcko_ zwYgWs+QpD236gx!7DgI+)3}BQBrQxqBSnFQ>aCXoIszF_@w$ zazVIh`B2#ZkY&RYSr3ekFAO(MC^2K5mPbFIhHE*AC{jNQ=Ork!%t#|0`bUXvSg!`{ zle4%%T|BbBHiVCr>ZWRQv`C$_HMD(tNPCqN@!8M%V7r<54WfJTL=9h9KtBpv6^rn+ z;bu^i{RV{@J;QIWO@!sLwe$=7y?xv73S$ml=4!&X;C`!g{v&&r4Pu_~=JXY?Nj`*z zcpt*2SvI8iT`O%mBg98i9AV+9#*$O!X5{JXY>-_ZgY?_(;|W7&fc`(`-#(>4LSx+l zUXJ5r6{a9d%?Qd4!L;L?Jh>i?VaHk_m1X%mk%zgjYs$g=j3(OEV?YX)yFq|p2RHKYd$eWSF#f+yQeBx@WVli- zcqhluzgvXZV2z^~pOycn;iMdGxYON0OC%*(*Muh=l$7Ue8&!yF*dD0p4?!x=Ut`xm zBQWc)rLHRsh{2vMu+rf%*LBg0^+v{v@%eVB5>C3CEauN27WLzEuMWY0dK^6%{+CRe zvt8u=MHWj(`eEO(FLR7$U?;9R-aseR z4Sqw5zL^n=hKGQ6M51FWbMT*e9HcC$VcU*y~iwQ3Fysl){*Z7IaTg zjFaRY*c~vNCYkr)*SCD3^6GuAHDE8+c-_M9$?v4YM=FxOJsyxCd4lE^rQ+K@b^LDm zHkz8QMCdB=XPM}%jLznj*$Eok6;Hh;xZM9G!D)ye> zQ$L7KdZ0_HS>E&N#5L&C@Itm7F9nJJn&`R*CS;AN3(VIK;&z=_jgzz_L6TwJ-w{G= zA#{Qm;?gK}Z=WOkx8Tz*_2Y+(1wi=$k?WAZL^r63<)qsu^M;|*%vSAq>Q zoWMCfnp-%<3;QxJ&40S_vRnxg(BlPa!-i5j&wg@IXQk+PlRWk@OT_=UZoY-I(^aa9 zWaRz1pt*6GK=1u9B8Zp?LH*~@{t8DD{rwB{jm;NYt}r9>e2O4??n#vP;4ThUp2Idf zo>Mnf339B$6K1phmv57ekYGiW*cUNwQy<=#%(%T_0Zk4Ou^uxykz`gD`lK9zZ5*!i zU)tO0f-Dhn?${*yq#VwDR~=xT{Kv#Rx$1i*Ze70^!s7C%@~wZkd5b5MO{(M!=Gx(= z>?|=3mk&sg++sUu&-135k@tz=UIo#r-e&aqY&x#OPx;N&t#qbkA#tvA7F9nKqBmy( z@u*=+@WZc-9^B6`bD|$?a!DwOyJkupHl2l+pA(UK%@tfyr~<_dqh^g6NleqXL#&Yv zXRwP$?e#MJf1R8sSQltXqz!1=J)~S#0ybzI3qNNz(%r1H?i$Pc*gJm`V8s%AK4>D$ z-PDB2dn)m~*^?o4d@UXGc?6lUWIOCu%i&CZY{t(rGI-H)riXtrA;(s`fFTZ{BmI1_ zd4?*?Kio=>e=otJBqz8%wXtNt%#0A%YhaiVgSL9z$Kw}Rz@wKe=eR(gWEHr>mskU? zQExJOR~13`S%%TQN9D+50|Kw)OQ;0nKeHTNpubTA)y+7C*Ss=SNf&L^R3zi7 z=E5X7Z@Q8y5t-2GFxGDzvPu|9oE>ih6+WfsyGyX~DJQu3vW%-WlOPxVdBP%v$3=tZ zO(r*nCxYP8E_C8j4!$u<9=7gmqD2$Nk_b09P#M_D`5t(Wj+hM>>&dAmGl|=yS`b;p z&{2scc(oO|J;n>0-%RAA4|h`K$x7Jda4LWK`Uh$~sTWUOb{H1e#!@b{ zpV+)|7ukwrae7f^VX<2c)#zruk@o&< zPwgnTV)zUkG&PGKGV}wr({9Igp>rX;D2KjMEyqgbdQh}{8}`YWPae`(83m$y(q%oD;?p_(QG>ZF7rZ6^M{_V_c`n0J@`j+E5G&< z>n(XBPn-h1VD-4;w9qCMKQwRPbsAdfg*sib&B_s;*=7i;y?>%7HK%y;pWjJ<^xr&l_shm4?vbmG>vEY+@AQ9zdD}vbzGApHYeG=yY;qkBfCW& zyXOj1f_I_c%Wvbo6Ia5Dl{aaW3+rL1iGVs;;Pf|m;+T$b&!@xIGvL`8n;`He`458l@eHY{ZCt{jCe?MGz!U$U2KC%?FX8s zk$}&q8Nm2w4Rp#)=0jt7pWNI}f-~R$%QZ{^8_Bn*Mp%i}L{r3>j@5x`B!TT&{5f}n zOUmAi`B|A_e3sf_Mik$#f%2$Onm@!Bt40h5y<@G^l=-V?Jc)olJY4vM>HK-0uEYKI z81z`}K7Me)5^h(#r2YDGq)NgA0)57E$FEF6DlNxoxMCRH$U6D;XAp=WMO2ukK`d|0 z1+Rnh=yPrq-kV^|{A>+$QW)!8`Vav-?4JqzhP=Q*Ok@9VkIDAId)zeM1(YL8DEC2@ zoIU3b-`i5SACq0MK$yi}p2FVastV*;B+IHtd(z=&nLb}@3A#57(bT^q$aAS2cV~`GW}r@8Z((_?nr_S&vqdjr5r4nqyUEp8tH_jF>E8!4gN~Iaku}pqmSp* z{?Cn9TasTfb-=Ym({+(T{6CV;!>{J|{o|E(X^1FN_GtN(Z0CL7w~>{t>`^o{l$H@H zZ7C@YNu;5)H|gBxI*3pbNomkhNg}h1-~Bzmf8cmHr}H}3`?_AQ=WCeVA0K=F;dnEy z;HsF3;NaIxyPf~w8?KHZAtuX>*{(`%>70N+tVbhLs}Y~~WE^9*yD(CpM7I1o1PdQk zaNiA_@cxx?0+W4AWA_Qk{!7-v*yYA()ovwx{>K%;&%+<-p@;hHwwniTU!T&VhbQr0 zG1mLcG`ZDHoOpGvgR6&X`18csJl5t8?#j+6_X)*+@Bb8pv@=$A2PF-6tb~6U_i2vm zAsmy<x-{P$9qNRu~s$dN0SPVnq=2z|aP z9yg@43XZbwHj2I>jkgh^-SQmX3-Z!>yU^y!JEV0x6bC3s!NJ%rdgO;J860wi-C7bf z{Ge3ViR>K*uZb4kDE2gP~mF0vB!xs_S}u1Od0|I%W+hh4C9!N5cvA* zKk9;#@HA@;D0Xe8p4V6xkCh|bnBc!uW0EeJ(h~?%H>4qn{TGk< zRiHKefZOyb4Qp1Ig2zBDeK=(pUuz5jbyIiFG=CDFosuF@I>&Ae>SCn#zoX!y5lYdJ z59Yg7GqV88G3CgSn!76@d{PNNvtNS*omvI2T6Ut*w+eCF2Xjyxn?oJk*mss?B4WIN zlQDF}uYY|J?Imvg{f#^390A@01-fs`Fp;;|DeTXd$LqVJ@v(wWf~Q_x^wvim@@SPU zWF)xp;?AiO<%p%wJeY)BuC6BIUVnlghWY#`mg@Ydy+M{ecSOVAKQGbc><&R5We$@kFc|b{M$$N*s?YxGky{Qo-4R+96IbZDfL>Y`NIw>$e z&-5MMFmW)t+?cV27aT}}$}_QO>+_q~D18)UI5yLd=4#}o>|w~4$J}Eh0m>_q7wsrA z7HN{RtSe!r*(2sxEF~e?yM!^4Ur~MjB`hC24eC;w>A%~o&)UHoKFs{Y^B4j6)X8}; zy|x4CEP95I%ghz+D;(#lk*4Q%5V|d!tIa-$t>sfh`-+pS8%~v(=?ZN9>Aq3N@ug{_ z!Ffst-GPVkuig;Y;;+V!X51|c=Uix?5s9*#@8kN?h49(^6>a+^L#&AdsF_XXj{Y=6 zj&P1<76wqyGt%V9WC8{IZd17&_FSBXp}{~J{c;P(C26xE!=;&q&l|=Pogtv}5LKmKw)7f8CB}tj`q9$+PXplcufv;Y^Po zjoGYB25&8b(*e_wKg&n=-N}QOzn;+J4$p|h-b2Ef{~FNX;oo?1iWB6-J}grj^B>{W z$APbwEBe!tivx}+Lb7TrZIaRHWfVPFdlDaf&?xBD z@1aFwrOC*@TjAsPdVcpjU2=JnCwy>sMrk)GPQCU^VD-F}zAWXF*mst~$Cnwiy7nM$ zk@+LgVb2tX1OK1fT76QBdN)PjJxBfssx!LijYw(oUbqePnq_!XLr0OOfGr>$8;ky) z8pMSW6QNhXnQDF3BOmTm!KxLZNc(UuZd6+)nvEwgfB1_`mM>f9!v#c};HlZS1fRP; z&@(pOxVvjL@aqexlMQ3_?kkybQTTGn5^eWR~UOaw1 z`mIQZH9Ry)pFZo$8+nE2ZvPbp2VeaE+1Nyz414FnzKqAzq^OqME#4taW4Fbg)uA|z zd2If-$M}0mhE&)6FXJFapX_5jo2P?e#6l-@Z)7RfTP+O|ajmqcT7&czt^s)oNA7dt zE-aQgLNq7q2O@Gb?G*%M1kq>l*Ri{vCgct@(d2_NWXTyvaGc<`v{hG^?ARI%wwKaS z{nrlsm)%p=k7%ToVQJW}XB8yBucdlAlW_XURM9+aIQS3W)^meLCZV+LziOQLdM>os zWO7w^eORc!Mxf4EcD%Xrq@VEtOh=aTFJzA;{_joUO|JzK82Ij=+yajD!8f6sPaW5oE;m(pJXA5HDdq;gC=oKK>qg zxhUC2|Zt1=(*^L}!HevKMJ}Vm$VIssnLo8ZhV$1`4DslKAj6hq1zg8)E)yk zllz*U8aa`ixo!=Gf%muq6(_95^4IQ_Jv7;?fn1h2E9|#kjn3R0iBFeY73`Y&k=lG_ z{?!e>VB{S|ox)CHpY~?KfOikQD=tN}OU&V4-YdRw)f8eG=?v%ntkL_G6d!B;BiQ(; zl?IM`P0&JLVZ`JlbZpu|eCqZ;LGi|3+R1$8yXX0W*L^J-zdr)^uVEcwC%Y)zQzbQy z_K8^Ep`J&2orUc|oT! zUe?MWUpSrN!|mT~f)|d@7EE5*M>mA^;9|C`SvI$b=4-P)>#}LEXnroYXR|+ckh(9@ zSeFGX^VPQw&h5LwPaQLbj4Hk_(%AjXGnQuQ3o+6UxxqMByySb2XeWF^MwaMpbO!0} zV0vFM9-EBq5KK7KNzaZRL#CUogcrThyld0GqQA!@1(&CNq<<%}4zDNqkkbE{wmp4L zXvj|Ch^Duwap)XAk}VDAw7aNUoHXfK>;$@;7#-`VOC;a0nKQu&ok=ah7x&44(t%bw zJj7;$;FU0|_7K-#xC<|{mK5o#XD^Qo`Mm=1ia^>m_B!tPs|mxGny9(4GJ96_t;c7Ad{+ZqAvuP;yTtnLO$6Ku-85YDbv68{tEE4_>EO2+ zX@d5(eN_E9dmlEtKwUyG&C{vI&i3=*UtA^^lIVj^{CO^#dn1(;$b4}#xNUcv&oR%^ z=142B-Q|j4Svnr@S_e@@$#l%)YVvodt#IV+MD)zV0jqENF3NH2VVxtXjn0rVR-XPj z9gRDx21T>3d<7J<|39VD_1C z^!9rRo_U=EAMF=($?+kq{nr^9S_3(SjkD0hSC>Q_<4M22;c(6rG>r>sW0H_uKc+0q zNVtWX9tPpFro|$SJ#AJ;cE0u&N^gqhGOK0CpV(ON8&QXbeIDW4O&g(Re>OeJbgawC z1s0|~*>37R zuZZmUzEgN)(Os0f)(5wks=~+44w{-igmcgPf?H5b`Oqs}QnxJy#MR=^nYU@!hxPlQ z#wMy!r$UskA7;IrJZ{>4ingnc6lrf{H|v04nb!3$fNuG0Omx;^Ok#*{!I^_F0DN#MT(X> z!1c@+Zk)q*>}-}Jy3_HKMi5IC0>Z)rbc3`Od5t$gU*kM9X~}3JHl_gH&wWBO^qvu6 zrLFLLcq2N`;>msv(8ZlV@3OtOJ!ul=0k z)c35TT~okK{y=RG%qJH^n&Hd82pX~FAF((ZE)0J@8^^DR$93hC;QoH~URfoQQp12(TV6zOw*+ysJKtU==^a9!Ds*lXWaf#$6q>V9q{9%@e% z?H{bzGpR7(tcWSmIr}6oPi_@yau?$>dsJ(czUO00=9?X0 zy(&$k8_2rGvqJd=H_(v172fMD1`lO=sXfbjOr3QWcE8c0XAPLgdz(0{4`klU7vd!F z$rjKJ8^NnOph~(vTR>e$42tL)z;-VtLI3GDH1~-fiTm>$o_+~Ms&U!a!)gWm+fqws z%^1epQW%4!%ZEFuYl63*%n{6Y=%f1v-s4Rr>*3U*LfWrdh0Ax%fIarP+?cWc`0L{b zf`lF2w4s)D+$gVtk@X4u6}6Lz*Ov!i-181;v-{eSi55_>B8OVDxq8;!vmj0%a;0jn z_*Li!QReQWhfv?75z8#UGiJ#8(fGsj%Q(-ZOYm?q2DOm+N1BW=H+dFaJEGdyz>saxK zb5=d5Wdu@*qH9=2VglT9Y@#JfQpBgs5mqkrU0Sn<>HpYJ2-3WXJ|F17{WE8aX5cyO zJ2;uHf~eI3Zpyk;45!w>c7s}~eOm`_X}Br)yuXjG{xFP#&a*CKw-7phR5eZ*y8x_e zGr6;8eDKW97XoMInRJa8BMXu_xK?nBf3Ke1WwuyD8Q&Gj=%iz#PiCwiHkqbaJR`x( zi*D?B4TXKM$5IVHL_3OQdx!8uMOS#TU7k*uGDKY5_X%^-f75Zt-|Yly>?E z6Xc`04G}WLF)|Lql9|bGMb<$aE77D023u!|! z<#ippM5`qg0uIEX0rqV2D`yPERW#99mZ^F6=rF`qEa7T(D4JoTB+}<1*2ikvy$URh zg*3Fph)hdpVDqyhI{YXK_n(^yw=OhOYw=;M)NmHeiUxQ^j1?K(xR9}nJ5YFjHU65q z0IJ+y(|voD$*!2gu=Y#_Hz2ga9{K4aeU6KpM(*K#@bje)Rn+jro1E1F?zYoEo3@f! z0Ru4W-UVNcfJMbK3#iWrHS*lv6buHX(1x91_~|x%kQ(1irEfhZ-=Yr*rM1&J&&A!?_?Igj zLygG0vkvb~-T-e$<nv-RlB+1U96=0`vkd75hAjh_B zfqFU*eF8Odp|=2*4?m_Q5dyMk`c9!(*c0^i8uNLsa|OFu56i};%ptPX37~Y<6>S=w zi_4W%M7!dFobe>+uMHf&vzIIM>p~G$;{}oxz0^Zt0qN0r3olbP0DY4#ZAhLnc|Tany?cVE6Ucv|-+OGH#6x ztn?Oe6*i7oM)sOWpKlpAko!yggucbAk<-zU_~epnBCY;$iZdcKj~6e7mFuYR)D$ovT(pT8mo%@M71 zwyzaF+$;wF+fl4wT~XRyXW^dXL~2bU@T&XFmn-a|C7YB=RzSVG^WkHPXd1^vSDNwUDv#Jc^y3gDVcR?5)NN>gh3zL)HD@(L`S^ewhiT z-*W`pQu^3lt{2CsZGx%&MRagY6<+^s1_Wp3a%SWG@%8N$qWQV%^<*+@O$GB^w;}hR z4{+M@{b1`|Odqq?EM>1bOY#vXHgFW5totA^I>$2aI$7D5lzNG!8bG#CDG zP{S*qUB-f(F3~LgA$Sl4vn;vUg^x6DP>c8;EQF~`Szp_>=OnIjk1)#c9U3}%4#z~w z!hV@9y4paJOlCXhkj&qF4+qw*ka8Zn*Bn7BUbAk3962~P)Iyu^POSU!|8@Ad+!AtK z@Cy8J04=e(hHEsmAlj;l?)o)?`5~PkeUH!5MdrH1KJq-QcD;$Ft?j@DJ&Z>^uaUxg zA+hL^6sG+-iCV%_@Swq3sL6j$B|>y?jCzJ>KitoB*uKmICgp|Dj(N-hbhB|@K@gDXp@DD#uL@;wWgI~U7BDvPf_yaR65j-itjj6lgX+aKM9A}RoT=^xM zlg*umaLx*Mki05S-&hWje-94`OC=QW)}~AN-_0L_5?$u;n=zhj&a{IC3XVMckt$@I z>vEVZorD_7my@ESpP_zh4&U*Z9-YMnA^t8oB5_WnONR3^bG z?Ek)DD*9BEh;LRkh;%q){amukv>E;=EzxPR__O|o5P{#md*>iz_UrA2eS_^%1ZgM8dKXB4pUs#sV zjUK1eVJ&WxD2w-O(g?PPcL3Fsm$-?|7TA1mzDS2FBE-mx>lmI&?V)a65y^%Ri~vn3!2U>Tp(v}>qk{%gD?-3a_oGLJXwE?Jjv0TFNVxB{LdR(o(=w7b|Q zJC~eRZ2_gqG%mq-B%Yv^B$!82|e@OCr;ep+GLEf$Nh&W|qWye+U_IoYW*~%Ej!~Rfn%$HNUG8fNQ$rm7& zZ6V2Rxb&$R+nwf8t2tFTp?Wq{$mDUcAN+7wMWrB#F+$b1P9_?jk6_t96TR!rzRi8hhFpxG@0k*_7YjLCdd=G`yn*qu*9<3#XE#OyVUS) zm&^F-#a@vPH*6b3=e?o@o8Eq;1zWYq&8bBo-cU*ZZa#;7)8(Lq&3pN(BS_#SCy@Oz z#E&@3@;f@=pnU%bs^Jym)LePE5Yj?V+X_junzZoJNp+M{zXOMtN<*ke50&m(L=p_^ zp{2;5j^4t@*LSRit~uh!{97V^r8p5L&S;|HZzYKO64n)d+Iy+|2G$etH4KCqHk1?;yg-Pc;?1QNmH^r|5n_tiA8ABZ`HvN`BjCJTtIa7_#GJpG2 zp%t|?sm7|=i{Zk_EN+3l4<7fgUSRf`WPIUuZ7c|8(vs{;BC zT|k5Li}A@^)_Y}IOT$O%qR#Ai(L8)F_zND%IQHM1^J#QvHU7_43v#EHaC?^oVcXs^ zK`~=!FFt8Zg8w!HME~U#?3E$#CLS)u)*&ma3cTRQ7Px#Wi%wS`#yiIzgU>IjxcrKh zcuQ}gXf_@?phU!z9N}-YKkb;SOl-gJ0Gsnuk-?QjtTVGopfj(N=4u)foxo;jGFptf zWV~^ltr}R3=%5Rj7pPDn0Okh9ma7fwlCPcVK)=SJuWhMVr(-O*v)z>* z3%TlYKB}9cD$?i0ib^EAe;Ih6zfIlD=a9+c8^PPd9vOa)#Cx{Q2G{?Z>D}qW_>67< zTqys{leXmJD-)K$&e(ROcAyH^^euvKY>I5IQ6yoK_VDd<8kcKrg`bYh61=GGp>@+I zli2iq@TTcBUHiZtPxw0)E_$`omysLE!D$2Fw8fMEz(J3cEG&hCH=|JNb-=-!IZ)QE zqwV$*q|nBZvDYSWSHBsc&0-ftbMl(Hf2X6E{v5H9{0*c!vW`Uy`mxP zyU)1B+&3&Gc@|cgzef}Ay}*Z;u#TjjY-&7Gf^08yfM+M8IQ3f=xZ`JmV3A)h-Ipdt z#@8@!jQbw?C4Ln7zO4vg`D6OPt&DtsVIh?KT!AF=hOm8sCp_-o7s-s~1<`#D68b?04*g}%>F0R?R3nhP?DENau(3JVc{;) zrfdG88nerIW%E=x%J$w@*gk4PrYFp4lHr=$b;)O!E1>f68VZ{58i!lV740h|#w!zv zXFFi$U>+A|?1)#!+z{wX_fj)zL?TRDAnQvi*Yi^m@1Au-aEockeup7ElMYGGx@%q{k zK;>HLQa>YtC0d|eT?R!ivc!cyB_PDOm-aR>Hdl23c#P7fYvqlJ-`_k~5aW&l^e{*u#7}tgCLM(#(4-KD!<)hR>spGg;W-=PGC~wR-ZP^>v|IKaYQvh0Gw{hIkCw9BM~$x@cx=eymdE;GF`FlXZ`R%P z$HW;#<%BJiyvyTH6Q4{xu2(|KqBito@jZNLi6t2SDWrEd4&(W=0^#VuBkuW47fjp- zL_EwJg_7jnPFD!A45U6v63g!0-zj`ITMd8Sav2|N?h{N1?4$|fW{~`gw(#LwI`3TU z7xdCNMzqJUx;BBFeq00>c2v^c#UVIvnLJ#*+(}_!mvi(h$CmuUN5097?- zWbmX2kF8RGRjXUr^Ysj}?W-Lm{qo`RXY9Zix66n!APYJdk#&8q!C}as&VEylPlT-l zb1iXXeLoRzMcS})1?yd6y>C`dPOzAFX6Xk{#@b?xl=Y+1(S?Y1oFZlj%veo-vmC^f z%QC_#-%p~*X(>3m$xM_7>695JN3$b@4@MnBAuqLY&fHAVPQz>8A1oW@1xmlp(N0{= zxPD7PvMP&PIK~I7g*6EFvfI%6HDW|=(+c2yzr{CY-Hzml6YJ%4Lpje1vANX&2z1Y* z0+Sb{YpT1@(g-+CC&J^owNZR&S+2s;%X2dk+H^c4L~1iH4ulKYBys_7+c6EiG$ z`ni*OODU5zKX-wI`YztOy{cq=7BKNo&%Kp8XoPeMC4SR;n^#H+R8Y$=Y3lQ`TM)eRGO~?H#oJ^w;QF~H8egP9hCS@TDSiPr zT859*Cyx?vvwCT$@<{TxVmVy!DrMgnL(*;420tD+`M^6Lm@vdto zVCC?dKKZCl@+aBCzmH|yl5viB{Js=HG1Jl*_>VY6HG{(RRBmspBKGz9e+|FEo{3CL z%)t4n6%Dy^9P6&>6hyD?p^rC6k;Lr%pc?X;U#O)+hKUDsUA06DPL$)!nUb*XMGIYd z;y)6!xEbURN+ZeV2knoOI^V4)=I*4 zmNU&WmLki~?1$_`8D6E)CtUvO|8;v{kv`EGsE6Nc!qBYVOl*?B3PNu_r=*OJ`_7ob z;Hi~d_N=*B5LF=BKkrcM!HF8?Fh`-72Hx?*sZ*W`einDr%&+ofMLmX$FOhsYVlo;1 ztrBuA+R(O9_i&+|C7kUkq)*-WSbVM-OgE3^%KcpM*zy6v|2mlN^huKRxo*&&8c4S! z{v~M<=0aOd73_TEGF~0;_8RvN!?5hmpwSW7JHV(&#_8TP&Cy;HG#ejL0 zRDKa3>t?QpeUGZRk6S`8RaXEb)^Yrcb?AKCdIaWu`oV7qX8i>}A|Ttx87W2;;oPw! zA)fu#pT9MgEL&>}5us-|yX@`QPE%H-+cSn1lDyaku#WMkQM=0V@jGVFCMk{z+!OIC za~)W@xQRaHixK@IC-`yY)Y3;by2QUR0xU^7%O|$uhMRL>u3;lpdNzeD7;OWW!(MV{ z%963nm-VnnqLxDJ5b24#D3qLj49yW}}jH)?8 zbgrex{|wA8yb*>r+ad8yk+_NV{k2SQrmxwv@Wz<+u&1Pi z7kHx_CuH-W`*b_fR(gsfbeDp*QaxShBv0~SEO~80@9UYo4MoidE zq@YBTD{MDFUeBXMxsv5$|6u9#<=`sL7#D#;GTKB=*dU&Ve)@#s9cSmj`$9P_YXuQGYUHFC{AM%F_zTIfagBra2!zM6P$fDV=|KXnoj!^A?kt^L|fz1|`2%gsU zQoFN~WG%ac_?57|boK+H;-nz-je3tv-BpQgSut>7l{9AJZBiYxUAUJ#K(&rC|^7(xbZVR^I#r>ozI=B7*%F**G@42kZK zCNMvLo~BN?LzG~LFePvp4IYcb*UG2E$(|-^D>aP2SbKp*pe!d;)+0B46Cv*Mb#zU< z9v}TW4{YbZrsFP*Asd`n2giv!TxOpGn;+5ys+)UhqygKLA8mn;D^j?s1VtQsAVu(k z*H2HgznQ9}4IqEUisrn3LEf!27e1BkLC#-};gz$xMS8w%l`d)h?GLFxj-nHv?_!_D z($JUELZ6AxA-)@0U}=RE`XGA%_gPAcG<@6Va%>*40W6+==3oA5L_Fn+;Po~Sbh$Vj zpC2PFn!RVNl_yiaIzZj5k-Ws%Sn{o@A9_#g;Bk-p@$B+haJs#bx{uT+&(a&gDlZIe zyKxIE$gF{9jWx9IcR3zexB))zTglz-Fvb^DiUoF0`slc4@3Haz?Jzf@h-SO^;Tnf$ zf{pjP=^dT|NmN}4I5LWV-G%ipjCu-1N7_)0aS5ikEg&W^gU)I$$9vN@K-Pg+E=t}7 z+bMk&d6-`YOA)^9ad?{9^drjO%r=!JCz7}AhP#CaUd+!zT87t&E~RU1}U zHiFEr4Rptn$z;gZ2A);aaxE6g_<-_8(auE1TpJIc&lc^m---?4(uh+~9~(mBHdf;x zNet1;|^Lq(hlcr_$OFA&_nG@hj824)1XBaXjMrRc0d15)ax`qOoDKK*FjLw zDxUdqRkGWA1AMSgMx7;wMAoAPhQ258=jG^;H5pG}$H53x!7IW?!dAj#i(0BOb{N0C zbsA<|3+8Svv_L)>xyFTeOn;5egUF;qC~tQ zao^MeXYUO0?1H4pvRhX{C9)39GcCufcWr=rk5uZf#QfVgPD4yvHK+Y{1vb;ZEx2&E zm*(!0CsP?~Mf{*It2s@5(emo6Yc-7NEk3toNaD46M1;PPct2$DqCu zQkUA6zt_+s>%y|3zUwlQNln51KQ%!?qKWRclp`f-4lqM)9`|kxADvu0M#MGhn#{EN zzc;X;$QFe+T*R72`e60GiFV2J@vZ+h!r-?O-t`IPca@5fc0K&O6G!3TH=`MJdsvA*UFRqBUZxFe>>?bB{zKNl%`0l1E#Da+`R!mW0 z>d&IPf`z2DTwZu@aUQB%7>fG?{)2M8CVG5_ki^bEB>Yl)gX{nHmBH-;!1zEnx|#b7 zi=}Ob9M??B3;lze=Q_eFmk7>E+k&yjO9f8fS@!|U`1tKv3oecOsD8yg@*+_|n0CDr zc~z}hgXy=72d{ui4 zEO%(8zXS+!8yCO2@@v zty=yd@bm!SZv&?NS z>AC~9yLVHh)d|A}q$;_EbwVX`FIFhxdFxUIYi9Jb-cLS0<+TZxsve{ZJztQ}Tnl0O z_ihw*@)-V6-y;w(K7%a#JBdHf_;|8!`D0&clm28c0C_94*7h#GyG;fR*0xaPbOVyZ z{!iEX zsWAkrx~nO@e3l!1%*} zLNw8Q7#|1>flkk}oQ#1nzS>(X+Mo1(c#n(ScEaFb5nZ#{54Y`kF8JNjP5-&bk$ssf z;M}W={D}sWNX(`xFpp?M!8#>4mt|BRKFgrjT%7T~3*SV0?Ee-qUQMP8>~uRz|9tyR z6eV{FN8D4!XZ+)Ev+STiYgs4N3Y$doj@!b@PszMalh5dUOPpw@-QB23I>(iQ49g2_ z+!c%^0~A4cp@R;T{lV(zj);2q=CT~hoqJKRWVQ=h1%=E@sSGlG&D2MF5{X-23nTqb za48oo*z>iVNT0RQ0y0(M4czSXqn*{|_(}RESYIoSIs>laP=m>UOBqXf$shc9)Df7m z^u*FRKDuO6MHCb?rz4?78~*2S4C*xvwC0fxNoutL^%>8(q0SrFN|WsjTb|SK_1gI6 z&m6(luYL5F#4zSrd&35sbF@ys8ox;);D0Hb>o4-gLuRcaeSW%rG>Iqn@bvOSzW%4# zT^mRn_7O_$$Uv_z+u|-yG5DW8k1ZR*$FMgn6H}xS zo1*aUbTRmTs*}FHE>2>T%%IrHlxO3mN)n%Kf(gm2)7H~~R9tF-7Q+O-`gJ|BVNn%0 zr$iwC%tBmq(G(Vpsik{=tGH4BHnYdQ}89Zlg=G&K%B?6z`4-* z$inFqu1{8nVE=ZyeaSGMAPfPcwz%?dih9IRG8f7ilS;5D1wR@!0j&Dp&{8Bz9#}cR zpVxCa*O7c=Q?4$`1CD;nSgeD~Aa_qbojOUMY)-SajZ*fApdrsYv9*+ulpaJuX3IhC z&P%E~={Gi#ae~Z*aa_|eLv&z%ES)eqhzc!#;xci@-Z9Cdyo*9|bDg3v&npk9+&PCI zFEe7yqBr!=tgpDYApj<+b|as`YW%%)3%sA2Ntacz-BGC{T*|t@nf03ENT)jjrLiAq zdZ{`oRX@UbbiP!t4@mb*1z{Y&9Zf|l#8j>n{O&)Z_n(xI8rF-Xd-FarV9#8pR^D(t zq_XVL3PbY6GX?aO-O%uiEUadt4wh_>^m?NjxtC)HlEgI8K17Foj^^xh zbSn;}QcrG^D{prT{U`rM=c;1yvC5eueb$=8JZY!AnMYlYJFccj?z<*|Yq#e9WE8$MKIpE3O83IS=Ue@2FPd*JcLvPLvZj6c|{_UG8F!}kB z{&!~vd9>m-xRXjclih|I$88s;zV1d{5y$YKj9!7JYY**XnW?F#9blYo3t#da>q<}# zf}fSlbG76y?!O}gUkzL6g$jLQS=bEG?vg0TX+QpJBPE)vm$n%Zd5IEOQtg4ZW-tXRSw8!S_Q^{FupXmX54~&zIX!`N|Buz-bMrcU+}emz;6Rr0*h+bj>a?qP+Vk z{I3huHs&`usI^PDKUNuAM#SN~%Y&lZ;*JG6WUaCdv|qWwlgb=G%|(|*nw&CUlSDr) zh3y>=Y5mw|Bs|4h7`FKx+BhK?uR1wWq|Yntf8%HF&hX{RAYVL0m)u_z4Gpm_=z&Wi z=Au+!AIs|gIH^ry{cPcu(=kqaiUoeKRvrShdZ_KT1!O^c6Z~21PhD1A#hRO@z&7C< zI@x#_d#pPGCO3{P-Rr@a>a(IjcT5Hv@$(%XqhtbZ&_HzzwaJCi?000_GfpA;2F}>H z86pRs(w?4KI#fTu9PvaepZ93%te%%R)9~auL2*l=kzi2 z8p(zE08b}`tChDw*T*%{FB$!G-SAiJ5o!((qKoKT1;%JvGZkjiV$SAvAdY+cK#tk zvE0*RVenWx9X&&jNGIn(ymvgBl8}rOYbL<2op0#tUTNaB(EFy_V|Ek_q0j}_e< z-}a9n*LNV0v16Imh5F=FQ41Kh*r7L?7x8yBLy=Zj&A*G^%qNiluMK(KeT*+p!Z4xq z70qsvCYkdcAW$)ht2eR4SGgiV;+$T(*g%fV6k7#92Dek=xTCo9%Xk=0uOg8} zpP(e=2!B+x9#Nk!fI|zS(YY6V+}^z$HV?d@eV2xCK{4x`>L1II7DKc{>avK3pMLrm zPJeF-Qx|5_9rswcDRb#lH@rL@B4C2Qnf$(%}H)zEb7{rHd|b7Wd4t@0h!Sf2JR39aU$3R~PU~@}>V|1*GP;f^b>QJM`kFGFhHq z3LXa^QB93v;$X5qO*e1kjiO#v52GFI)Ce!BYfbdqR)2i)u*(eR12z)>x$GmfSHLY;slq4Do z*oT8|NrPim5AFYpNwHZ21Rp#`Gfx;1ia0Kfm z^1P>^7fGd0ANV}f#EaTLVwExj(cZ&TSD&2y&4*ER>I4=`dT7~OITDh#1~M`u`EKWR z$l{!5@IAi`1+ZF6mCXz-)JLoh@;%#0sfF@my7yKLgNEZfZkQB$; z;AZ!b9x`Fp| zTi`|+^Xz?nO}Zt|3LhqJM-Kdn_yx)rSjl~)nJiD#ndb|df6h@YvudolZY6wQp2G$B zd*iRDT@b@|YgbFeNZ-zlpnp4yKTAWGD9rML3jrReb7?vbAiJRJYZ`4cDkJwbEQJe~ zMWTNvZ19Kg;?Q2qdSRY0hP;n26on|#^qs29eixq;I`F38*uF^o{-Fd+zSK#7zLO&M zCEG#9XFadWT$RKanZuWkWOVYdKIzMN3(23a@F#*ExtLZ1O}j55rC$Yj@7Oh>8C!wv z40k2^g6Y-}PWz@cGAU{n>Gm?-cN|@~1BO`MZMs$!J}5CA4ycrHIi~_~d-g-YY1Z$s z#!jCcNPi1MvLiu0z^Pw=xE=7d%(swbkW< zk@g?x;51pXyqtCGbb8aj#gfZBUYHAyf(G7Oe-)>U>lLhc-brt+(FMu;;@o2eQGHx3+5mx)Yp`!++$j=4`DA;Di zUGOhQkF7LB^Y*oGBZ$ul0(UdAsQ5O0q8a`cnu8Cc!w(|xUX?k}oyKmL#btQ>?q%@o zX&d4>KE@>%3G~xfbZem$k+Em&+4tADpFB%kKcPfmAJ$8YLPn7OCJcsV8)@Clqj+{R z3@r@vVKDF5CkxWCbfAC;j;MzjOiUy4TJ>^7t}ZzXWuFX&jWAT0OEokh*lg(S>HSr{pmkCJ|b;Jb2jMH>EQ=^)+{5hT*^&)HA# z@X!_rlgpr!-m%==G#9A7c7ZDjHOJd>$_3YLS+Ch-)*}|`0QT2T(TTsyiN!w!;qu&8 z#`IGr-;dme!xJ9S+L$8ZwRM*eY28C-(ikVo$rmpFt1N4)G9ZOgH(|p9HzaP#db>7^ z1JBAP+ILlj%+fdvt7mND7Vhsrp{r+#H2hhnK6xYd4q_zF)7e*zNa)>qcx&g1HoT3& z$sw~LWPKA|U^PZk>d`JXTQZxDPUBRgxWM-;+g)7K|kgdy+>5Y&{;d+wG?uH zraNGN$!x(UwnJOIo&BcAzhm5_WNwY00{*f-U9iWzpPpDUjd-}-0VUIi^p8R<`B=J3 zcrvLQrA_z5Ua$HEqjlIG^1c+wZ(%*=I&b(>59*SQ=g&cqhZ{QNREAY06u{>f;|46# zCzE5|!OSK}q&sIH{(D?TG-GQw@W^?WdI)&#MsLhxyKC<|;HvD2tS^UQqZT=s#P6h5 zSyIG?^}8KeDaR|X_=uaF=Rn)YH`IHkKJg5G2lk2=knYD+{P)fp2&#HYWtKc6-g1Y9 zUlevC*+e6(BvB@sw`H7P;a9dB;EGB*?Q4}Jo0%8oOU`@lh`b+`SXwU_VbMba#>kVu za%ON@Es8H=p+hP@)UckZHgwpp7$*z%z_E3=7=!K^35z@|y!0Ur*&jTDXO<6%X76{a zf8$;qH+b{ahvvPB#j@*u2_DVwq@TxX5%Gg|p!EA1Pdwoh+PwXWXx_H08%NrQ*xkIh zf@U`gNa<2`M^36mF4jRfWxTRTw-?9{;dz!vA!z&;egb2_=Fg0SY3Gij6+Q**cW@M( zGHa$)rzVi?e{G@ZfE(95#~jyzf@t2}7d)SwvuK5VbNwkzOTZzv(?CD_4V`#p2q%9! z3J;o(Eme(XUKEu$XfMe?r*+@qgTwPhx;?aH0(qHW3s1zKa{XJAaLcPLFdjXpl{&A< zQtz`uxh31t##IyXhKbBq{J4)EvSD7DwzIH&Zz#RHuloOJIuC!U-~a!c8Iek9?;;tA zcJaEd3k^j|5-M6MvMJH9m6FP+L>d$g8baY*=Xpf3Ba~HEW=6xiQ2nmY`QCniK;5Eq zp0DTY@q9e)4=g@r1Ej>Javh6(@xy1W{QG0NXyk4&@=nGa+!sILJ$0H#n$6rnI?n;g zk9mOq>)H(&vy&;EoI~QL*$Kvui9+gs?eOa7Vi1r!cm-7wB=3V?@+b&yPjj?)n`7LTakAaec30)|IB=(@)E!CmgAdX!=4nX{!~C# z^^Fzq4W6NYexaDDN$}=K9le?L4ZpTH2OhE=X#Rz_IMCA!^3EsG_o5F3>oNr2{|!u=((5|Je7-m?E6pkM^^@eVaY}y|;z)p4^HQN>qh&JNbtSN!6%> zDG&d5&ssv3{Hy^Vb2sEbu41aD23ITUXwRl$Tv{0bv28M3_Z)R{qy8RD5V?yq<0`RK z-dcElq?)RUD3D~Py<~MQQIdPL?XFas9htI(fDCtvQWF$-aeoF z`1ulkZq28^Jt~NQ=`O*KwVkNHfMWAwv(Z4%l33QkTr zj@}zy#8F)`aLbJC-uEPkZt_tm*dVR9_{v4nJKO=IKPcf>XTRdYN-en9RZAlxHAqfi zGg$jvLW-SALJ8^4|j+LC<0ZyzSXF{3YbK zkU@H$P9usfjLDW5uV=Bh4^7w~$G6bxrHvCOlkp+1pleq?y_&%zr=u(de(B}NNck*Y zsxVeK&mFlTEXRo7VVU1}_ntG3$Bh_R)#rwyWS`?xd_`C;*FYtiMt5keB{+od*~C-o`cex5Lx^aw^r8MUHsc2|N$4MIY%5T*-W} z|MP4|2M*!2=K>*g4x8r_N^#GHjj$p)m6KoTi!Zi+;amDJ4@rYKX}oI*amSzW{w-D` zNyWbKZ2fWMQ=5!WSlWPtX)={KXNTSV#Dz0_=eHqjoEr$c=g8C9Z^iZ9T6_g@rzhZN zh7nkBLjvRt+UPCjV+>ll1J>qj&~v`1K}J@zGMzk*x3^85Oq72QdXplMYr#|8R%rwc zX61B|#V}6z70BNE&U3c?cIaV!6YZi*)7JThr!qc|h*cVWw4?-wnybQw#0;)rZ3sT= zTO^#@L;h@^U)Tz&fkS$29NV`Y?+WL(hEEH1^g~xomN=ZLK3% zbT8(P-_J%Ssndj-$=q|y^WSR-hc7&)iHcyQ1`BU;W5W01_w!x}=XPwT zIC*h~u?`%z(y&i1*mloMux_tYXQnCs;K?DJTXar1!pYY(7UsjlBn)_D6$~v ze|PFv)qzkuz9_3AK$9dtegMkx9_V(>Lwq=EDlGX@Pra6mAyujNuxNz|hl*Q}#{o6r zJU68pgm|^W;j}P1)mn=j*z^JBZ+Au3Dy-MWO&!{%*3;7g!+7%8Aed(;%eAahC$TO` z@OJlI^kngSJdN>cY_`|X82=J%c1;y5wfwjW?0}buJ{4-+8=2P8Sl$YTw-UJj1hTkV z{vn^Q&`UKuSw7J#3v#>i=!Sz8uke-)^01%rtnB})lkrbmA)82|UH|RICJoZ?;C3f9$j~E&?`pv= z-jmkY@o*c{F;*X!KyORJaQXSs@MBFIee5nyMAkX6_YNsN(`y$QMU1ysf~;Z-GKpcnyV44^1_{b7RxkkF>izkQv+zam88mCtxP|BNAH-7R57g$bI*I%mW7?u8%Ulj#vJ9THX30Da@fptl_dam#WEILk6k zCQPqh^eYIydCOA`D{+0Z7(c;HG6BC8i@+kWlHj$njYdby6I0QnaK+SGug6A_ESqTy zwjb}K(qVP-SGx@$Hjbyz%5;?%RWR#N1VTN}u=iVIp|0ZMGK^;`2ZM*{d2Y&iJ0yRi zML6fb81!PN3p+tP?J4_?l;FrUYS6qOlRG69f+csB2=(xvJ?doZtTyHW7}8rXUXt{m zOaQy?Ds<;nF0P)j7sM8((6KSB>vnB0=taNd?tM1E`>=qo)z(eBZ%B}1vaTS5PSWu! z#r2aitpxPJWUOO!6JN^c=exAG(G^skyl8HPe4Ujjmh;9Y52nInsTLY}cpH%r`35HQ z#CU2_6UltZc<{Lzf&xVDV*dNtj73mOf7}owpZ}L_d8)}Bmd!>NGNudtffjQaszELNVnfVZX=_@ugBZI1PkfPdwBH@)97hMZJ)g3{3^XxnTB zGAr4V^_;4reJ1imXLS~=YR#t)^R-Fya6Q0gjCd=C@h7QZs0u5}`o3C|w0ArNqXecc zFL{XVqNl;LBlR@2L5_Sbwuio`&D@d+t;qkV2LHtAZu&J#ome)ug3Qt|dXn8kKi~TR zJ9fFCN9ob{mW2jz?R8W>WEd~j4u;aRvfQY3>g3)~GE97W7ybEIiARMZ;hbM{S&lq5 zwuhnNC*1PI4){*xGyeR?UGxoKo&1*kBAoN8)w1}`$w&N4t;@r)hu&Smx$-C zFcE4m-Zn#ILER<68vj7_qIe0O)y?AvOMInQyeqM*>^2yE^*$|%7A5br9AT?e3-={1 z01t{Z@Sm~H?)9v@{P#NpMnnzenL5uRUqjxr{8tMKXimdAe{7+>{sAo#w2_~~fr7@q zS7@fYBaTx1$3Mkbb8mkC!GqQ(A?FP9?k4^wJFgrNjL}xWE8DN)HB0{SJ@Q*=!Fa~P zJ!}oPwIlTK-d>b7E1oa8sh6q@D3K>J*`V+;k3JZiMG{+g3KoZ!px6^3I5K}6>riW< z%4}~RQ91z+FMj7mvYEg0d>kxhUQ;{CXE?8NB0OR&5vj&8U4zW15Ve#|h9<@z#Y~YDC2; z4iv9EL{}6)BvJDP+T`HZ1}NArkE+!UVxu|<_`sN}no^8W zJSGIbKbNNt2gUR!7x@XIoE352?JGFYcNBy%#@(|6a>Q^e%X}4B>b;awBnQ9k1?80c z=v|lwDSh4!pU&LmP5rJ;kVg#^5XvHvzVrt4C95%Lg19|c`nW80NU)> zLSIWTP13RlDLEfJ09U4n^30Y`B&io~ zft&bQc0RjDy?LZVz@FDT&UbLsyvzW1~Zptz$M88a5Qa=syaU(VQu zyBKqOt0U+q#&X7zd-1$|Is7p0aLYteZOxqH&Ij#Xd z+gk7*GEJ;@M*%Erx{A8hUg5`P8$cqtoZ8+Q!u%7g7m1s~g$+cb5f54ZH=`apjrRw; zUo;oy;$N^#v{Uj7aJiMuaeL0;paUyla7GL`K~v|HFt7_n#>Iw)+uK03Xa&DqEb1sdpHXU67y*w z;|7>0vs}zBgjTF(tjI+nuz#Q^E2>U|RLVbw$WRY7O6(!NSU(*cgX`(IEY?+|;{fB< zZsLw?X+bBFH2Hqw-E{v?W%9VK5u%IF(&q~_iT1Y-ux5uddSDoh1#2|n`tv%P@q>qB zP8h?foC-Z#Hrr2oKZO5&-$k<~RN`?rG1N6zQ?zk3S?Ix7xVKWd?SJgCRCpTSx2TKy ze$*fzCwG8lX(BiCiY(rG>k+@hv6sr7oJUTC<-pIA`E>L<)-7UY%+7%CxkvGyc=+TG zp(eAID+rIDxUvKHKH1F3BqR|LpkGKVWVGTV9^fdlYFT`qQ17n;Hpu`(S0|T z=$Cr&EP%W~ zq?Eh_FIJ=clLI|;>8A>u(6$v$Y2K%iFGL7`)=~Hn(Zt2^0`L(*13$Bqe|*n`R%%}&O1^ll2cO6wy)9qABD+zyggdTci)H-SC6=>J96u85Ix3%REp->{Cn! zlt7NFr)x@-$OTnxF;sbZ@dh2?ptC5+5HzBz9A<_^1gq4PLVZ7l-D!G|;g&&v&zj?u& z6267aE?dCJsd74pWn`|*X$0-CXWWZj({Tu-3wsqUqj*@dh-H6{?4XuaL%6u!2Rys0 zxrJ_L@W_cC{`03@^qm3gX3Ai94bvQ6(d*gd%H0!Sp?U;m7S`f473M{cucM_!TEu6t z0cKs6LjflbV9^jsI5W~gRUCQvaJ&id57h8nrqz($e=G!A3ExrW`YZUmy%ek{XZ;Q` zqsg~zN8!*v3q6hd8pQHyCrlZ<$y+(3P8O(rg!3~a(b&F6_zz=cRDCLfb~J(c zab{eF(E)UAHRCz0?WIQiE*!em62>R6zNhwJ?CkxHZ)MIpcbFd7e7X|?_l)TA{Uk`O z^*!kBuR;gia&YU>-E0p}ro^0wy@O0(?}B)4zqbMAZ^+|2t?i+buO-O5a!+_@eTtqt z^Orbo+$pH`nSj-=$KlNxKlslBST4y!gUmPUgjE%*kjIJ>n7B>{!wD^P%UBcA@Sz`e z_x;N`yn7?TCpCY*S)7w zt3*gM`#!b?-r#oKw#Dn)dBPj$h=mAQVYD9FFK?zJeNK39+H9eIo_SY`sJw0fAG002 z;VO0VSga7{uDON+hcdBp`UdDoFQZ@CT-{R4@>$oWaEEN7QP$GY{Dp72>F`D|qUNz1 zyhAc*g-8j0pgIeDUu1Lt`p@Ex%T~gjZ?&{1TZoXv}rH*p`vZVZ|0}$BA z6(4Uwk7BfhJGqY5Tw<^ap z6fVBU6>gBl5~ou5V~cy~_2YAipou5cUaELGxci?8?4S9bn;qeS=lvQKYA>cXBE)#I zGferflK1v9^DV!+0=N8*p?mf(@tdBpa7n&_dNcoksb3eY2_A(kgLYvj&Cx>bC1=T6 zazwiUylUNPae6j}pT^KAErHg?UcfGLW8miLR;oWwgqXc%+RGgYy~iEFWP8IGAejpI zwuN=}fCM?0n+#U0;7pono%#yJmRnH8tt)=Yo8 zcI8#PFF+KE99n7c*NJ3wwmq~xh|!z>u?OY*-V)wJcfOiPuDRrZ``_2pr7V*~=U587 zTZ>S5Q84cFR)q2KE%XiJ;0;Hg0`Idwcm?m&$mhUYkdo|y%*a!GW7=dGH?N+q+clAt zn%TqCQhP2U&kTF}E5I)GPWt2bV&ZtO5i+LvQA7HYEc{?4Fdr|9`zvnXo|B7&+KcFm zA-t{k6e!L1(f!2wq0IK*f&&_l&^Uuncv&EIH)W91x}IU$5g<;COkemkLY zYdJNJUre%e8ewJpQ!aMtbo@;wQ`oC0`YQ)VeAoikvv<(#a;ytr-D!yMso}!APUCRp zUf~{|s~}6B4jcvFA6dL0#*FRX77Vs2Ug&-AM{JfF0iNsX=-11ON!i>+(ElzT*kZhNrOCl?$?OQl49oHaL?GG zm&oRJiFG%e-x1Hdz}O4BnC^GnArcM5J;dv@jUYO^kd7b2!!P@{fJTWK_iN5UL?(35 zptF6HlV@`~$qM@HQfW$NFy6YWQaHCa#A*<`&D{_o`bSSjPlCv8y$^%KRp>!MHXe7B z`NKt$Y3NIqr%O8rGEEiSQ7r>(ke<(PGVY8H)`GTe6LFGN z95!nl4k|)`B;a~4r zB=_t#w#c6c)pE7;>aD-nqsbBCrm1n$EwWKl+#LSnjBfhH?+@0kUk7LACDGX@Gzfos zH+T&@qRO@5_`vFAObe}}u?GcYjLbnn*LljF>deHtrbbZF-h`Ize2p(Pt^-%s3i{gi zFMgls2x9|dxMR__I69NhkFM{clNK?4&hpK$7Pe47M<-l#WsXo|ao)L@jH_*cW2?-0 zw1C~CuM~k5>sf$`OuT1>5ghC*qX~=|J9GFHh}KWxYA;2j!elw2mL9xcjKt^Lz_o!4 z8Y;=|8kMu**>E;DcuiGM`RQat9NXH zsfTXSTqWkm-g+8N>R#c>(zY}1biPny`L$Y>)U0uYyuYqgGHEoqygmmMf8^0GQj3YY zM+0L4>7h6CdH9lyDNG!Q$?`j4u7&{tjN*u#j}&To?1z^N7h2~ zd1u-jlZ_+8wg~s__2w7wG!X?TaBHPc_5b47G0xyyCayR2Y%nQz?SK#I0Zfx4M z3KBwU>GcE5pSisU%nYv}r@}=1Z)h7BDVEaX2fvX$_reAKihjs++!EZ{C*Wu9|4MgH zF2y!ew?WS01iE{<{QCEP_-Xin7ROOCX6b%GKz%F{Nq4{(N<^V4qk~q@5+j?^10mQmgicVqicK=b zpfI(SmV}Fv-+i0GrY12A*08iX)3q%h6yw zdGiFwc50!gtyuS2-Wdq_{)6{lnHu@{`!?jtd!p+fp5P}drhvqDB8p&+C4etJr(5k>sc$gtu|Hs_6a45l1MRP%2JA`vP5RZHATf$STaysvbCdsgE zgzUFZxFnV7_<;LM;SF@D>>unEaUO=6E>ZzwkZNlAf*`+!%Y1d3`N8`6pNhMv^-pOM z&fdFwvR?82m)rf469OwIoj^LXKjJA|B=`-pT63LSezUO3u7SA4g3n5YFwkX(A-{f-9&PdeVgsBgBIJzniBk;;=8VSoO&-{(rOD z=%)7LI97Hh^fWcoy)H&%ltVwv@fyjQqQ~@A2_8IXk3$PoZe#U?`LI9jBTY&h!9N&t z%w+N+Zq?o_B(Za@Fn2j={U1E*TY@>4}ov>!WT%k_#cakO{zZ+n@`gY!vGIg?lO$lgJUqc6OjdT6%e@CV4WW5zdM#aqZrH*l_7Z*!!v-`CToe#b*PbNnz)N4~K6)D`ZD z^>(~nr$9KX$0f*+O}A3_E)9Ahk(0?-v|tuQ->Rbz85dN7@z!FS)^XtMCTasp0ZG|!@Gx5{v?A{3sZ&rcKDt- zBrAbJ^6WesY+Xj2;ef#8a0hbz?2emMehcTe;dIt7cGC%T9pCXj7pjqp>PQ$cJC1@I zGI6Bec#tivr!KtXq*z&1@H!u%mY3FeNKsBWw+H91C5o<}z|GZz#$z4^c8ipElSFFY z&f}EdV<5J_g~r&7;JhBzo!2I&$J)Kf_}d-8+pK_F$9ChbMyp}#fm+(Yazh6VUvUFAmXz4tVJYQ8;_1gN82?C6`45p))L)j?_ite&(Gk+Sp2wnkdQ6+6?_( zL3+Q}_Mj2JJHolmJ(@t)jiTV`{hFRO%pf8Atp!ceMM!F5Fy1zQB6u6M(5UDkd}6vE zRNnl_`_!dItk2(tp&Op4+w%$DW;qq+mDSM$nd6DXS9^H5=@6IhyAAi1j0H8O+YGyE zkkDGTuiiaFpLJ^!UCnB+dvXH(Y>C0)8`WVsyBE(Y7{dRS`N7cSle*{f)kx9dyWm&z z2%SFBh^wy=a9RG5POvG#a~$S_u2l%f@4bnW+5Wi-l~d^r8YF?`b}{Sj86!6x-zt73 z^dhz?Ymh6~`EaQxm+o(1IuG)L6_Y=3pXZ*&x`F}zw1h7DjW0#aPqOZ2o0q(sThz#5 z<#TY}`vj8I{eXvQButB~rKeVCkOSe3P<>Yx9sF+}?*1SJ?>=?V9~YP>_!%7vk?{=-KW%7gV?6^!Z=lD)TezBe@t5r&qV5|$TfF*5F28oTi-yisBtwjO(s#;%o@Y0pTNd+#v-&67 z;R{zvvF$8{DO%T&1Jg$4fiXmMGL{8n2zXohf$6oWoWhnUVB^ut)N2&|6VQXa5*Q zMkyVIb;k`k_v$8;S+Z1^!K_o6L+)fWK;Gsc8pD1M=Ir;dD#Qi3rbpsG655c+{;Uq; z-*!HH3JcdKB2$YB{BrUJusl~oQ{zUF($fxLEO@{rYS`m>K3V*)2Hn(?=Sdp&2uj%LYj8|WDNKi4h6Ok$I`0tlteq#vhmdzN#wO^be zM7*4LIY*6bRK5x-pO2#|qfC4$U;;e4#X2=wt?<0P^1_+?e(qZ0e5@JdjXmkrU0S4S za~>RB;f0nvpU2P7kA>+aEmVRr3{77-Ln$Ywr~5jHgkA22E@cIra;po^Ro8_G-&)#q zT!Z=W`{24v1k%e-#5JpS039l&N%bE|uzG+%^Y3AFEk+CX+{@#CO8rV5#Y(Z%eRHs2 zJt?Ca0t$DQyrwbrFGz=@wZNwBEs9ME!j;_aq+}wPNghMXRG;9FVbh>Iua5q-8%M6FJAhv3LGH%DRvhX(4$Lb%Xxlao zqJ88u*h~0Q%g;+l+s$go;d`NmxEMUuP6LdxYw74$L%6`mAH2?-)V-6XM(k@6z((mY z(mGR*=cN%yi>;vrhfA>I3}way2;r21Z({i@Yp`2UPD2bd$kiR6fn!|~eh;SMfQl?3 zhf4g2I*GOdSa>{_ae7(qW{p268hqeBRGz{H3E%k}nS-OpX%sQGcVsN(3|^cG zdp|>ioSgp|tS&{NlRfuwMywIMihDy1Pwz+HoqL1~lSPcN@7B2oX11r$Ra$?Eu7|B4 zsHqJpI|k$54j=h*i#q6F);;1i{g8n5By;~6iIX>flEM0O6|%%H@$_IDnAd!dW-ZZY znns~;CJ!48;dIUg)DOB)?)fmu$9n|gJVo5IDi&L$jPSR-X{EIP7&$jzO|U#P2z90& z!#|$Q63*o4UF(S3jy|~P@GIxzZgn!w1Yp6Pn@DEuE&TedGI;8JqzXwxc+7Pds9&eb zU6;;6_f!@LGds2OhH&pjBf!`1(K22b-X6RHii&FKpHmrFtH2m8pJ+nzE)-V}t^+xv zQmX%O2+xUif$@^pxqxCD9CV>s{fhX?$roYeX#bY`Q1aA#iLBt_6K zXQ;l!r+F+VmHT-CnAPWS7p+3D8SAw?|(h6*H~F{nRz^p5}#gDl>4z?TMhgx1P2?b0;2eR0R!`&g7e4 zw8+ajH4xf)9La8s!L!{oh5K;q5X&H+3jpusr*!}S-+9yTF)CTwfD<(gVOqimdh%)s z-qxoACz?XoUGgS=SiB1&G|Q-Y!0 zb}FcXCvq-})oH6Um-^DQ=MFugbygS7_8OW#QfM zQ{ZnrSiT8z9q!Q7TXfjgV8HQsIuY@s=YUyOwZRGmP1m@T_A&Uj9mehI! zJh3dLi{gjy*-SUM$6e<(r`q6E``_^IS$5NHCF6+A5+`^fVNaV5AI0~_Er1mx&9w5I z25~>q49~u9=T$ed_w>~jkXU;iJy*)aFy9nZUY66kRm1qhg8+C+rg1%0dJU;DGU>cgQ3iwRmah-}GIN|nMSa`XXT4rdFngo`yx~|0eeE*84J-H;D z$vuXJcwO27csc$NZP`4GE7AhsoI?a>@|Ed(dL{f(O#lBBEKO<;xWg207g}{dTtE8$ z4nbqdbgbzwL*hsA!Km;x^<*=jzrPur!t~IinLEhVDc_*JdU5ui^Xz_6p9a5;J(1ba zef%J0E^K>U%b+U~D_fhE4`fQUpL?etJ5m9NuaeODqfSi!uG8S5cW;ypdTi`}FDbAVR+ByOne2);1F z<5yf_?>MtOiLHv7;H2_bE=olPTMj(quUgbc70p@y;A;TY#$0OV3`8p3N}!-vi*EY5 z;c~6N!acc;@d33@8{z_8z;xo8Lxl*kOTEtlC4aB>9q47MZCiNgc zyA=suKEQu-_P~C>yR@wC2)11&0S4^WAI%@eo&y1pQWQYv?UB?kQS}paUYd$W_eJ5i ziIOm{uZ7y}Wm)VmEH`~9R8Ks(3yJf0Cxv@$1iZyXD5WS6 zzp$AEgD%Z<{R8GlJrxM=WdGxde^nzMf9}JEhGWROE(NdJJ_B}E*3$aAF=TFr1L&&l z<8Y5D{xJA|^Es30UBI#xp2@!S#{0#jCZGl;_a8%lUtPyVYZrsRMJ>JfYY0o;4}_S9 zr*vIv)rd*=eTXP}j5dyZz+>0y!{6%n^zqpe>~=|&b;O_LA_L>_gB!bHq`i#(WLasu z&n>We(^GDY+BEE;#S?N%Mi_@gNjw)mX9_5iXH2uFfl%f0k&7!niKmMHC%hGESxJy< zO!IHN{DSv|bG#VKkyoYyx-vmkt`BbI5ki?oC5=^i_kgnwu2i~agk+xH zFG&3~0bebeoI|JB z{v7`r+HB%c-qm=l^I{X&Ux}9^l@j%58l73RMlN@YgtZQ^^D|qI=N-CIqHX z^xK^j-c%F(u}wyQ`Y&J!qg7za{C>Y4E+su~4Y28p4yP27j?q|C(9>u_XIygdR>t$$ z(_Bn{Fnz0YL5Rn;5?WpB(Wq&A_6TC4dh!(h#tbIQg? zaGMujxMN@Q_avcS8iLWDy(|(bjg8II_zQ-6X}a%B(xjCO^#Qpw|E4Q`YApi0_H@w3 zob_;VYQF38=07%>mh$4 zP-1(vwj9p>)PcRMF?=rgNT0>An||<5<_U~MlXwaESC*x4uYSK~DVZ_55h@26KKJ-y zJW=H>zxdo&shAEqxdzPYlZ)faht;<()Id<*yV$bfAM?W*L(^{jD(ek}tjeMw94N)xYUd=E5cmC^1N#((Q;g;%Sda-Z6#;yW9tkZlsDyNK+&m^SWo(noi%>q|jaH_-$Df@h)mxuG*8n$W?xxv-cVtGejbKi6KN{`}$M-7bp)`+m z4J;BT%jP}XO-C$M{5Y%45T6pi{s?=v0S1a`c6Lls4OL6@Z_L=dDrLO|SNb1@+s zQaby9V5{~7y#DeHJUvVl{-=kCPjw@4erf{QPXXxg0S_!&HV0lUX{OsUbx3PZ1L&P@ z&MAyhCl?L#A-W(QT{#%fI>c3BU!-)}3)fhkSY40E0_)xIoQxTyMBlIL`+*X5;$_ z8{p=@B5J+46n{0`1l4m+apM(iu#8V3f5VY(>g}mO4)r;~jdnXKaCX401%k8jJ z+87p*uro<?yd6Ue;TB`+Wv9Ub=@GlM3*S3`1D^x0L!apTlF*qd@1};}*ys!E43| z_{ZG3X-@M=vQ2TR;0_t&ZrMoV_n|NNuW=v!^nM0;G?)v6vva9v&MPvI$vS-!DpAh@ zSFEWgDxBxt>~rE6w;ARfdc@n2r$*%ZV?l)7hQimTW9QPzFz09;6@TYS0ILfY73m?J z!kzfLyE3lm4ctuLed>b1!nt`Sc4@VRc~#aP$3 zkY649l@@+3!s?k;aA6tS$p=_AR_p{Uo%@L^-|de@TzdJFuXfSp_M=GAoxO1M!WG`_ z!s+C|`A@KMQ!9FPsu_RiiG~}dwNx`wo17hP08NDnNML>#8}4Gf@#!5jg!R?_8x;!Q ztU_pYkc586#Q?!1v#I#5Y!sfcOB%c*Sr)QFj{Npx44=#^ddm5ojN@>RzpuQPo~ay1 zdhQCqyH`NVM72pJ%NpD-cMf_7f4#(~KO@Q?MCZ@*ZA z_k34}S8ivyXMVBFTW$kau9eX;=1uB9+zx3f&$#P1rs7E_`Fz)zOoOtx~QU(7&&yp2_{QD=Q%S5_;PXyvV43{@7qcorgIf$ z(GT=6^MWcJZwIM^a;Q?%79R~84IVxnG*gb*v`#icNYXC4RwHAbVwk4KmC5 z$3OPaZL5ZGOtly6{OwBTEx&<%uZqENOe>Y&?n*3-)CF=y0cdl(JJ!sf3txfG7_o8bDsCDBD0XaDI=s^lz!*;eE)M@uIss6x95JH_j$cvV{$B#6pO)Oee*;! zxelAj3)Xmn{E>Owz47*aLD|t(AXb|~XR3G-m5W;Z-|&0LQT_r}{Imqd zYt>RSgZZSrwE-fR%;z=<9%KI?#ve{+UlL+e9K^S02Eq%YNt{Lhb#!Bjve2Dnw5FraxP7`cJe5wOrHt!-bVCy+e;07~ zKKSDjT@JP^uca^YwTSHZ4tSD2o|9hJgC!&gguzc6ViP+Nh7GBru05`Rrs4trpS3U0lJixIYp|zxS z@@Fvns*(L_MGpRVjCHE6l0iY5ckm@{HXN&}rO%Iulc`%=pr*%|>+Whs9}JB|`Vem? zRWeSY4jvskO^a_bFF?* zAQp*HkkIdihAU)Z8!c7nT+4KZf~|O3;waJn(fk|hX1dV8zGF^w&P5$EV^<+?^Sw|@ z|2f=d{y*H7|2@F&L|#yMQo`8iYzIDCLg3@KYO4BEiyXH91!Kg6(J!Uj_|%3SuxQE~ zdh~}L({D7uJVhb5bBPXK@~=Sn^<6Jb4KBtDC9J{n-fenjJyafh8lY{1GP7>(!{07S!!QljcXpKG z-Bqh$O4v#|H@cdP-M@wR-|`2U$p_;<(Xyb%JTIAa1nHT(9}I3^HNLIeg*If~5n=VN zIZ8x&Q7$|@&eJ8#8xl~~06}&uP+pfG{xEWa2&)@U2{7`r1l{6nLH}P3qJ2II^o)<9 z?U$1=T$~0ojBBaA+6YqS>I@H&HK+7?4gPRoEXbO7(b??Y8sgps0ck#z7i0d8Q8n=N z!a?*rEeyx4n-6-dNak`QOh7Bob=AugcKz)S>s|SlC@V!a9 z;h}aZUA|9?EM3?IdJ&Jf>T?tD$PXZV8rVw@6{wSz$uHrE8PFOX0ru6jgn-1`oObCk zoE9-C%H^IsAVzM+xWb;-X@b@JST|GLRrr(djeh3G;kwLyaOcl$dY$dieJ#4c`{hVP zf9%4gr$@r9+)mo+%#n->O<-xqxNcJcj$UpFkH*w-x@wnkXP6@VTGvM34~Y?vyDal_ z;VNT;6az9WNQ&3UN*1JS(IUN5y1?mVC|X={8_P2dZIeMB)gI_1mxiC^XSezx_nS6o z)|GFf>?yMyW%!NE1~4v+p?_A2k?d_QVARsZjqmlxRae`Devw^taI_a`oUwpEGRlCn z`op|kr757Xpc0k0XJF5twvd&XK;uT{6199gezaI3G9E?n`rT#1Ox<33#E$Khb-V#x z@}L9n!g2lu3Akq0PW{6UklNu|eB)C;bZ`^XT*b^3;d9e;Jz~V>kRwZ)b3&pu$?=fa zFnA~yEl!HYPljp2?`bu3Hq+ar-}8o7P4l?G*UykugNBGR@p>|hruBBhPbcqtv+G$woahB^JV|n2QST~{tSvfqzWB;;lsoSq< z3D0t>FMC74o^Wog>Q21=V6l+S`$)A-6-mz_PZ+tzfu0y}#3xPFMVgS_3@x%Dl706k zZxO6!Gqy3Vftmvm==*h+-E@8>1amJbw@rX;w^_m-*l1vM z=1AL_|1OPrplVzZvMyLn)^F$slO6N2ZQ8T3)=SoNx1iy&k4?o~8>k86Ozk1+w!GqM)1C@bv!0FzkIT&7F}; z{*mpDBFJE2a^uVq_`v^=Qi`aD{&R@YkT1Lb2G7 zl<)T=aKfnART2fFk#Cvlxp`F{}rDIYh>%Fk?#RAqeP2ucxa5QI=A3) z@0CPYE$yaDn%IowEbd4f+O>(V?+rJ%@{7EKK;-O6^$QS5(t+xS1hgJY>^` zYaIymhrFX_UucmGqd~ZEG#H)v8;=7YTZ4RXDSf+7mna7@Pw05cZF#PZ0~QnuW&ZTi z-xCD*@5(i>HsvO*BZD~p<_XxR)y#dC@WuSNFTxkhbGQ4R91$*Np3SIG!F&BlcjmDC&|oy6p4AMk94g2VB-90|K#5>SxJtHEa#MlUYf*#455y zxQ(wH97Jc|-N1raInj<%&Q6Xb*E_?#n^%ngZsh-PG$=nW@!?=X(`~{aum%rOvbi})4^M# zmd5@bPX0tX!>q?voc7o?xNTspXvW@od^+iP&h+gy?v(qnt?RplRj-eNi`MLXto?_51g@~Ta;35785JVcQxAvb zE(`P+m;S7*8>ZEUqIc^PaiPI_P&dh^StVacPu(S6^T|2nW^aS?On-h<~Ce+{_bY2vJRBUOakw-qvQ zT(BJ+Sd~DnUhqUp*Pfp`HW6u*V|+WmTo|#Tmwunmc7MtzVBnPp-5(N;M_!bK6IB>SPK@}Br}gc_8yJ@t!59a3iA2-j7ba;87fB*SzHA>?f=`n5P3H#cj7 z_=jq0!T7Y7StlT5mIk-?*)!Hht0nTtsGT1{Dpt9{yW`JkT#!4t(yz_SY-fELXM*s9 z0Yh+Ndyx0ZIz&Of5pKEZa$omlV5L;*$5zo?}E7FjR6ljs|O&`G^VT%B>y+d4AEi@NL zpvsX+Sa8rB#>>2@Oa%kp_SkxUD$qr{IbyDtvB>=r(9+5 zwk=OZ+{n1PiNy2IOStz5=-lT|iGuHT-XN|FB~drL;-Q2HxA{{no28WX_-rl{+++Jn z|4nf)qx=|(sLjBMBPKz7W-WEt?@PY68u6i<)}X7Wx8SKyN5kmrU3B3b9nu%v2uI5u z=9Q;>@>cdQ zWW5PSsTbmLQ{GPK^ed%?%B)N18oM(p2{@flZG1VoM5trdNAsiv*sNzQ?Crcs|FAn_ zxZx?-tlZ3*z4E~(HD86UOar|1=x|c!$$VkwLInCslgLv0Hi+(PM=@WTuzheCIQ8RZ`TOvAC-`8#a?WgA}hk}an=ItY`YEwUMuP36*utQog?7Qi8gwXb)7^QyTI*x zmyJKGv96$<_k^Q9_R%Z96v@kDFMz#zboXX$QlrQ?c`p-`&iP@Ll!;(As+DeP&cV0z z*1^rzY{BShnxrTy70S)MP;+|{E-Rh^?^J3j0$Ea(&$7qIZ|8>pvc!kQ#)F-I7cH8j zMna^U;k)Z$8YH1bOm^2pbo3##h!lKBx^wMov($4N;s*6~sz^DlPbs6j5TwF@IJ1pb$PY*muP3M*ms^Y~n zUI;7FdTG?&IRq}hf-i@JG~8wo+aEg*$}j4;pKV_F==ULE+xsrMvEeViHqs5Y2c!y) zunx`PJ~v=l=5h4!R4i7W?*zKutdo&tw4TWBfeI&iv|{-#JgBE2(w4kD@E_@TSqqi( zH&NFsm+<|AN?@SVM!f_6;=(Lfc)P*OIR52g(#ksSBMOoPSN3X=iwQmO#5fEs8I_0| z{5OEReLme|S5IDM`0~H~j-d&=Y*3@cFS_RECwkSo7`FzlgT!-@^p4FREPuxZHogA9 zg~u@M<&F*!RzE#^l;mz$$U9s&;QBX-lZQSJVcg_Ol-+nA|95*EbmB<*b~R6avmC`x znM5SD7h?tGcS3d2OXK3%j`-OrD7@uK{bz^c=blpVQLddDOSqFCl{)EA;Q6NB)iY9rB%z1~HeC~Gx>>Qx<1 z)iDF>4Q+z2rOoK&&{O<{X;E^%zNQZEncnZuDKHoo!THo$BCLMrsz^Gv9))d& z`{-C*N9;X)9_%q}qp}y4kv3N;{=2EC;K>Xv@++_&EL0*aZ zaGvRPCv&YQucK$j$BFimb4#H;eq+#NoMiEvZftrXSTt9!T$qak zgB(QJQ1_VML@Vq(_;SJAKH2s7yLqKBEV_p}35T#ls~h}2ZA%?<|B;vbt@*^Ss<>oS zEH=C12pdoCqmOlt5cdb_{QT&1$koQ29G35g7Yo(1J!Nw6L$Vfnn`Ka<%x!#bw>ku> z*U(GX|6sXF7nnYMDK}$zGa9K*gc-FTY3_9u^5<3~v_3vf4cIxQJ*gMS&O>M|T*dqy z1K547mQJqbiNs`hB$PXMc&Y#Y&L>Rz$Tc265$drcI@BoW?f? z{G%jagwIl`e#B@t;saNUqZ?i__+0B#p$+rihOeGT=DmFhqxJ&*@#_gGT)dsX*Zmg7 z?svn9Z4xkSPA9!^a{yM$tEwC~1Mh_ljU{l9Q;KX$71#1ov*^N4U z&0G%M*}DZR42~B0(4XmOljz0G8V-Gc?)aT7@P ztrk&^tLlU%ywWfXq!OzsDP|d%HVv>%RS9+a?ZxXdWx+nbgTDE69mlR70mnx&56co+ z@}Oxy%n83_+%N1vxf|{a_f7jm$5|^9@u@Fi&H~Ca)hKTn#ZebFh@C&Ebq5bLF9S4o3Mzi-dPI=E^nYe%-@nD zC-?E=w|qgL=3T<=t4D+7_f~o@d=U34xxuQLrp7&vr^!LDW*DP4mU(s;k;F;T{0WI9 z!HYdwWQSuPxP*tH;LVBH)OQoi(RxjF@6{6BC%*g>CC0fu-;F|U{}yr7no*@Vis|!v z&PLOIrY|klXS{dJd+yz8f7~F|C3LymMIHVgAs5LaK0U#J(`J3mb;r^~vvkP3`&id` zJ81lfpc87ViPbHZNtp5st>Q5Dcu*<)%AVDf+2UkE=NU*2^rm|zD=hmX8_3`LrHl`^0}@flw9?Z=B3J#P__pwUig&itn?t(O7r=@+4s@TXXkNm zjxqSL@6sy=E#iNJd0l(8InU;Fd`)o+jEZVT%agP4_nm9ttacGi`96S8PWOS08zQ(5 zcdfB}beZr;M}<0)-o9IY zC#EhFax*?s_1y7fnQ{{pY&%Wgy=L6bw?2?(K8V?iuVOp4hgu&(lCb%<3+> zx(DzWDN`85I>L6a*|KAaD>PWdaotZG*qK`(%&h-N`)*Dok4oNyo7+w9*I#LT%`Z#X z6Z46x+D{&P*#86fupN z(fS0Ce(sGjG46piA};@9c5HWs6|%p730&w zLl75v3$Lu&4PI+YsU+hVqw|{JzH|<^+*J$T33(&(xilXtz!O*5!i4AqI*-i{d7VDs zCE3EgUFn0jS^X4o&bpE^B$IXJpw%}7hAHET{<3E1k8eWbY8$YQ+f8_9T}?xlX_2EZ znxJ>75-P~B$HlsG;9c24r%u%;=KEfQ)NV?jKPn>`>$da6|0g;Yc^wa1E)Q=F+GuN^ zH2Hhq1x#*TG`^wGflezv5N1n#qNhG6Fg?Rd&@}}*o89#uOEp8wC=*n8+ZQ{#PZr^@ zt)?bXeZrxW(pY-S_k7N zyU`JBFJt(=32s*%M)rLnSfXtqq`TG7+jq7QiF2P}R8zgtY!yxNH0BZHYCS~V*URt` zmP2mw{tfLnlO|RS+xsKZxnJ|b@rUJm;6J8UH#0j#oZ9E|+ob<-{g+hn!kAaWi4*(i z=5e#hliB(3f>OFH^C*^77KiUFUpI#B!Y*{Ufn{*A;4I7ci+5x9&FB*-c2P9mz03(- z|A?pE@dwFOkGXuQy%`#*xD(SzMUl_tIax>wn7(@c-t~0<_EM5#xR39-+>a)-Uc^gH zl;K%dE3I5NfcYUe2=`oJ>^12GyO%YAI#I^oxrHQCN1E?j^+525Vb|0Z{m>_Q6V+%X zVv{eMAK5_OB_kh_MVozj_33B0b%kQ&sM8}@WL$}kJh+cJ*a04|B5B6)YI4urm!Hc& zL&m)bZy!@F+gtJ+O$z=na>_BfB1mDG_WiT`o!q(jl+R7P!-M6_=eN-f^~z-W zr&>@yKNA^yx#LlI4%}cp0-5X_nQYn&0j>=>k(rvLZN?j@ZHPlL|040{N*(C*s-|f8 zATBcXg{JwM+-k3<$h$#Tgu_FzGQ@YQ8zhW+LdU-FAW2yZc)v3b&{FO5SZhBAO~o~I z0((}jTiN%2hYqK=GaWb2*$Q_(no-!!ER3?(f`)MsZR=wh9ZP(nJ0yZr6}QHh+scI( z&VHn6Z=}h`P8S&cbvyl(>VUroXoz-&a;1n!U6A6M zGl%CZfU4MEN4bAgL^wQRzZlUsJ`4|IpHh9dGgvs@MC3yZWg2)3=BL|wtplaWJjW00 zY*-$39Mv>fhi&K9h_oCL(X6w^>;Md0-9_bY{UIm1cJfQls^D*(QF!MYM<`>M)3@(1 z*_t$uKUIAW87?#>QKS0d_p;g9ZqGDHt0#bxnHRcalYrMo&x74#Yv>o|5j$tcJfypq zaQ>1_=zX4v$mgQaGmZowX@VvFr|1%uBP4g01|PF774kc-2}%Kj&z&-Z22f z$9GYOhY;%sS)W>bK0VAdu8EHhz{UJH&hL%`ezmtq7^&Vv&8jAn^6Cz#QVQqpJdtM4 z@VW5NlTS4Ffhv*X^I)#8kj@HxOh&b`enZnYXcBe7i)*A{&C?EQlQY2fw!RRUTrS9D zUBCxhZiAueanu)>j`!G3g`JaXsmI4L@3dL zj1NUk;7iVd{0Ijv#67EwOd!Z0U?yLwRz2ilbh4XpZTw?{s{(P{$=R>xDp81@{P zm!vheh1)UO2alioTZG9VDNVApUE#g!bwQo{STbd(0gi00M>~GkW1C+$!B4iD?&6p> z{%{LKUQj}x|Fg$6fB%Qc$3qs7$U_BiSDVt#XJsUP@ecmI*e@ijcO6U2P=GQvv%M8a z5rtA0NC>}RTzK~b8YP(|9J7=?=UED*)bF8FmkRZovx%slCH7mV|4_zM~2{|{fk8S{G)s`;ex+F_rZFj#WR?nS1$t= zoqvdmUY1~xG6Rbv#q_s^6d7jd0`~TgxEJSc;wj?x%wtkQJ60behqW~L%KQJg@SUo7 z?T0+!itT;$ZqO`}rTiMk1yXvX;Rv3WEe_SBiw4dfz&{7wp|C7j;2y6*mb8RHqx4A> zs2GJO5+~5oi>Jq%J;@R6dHf(YLyMs9736Lbc?R+e$dahWHXo@Zk^WG|~k3MU@mVP|&1 z;npZxjWWsSoz{GNW+bZKfbeI{8WGPdm@tIri}{1$)}wS_j^eUV@AG_m-aKq(bQ9N{ zkcF)|tjoYfnRvI=L6rAQWd8gB4*4@j#5seV7SnRKh9{T6f=-9mF-MdEET zdSDk?O~>goKFZq$HDka8KTC!L-wI3bPcaUVyfDp%5f{o$T^2S z4G~<3uc5Z=^IQJ5Kx4WN=U?{-%W&HOn>C{d;Zr;>W-Y8~ETGR84dVLaelTieBqvp} z180Q26MC@Rr&!i6KjEGmBvx#v<38=h$N$q5&B<1WIWj6jieJ&|Ca`4ra*nMnU}G7D zEXxyddYn0|zb&K#$BW3y&b_>BkQgfMx`t8;R7HBcgk%_4C3c`fwJdx`#TGW0#!=hLZ-}+e zettyzQRJqy4x8203eT1H&^xk&_;IBNNUqyWU0(blo78OhlQk+>zLcGJEsk(F(4LOo z=|SF3o6C1~1)^IfD@bx#KRm9Om2L4#lRQ$%1-WW3l+zWDtwS_KGj=WW!l&1Jz|&7l zIFApF=-;^&qP?N-k+I}PUnBgQc9L#ddXUt+%;WbxPDUSeuHXZGOJRCy4b^7ZgFbU} zp<>!Sl;J_~4o5Q>^F5DFdB=R;2_8_}6~~pWa=?crOGJ3C+&7WfUF!r(i*U}aUK+bB zX5KWdei~_{O4dBjgJn~N)MY{@S)psqORBs@2Y0w&9|>vre!7F^D>BdiK0lyiD+Kk7 z7v1Wc2vft3BW^)DJ`yz*UX|C-!?h~p_Fx+{Dt+gwLs*vVh_NC)UehDy?X_=(tC0@0 zh-E(prk25)6<$a!ED%>rQiXA>FQk;|xIUltgH5BQjMMMe;G|{@J|)HUDW^>Wzlig% z147Z~mN;D8YXj>fO6d)zH|ue3g_8q0ocv)eET8s2JYSockFye(CMqnRs_$XFBscuv z*05G?g0c@Tc=}t!IiD1hA{YCdVcM>1g2~TElinKUC6}y0@0rhfZR1V2l~hIb~oG0jNI~(2#%E@VEsEpq|r8S#u3>IN=O!;X%eq z-`}G|L6V5yc#K&(URd>aU)mZQ;2eX)e=R5-8SN^h^`$i4g;I8ek< zewik5ZFmgQYrK)|%m;XZ%pCZ;v4-B6&GOmeTwtI4My_|71rFJw3U?oO(j}2o$O4Hb zz|IHg8!e_&@@RugV~-+T7%vjYGhB`YuNH# zK!I z3F0r_qB3TlWV)<|2*V#I@4&OVN5K@APU;Xip9Ed1g_?@VPrB|2YOiXM(h=XFuIVNk ztC@%mjJHG9)&i>Myc?At|3_OY`sq8}Qe2R|9cqCDXnp*^+1H=JhMj#P z+-{sKMrO^-fa&U$sATL%JbZUJ?C7he-{v74{-RbiKaXL)?ECA^z$3Rq^j&QjmUA5r zpICqT&l{u3OM`mI`85L-sU5%`~*2mPT1^!pUnJACO3B&=Xf z2|+vXd9F&tT{NwiCQ;|yMVS2i>|V@kX^DJ`i`0#YPO22&+T<$8!dgVM@3TZW%SMqomG8~eetTP=HPA@hW0 zzJM(2V`#^vcwF#66L`kqzpG~)PUS&}pSYB>yV!^nRm?=#o9aA<93N_g^^zy3bDk$j zv(ezAOOsJx>t$T>%McDTErDW^K3S~Y00~X2IWwlm{!s7&&Y!%8{@ux8yJ<6+;`xe7 zH!@zL>LC1Dc#FHzyccWUC>6S>_Ru+xCJ?nVU9czTCU`knp&wnVBoo-DaVcy53*lomQ{5Y5|&N{gcXp!+^?_tlpeT$ z{>lg9!k7sV^0b8(FuiWUW`B^glQJHqT8-aaUIu23MfBr$E%I`Y1b_8cC^{?~haFPv zptZDwzGj%#R@Dy6mI%1^-Up)Iv?+*bDm0&3_n-Mw7M$D%TgqD^J_pQ_#Mg~TZcP7g~MppM?YeO7MXOXopG(B zQSJ6UIQz~>xbvlh2BZ0899IN|egc|V`j+U5@8U`2PgHT@8m{}J2qzO;Y19b`BDsip z^zNTGK6CLs3VD<))XA6NdI1B&7`^xQNFvTw)*igMO-_No?mz-@v^Yj=TZ zZ*(3tfLOT;wa8-pWNo$A4gJT0>_jZzMAIU*X89TBBd;nq<|gCm{V_ z8d4}J#IKXgVCBL>`sl|na^#Tf20K|*61LYAA+jkO8Rf@pxA2>nQ&p0~% zya(a(H24QI&Cm$b9e6w_LD9KRI;5pXdLn8;IABTN9Rl)OW+z{r*MgcKU%+Qd$HHaP zR+<-5g0DEOVqBIQ(=oEVg0y;wnXP~yCF?P7uQWf)_@3Z7(;WV6`3@c?;poM|MC@v| z19H_1sZP}bV&C2XB&>wn7ix=?WQGayXlV$ z6UiEfkKnZ7qw(o{rVmkn46iIJ(V8jUIJzqwcAcxHv$Gcvx!eZ!u1!SB?>Q`MSTD55 z?xpM4-S$I*KRBBlrtJY?_@$E^r0r>=RWO=dR$)8ku$icscf-d@SqC@UeIFdIMc)5y zhw77!IlI|>rN+Gj3(0ttr4)&mOj#h}G#<=h9Qz}G&|Ip;sjYj0_Mg@ldC5a+Wk~F` z!%(~ADGhitjvO*<2c!JW$nnQnTqRCK_*^!mNh+8xNqdqm7ycs+AGprCekM1gm8&!H z6@zsU_&c9YG9ASCbNwOrUL<$PUpq*i7tlZ#PUnz*@U4*5XAk8$@%mWdC2X+G8*OpWFoe>ufl#X>f#IJ3G30 zvpX^CoyU8LokiCJ7Z6R~1{hmBF58FU^Y*o`z_jrg(lm?5epOnqrHtK8n7?U95bI#_ zn84jX--wQUTPfQ8b)OkS=I633o$3?x+Iml7v`Le%=t@Qlc3#HUvW#GkJKO2FEFcwZ zC)L_+!Sy$5lCS$-L0bC@tS+4d!!B{7Ii)sMjB;9FddU@tb=`&Kw>Gs`ev zs!AIFbV5;T7}wJ$g?GgXgwbRBsl(UtdA-d7AmmqtV640*F|xT2J7Z6vG}A};VeSmr5LLsp2dZR(VHebg{p5~!Z@{E+ z9MfENQMGG~p9y&nCg&aK43<6h?rbHrefL5q(gW~8)^jm7xP{(O8pMAO1i-^cDPs%s zDm<8A!t(cu=(4p+WZt9(P`YvwEp~~;13r6Tbx;WnVI4YK+TVkZihxVLpov$^suZsF zVcHDC7g#047UU~pY4wOfy#06pq}Q}^9*a)nb?QSx2ln1M#S9}AY`=eY_Z0z=l_$1I zm7q7h46V_x#ZM1K0CZGR$-B(w)%+ez6-FcX+je--I(b-~)j@r(>k;*-#c)JZz;a^W zk~mo#UhVKNv~kWg{IF*foIKM?f9x4X<~h4UZPq#C{nhPgXn%@`_b~PxNgSN>!M~Ey z*knyI1AlB5c3DwuL{QI zw+$e_Z_ISv$uwbJF8Y)+8#g2_|OjB96lkcIh7%akjRYfkEt zOa9XQ$IEvGGh?)f1OF4gri7#8vlH>_3)YZ@3#p3De9~R|{~aI2T+wtJlwdeaD0Aft z{eD)A*ovKp#)+?JZO;JqKwfaJpo3EgJcG&0FG78(ZhFCa5;^M82gg?Q8uuCe!}Sv~ zVau*cG}5{YFAs@;w#{s>v~xarThsstttYSyXAalfG>GiI%QiYfY&1!~)CeXzGm%W4D~@-b2X|Svz&1CQr?IR9Yy+Bdaw;{+!k$X_uqz%} zrbl2uHGSarR?~}?gLqeG05sp#;`GIypci=yMOZ!klO*Z%^MvP@GU#QOaU|68J+u~W zM#42`@#!-JOa`iHQGgbCYTE%f6!o}GUTOGQ>JI1`Y(ic4GVmtpbx?aXkCv_+#O3b; z!1_ldCo8!F+h3>^a$|ew+vBoiz4S3iSKLKq*W2UNd~MMz{rB8bvZhpuZx=cXUU;(1 zhm{?0IWQW%J$wf*H(CqAIG&2-Uqzv3CW-LbZj~%avkipn<}Yb8|BF1Uw&TYZbR&E0 zhxsvPqP_s9S`SjOLW@s{+R6po?ZAef;UZ3B!<35DoRV#6P`W#DJE+OW2c1Q)7qhPO$OiZ+ zH7?tP`Ci|S$cG<+-Y8Bp9?#L!5%JQO7&r36$_q?emU1IjHzJ3~RidnE(}K}tfNuip zOWri+kS9reti|7UPeDsNF5v|ijlsvLhDNdO+RQV|`_{;|!vCMSr<@PYM)y%dRu*3F zZ3blW3mVJz2r|}Qu(ahCC$)Yre)X+P_+v#6&0IK{Ou79Dbc-UnjUT1(wFy-C$fTdX z+B=@iY<&$^rc)}#>5)Ya^^jCyfs`0lFS{fQ@sS<$i5~NHRtG@o?stO8o7nzB`vLsY zJBiv-)9`UR0~91!&iu~}xW#Zh%w!&l(}h}Oqo4z}Zgr$v*xc*yRs~KW$B^%p0KD$u zMA(0#g(fhKP5a*f$b2tlTyv%pr+b^g^MXPuy+o1h+Q@XgquE}Pi^a2(_dtky2~B3& ziKWm1k+zhRi`K*$w=0ECS$(u`i6rU$69!o|)iga`fE7|K;MUe8P9Sj_TdyAyG*?7%L z3&{7BL$QtbSk}!vaAoKF-``>+X0t2A^sV8PN36n`WfMj7^XbVG$;?icd0XpDhgPxs zte_K`zImaKvx4!t$|W#+ZVgqRwU%7E{{^nEsxta-sU~T*%YxqiG&Dv(53dg}g)Z|v z`l?8bC`-7)ikM{Xw|FSl&U1iGCyQxsk~cZ}PMh5H7VE50|rB z=mEwd^o;gq*?nfl29EBeS-uH0FUsRb7CJ=vtTex)`i{Vobxi*W`wdQ$B9O+)MEqjI zE>XA3Ej2x2-q`?+Rz;laYFpIYEg{re^^I{F0-PRb309k~(`AfL_;u482An&&3scYF zrE|UsZ{B0`M$$www!aUiX7?B`dNzcoNPS0}cZ6bS)CRdmr@JtEDr1%}0| zqH*&%T;0(q6cqQ;=6?e0m(Kd;Mi|nDebr5PE5l&_0}TXzPu?Je;;EGF;$d$ZWdtmKda%ZzAHEKg%!@5QZMw=@1fI! zWysT@V{rSUHQoDg57zZz_{O?-e`qWrw_Zr`!$bB96n(TvkW?46^+uzzlZp7=)wM9Q z6XOij_WMYMPdqmvGDW@;Qd(A~YwUC_;Z`WYG zj%MMc>Ah4fWdPqA>kYR9Z0NzLP|cjG=1|M(0)TCftr zBXj8mwqMgf?hRYD;<;Ywy;$d5g=pUP9hyY4S(emP9K}^llfn*5gu;I%pXipvab(W= zLa=@>pzCvW$R2a%xhr3V%9rlPzbl7B@udzLA}+wv0!zqlixbE&{lNZh$#DDPNmR1v z5mviB3qqNvDLYSzoN8-^&oMom+Pn2wb-9X&4>@;%dGptH1MPOC)-21t@K+7=FY-ns zWCL*K%*oKbt%c5DT{$M=Yv9!ELZc<~-{Bc(1;{EF(wK(|WdDMC7`wt7wQP&VLvQv# z3gbzlSbt68fo@=xq}(_?O}ybpweXrW>+A@VAevjlVezGEI*D~RBr2|fbdMy??$1fw zcvg(*$(c5c^$i^_a)oWHFA0<$$`G%kZ^71}5Unw0UEyOK!7Mn2-aMp5l6Q84!aikG zootI08WcqHw)lG;5@A~cty6NSFo|iH<1OLwD%StC_bMKKXEgXsX{CQQijiw=u3#|` zXza|jql0b_g;VQ3(WAO?IDD%kBpF-NGH2E`pWF?}a;9j-z0=smWd`f2XrWWD7?9t} zwcv4fDb3oRjh~%g4aiXreNwxJFTS4#7gki$%))>8FXMCM0xh|wt>$=y(|9q6xFm7AJVWr4uzj#+Wiefns+*Z6 zu-FNfw#U%PZ3l?S4sCu3XNIcpZpVS2l|}QmB-3u~&#Gm8i>qki`KP45c`HBmel>dU z9fVC5slbv;EmZvp(vT4G+cq4tbb5zKu$49zzN?yoVq6W+R0{ z7yNCCrijP3xW@ABo4TRuS#ypT%g|8ST??1=6VS5X;rPe2MbK|tO;5AV9c;Mf0{P6e)DmTqb@ko(QFD5@7A7VbxF!v~yN&bcSUA)A1Ex3lJWvszd@3sn4 zJbLLT?E!rJ)p0oDWkc2OgyO)1tPi(qH@$zyjr1SU;uGZ0qRvzua;C5Wb_a~fR{Wt! z;!Fx5Ch9nH{1b;=U+BUzi)xz9bdQhHPQbS-hMeb#1~e?tQpA}Yo;HfKzHNj#E05AZ z1$UC>tpQI zs`-uOZC*S9$u{wvs@PuaeYjG%IIV}~ZXHA3?Ee5ahi-7ypCxhkZV+)Mg_`3?;=&@h zFA&fT$F<2Ay9Q7$G)HSooG?z46V2gzRXO;8*;=@xa7!RDh3!OIQXqNwDYR{J8Xh%$ zHk>x7p*M{b$b>t;H$7NR#68bx{QlTnAC!1`6MQ1{yk{Qj{i{2Wn8i$*Ds{<3=bTXPJR z9g4!W`u0$~w1~c7XT*5T9(cH3$X#yGz^Y4Yg^{XEn=xI2l*&fHd&6qFf@QhrjyVtI zf$dz7HR~nWEDqAAx~OXN5KcF9gY>|Qg0DvkDWi>}ZE;VqB216&pu0SENUUEeOpwi?YsX#1jS7ij!E zs}0pzrU{F`f1=+f$KmJSoj~HTHT}$XK%e}2;PEw66us><-eEoyq^w$Kitc|TV}338 z1TJAeXX9z3*TB?Ea_CmlU98xl0ig=jbnffF7!|vMlhJB!{nwQ^%5bu1Cht~LCB~bY z;Ft7%s=&N>7k9ATlc6`_4&1=sstsX?%>WogAHWt*hgtlLSQw+&!P=25E7O%;^A)*xoLpSK)7msZmsH`xB@ZVz;9 zo6r5#c!=Gn?`FAwO~~Bt0iG|*@>h=t=$ySwhri}LBy~k`hv!;hWYr|X^Gt<*IQX9% z%-z3^+9}xKqbM@9@vr*gL0oIV$Z1?;l5lh&G^NW z4ZrsCXU6{GexJOG8plujpRO-s9N8ao6DFF~(Jw9Ty8PmzfoPr`xTY8`Ash$Tied+IA^t7`tQCwimw;j5H-tX5YJ31K8mam+h_mO=k zYl@&v`2-s69f$o>^uSUtU?%ZktLo0PmnS3M~#Fv+xhlrR;LC-c#Vx5=@6N65n9gPq1aF^LI zeI(nTZk!Izw`YEyzqL?b*|@nUn4P_ zUcOmE#@u!1yU+bX6+=$pl?4hA^t+KJ3V-8+?{*L2cnnDyQdU2QpocU>}vP0uUo zn_DZ0+TT8i?s{jw-Ozw698MvvBMliT=Hf5Mm%|g&=X5js49D~a!q z0dMrktHEmc^~8dn-}#j2k8t1v1(oPPc?6z6N{w}dHd5!F0qpiG5KJCf2&xTsl3=a@ zqI5^&L3wS`0so-RBVKsyEqfPR`ww`J%jk@H68@&|3S%a`ri*tmEMom&8$DifDi2K1 zsF-pwKKrpgKsUCtGd`u0Tel+wUy1o8=G9TlmC5?_E^zl~6L`h{#$Tf{#F+fzd@H_q zKOUOP$|>)~_TyM)@TSLj6r?4<8Y7#$IBo1waD2h?0*~(Fb!01CxL=QI z_T0f*5ta~BnnP#)v&TvrjiSD5-SqrR_N)$P-tyL!be@YdUKltN^mTxvGq6ngweORRO=HdH41%qMf9gJs;}2QdA{ ze5dlCxjp8=_`(t^F|Ho6Ilz3abNH-BTR1JhRvdphUd)qyho@jd9N?|@c{=x+4PGi} z73&+$&Fq%(H4wIbbfzBO5~Sn5mvAeT(uS|QiS)Bs{7AV76cNC(>bvToYn4KF@;7!* zKmGxK_V_{>hMQD4haB(Iltg2dZEYN+f> zmP8x#LEZOJ!@6iZh4sQkHdIpe6NaQNs16eBmvfWZ_hbC&H&FN>1r-)&;q1+}@Jg6R z|FJE(D3u_Xt$vg18s~<$233jfhIBJ8hb&17Z-9%RPjWYmhT)P?xnjS^uR2BYY1?b4 z{h34cw3*-RAL9&aE0FWKZTOz%81P-sH0l~^-7fIyd@lx~NGI?{11C|qGywvJF7wZ z(p>uKgaILaBDgDa1SvEpWAw)mY}tmIkvq$E7J9=d9ZRnJ;BwYUr6JxCh$~`U0YS}h zX7(=H$n=?iKYBps1oOI|IfKc0ff###saX*1uYEB7S&8|s4F<&Su?Qw_e}wEa0QcoC z2V28j>b_?H+gEzSmG;|Qvg=vAVcm9co%o8TT~a5VGuj|zS0X33U_3T9D-qulk4@4d z?yufJzJE5&r#{%}$w)Zg*iK_E4`9KEASjM`Anak-JL&vQFfI;6=ii^j6GrZU*I(l4 zP(3AbCiw&Gs{h5=eB6K=q?O@?Ne7*KLYFN3Sq%&BET<^rDY+-*$j=;Eg^nGGz?C&> zFx9+~?in_S6~_fb{Dc*Pq9v2axVwLWDqa@8ZDRemmnHZqHJ8ysZuc?a< zyQBTB2d|o!+@0elXbjVp7rEwARkm&FJN+_zUs^>I{xQBS7cA~p%2x@&rpkk2KK$>7 z61i#94QGe731mk6#(f@{V6~2JnR=X(eYj~#ASUw%$TW#{`K#`c}I=JebinTXOfY2{SdLZ zEoYJ%+hmNY2PMx$r1tg#)*mxZjJ>Wq($Qhbh2k5c>BvFc>&kduq|;2xcT4D^$5VB9)TUXV-AH&+sq z1Hn9rl16tcVo>$hNn#wnpRGg&3@^de8`ZS2cL1MU`5$*pZR4A=OovPeRp4h|KB|fP)x-&^Eboa2eH&;po(;AhVa-R6nW3G!JScUqF3^t zXhIXqQb`2EENd5<+x-tWjVpxGm6Qf|DUhAT)nGSQ7Xj1xr^|gH&HizFjJPSiEV@pKTmS=S|st$k`k~ z=g>M6)`w8k0R7ijAn68AeCW*>P}ORuQ@SuYG*|`Yho@0_Y(RztKY}e*fk++h;Ww*w z;Of>2y7k#;;wNGqZd@xje4HJ-Wvh#`EkQbyNor6d_}|z>zv-~-WN8C@KIf0(grT_S zycQ^oY^09sHjuT;zk*VOr{LHHBN99E30$laq12@%*fqrhmM0d_vuWbR9&c zS(osz8y=8%yomn2tA}GB)QUCd#HT{+R_qQkbFa|8$0DNnY6Gt`@c|kaav0m(mxR9~ zI@yREyKT+b4QDPy3LhSlB!2ITp+`0!)%Cx}>0Vc$ru{uNN!>$CupU3L%?=f-I$_zk zv9Lk2oi1iK&BOFXA`S){Mblwkksi^Ao-pKY)wOc7vPaQNe~k zjVR~YBhf+mUh42~6zSGx?-BhuRL5)&iJ7U#3l2r2&)ETZqi8C`X*5#p#iqnBt{Ot_ zo6#vDZ1e6Q4=WBIK~o%(@u6-bNDr={Eez{!O!I-J6ie>r@a0%$oTfP2!b_==Cg~P% zPTon!51hsci#a&ErIKRlWh7)%AJj?|n+N+Ekk1}G9B6oiZfq6d6h#Y|Z^%=fV*@x< z-Ups9yu(EnoWVsh3^U7%XbwxEEZEo%!G4L{;br5oQq?<=w_-2#BbwwidJ8?xS+srW z6Y_YJBX2hU23jZMgB83-fq6e)hC;#Cc)?NL1?*cY52GVaYqsc$hN%8GXy!*BaDaZ#9WWy;X^L zpNhzKXs;T?W?U8!i*mFeqZw~Wy8;m^<ep4GD(VXUeO z3jDYb-&1N8$+~@_a_;lVm`U%zcWDNlpY)Do8EoQL;D6|h)p@*q-dLC$-$bJ&WXZdl zMwqyK68dk}4y?6c2KcRSqVml%$o#3_ptHF($C7cUVYZEsSDc6hP8V?V?|CrvWd$8( zl8!F8nv46Tw>uBwfL0$cc21?SpGFhglXVa*Wr>i(F}&AwISf&&qB}i-I2Rn_XJ{92 zBO34Fv1eW2#+7 zIqze`?y6g{?g10A-{X6(30c@PoPWHz?u=)kX?Ba{xxAEl8rP@OTeiz z0IBUrzz!9ru%W7ghHo0gdX6EmV1j^a`&@&{gVu=ehV%GwOCJ-xfhMRMIa(Lvlu~3Fhy$;Phk+$*al|nChE~MkhSO3ntl$y&p>)8LwtP z|M%OQTVXP+Hy_SreOAOI;`55?EZ*hb`F1D(5K zJtU2!h2gK$(A3*ux5BZdU*IfUSoR&1|r|nCDEZ|ES<}54|hS{GEVq+ z!C3GzY^MRtCz)`)1m^l@(GzP*nMcu!KQH|UZF+eUS6e8us&qF(y($SAV4=@onP&Y?@{e2Jc!KCgE*8cmW3z-6bV!LAXFbmTu{a_@OH zMCZ?;2hJOi*lEvUx=bLtU6h0~-pznKqYBz}Z~%82?t!=MmfVm#%P{_=Db_dKos@{< zoCffY^PnDUe94w_J>GRl8hS=guJ&_BM9FHx>ycb0Z zdZ|W+1_@@lW}Ew2bnS_B65Hy?@B4HeHCFA$+r6d0pr@U_e#+i!ri6lp#Y3SP+l4HQ zONLmBAoTc29^RsN6)NQ3)9}@b%@T6Z@bTOOPMwl5o~%|gbJwueIP2us2J2yY^Dv=fReW$=*U8f4^@KagE; zK{)!OAqhP?lvjTgj}qE%;91ky246)H-RW;g5|1>)#nM9V>NgW4|D}fAuAkGTNz!EQ z*?2g8vXX`|Y%B=~g>x!hoYxb^53B!*u|2d;jRem53C{w01nBtyZZ^&qd->cOn{d0u zRnRCcqbW=i5G6Fjh7&62gk{;o;QuxwEh zDxP!!FV=EU49QN?Y5z{Q?}wyYfZ(zYu!*|^5EBSzIU^m@IwK+=ML`&xr5hG zlOOZvth9$#|L1gyMY{xI*cMJU+McctfDM=VN_4B;mmPQ}fhfAITXg>dAskj_+5BEMeN!;n4t zsEYYNU#2$0@STd;sz!#S>sBcoK6M1;3`@W#YG*@yb_Lz>-yqgL777ue0xr0<2H9+0 zCz`3!O-~oglPAC1p{(gJ&D*a+W>+)Mywhg1WLgydRk#=y#8uL&6hm?>yIFisG-X_R z`u$QE^&=Jiwta?2`PqT1!E@^1FvvC9isbF5L(Zr{`9yYtSa=oQ1@%!f!#F~jji#i!4^#P)$ zt)*QPS^v`97O1`#fKCnz#ro!xK~dB|r)#b!+nc_D&S6hMnyL}GdHEUZK?Sr}Sb`&S ztl@he>(Y5Wn#k%lf(tr?Vy9igHPg1k=l4Z4T+u5 z%Q(`ieeh&~73VW#8U7uiCGI%wic%yp7aAbH%blt^`x3vY2K*hrH1u}fX|}n^dLwZq z)wVGu1*&!MZ+?z>-!TJ{diMp?raVT~$8&I`p9Sa*5z!$r1Neg1K9H)s!%aVb8ea_F z2|lZe=%ff`9Mu0_%+*~rG)R1RF?hLW(SzemiA8ZOEbg0x{*B*_-)TsTxw-_q-Ne`( zg}nO@g_f*Ob+_(qSaT`}B^A8Di6^eYwcDk%EKq@DO4h@{QNOsUhU>AMu?oPb4m#x3 zRPttQ4a|#KLOVy95WR5bd#PB1-YyEqQA;O+`^g5HpgoAc9zF^Zt1Sh4^d^#(XaB%h z=L^E<0Yh^3s3h-Ua0U6yyn**uxkIvV5v^pI6q_3@a6Y$?yZOQdCGM`J!#bYR@@di} zb;T7(no~(nFx~!G!cjCwT3Vy)8nAV&JFWAP4MGNeo zmxRvjjKhzCIbJuhceiatWaZdxyndD}x~Gti+5(WcL$5uI>F_T5L0#c4(?(=Tg;Ohx z+PxB8sX2-lur9kqFXjiBx`*W6H{jKp{JC6-dpM@kO^oN?%#*R_P#Xw(n?-}<-;=xn zA6_!(7_#cxfG1yQ6MM5K9(jXP##_Rw?|O7|h!d{Rm@UTh%cpfo>r4q=VvoIW=S${0 zt@s8m^$gF?CgJ(&n?P6Y1vMIDO2P|jA@+y|=P*77)u>DrbM=~d31XBP2Ki;#w5fOi zd*0gzbE|qd9p;HW6=Mr>8$Qq#4XvHAjed;L8>vp9(?hIeFc3%jOW2RvK;BS_>DuTs! zLVE4UI8qZ(3u`-dP>2T8Lxe35w?;8r*_7!d_AJMw5QtW1Ud7ImW-v3af(jzoJJF+~ zuJb+6!!uCwp2u;8WgVx_qn(`%Y{XV|x+n3AadF0%t;)cb7dg_K#X% zRJ;Wzqi;y`SC+wR>$}KI<0&>NwgU%?T>5zz`<+?#>hQiq?&((-oH?sO^!Zaab?cHM z87J$Z_+1oNs4j`Cb@N4ezP+^8aU3ZdQw%Yev#D!5>ozxKxs~;n$ak#=o^2{8#`XbU zbE0fk4Q2`2^oU0ezUR9F&R5Hz?;7{;l?4W1`KW^0&KOPH9yY>T%QkLf*h(CIf1S0dqe&pqJ39Fgx1VPFxDyaUC)LZNG^H|4h{~cZI zv9D3g+b2{!!TFKS&~+=0_W6_$+1WotE}MQ6i30qpAAT}@QElwqL0qxMv}Cj zuc2&c4n44NH~G?{&%3>hLdQ}LVr)0qI+I-bQ4RB&OsW4h1Cq{q?Q-G*k#a>M zHheh?>V)MKyAELVAIq?WTXCj0m*NCBmeXOL`Q!T(i3NK{OLp_1e%(GKU&W9=bv_Nr z7o5VElv#vIwUSy-G$AiH)xl_&Z1ZlmG32o*AL56lBb$TSm>;tO&V~{Fruh>o@f4#R*qS8j%G-!}yn1uOMsIQKQ!24w8oosSmr` z&VAhm*_VpAlw4CZd0PX0u_KQr-H;-p!7E@?SwS@zSAQ!!27N!exQJ;C=O+(=|KIt_ z&QN7O{9mxC|Fb|R^%w4%D1?!x%2Dle)`9cg1H5%F(vM-Rms_eG=p0paa^ym+=G7_o za@R%ACA$pDATr_^-JD!PoWP0i-}?_qEIo(2)LBp3ye4`ea14>PYk>uyw2-%88}__3 z3v2}}XJlqXzAgO;;jXPY(-~J^c(D!6j7&yrro~~o=7n(bzY041S`m3?x`W@WFNZX? zKStj?vDi2Al8jk~yw6sD z?)ingc&3(z80W{&xrGx-ZQ-U(4jo!iO7b4;;qP5LhREp+xKzJG%-cmL84h1M03NSb zQsF!&JblI-$o6LYYv*-{q>}_cCwHUJu$*-bW&Z$;Ro9WAISJ36xf%X6yrAwEjEPi6 zE!0nP=K{lG(DE?N%t9;D{pkM&d`prD6`>!SX4W+}dGl*9va-e5TLHR6uR^T_pD? z9j|DxgM3|{R-YZjL#mI#wE9G@evJ$6I?*Wh1g1Mnk%y=r>bFO6yQL(txHU1TqP zdEz?Gy6pkJx9sQ}_Kq-nF3YEgtk82c58US~2fK!`?$BimiOr!Zu+5xIOSE%vbT0Gl zQyC;IzKfIh8o+a3#^E_tk~i`f=okFq{%v20NA^t=cU*rQrAAhT)_`!uYMOeVeNUOU zgX+{klm;QV>6A8X>uI2llk7;$$v%j`;4Hul=jX4^ghf*UCH>6DYql+gr*A}bp`0`s zy|DpavF!Gd(U#PiNmLoxLvOo2#R;h{u*UQP zRbaE4Hp86w|6J2h$Df0^;oorRQSP8FjH60lJ^=M`Q9^yYp~Ud{|8Tw~tpq3Dy$W-8 zl+rf#J+kwvKEEB?B6I7__`sk7>vd_P-JN(daw=@gFmN1$+kJ@dJcPWogX%fxNFqG-;G+x<(oGaJRS`PgWG9uf)F29 zuz@Af$A$f}24ucjDsb|_$ZG0yye2q--P}v*&R{hnHS7~uYDuDiMeDHc8&$DBvo}PW zeB4k2Qldq)`_fE8zkh&Rb*qp{R2c64s{w5m4RkFPVrSMZ?=w_g5HwqjXgdFfAp2Nh zhMg+8KC=tZN;74JJ+<++o#o z*mWT3gV{z6ppZV4OH~oUbC9OI8ZCJmwUk9{?BqO&^ zv3P@$0P12ZXyM#KlCpmXU%6ivY0Y?yM!zKDT`)7L0i3hw5Omx~r7K&c$!XhW7+GS8 zRxdq@wRT&HyQCgS?PhsNhVyNHT(HJnd~<;(h<4N?UFRemsc#FOx3cIAy$#G4*D1z! zZRRg}S#Stab!=H*?iRf8$N#YXf!uU*X0imo%W;FSpwW<&U;hPF&#xo9%H21QL2LV`i?RJ+p%8l^8+dvyiq0Eg*ly|vpUQeU-GV@z`Fs^@ zdH#W3+0=xc{IA24@Y;xV1!ck z1$JM%lv@eE?*yV9T~~1B=y_s1*K!x)ucg-Dq%f9K%B@Bg-|fYCZqz7GY$tvK>*+`6 z#u6oRv7{Bw;!SA$=Lr05&ocP5vXUNV-*^8RcS4qzCHIPD>#mkmg4>LH$inI_u6}6& z$4_R^G+QCt1hfYKU4Gn(zs`84NwZjQmtQDFI&U_@tL`Z7pXX3){-;39+ar^&;nrE( zK*qt2PT6EgXj&)q8Cau-dhS^GL>{1{jh2SaCw6w#&@Y@sQ?_N}y)Uic_DvbIPx&r> zINt~i^x6C1A!*Y1q8YCL*T$V#YJ(FcHO2i=C`N_2=zf3@y;am_EBpP6JE3A%Ad)c) z!HV)z#k_sY-j!r&H`Ci=whE52-{DwLHcVUsX#d$f{Oi{;XdES?R#~ISw1EcrQMC^p z8*%~v8{7eQ359gymcwMI-W-0`Iay>isDq#VXcpzV_0S2uPw;6ocd;h(TQie<8EMbw zy-h)LBo5*?UL&FVb2}C7Vm>#k!?5pblyL3sA>_~w#-o_0Mc=;|Pc2V?Cv!?^aho^! zIM0w@u-O)=oOQ%mp-N)C-CJ6Z6pt+jxwV;8t@{}{oW6ly8B>qarkue09;iX>qXxPl zU;wWYSh492@~4FdLiCFEQDCyAmkuO#J9Cf!MLEDzP-kL7c%}}?`zFXHCuv% z!zYXHr>%1o$l`s?P=3#yUP|yG1->(Q!ZTmN zZSfthAXEuQ2r9*R-uIU^{Z+n$M@E_S&Wf32`|>)tdX{0)c5iGNJO-NgwA0ke9K7O- z4S1sC!f++lGfeNoY%`hmhiQc$-;`Rs=@y5Yib~Cl}7=T3@tvTFshB>o8!i%P4 z^uj9^TlNaX`pmW}p3F~o<$I&0kZ$%PbhUetn74;dVBY)VhoR|jDve}4hpiW_VN`P! z4fWei%C8#n$`byZiS_M~_M^xw0dfcVeCDvg$GJwb5Jq)VL zY-xbX7W|>sjNP`HY4XRZq{mQ#@7}v!=uye|+pa-&;Js;?C z!yMu=?KB^B<}P>Yc_V&AZixAL#EKsL^2s$QZ78E-%VrSm$FqEBMUx`C>f3K8z;7zxXA^w zu6z~Vd#6fp>L(D2oY8m72z*C!IoQ;(@7xwcvP_EY=?qwM_m;8z%VD+;6@3rwFiFLk znk&FK_ZiJuA;bw@E8$MPA7``K87rJ<5&IH%c823QPOjiQQkKh9ABvy9`X082BUf{sSM7m8+oJUxnk(i(Mh9%4slcp4JV_%66C z3PiQp!FWc_ROkq8plvQINmpS%IP`B7Y*{voa9emtl*~guhx0IZ)dCJK7tz4Y;W+w+ z3sgS+$^Gkz#cN0H1TT0=_eX~i(Mpc58m@#!eAU5UZnlb~x_W3q_#eeLW`8nldf4l=iMU*5#_TC*YMLOI*ZX8g+V2rLF`E;4E{el$f}>`QFDCQmAq z8^Id6(3_gO$=0M9{N77xNM(Br{>8R;hn}yXTjtClm)TwN-jNLRwO2Ni>@-O}Yh)K% z;g^a3`)LKQHwfv;I<|Eca0Kq4RL+Tp;~y!m(2s#$*{sNRsM|p6egZd6poBxbt3=73 z>}I-Koou;R3M0N}P+iFxBw}kFRKL(bi3=ei9M5jeqlH+p*%n%ojtec-4M^0o z`=EO=7^x?RQ=Hq^@PjM~opQ|p`UQBc*k=OfbV0#6oni6dD zLZucuQf$%S^W*G!(1L}Z>gmaVLEJGX0)nPn3)h}-F4xB4QWQ-Jw z+U3a9Z}pI19*VX`UBw%GJ>lHP0xD!2Y~R^#kU#vI>-l4hWd3WWu`gcGU9zKy&p-kw zrm7xnAJ^{0C-L$}l0h9G%~O4a*wr zfCj0HG>`G~Cjs5yw@nRwygnbNPx~b961*cnhfLpI0nz%b-;XOHqQ7o@{cH(*)ATG> z=~ae1g^g5^gyZiuE|7ET3MakA1J9H;73(l60S08|%0U>cXvtAxpV_d<-EiIQ7Te7{ zkIUb2@SO3hM?#+DZFlD*bEQz^rAKJ)_9bEuc>>EGIur#!-Nw7LjD4maj&_A5w2;$g zU5IC&+lV(2Obt_62hn!efa_6&QWCb5S`DF7vngV?k7vQ%Vh_yF^8+~1^a#@mY^iJD zW^8|dE-2k-rkj^dB}wMXnkD|WsaLGG$g+;m z^*RyIN8PE%zH$=1-JZ{3`9*A_xs(J8r7R3*gMb3YKda#8cNtKwKE&cB@sRJk8Cbo;lt0A$vA}JsaTg zRXBsNTR=h|Ec16m2Cd=PqJ23eGS8AZ>(eO0AK=End#Iu^1skol6l3`Iv_b5-Is#s` zByp9B&iFmoCX!-zWU?k4YY(`9?`auM<_;l?5uzG2$8M$z_3chw~ zQk~h^cw(K6STp~$G!_5$odH_xd7d;U9BUT1K<*4TPPyM2R}n4P^}3U$b}N(mrW)vs zwWSVO?8eP9R?SL5$Rdm7q$W;d?_~{ia zHL}Zni&v&xV_dhC%8m0TA=8a`qh+?Jv2YU(TBi&KlI;}AbjSqOujLh(LA@?NBi6g@ zd4-&MwB>3v?!B$f^vnkOh#$Z@&PRaPJudi_Uxx-4WQrE-=%dx;!$|b}Vy5S3(KCWW zcuT6j7^}Z<`owT~4g4~gMMpkhxc&7tM5F~FsZBR=>$EwrXiqtPmp*`}zX$|P&W7t9 zu^1n%(+2&f4(eJpkv#DF0SyliP>X}RNwM)PzJApsl%*1bhomn7<%9}a{f+H1i0WY1 zxo74cthaDCdBZfHCx~9l!cl!Ip{<$HpC!!GRT>B{kEL?A`opmFfGgxZ7SYFrvSiEq zddQW(#69?+h}#ZUi?KTCxf-$E_#QgqGH43x)OGZ!gRfsFqGPkY@cYrS5GiPa zWi1kxSOfPYG2P4VM3Jn6!a>^>4GBGtZLUm$lArZ-su$}tTNMfRN2~?H@+oBFn%m&A z>;;-tABLxwGpr68Db)NshPV%{g@KPj$P=#M;r~40`K|&QK&lS`)ndI(*I~pxrnx2V zBhO8B`Czucu-SV)?#uWrGOqtb^;%5Hm#hl-==g;CJC%@jX-|GpxCGwQbOx7nj)%a< zjWpzK81Bh(1>=w_oMkM_L}!}9NtGrVDPuqsLVk-e`7ql`7}EX;WQuN~#Q)CYyVnu? zY%8Z9mhi;?p$D({R0^%lNJC4;EfssqXR%v+LTDfq-M>pmWrpDqajvl6xsaQX6pE*Q zUI~As5nd}}qiH8+_5_$d+{Dp`jgjQcE#AKp!4 zv)R^gL7+HCdE|{F_S!K|%(tTqrVyu83BJu?olyP<^V`_{g9_!FD7-BRXZ>{r(---) z>;%((7cy^Z{8mokv@zQ8ZstvzGQAGAD3o)9nJaK|exDeV2e%Gl&MFdm zX0V&luX2*}eiQ%o$Z)Jt6NcBnb%i=>JG#$8jhI#S!3--?G;Vqb3Hf5eD|)zO?`AiY zKLe~+@L~{>$&bh5^%uh8)fM#E#VVu`wnfaV>ng%<$4ghpSNSUZqbEnKb~L~Q<27iL zML2$S*aGaGE2!0hP+|(R`4d`~xr=L9N7I*DC~>-v+-h!NeyauC>rSV$g16$Xq;_#$ zvM??TM|iox_W&8rS8WLHvMUn%$pa6|5vkZxSd6l0-rGIoQLYZZr{ff|v2(>09pl7Y zT4&iDLW8S;lhLF_M-7PnJQ3{j2}a8=q~OJ57TnugPUi=Q;oXjIAeidL=_Xm>1E!P2 ze)0>UYNV#O8SeV8ql-e=GiKKVX+A+{>!M)%GHp7TKW?DA|7H`Kxv5!N`JqD^ms1RnL|!-hXbmXiCiY=#t^+}2JFBL^^q1i`)+ z(ZZv)VK~6V4dSM(M%s(t;Q!*TLu=|gs$JkkmZF*b)8Dq}r`jewrF}eHv}mVZMbnA5 zQ6+S$W>DidPsm~q2maF5I7Ut}J@2QjtuQ{QweQXCUd<2XS<=0WA95KxfP85nt~bs986YKFc;Bg^6z= zdPp#;{d5ES8JNL$8^-aT3}Dh21VgXdaB9(uu*dZ&Q1P#W*1w!UQX+o9k4O7yladeF z_SKlbZvGezOFfAlFD`}ZpbDzWo|)Cj^$@Z8nfY9`%_KEoIG?(&3(fkQg@?+of=Sm! z)Pi+I+WiQEzJ^rpT2L5vt8#-$H$-&hfGoMe{L=K{CGJC(BF<^95q&P{Wn5j2c(6O& ze5VXLiD|G2SL@;ar-|s#crUzAT~5raX9W;qzq$&%9Y@oy=>|k?a~hP(hoEHdFgz*C z4R%GJrJD;!6HnI167ivj%gA1hJwqpe=i7ElJ2gmsN)2q0Lv;TH2jQ^<~hJFHvg1fwu22ugb#k3FVugUtAR+8Je! z(j{cX{efYVN0P}t*C9^5oW?&3#Bq+pK}Og?!*++^6+$=2H&`!tk^LRZ=JU|}xf~to zt-+_yUWY&5-_f)Fdr3p8E^oTp0c{&LAHNvUE5_%VvnFIzLj}CwnNG*pl(F-l7f($j zvHGDic<7ujZORpdHwf)49WtsAl$n z#r)go@|g4ZcsvHX(sJ69Tt$N31@p@BYAD(%4Q;hsCdTJD#{sPJCv(nLA;JW<9c*l8o=CtOwUwLTdK1 ziUhX>^DY&UC|7eGZYMqBeFUe30sOEm2=pJ@(HBP?@rOh6L8X^lIioG>*1D~Gsm$G8M{49Tg^MmbaHvpfASjJ zUoNL6EH5B4As8$&zi=PtAHf9;>%_QyxLJu*C$e{+Thg48W&`d|NrW9u?P%kwPuOqd zO|}JGMi=jAJcMzHg~!S{{dx<0A?1r`ontrEtrn0DTn1Y{+^3Q6%1B(eBQHB*IL?S> z|DR88V7bSRmS2}AE%q%i?65BS?Gi$8!fbxDqigouZOr?`*R%KWAe7}3kMkF^25*Mj zajUA(FWs$T{yaREJ#T;9#Qb?e{TQ-tTOEL-9g6MB-`4$3M;!NR)L4th}<3=CND+rZIi+jSoWC8-nnh zojPLO!$f8UX`S2;T>*}QOFD#%nNSS}CR8I<6Mz#2EMVcAY})1(#yGq?Bj^g?D`u7ekAhLrmK%8MfEkP&ETg|458#5&!O-#3hMUeU!fy^w6?;xH*{#qRe!+s&l*AtQ;{A>f#nSW6;NUz}F;>SWyJ6L^Ibt99mq9)9DdI1r zpK8fj!*U!I$JtKYgWKpR^BV%sI=&y;8eo4&W2FgJI{gd(`#l2qGcH zJd=x-qYSA~T+#eLOx~WTPQudL!7+0RXJ2*)zb$3?bme-~&%7VSA2&d%t&sl65RyIr z-1(I|_o7`bYq3OKueg8vD|_Gk+{QMolvdI9agO-4(*pQUyM=~K(;|P*{DrLxRtb-5 z8Ig^bhwwwjB_f+8$ylY%6D)OJ(omLFJkC66=bk!qn-opZik3?H?#o%0=aM6DwXTDn zX*tz#VjUODLm=DXD<>NtfET}659RK))bh0oIo0|F^cY@6$JOIpuOt}X*^a6;x^cO~ zO?Wz{jCutdl6glPK|{KNdw9kIKh*9QZ>C3^n3G>}Wia~AJ+_JVjtGr6@rqj|@tehR zL{r!dEvs~p%kWU*SY*am{dUXN-ox@Rni|S-F=36caQy@H^Gh-&+blu* zK|1ZMDkj-8ckp4$B9SoC2@4`VihEq2^+@2m-(HEei_HIIN!FP6Fg7HUCZF9yJUKl+ zeg0{b5#fS+>J>otP#evCXF^&FtDtS&M7m34Kyt%*sQwy^d|%zcQSQcY{d*Z*JIe~M zwww&;K_^u(oJit+cf#amd-{Cl9@6kjm-o(mg8n50;X{XYpxwNI?pIq*itWF^^CJ#| zLx_-Xv>Hq{R3q7T!0ury;ACGm{jhr^skzV!t0VR!%O2M2^2r+-W){*yb#;>5(FR63 z54lVHbQ~7dDVjL8muCLCgBNj|;eJjGbsv*XL`xlb$Jkp))_Whm3esYpJf9oHgL6V4 z@z4pON%$+Qcj`K%on|}Wx0T4a*LAF)RuWw)w#U-8DzN`_8@;h$8j+T-grC(<>72H7 za?)lKpHy6nN`0fSlb#05DXFLSlUeWm^bn{}3KN*j_<*{{MS;Xfuc3`ZXOr_;3RM z+q@k1uB@O%dzlZ-s2TE?XPB3-cOa1s!};tZohV#46Svu~hW-AO7L6ao{wNfd-Mq_9 zsffn&SjO}2s+Uywc?>yyqY(<&hLPK#0^8866?5bHlb8?iMLBeRc}5+rSq`1uUq}Lb za|z2JvH=SPmU+`!+%pA3S`GkAm-5v0yH=k-fUW-2VjTY%H{7gHi zk08CdH^9!jj3(Zv#3^ATzuMsm`X&{KuQiMS`?Vc3URI9$oYxQ1olOFZ{e5_+6~Ixy zQnbgc3SX(c4qLXB(3+cj$cPwy-szG9>b0MThvt3}MJRlx9^Yn?8p%qC33)_cT%zP{ z_(uM~m2MOTr?GaN8XTR`NK^Aik&D5daQcHLk~MR~Z~V=~JbB?NJ#xnLA4n~0$svKP zhxY$Sx(`3wMN856q(w$cOV+v1`)N-j zd&}NgiH6_(J->h8yn5-J>$#rmeGU5_wwsoOoOCYX)GbTkNnjy`fMRk*Bak=tR7MZB zq@W91R|=aiwb1y*gE;z20C?PfNGs$`lkolDd%;J#3MD>?$A@hmLlu0ZPH74*Bs{4E$Z`sa?cygC#F%e~VdZg+WitmN4hILF!d|`HgxUJCU@Bcipyt9NT z;R|Zon?q)^o{jL>)5ut1D;_bfP55DM86HL59} ziOFG;3K(&+6irE_c=IF+cx|6Sy?>4*S`N+7`ra2=^jyLkoA<*kcCR1SpiJ7%G{cef z6wbR=150mh6%G}3Qo-e4_}0ri@Nwxk8qe}35$+Wr_dk!Nl@D%K8VA)Hjns?faJ`!Y z;m5s5!L+Q8c*TM{z`e_%f2JxBz3o+S>-I2|-{^p2Un)Vw%?9e6%rN0kF>J1WL1!2n zk>}IPp?#Ah^2<4mTVGFuGci^4emc`hdIO={I@Bz5WjT7fIZN0W#PrOlVPxL47=@^2|8pP#n8K4KcG@(X^q(8}rsE$*pMEed_c(ni) zvu>khI!NtO zK`+Md#%Jcr!aGHVy<^SDmLS$2J}`>rt`M)@TYvps=_$Bu+{d8X}GNfX(-eNbsp zYxc3H6?-lgK;^=0RDGzJ<$&(MoW;2mwt10YGj0Ch)Qu>%dLEYe(<7Y7{0xWg=@W@5 z#Vnirgxd88NLu7ZKE=EZ?bvbwpE)rZ3?*u41RX()?>EAZzNu*PeOH{bd7fyWSKM?b z@u)T6zipZ-*v0hQXAAp4?otwpFN?y%yjjm`WFdXM%9y-jUO4;elbm983JQ<55Zwd| zt=Sf5Um$o6dqgWu*sjeX_TGAY6Q$Qx!$m3tlW62-;v z!LE+3`!;fuwzk@@+yMz4UH*~Y6E;$oe2TxU8xWXxh z$ZkfNNZKA^+6(^2t`G zQG@3eJbp{NQ0{jt9ra0$2*dwEZ0QwFbCej~x-(l?diw{xFhh#0no|hpC#KU`s_fk@ zMu&fGbpbU`1S>X*?cvXi_S4c%Q|DD7wcV@$) zsw%oH!H7)dDnY^2+^qa4CO=Xuq4-`YdNJn}j<{?MA2lf5@^=);e%l5udyb+x<1XUm zu6v=u|1BMr#ooJ*HM5TB$6Ros26mBZ7cSlOgZ`}P$8{&}0-g1Z9$acfzOwsoV#_RK z@$3M;TQ?4j$2HQS>Os6qIT&{Qixf=x^#T8Sa|eVMa_H~Xazxg=5*oLNqX&l_@Bs6V zWn?zcbCENNnN|se$-JO?^>c^}yZ=fo+K7VOSfBqTRrtQ8ir#D<#QSxF!7(}1>_tc! z!qNiK-S9@cIJqeC4O}Os(<4rDWcK4qIFYS~`d1yoGlv<7JlOU+>LlY%8Jz#7L)ZV( zA&I_)pt>ReEvUMUquB1}|NI`Za%@wZ?e+NWw&rXE80%!rg85O+^gxn4S(4WYb~U?b zM9M+(GkGDO9F>NSjEux1bytb--2FYfFYxv7a!1-?%^7xN96y{_>#Rd2&tKrG+_kXp zaVEX3%W^BHgCSzg_kgYS|B=j zJqtU`x(oevIaG7f81l}%8fv3Dxdq#8@D{6SA|9?5sZ0{Y%i+VdMfBJMmgl`u4=${W zW^+mq?tY^Vau!u|VzLc++TI14;~tm^j?E-{G#b-hIepN9fzDS`yIay@1q$7XKz7;)Fx_}#* zCjUQdPkJ}S3i6gw%6es4%dJ!1LU zuttuiufv@_eWE+#`J6%g!hz*YTy5!|P)D}yXa+wo*U^M^Q^~o&A@DP|7AzW?MDpG@ zL7x5v6z+W+D{vlgj8Oha_wdpQ-VT%ryerHL=T%c6;llW+cw zkH!VFEPO9lWO)pqwr~U=u9AwMRU*q=2cY_<3^%L40#7SXfCFQi(CDPwIR1H7WD^o>g7Cg{;D&t-!FlC;<~W8aW32n z%Ah;ujwP#=zC&S`8oGM*7#Vlcn12|uIa7F!Wr#kr+|vTaPb9BnBOeU?IxJslP>lMo zdI%d?KX&qENn&Ev2y5~^semSGSpWLmXlsm6ZXCtx3LL!7EVJ$WEWN#l7s218|i=37Lt;L67bkDl4`AE zT`St@@Y6jI9UYy;`b+;G&-3y|k@a7y;G9$kw?xVYR~e{+prVn699JS6rj~=$`-SuY z>(6ry+OjH_2dRFzq0lf&p z*)L;=$(UM}{XB(UEV_n+oA$tx@$cxA6@Elk$CwY*n20tGtwXXY(!vbZ*&#*v*5G#boYJy?hgSO* z;d@i!K-wjjYCiKMdoSzoa~?XNZn=5b<)o|1hR*cIRPtgvStIGd4}5Gy z2NKTXxsFre8S9SNaDjCSZRvsBt7=Hs*#$fNoG;?)#q7?me5DQ6oy*BO{Y;k(QyKuw zN{W1jMd8(J%puaYkXoOeLyEswz~%1a+}5JUX#7)4k?yT=R*X1)4~OlZ&uFaL2$Is& z43$$>q2aRvaBQ$0EDkTD@K>3P32g`Ex9Xf;M*^OLyx{uBN_1v09zRKA%Dt|Tj*Of` z7S}K@<^Be)a{D^$CD$*?+C081z)roE@MTby7W~|Z^_$G#&f_|2F^YNk_lWWT4qFQb z&nS_qwXJY;@ohLY6%A4ZNyou` zrjv-Xjg>}EOVIUA@U6BsNl;ZDe|zyT72qTJ2Qj(J2dxrp7E?z6pT=DpXnVjDW0oI>Oe zY><%)mlkKxd*Wlst}V5IXRD*^)3HSAlPjOT;Y?;I+lE+wwh7F`1JLe=*KpQpBEoaq z4MnK(&UVo)az7qUv~Dy&xW+#EnPsLX9jk>Omu*lr+pzF>y#``OvYlw=xqZoYGm~}C zaZ93@ckX->$c=u2>}Dt6W9n<+?Xgrk=-f_r%7pW`FUF#gFE?YoYd=IA!IS!Bh@a9Q z(EAY0P5SWQrZ{Xe$zO%Zt76ZUU*Sxr}J$`bj1Rd8^* z9-5o(gSGa|ffN4K)S2ytdA%tEUp;MFG+dYXWtTv8bpX2f>=vF7x)`=L70{Z_EW9<( z3RYqju096g4`a1NTzzA(EOCkNgrBg37H?J}VM%Rpw$B5-8#seIqb#8RY$3hNx|P15 z7U)*ZSbTG#CAp?2&L7=ajtWzs;l>Dy+(1<5MewcN@kD{ z+Z2d%dxM7h$CB62`at4fgkavNG345sS}3{ikDR7m!53HTh8?A^X}9Z9a$>P5|3YsP z3bHi*Jx0`(MW$OOOx&c z1K>8f&g_zG4aRHJMA+_LQiz>i$APMKE?xe89~ohy%ggvUpaZFMaaL=;@UL12{nMyT zYPJ_c()UO78AxEu72{6 z29fX-iJX4+m|; z`JXu$tgWNZ<&;R2!XMChVn^`}V}SL}O_Y z)GSV>($2X={GSVNnj(S4V>KdKta@$Czs@e^lurCZB|&+@i3VL%la3`S3B}O=GL62{-^w(B zNw9Hj1AW@SHWc_$sGFulpS;!~;Srx8%PSD2=q2E%)8>I&Lp~Mgj3Bvezr(e=p1WbO z62HHo0h=bY(36s?q)PV}G?{Lr?Ue@zVSVYNzonu52T$O~%XLNCOJJ!!Nr+;1#-&Tl zK6N0H>|P5}_KfGQO2@lLt%eBiRJzsS6#h2S9o{;1bJ_PIuy^oIP-EY#g0V_uvsXLx z9Zcb>4b`!0O{d7e9WuTTPhJ%d?~U?kr912DoKy)Zj_Sy^*$b!);Of_KtXSs;C(fRu*2*&EtWqTyDGzZ)k{fVk{S?+o-avzxmpIC<1di-`N?$F| zBV(VGgHXjD@tec3|Gb$HIlhXXYstbhbgg0XIBT<-&Jwiwj!@WM&_!bovaHiz7Z{8* zr_+NJNr!6_2*r%ieG?y?;AjZRSE^}c>U5G=QwHN*X4Ce`Y+LrfGLUB35W#_4I33Ku zad;us_|7(5j#`6hfC{Igf$+~FEw+2oOxJjY;mJQ;z;aiGz;2ZyIWxKmmb-657ml&b z^sTGmB6}ZSa+l?@C$@p~t&GLXJS|DA^)UXiOaJ<0owzUxM+JheCR-}aEWynefLO_m_rHMw@RhiLAvB{M=N+I zt0L8!9a!2?0VLZSXph}IBKxTXOgbd#a~~b@bz>Gh{}+g)>@slcejUoY8;G6Qd&=K|N?Nm* zk~2Enc*7nQ&icd*a&G4nc(CCOGFUo_?5_U-iE7~j%VA-7{UR6WR}@FM^eTSx&{O0O zyv00APu|o(=gkamZN4q~D?VPNy=2!*kWuUJf$fxh+TH^sLBoyTyEz@r@;i#pTpI&E zCXMuzIqR=j`4@sx8qBtB4Z~ZDU106F14!><0Zvhi2b1C)>g}_SeAUt8wPGC*a+!;b zHw*~BFYll&*JhIw`->r}>mhwEobxZA-UzD8f= z-kjNnXH_kPQq@{&dQ+XmzYyckbW~@}0j5{H{sT*W?;|tWi+Iw{<*=fwfHse0z4}s> zVC#02t7cmQ3Z-jAzQHl}<-yi2>G-+N(-~zBu5a zKm=+OEMJ_OwKqwIoUy2a6sK_XOy?GkIJ6U7Uc9DeUv$ZpHEpm*!JX5I zHADs1zEgwam#L+i6bXcQa1G9<&sO}#YkI=q*55wv>GY#mqGB_gpI1e30Q*hJxq`t9 zf3po?<+x*8G8j2Gp~8U%yjVN|a!!4tYch4o`FU+%VqMC0+APOYD*uQ)-oEoqiLFHu zAe2O1`*X>ZFn8X;dN|%hI&jC8Ja}*}ol5G2;Shfp_}p-Z6I=Knd7AFZXZ;P|jY zu}&M9nFS)Nq^sCz?ov4XxR9z;7oy&_T_P&n|aiRulojrdKU!TV_-3X@2{(|zZGS$;m@4+v88*&7XBa&aj#m zmg$j{f(jT~Ma({QB4X9Ud_G6YP*iIM-oDNXu4<*xu3CRw8|wzjPrA6p7sBv(ZC7yH zok91AjVC6#RiHHS9#{NV4UduhA@X~Bvd+o9_VMg4mP_ZK(j(%o72tVI4OxEh!p^(@ zAJ1Rz_>K2ThJ%>)Il&u-S0xOu%H+<{e+ANHlXxWvU;X2j@%A{abBahypFpOOtzpF= z75#)-Y-1Y%Kg%Ff+YU(^hhu)lOjuZ3N$c5XhOy5~K5abnTGv3drXwm- zVEvZMEn(NnLb`gV1qmBDj32(G4E0}1!lttoQu)avY~zTw&dkNnHCxIqdzsj_u2I(XLDd64YM;ZFVo{BcFrhMYbk?mAaxO>O1iB zQHqfKqJbX&ZA$)YDS_4VB&pjz9p-Nr!1jef=yP~Fo+1?w%ENOgm%%bnt}J`lzK?r< zYz;2iF#~oDHd3Fb6G(eeIg|?KQ)k12-#QvQ)$E4qORwk-mc^LC zbkT2O8Jx|Eb*S21R=B3WlYa4&Ai0wgz^a91`RuYtm!C85x8?pk14(oJ1D~N zliRh(s7uALhIz25X&ULc;KVzfY((?!pTn25RKfIkH4Q!Ij}4Mozn0-u?)+b8Y${j; zk_&3-i|UzVhq)N9KD#PwJ>!|m3IAYh=Y3?5bOFz5SphdI3TX5@)@7kx2|5~nTvPQU zRCvHflz$IC$~ygm-JzlCHCK1@6y9#Q5wt^DUn|?H_(>RFT|b?>bpIYckm@7C@KWgn zd}*FL;I}+2C}Nwls1kCOYPqe$ZSj4}-y+TYAM-oS_!|z7=dGtF=R08WO&GF&)KRnQ zP~3RS73MEZ&8m7ULq;gpKw5D)+U9r*hx_aXanCnYFxm(~T^()Gji%+v(^R@>%9LU7>dPUGD1Z z!$fkqDSz#-Q|46m_naiv0h|A0+-dPuEIVfzWL_+!CpQ)%-g1v{7uy%h-Y-TnlIy^9 z>rOg}`L~BZa%CCk9M0)eFjkke6?F{WIpj%(8yfIm%Fl7GtjDRpy&Yz{K1IUn1nk#n z4|#{vsN3RFQqtqkU%qk?Jv7*aZL4~PVP9Hl=V@8eq%n+7tGUXJ-ToJ$8~H*M*+mOO z#}N6t63|vjqb9Nbq@>J@Z|VOJX@6z>e4`Sqds$DHJI*GTzn20zJ&~5bVm(ONU!jNb zrPI6b;U;_L!{_s_PuX!FPzg-sc zeR4c}|WseQ)>rA5w8UA>i z{&x71+RaUR5Q^0U-5_UH2EB7%nsDc;;e&lVmvUAOTlsa1^pg*(dhoKSd!YL;m-0(= zN#n;#h>}x7%~|{LqOapYJF0HI2-l#deb`HL3D+U6MJr z3icNVqSci*ag{QL^{Rz5{=ONW);?RLf!pp0#d7{`P%Bd*C^uz%FSiC{wr)hmai?*! znic427t)83am4Y2D{n3|G8^kT^HWtyP~-Rn{8F$I&f7nt{>!5A)2ktH#k!16 zS`mspi5sjpnZ%t+k;QY;>qR)+#yYHoa;0pu<~hw<7*g| z8AP3UgLE@SkdlZlnClrPP%~iP2W2-HH(nfV8Mur;O6`TBhp%W^wGv63RSS84(m9#8 zwrGQzoCt@FM@kTJpK z^zs{aYK@1X-fa3SaxdAdV8Gk8I3QnSird0|i*A=`voy)vJH=3D_<#Me9W27CY2$c*{KCxx+7+&Hhl8DQdCFqgyt|gB8q6ez6WE=iurf=ml4(%u z#CY$+576P27x2S|mGJpn0d?NXx-8f|Wrm3#C!Npu^LSfPH>`)v1fu@o9t^vbPaA%+ zPLH`Ba5CjJ_t@eTjxcZp+yBbxvkXO2KdFt)98c$T=H0^^N)Ezwz7l2qipMhE?$9>~ zbQSaG_gk@^@UHLNi(6~4X3-y!FJ-46N76G2Af@Ft-F#*P>jWku9NrNeikBw4iMX^H zFGD6j_zpr7maiQ10&|;!;h{|x)fgK{W|*1smUkX;t!73@oV|NJNr|R$n&U{0Spo#L zeWUGP{P5K@XV6_+P0KPvam5ICn33skb~maFCro_+9e0{gMRy&(`6mGi((|b0P9GBD zsKp=ZP(~Ti<~X}#NVMIs_lyy-3@HM38>F*-=8<0CU3}sJN!;t+hQ(XILH-hk&mTka zuBq0}A*O7g| z@x7L{TtLqs^j=UPtjzDCc7vmdW)$m7sd-8J)D(zxMj8AOH$l2_RShOej^h_Kp$VRcvt+c0{M&367}-;JzB5mp~^ z$;3;K*@D=Wbegj^6l+JY?-lFTj>(WF!_2=!eq}tTwn_~TmG%f1uKGbW4tL`{OA?^L zH<#uzFY%?wYA8FRhGs6>k4MGJityRI$&P$-?1H5q`UP{Ahhq0gcbKeumQLF_mfW6L z0fiR_xp7PFu%rAm$otqp3sR<#b!SV!sNpe{Q`aT@KKAdNXODCjh2iJ#)J0gGu)G-6 znY|LmqHg+`<%U$$J>cnAbNZg`%+`PE0sr+2P~&`WJc@03{7=)qV5dTMXqU6wv?leL zr%Otzs{zdoLV0#Karr+CQdI?X(@8VDV?Y~Fdox{Y5sHU3yTkPp6$1VSd#2b{0ViRP zY{_Z7Q(+A#PcNj8XWk`;7rFA+?i!jktu!an?A>|y*FxlDpTM|>1(Xauq7(OD#;3AF zfcsoZo34lAMcy8;W~35#+fx>w8*C6pf9;~%U(1n;W~H#H^cnqUc!1n^r^P=PxS(nO zJaFpe32@?C0~KFqOmy{1A-zz7wukGGQMx=d7X+baLocyV{2s_hXVYDGLh+L09zb>W zb7{y5?|R3&f7x9!K4}UW-roc)x=aV&c@xuPTKxNEmyy}~04%MjEyCyDwprw@tec1@ zKeEy%!7JZ@zj`5(h?gKqkK4gIHCV9AD+Gu7GW^dHLyb$4@K>V{P+na@lS`F}{IUj^ znwZJO)T~8k{*x01g?7?}z+vQzB=)$vh~QlssQTG5D=by)cZ&$&w`vvs%0hZm?XIwPfkE0zA(eHR$k+&rDyCQLAeDd(N zeA=k&k0&bafUe*-Tx7F9R#0*h;j@^m5}7lx2l6}Bxyr2i zo<|ku29s?!7w}`Mv`}01GTgjh4F1>q7o%@T;x89LU(h{Tys#DPIp)LG_B0x9Ig&^% ztcR|NGZD4CN`k!I_)R`xnRnTH!Orw9cx4rYH1}V@7mSv}-aSlj>@7fh-gydLI@wO# zDKR27q6rfEchRua5u|ld9VGTyq8ZbJ@zmk#ML2BiJDKDeG{X0li?~wuna|m0Ht%|d zdQ|V>rN1^n&eoT7m}v*nHb^Ss|K`XsKdN{e_+5yXyBe)SUe~{!r zfpA?`7j5wvO-$#N!Xb;7bofPi@?}5sr}-MAmg$@EB+viH;h4#qBw=wWAjQ`9lidQE{04Qm7KzqWK9 zc$2#eP58TK(ot)~G5lnO0W|)sqP|S?i8xsUMOMUYr3oU%5lygUL^<-EAi!y@>jAlD z(lNf0q~`Yz(0+0R{cDfKV~>P@;u>&1sgl;sFGAsouS8n(=jAeF zxqdxFy6d6#XfLe%*hGZA|EW$T|CldAeby|R%JAID|2y~`3_`;zV)3PJ0=rp{jpf(H z*e^l{E@n5=oc0mKVqOF6>u{tO=8hv3E0~w#pB)-t_sy%FYoKyiA#EDEO*-ve`L6|Y z%&y#BLfSiqVDavJ6frIl8);a9(bN=LbvK(BM(^Tz*$c?6^%Bln6$)3}HYa1Rc6X4BQrm5BeM25_1wh0bj@!C&P6i8%9^SL$SJaWUAO zN~X@~MnqhP-4|rHA?xF3vHjN>uyCM?DymA7gX6kE&@l}qyKKdBdpUS^qn0ioKb>65 z5#y0&Mb_2plgYjb&FtQB9X<3qkG;SG5^fjJf)M7V5w8Vu{3z!*;Su5j){8jvOdUm1 zz$HS#$8R*bY6MxbpbzeguR-Op{@6x)6U4tOrv*2aNJM5I1P+_Und-&k$*qUsRd6MW z885_{A;C~Gx0>p+9Z$FV@61b3$1UDugB#Zj33KkXQczn&3=b7R{VPf!lH5)EQatSDLlGw5*jS6P zc@k7PEq?A1C4}!T!_&>h!B4E63R?|GA}xZlNAXm8laSP*jl9sV7bz@k z!AF1OLpZy;EnYg3z^4Xy8#)tx+`fxEwKCvY;vjQ4yLGmE_ki$n5K8Zh!EYz6fHR8= z>7x%tB=$l8FTXBe&OA9$j97KB9@oFS>4!}t$Qe=(>7%SrhgV>tzX#>a}DA)D|7eCmi3lrxQG><34jvS~o5`>2&B=1Y*X z&wfC6OavGF@Hbj;vq;z@(M_k5QRG8yDO|XaN@It~lc?Dha3jnZRc+pc^XOzKuBoU0 zu4|D0dP^bDM3G+q&Gyc^zJc;k5IQt19(TGg2BY=)^hB@>nJX{B|I8WS_N+3;m%Fq? zn#Q^+MRKnA2UNecqig2)kg5LjcR={M%;qO>q^Y?D zlxLTtf?qGO+u&MAYE7k2Cl4o=oV&o>*B434$6|qVC{$;b(ImYwBynaXnC`vJJv%TH zPo3~n#F=AKf8eO2iD22AL*p0^_xxQ8H?capQ??J+OUXlyX#=%AU`v!&bb%!86&1$l)@x?>pwUkn}`0f?@XlZ8d%-+n3k{3AzHKd@`JJXG`3= zRb7PVFMZXCThsttmbRjHp*Tvta@F;7uJk_N7TchIRL5>)Lm{yCMLCVBS0=@=&0z5$i(AL? zna$1e!s#}hbfJ$p$%smVyTN%>+s2r@2(18H1%0&2+!qV{r2!ppp#Eu+WYeo&PXSzUs#57ba+=4B1kOV@>CXqRD3FN8 zM0mXQ8(sEzIH|4ZhLOuwqaQ*3c>2-JFmh1^^`Fc7%$=AoeUc`(_H`U?9)3iG=OYeM zY%LuE9iysg(^6eBeN7!?ZmZ)om2I%Jw;247V}JR+fJ}c_01BP4bV%GDPkpl#boSTN z>WndDr&R~UbuJVHz8FJhxmJP2-Vl_Odjl^H-zV~fNVE4c1FXYujk?3NN*ST(j#j!M zB8CbNjUl_3$3y#J9$jygOCHYI$1nKs6M4m`?vMUlJ`YWogGIP zybzE9sf~Q&lWt@)tr;sg6hOUu8g*$MK@^}7q@!k{mJ2bYMa7+ea6L40Wl#(@`?UfV zPh|b}2F7HDGrMgGBe+k^`DnYRx5yKcb@m_bW$%V+TDxfRpHU>-sueEAuSJgWK{#uX zy$H`Wrg)MjITPMs<^`^(N0%7w=z}kA&ryL&0(J`C1Zk_&>02>l(xqMjj|2NS_h?5v zP5!sAuCOZM;yFa@1H|C z3U_{qcS@{-nNJy>f0rO!ayR@f@kKZH+`ub8hC=1ZGWz7t7}7L~b!!yf;daW;#9o&D zqCC#u_no+0F$q2-bx6`+9Rw?@qkk*+;k{+@a72sww@a8c9qw+X1jjM&- zhqY1D>ixLJVy@_hIC|7%5@}x!QK{;b57Z%3rRrht#UNB%c>~*~E`J@VrpzILW?X z%#Tpe(Z_T=RJ?I8A*@E8M>k%lqDZ_o_>%=3x}p8W{$4%S&mB ziX8EI^9O=dEIrWv&2U% zG(crf6ZObrUS-o(7+j61_a86v_P!4Pz49`0DmsM^rs|6L`BYycBC((n7ByZr^D@vU z=^Y>7Jt;y8XC#R4;coa-6C!Bp4aCY~?%@9WA6Lw@prqhX*vRzT{t_jUl-Ufk>NB~c z?KbFvo}%!n-Vd5xAx6w5C4=+0Jf@Qv5%-4`&~L1V9=jaIt7geS+>8dg{Ej5~x%MY) z;mXV;BFk~;YXKNqKkn9=XLB@GB+8AMsW30sBe_6|y8)p)$ z@5P|@E|KxaVpxs^1m&YL{7(dB=< zyTk1(2}7QebA^`sTB&a4Xd*bB1kS_r==sm`3C5Mv=^tR`~r%9o6sMNe(I)@&^vC z%}nII$g=<)Ui(xADx465J=#}7z+eH(`WcdhV-@gDGJ;cb&PQ3F4~V=X6~6!QjF1+X zUAT)n&KgD9Lt5e8kPX_nB?#|aw*hpGN~kYZB18F2;4^k1r#i^Gcb4|U@~Y=3f5$!C zx@OX#NW zibs$uFPXmW#Ip8fazt@T6%70}MmHZh;i_*_L|zf^i)!SQe<_SFmZz84^IG?-B?acx)V%0Lf3kQk&$_Bw}?He7ZHjDOj$u~arI$O zClSe!B@mzXfDTX4CAnuCKzWw~S}Di0@uQkxHouZ`=iZR|moB`clq08aRDjGX--tAp zXIFkueOqdt&Li^F+7E;$9_keqT9w4XV)#YjnwdmNoV{ z8H@&Y-oTEJmx1Zz0-B$?2uG{ygWAIuy2VnGR4!VUi>+gc=OdOqIcATPqQmf% zh_&GMwt#+~cZ_A7On9U|)~xFDLQ=KxH%zeng0d|W@P!d;Vdy{#-Saz-e3|9L8?L^D zq@tqm+qy82D=4Kml_!uX!eM-aS`xSEjttI@YY}ca(nU2&m~T0z6pSlU=x5FSD53ts_7Hiv!&2CL!9cfjO4ty_fR(!jLNg0<5!sp(0lbO^}iuW z=CaIP-MtR3#bz~*sMUbUq=}y0#_p1+4GNZGdhPFF@(mgCzkXjugMO!QU8Ei?DypQf z)D4O0no72vciHSc(I*3OpWxm5B4jflP84w$OiT$D7)=YrUOMjJs_~EO3}iXM{7@*> zET?yEl-bsE8*CWJ;uOuTQM9t6$m5r_QH*U~B*USnx%4-kLyTAs{rY-c^f&1cUREaq zt2^qcxIXjZn)bsnlQOfyk7Zc-02OKAL;q#tp{PU{`}QkccvzNvzs7n*Z;U`UW*KAs z0WtVr=gHuL8KiGS30x6Nq{n6&5brN#aPQ}4G{Ghkqs{8T9jKz#J)O8Ir4p3NX~>+hIqAfabBx{wlpDFv+jy%sbZL#!PWI6WU6vH_Rui zHy1%Nj-^W`k0ZW{z3`*UOz`{g7;@g^yGZvw<@*HZM25neuNAa%g%|nit;?^Se206J z9)|SLJfS9gE*Q-lO{^Cs!_h~%^vsfU@_X+Feo@&=w7p)6+%W2g>$gX7_dXY6NyQXM zY-mF1Q>$4IVKQtR%%P?^M@S{}wwai#qBR?r;$3zU@OgYYRa9d-fJ`wgnSGZg)@PFC z#~oR(OBXtw-+)IiEQDybNAN3lB*`>ygWf&=N78lp)%^Y8hE!A}3Xv!yZH1)n=bR%V zvXvs0_97}PZXUkF=C!t4FXAFYL=4@o}={Al#;sm|L%-im3NG^C( z!r;j79M9PvI|%-W@L6eO2VSRG0bPF%adVFhB8?4Yf&;3(RN;yg8MdMvPRBAmzyR}2 zOm2brI#cxe$|fxTd$MT%m@{32QOg9C0 z;|t4c;KBMLZdHs0J}j>z((J>srBG+k)p;!XwlDyCC{z1qw3D!fLP9LBNVE8vmG(xv6u7Yi~V59jcdb{+UQv z%5rsFePl`V{aO%jyT;j_n1*#G4+)~`x~UXD33pd|f^WcaijL|M8UI$mrfd3DguxF zxfWI|D53LTUnc3p-Gmpr^>}tFCZuoL0QBd)LG$&Jas0FOaN5(_a~Mfy28YNTaoGrHypHi zA`C5K+VuuqwjV5mU%_JZOPUUOVeuBOT85){CRuo3OR@-`Co}GPOK=-}3h3et>Xzf? z+?k?zd*QPwL=pExa^zCF`C1S;Hp5WpXBm%P>xSS@yY)r*eCwM5Vaq}|<9&`-FrZI< zs};hx38l!Bc~tkd_dr!_7=PK;qxkF*cgQ*Xhf`Z0i+5;y!~643=!q$lNrHYajOYc< z<-uxX5TY#7jYJ&!hdm8b;D*shs<6j^Ok(~Kv`Yt#H`$F7-i(H=zZ&TfCqcS*eTOk) zzwnxumE(gB0(idj74wV5;)3g5kX>?|^=ytNNi(a#$YwaA@kV$kOdM`>chXC$Q;Ef_ zQcy6xL(kXiksUqdAgpviUH^__mGv_~+pC)9I(K2-<7)Vrq==gBwqP^)MX-i6&;=#R z#93xE(|5U~Cvc;%??n!>-xq{F`ML=@YODBm8}c{ z?<1Zrc0NSD=$Z(R@?N5iOD^kGqqQ!31T{LHbW`Vd z{D$eEZiTzhe!@JeR_?I){yWb8O(^!=V-NfHmr}1mHlubA!TVR)C{+6n)=1q7r7UkB zYZ{Q;P^NAE*uy=XX^-V2{)zN{ld7ahwB;`-O*+M?T^K;a{+0$bNSZp4SdXsOk>@o~R zGmGi2;x@cwZw2K4E##nc5w=g(5zX84D<0yH_~B90!2 zgi@x3F!>dUcg%1F6=_ZGh2b=uX7NjK_D46}fs$~+8!s^2e4Hws(IvKXSO<{UOyqad z59jlgp-`cTW(!sjfo>1zG<@Tq|0uv4N8E+Md4*K1A`(B7b_M6}`?(iUYw;mX4VYrz zMBmsd6EFEP&@xS-9V}n^LPr~H-D;2aj|j(3A7{has!HmWAtY_SZo=$wcAV+405mko zO;G(eiuHW`#BO)WVA+iv+VPxuF^pY7Y2;l_EMYqi?)*Q7?+8{QJ4aT4i-rajXPING zg4*GuNjTEKb_p-fw1k!)#nd=iNJ^-iFx7oJTHG9nl)T*qW4H-aypD0X?v1d&+J<_E zN8;c@7Z5Kl;XF@8;5pydL7;UBRqwe(MtivlQ?}{xWNyzV!`BYNsrzqG?}%i4c9soH z5PL`$XaG6!-9@-|ek8*BL8u_rT_Bg8#s9`vB#BvK!eGN&-0VCBEZE*5^4EN5l_OUk zl)+7>`!qRhJGtJcE1aIT6}|Lv#g1~SP^j0$`nhz-&Szzy@#G(WS|;;nmAnIo6X9t2 zrc9iXo(ztpkg9e{k>02d_;Ib9JGO2)2De!vY!9ziBePER!?$mi^paOFv3+hLbl13o z)R;a$e!YPR+tu#qlN*s$;BxCMZ>OpOX)S#Z^B*uRe1aHx`@07!)x!9bHAC>BayNMR z`4_jhl6k45+~Imy4viSgyn*UnuqTzzN#j-MTBx#U_O51c-i{|Jpi}aJj-8`VCiYdr z(KFiU`mSC0>kdWu@u-p7wTTn&pgzbk{K6YLQifOm6u^x&uh6ixNW5La73%6EY3#94 zq$jTmGLA~26cZ!-ewKuYOF7X!h4iVH!W-w?ba*n;ibzyI#q-Tb>E3a?$#^D+udAlB zvpR9#4VFneS`pd*alpYNETH&!1C0)5IsBA)2mHCb^GC;%>&(|?^fLi%);xjhT33N3 z^G7s2V7*ZV?Vz4?h>Pt=L5@nBMBKQ7?HJOYlL9+Gf20!{zu{(K4U{5NH0k+a{L0S- zbmOb2QxZErgD$W<=K?QZ>;_&F9t=x^s~AU=glo2V!{IbOO=fz4Tbb=JZm@|P9I*-q z&5#t$-t#xjCx)J1;gil~dQvF>$!53;CU23X+sDh3NaI1^@4)>A0;sNUOEJ@cN4D+|N0Y2(YO@<$F6_GEIgA?q=Ub`v>|e;xX}hRQP%hhx`Eedm&7BoY_q-akWDAbD{jC8R$oAULoRKZ z9)j;xxqdE{<`EK*Kqb`+~xw>4o@i5>JgjRN*ET`&9$c3;TM5o@SjFycYGUO zpIZSTA%{30(*fiZwm9 z8hK@Kl`7IimTR#gvmCz1g`@lNH?a0%_U>CyOhcS{@fnsI{Ghyq^9xyof3m)S|MFvP zm_P2}1sAAa@rvJjUzL1k-932pPISt8FLqRz3y;}ba(t^Uv0=JXKa<70&NDpH?%x9j zKPr&I&rE#(+y-bl$ntMXtVmf2PZ+5oMAt1Y;vHg9@H?rD+Fy*sIz29MDpP|S^Lr|G za{DDX{JxulRtNStdJnv`-m`v|UBrFQOyTBGKNM!~hqLUI;cZhRUEXR%t{>=vjg=kz z-}?pZZITSFzY18+Y9zL1eP>Y)`?)-)wRjrR0NE8y)FyEpd1_q>p?mI8+jqL8r>h;Z zCu~Bi`oeJIz--`(Dyci~8R^*WF3fvv$3;Z$M5=Gy1algq==2Bu_^xX?3`OM7<6`XY zJMId5&L?xS6Sw1lT2oOEj!%{{X+K&4&oZY`N46LC;dO$_@o=p8gR&&=;s6CZ==95^Iv0SHu5uS%_!Nn3J_Vp8 zaSwskiY&gSuL5qn&?(|o9`%nT3*Ita)7^BsJ8UdbTw4nN+T_rhZ!UOettz;hHPJwG*fP6tz%o^V?Moc$P%PCj^ubGf_Fsawc8hNMW!{SJ`+(#6faV1*lg%@Xk{ z&Zii*SO0`tDog33mq*C7dUN3>)=7JfW+=k;AP+qU_N(Q&iekBU} zsVq1i@QsGJ{lRt1Q$b_L2fBv!ZEaMq0;LzT(So!ftgkr+!uB-M?|a2bob3169KHg3V~0#c|v;Y8IrP4xo!Hu~7F3cIkub^u)8UIjnBPFv1|x9BVdnL) z;PMjtRY^tucPMSTjMA^f;v?y+VRbyyAt zJKx6#%Ok<7uY#&=_a}Rr^o5(oT<0VQBhWFsg@R#In4jg6G?COyg(c@d(8l9=$&WTJe zHDTxK1DntH24CUs@|{S*9erVB`|_ukW+*ZoKtJJp@%d(~9dy@U`>qkj}b?mV1WcqPorCt6WB9FN`K( zQgskuKZiTZ@^ynM{z7eY4musn@&MaCz-t_zo?)Er_N+=!+|k9o)3(FU^~B*n9ZOfd z6nVJnFZ{DU%`Keq6L}X_h<2SzpGDyJ#%>}E*PJ|tnD1?bVe96h91VM1Xs0gX!?PYv zA-@inL#DJMeW#{N#HLokriySRkhp<2OtpX}gJN2!*@aIsZuYWaF}Lso!BZ#ciM;U5 zF%dZMn=5>ld&QUEHj32Qu)K6xCp6@@2lu4SgV8st>Cvv6#Bi3Yu)g~#?<~t8-O&9V zx^*g1l=@xl9kv`UEVxG<4{RgHG+czI&ov@noQQ`NM!}F<8NL2F0yhOSkHBROj!I6& z_Z0pJ?2dNR*;m>yTu1@ACxz7FTM(I{p(T{0ekd!_7r(4jfj#2PS8{hL**3Eq+{U-_ z3;kR13a=`7q(RY|i4-@s-h~Ud3fR6T0>fN4Xw}%yso1T-4^L@|@O~ z?cRCh`=sA+qvj3Dd~gTPm$8Gdeh=wy<(+8Ppu6BfVkV!Hlp>z^8?3z?$Ng=Q$NPQ1 ziDvTHKO@LcNf{V)q|y9OO5|g0DWqPMLq(P@*fn7im`rV=j)!!K*}Q6K8Yxb{z0x5g z4c~){egsI`brC&u95&-iC0xtCHqB>k|FZ)v($53~vu-Ky2-bSmt3F8oTr_#)-W!xc3-; z59=!#Jm3cQXR_$7Iu$ZqqYHHYJmof@UWrbdjTdQD)DHi~14F4GVf=xv-oi3knI9@T zdN$%|2jRp2{*TqG|A-NrY5gLO1$0ZXWQb6tQOUl>{39pa;Khwds<2ItXiuyJM|(;1 z)_4w<*&qr3buQ#5PiA`5QW*XACJnUGB{O@gSO$m#dX^D`XXnm>ikvDMytxS%vGWjd zR36!tZN}dD|Ho>(D-o<`!3_@EaCzbL70LDM4e)l;S!6Ia7BBQ(1IN}E)3(JSL?_Hh zxaWp|OW&M=u)slt+cnyX#AaL?%$NR1vnF-o2Mg*zS;Z8sT6Y+atZ;+c`PH=HP6S2? zZg45=0#7*WI)1j}u!v)sGvf(H9g)CWUPWV#cahi|TEdMnn#gA9O01YM40h(U)8Q6# z$s-4b;Zm1q#+MyvY@WLy@RTH7!8|XHpWNV6nKU~4A|1y&M!~533R+H8$x(Jb$9`DH zh4Lei;tn%GuT=+KWGGD*eM^O7?jNZ8+HBIBWG^)H%|?3l{^)Iyn?RjL~Pe4 zp@EYFRUKakBlCs-Z@^Y6b~AH}uUd_t|J2SmD*HCMXuyUPtwnBh!=431!JPY<}d>Mf^Z z6^hfz7Lbc5qwgzJ2sg0{0zWV0_Ri5GDNbU-BG+8B`u#1OQ|$&-0Z(Y<1?F|#Pz}8L zE^gq(Ml3ccE}FMBecEt93ey$8KFq}~?MIu>Rf>2OzwPWdzSJEQk1eDhSwCiyaWm|y zpNFy??QrG~b&-!!H%^VjvkVPY$I-Nec?q9&RD+C31ga=z_w}B|B3(+uiDn!iSq0N( z7ILzq30|D62k~vKG;?tT{-x{==S^Sn`4XcDe+4@~{~XcO`@6B(-ud7jQ%z;GZ<4nK zu0qRWPkAph%*psIKcLv65{)!xo})@D=uAzf=bpD!OaZXJNc#JQk=LZ6bSDu#erHdaj&hx=HLdU}! zej|1FwIn4cx?#iAHonZfRy;>g4U!iqvN7S~`)lvPXWIh0jQut>D&3*1c|UhtY7JIA zG+ngQJE6RMHs-1SDyxr*L1tE%#T- zAC)D#3yQZy(KN|E{CjK#97)Tj_6%Fx)I8wpn7f>;<~DrtlNrRR)zX)48e|6ZUEW!3 zNcXb+)M4=+_`NCuoejH)YdWle)ECpw9i?Q#!=u8(>rGL0)OK`oy1QVJs|qdl6(i|) zn&C^J4b@m5f$yfci#V3Q`QbR+-WHCRmC)?m1QL|%CM-47;q80H^5Tm6q5I}@bTQ*L z&hfMpapqSiKP7QnT!e`S!ccs)KQfu*AqZ8-+4?8Fk*ZeZ5iIhX_ueY*Jy~!eu#mr8Z=sc}~VW#4=F`xD3lz)I52O`j$ zsTp|k^n1`OD4@?~OA)_$-S926hwJAr!;xvTVb84=DqTOBJaHO=N9&hTu@)sFoxn1? zc9|kw&%=0}O9!3OdSPm889Hg56!~ zIP3OsG%3qWq)X{z9Y*bE(pV162kJUHi`@NcFHDTiLJ=1JsQZh%V6#*u|4l#yo>%7% z%2{X8o=as|-!>JTFBZ~6b0!jlo(AwZ^@>}uh~S~J;UK@Zlb%~LliaKL3YMF$Qq|SQ zgmjm}kkAup-mS&@AHG6id=9lt7)A;VyI`fcCMrdnN%nP?o7cPasa)=EBHc7!xP%j; zB~j<_rpv2fnR5xfeUj3}45`1 zYtYIuq4?4sN3j1;Mh`5TK%B>Yhm%uyoM0jAzuqV=%x=j=#yKzWSriGjxmC10L6`6p zYoUKfH+OK&MttP4gb2@d4oHy?oS4w(^J(to-F~!pZEQ=zU}Ag(l3j8g_uDRpS)Yqo z=S3qfxl{qQN%`ECL5#6F4cg)>=v~0;cgsKHy@rn zVVyNfH%L;xi?G)73GZ;JIk~Og4*_wNsC;rVZuM9JOH=OB-Iwcd=i^eiJ!TUcwk81w z=tV<+XDKxks^hEQ{))Kq)Yuk$<3V#$6FoR= z3GuM$f*A=dd`0ONJfFSszw-I0=5rqQFu4b}MitOcwbI1Ay%Fl~4skQ?tj3>qOc%}D ze}cylsgP1QXOzrds)6Kftd_8MOd@KBW7ysE{}`TfL_iEvJ%xXiHgZSf{Lr= zl9D3Ot6waO^2Kual~hdK-+m!!{zrwrjV5SB>^AhPz+G^Di3*+a_a80^X@PWa8+yVw z95<}kD8lWcfAM5sjl0nHvo;TO49FATewbwU487#v#wHq@Aj$M0RXphPN_~r z^y4;kaFmB&F6PgC4X5iw{7LHv9Wpii6EwVGJ1@Hj_}KY-;2KpxbvzV^sjWEk z-io74+hzD&j5d6%ZlQKDV~O^nPB<%WP7gd(BBz@wz~jCt%9wr_i*rUW^H(Jm3)3an z)9b)P`z)_P&w$KJ`V51Y%8{e)Pn-qZ1HPqF@N9ZYrAMyuKb@Tb#b zMYw&_=Phn#oUPuJ0@^MwM`mVJL&9T8)Gcj@$8H@4-@`j;h!6APxw0b-?u&(Y=3mkr{b9!t^6KoaKZRq+8@9ch{599maJi&_P;p}DJnZCE3pm#%+!_`SRX7Le-k*-3=?>)k8U!tHQt&++t3m_%a zXA6IB)j)T6)>v)yaL|uyrxGmdd+)namIswc$GUAp_P5*xc_$?(&5-NEX^iHS)%sAs&Ve@ioo>YB~MeK}cZ z^5bpj>VUgo)W!;ap{+ErD*pktFpQgEk%POYUxeT_uhG+pQf&Sx70k5?X|?)x!v8pj zaUiPb*oO-pO> zVx~p^51)x?JpSDr4Q6qrblT7qJYlC8{I|Q*;WguBRjH7(v4AS;1QKB`(v?i) zs$PxfE}kjsc5hs)NP;5S_kQ*cRk$5M_A!0weaA#(ZgmW28R)}>J(VOJhx~C+>R@z>m9z3yvSxe}YQzGZcM;c?bSFKv8@q zeX5*CY-W23b%fz)!A(D88R;PiP=Q%7N-%E*+PxV$C8n|x`1|?(<{DX$@GM3#$TDC8M%kB zrmitO9bQH4PU({2`;r-y9vpVuk5&kb6&4Sx(5-6%DZD zr8Zi;k>wb;jsunX%oAb#2V1=D2cNYiy!fSWuvJb9tUsGil~tI3kiFLy8%UyA9R@hi zLQ1r+e91JBp0TB%6>*&gGj2y_VFMg!-GY=Nqw&+V+Av~S6_tBjkDaS4;o53>w2IC;PlW=3EUelO09Q?EL|SlIomBVG_2R z9wOpKsylPB7wbm9=k$MFUv<`O;nc|*$hvC~PyNeue|wTi>I zVYjmJn@1O6ulZ|~boDEKZ=MFBH3hU#cM>UC+787A?>N&ij9=Kxh;aK>*mNS-zquPe(e@ zU5eb5?t`!f=H*E^icgd}!!?_7>Um)zX-yvhtq+LPicux2H?)CC&rPH{@C*x;qQJVO zl3q8}C3VsbuwAN$a}2a)otneozwD`-SHuW@`3qh?i{)h3_Ms;SYXqmPdg)rpe>k$J z90ot$r$xu)NU&->D6cYPS)H~x#92ecZ#yn$-Bk_c;Nq!3PgXHsMp^@`XpTU|AFkm) z9ZN-e?}s*x_;F+nY{P}z?>L0#N*lsT$2QvWUW#mc)dZVd7E|*pBT3McTF?pKjA~}> z!aE&IL9xA>mVHbjH|M(v|0q1>ef?%e=1LF2q=rf~qpqFpXqw@GmOE;@9EW8$#DJ4u zDb?R3P3DKS!aAn^Z}OXh_jHKCe|yO!>n7~yn+9{`3+TQ5yNU5eeWA*Q9q6i_Hx80i z1-1M}sxM_s($`l(OlC1Zd`}ZDDX0az#S|r;dV)WNrNCLAe5zC;MP!GXpt)~=>+@ZO zKfIeM%AuNKF`Dd5D1%XDw`mdcm`quqBb3>Yh)zfx!*^#IK*!Na>eg#SGS*cA-{2kZ zuZ0h4C~_Al4vVBCR&?QI-W7nWSWXD1OrCxg7dkyNLnn6n;*MwzCVJG;6Ka}dy4)aq zJ8VQ-Z|jn4;r)OdBaxqUB7St$8b+=xrpK=s5tSuX;B+d1%d_@Ddn()oM;0nmpErN; z%d|F7VSd=?)l%e;XA|&#twmFE!tiVhdl83T=s^*lw^`o7 zyNn${GbxicT`(e7%&I`rL>!&%@IkBhcnF5vGx&GwhmkvlePHREz-?M6hyQNw72&z$ zI%$%J%As+73Uvq{OX6Kv7S?kGge#r!)Js#Ks;!Y~bm)*nn;StPUz~3F#(F*emO#$# zNVMT~I_B?60f)&9&p*qP^*1Gilgh}mvSO4k|sh~y}a68L;;AlXyQ5i(%SD^OX0sL+_`yFjyc(X6RqTWiw&`>6Xz8!OZ9DQUm8n8n^H8a&*aKqNw{a*kge4X7{1Fq>u&{ z>Jat0jlhr5M(^+J#NissP%^5K{#q(Q&fNM3hYTxt(*Ccp%iL6$w;`XJM9UKU(ke(C zFM)nr8{p>WQot`@8nY!6NNijwT!Cve>ah;Vp4bTE&u>9^Q8eDUUI(VEucB+%>^+n1 zPnSC@pywa$@txz#V9NPMdSTfJk}1{&1;3x=dA%D!)L913be9t-dsqyP+PfYO?ku93 zMuFs>jjr(bx@>Ocs(Yxz#6>iR>r^R_BX93R+iv!D=&i&qPzwIB21w225Z-9!1E{Zt z-Z`y6o_qF#^WYTD$~p_OM{&5O3&cMxXMQDBVxsw**&_+ZQ&uH} zWkA`~-$Y8Ao?)?jQLsC`lCB)bG9k}2!Y9WbmV;`8HKe3O*go~gKP;>M3sg;FIirPr z=;e zHe;v{G=h&0)8mtC*znC#Fs&}4hi&U{v|<(XJ%7iAIUxL6-w?7_x6vE2QshTxBdqkb zpn4ZZlEt&@!0PU1RNESaW6qh1Je!XO50X)q#=`Mxr+IFRb;yQ84G_BPEox&KL{}cH zg&SQdG|;*l8z`5<%`x`q_@Owgw)_7$Z{R(ec) zf?NDk;Ja2nJ=-Wnl)Rbu)^w0Fk6ndlXwDMN>QM=!$U2s5>Y;s`-Z2Rz=k0ZckLO%O z9#2E@@KFY^NUM^j^vofh+bThS`di+#(_YB(xx3(Da0I=Q*@;^Yu>N9RCOz0Zj(iW4 z5N>KRLwAdOu&EaU{eW6}&q0G^XAVO4Oe6a2I_qiLFaY5XBT?v$1nio!5^^ny>6{gF z2yCi?OTu_gtb>y>1BAty9Y?BPb1kHoutzl-$b7kyaP-$r&$j^Cqe@ffo9IGd~cfrlTGbC;wj1}tUiuRkklUVkbTnji@o#SPC z8j#mw6%e(y65;y;xclJ`2zwFA&-5Hl-fSEMxgViu=029G8y*9j>q_adXDp9GyBe%c zr*OLcR>)+sstD&tnO?&RlAhq<9ZoG`bV+D;GrURHLEqYT;H#y|aG<<_zO0ZS=dHwr z#@{M=vZr1#-ES(q8I?~Zy=BR+g*5=S66lqz0Zxq^F7o&|@Wzv&C#7IF`WlVcuS;f> zHA9z@6FUAP3dfJug&6h*$yWc456o<6DTe^ z8b4dU0d$uav0YdIxoDs#!gkLUchQSD7tyRfd8Dydb=J`(F=B$OAjoRH}&aH_Wq4E<=Q zk1O;@AIqG4J|Ujoed~p${dO0mZWgDLZKYT)H0!NvGUe}{Je*wI)(Xx>;pmx53Lbwu z2HfJysmp`$#KW}}T3y$2|7yd~%Vs3PbK|gKY`6XZ!mbxmzbr%Y_(~;=$T32pE4-24 z0S^(LOPpp|99=))nw2D%dN>Pb^<9Fg2Cq?eT`ZoW`3 ze)v)rx*vAZeTOuNN=O-8(Ys8??$IX?ipyX}kSj7?QiaDPmc#QkIdp$mH{L(78ZxVt z(M${0Z!%#Bc|bV z+h9l94fIy-8eS#z0G?egJ^q>HOs;EzhktrGa?J)?e3pX$eD~{EC)CSENuhVxSuXPZ zFRU`70+uAFQ|S*Q$h(vEEc@30y?J7TSJi2X=5u@131qoc1uU8jv; zDj$-t=_e~lkSnHtQfqLHVl~L`ddK-6kR%-}=#Xq0E__~+$-7*qBoE(Hk z|MA47rzb(cgGTBQU`R~k*!+3!6JJWa7IQJxux$8K6j1dDzjRE6XSMHW*FhnX!y!N^5luWFsJV#TH_ju|BBBM&F8SzkhmSI zf-4i=@B;O{(SyI90+scV^tDz8J`u;d8}2-$rmKgON!wUY&ZC09Cp_&iph2tl5c`@r!ey*i-N`fo8>g*eIp@W6!=M3i^Q(fg?{Qpex)(Zi$Wt_* z7t8cxnUCzQ+o7afWk!&_qdZ5#M6$YfT>2a>6Xq%{4oZ#E)0^ ziRN>sBT{6Z7n=d9@6xI9isXb=4J2mBA?Z>_JPJ>R5yPA4MaCVSe9;P$?Gkhi!|gfD z_w;gF6f*gpiVG&B!W`dxDtDj_&y+3)^D$q!;8m7bK21-A+n&lS+viCS6f7~PEklZA zyr2dy?qiyY=Lhk{!g(S--0T*ci%MES@y?B!v4u~P-aOWn!&W(expkH z{0#~u?%*I8q_OU~psRRw+5hqULrpe5_$mfUQYz>IAAcfks4J{c)Ict>%W?HX8Q5yt zPLJ=_V;!dD@JKnHa&NuS!#FR2n}Y<6zB-J3wm)IV5mSD{1}U;Srxj397>d@4#qP`} z_4HyEt>q>Xr~RE!p}K+Ne-1+*Er_6IR|m~xxk>#E4`A%xLb`5)0U->}i?ZjSIWpep z+80j|_p-BV7}>mW0LsS><9OdQ@tyORMRw@=4;zWoj z7t7qD881<3g8OT>P}*%lJb%m=N*Y{3($kLO-ZD1`jj5o6TcdCd(}9;MrSalhCJ^x- z9WXQGCJNt`gl}E-1Pjev`javb{?AsZ+5VmTEoOu3_74~F=i{gR#m|TSz{x|g+=bjA z)WUSd>7#a0;Y8N4Zd3th#M7zk*pcK)Qln@-pFGP3cPC93VSC0e6;jCd;E_IZbScw^ zE8J^?HtQ&KMm`Da`!9zBp+$6#dJWbaTLZW6zT>hs>_Q_k#guc~+ye1kWph!Mta{aDQljWCR2q@Xn;bNsc(d>8)!}*lzPLmb;y)cdRikzGDir;QhXJsUOwfPDf z$~ua5x6J{I#tIs&Xh2>u4RgWd*Sx4lUdV5@w}@9i#B`6EtfMD(%tN}PB?R}3^?>bz zH@PP-ym9Mt0uP?l(iu!^S97x;6dd%a!{eP~)^r2mk03z2+woX!&uZA+TtsgQ^~uP~ zRWRB-j*ETag?7#J7Sz92roO#Qs~^??*Yj7>d$u9ic^vbR>3raxwH(89ZaTn+{hz7x zqVZ(Jln&UWlVTpiwA>}z{=nrC&(Ws0x3S$V7jSaSqE~L|lbC%htHkdwCph4R!aBV~ zJWSFhDYA9TFUWm!k(>Ep1U8rbA?mN^*GJ;Qg{~0!*MQEys7R_9uT`!rkIpZ3#9w5l ziEy6J=I8lm+TkQ8NnbNx@GgULSh*((X(*@Sr(UUWNhzO-o&1Jhx!1t0mg(79IVgqy>kVPp~Yly^tX0DL) zSC2bmZiQYmod0j{S+34{j>^4Yv2Hl6W!l}wi|tHTsf!$b`r`u$H#~O{&QF*vPaN|z z;Js}jmC&iccIPWVYtR5y^ar9%zU~5<`ci(B_9!y_@o#vhHjNwh?+QNX6)KwB^~Po6 zSiR#QzN&(%eArInr1eBNKSpLbUiL&*#Iaj5e&Ejn)^j&EjyfD=INawg@VYBO_en^R zVACN`zO#_;W*&kin%&^kgkh*YhjrzAcY%33?$c-1VQ8R(h;-xe7bQvH$qdNXE2N`! z^~t%KN_h6o5XG}u{aGISo8lFGu_Iz+zn}*`jThq<@5sbCnKK_szzfy`<$CBz=X}IzTy9P{+Z1f-7@BuAlPrC0II$IF3u6;Unmemu0hA2z5fmMSt{S_ikdM-7< z+CfC0Sw`Y33tZrBZ5elo3&dJm&B1&|4Xs{tnaq9dCPdLWJSm;IM6K`#Jo5dF!n%^N ztGO*iK24=JeZOMe64v>9Vgr)y4nXQbZh{pF>HM`}O60GxgwVh;liSiVne|`%AJ6@6 z)M1||=}>a~9nIdwc53^+z^h4P(D+TBxZ=wH@w}9slhd`8Ods-r&x@(UcL(d>s45@H zC+6a3H&fxG)jMjkW-L)^kq|mtk3=tqta0A%*$}$0nf|&XN3zw+z-;tQI{fku^3g_L zSd@{76e^D5n5H?<$yL(3lk~}lca?Mlw@9{kO;0Uj4x({)#m;O+MAuw6O&CsG zjQ&CD<;&cZ!y|C?lzxHn!XEmE>C+A|kLoH51A50+o_x8_yuB-BkxVJe04bd&(ynwr z(jt30nqkCwF?vajVR&5y#D9oF$IVl4c6KU!g?IEsejE1KPz9QTQZ9fj!7pbSK*YgT z>cjAAP6qS9COqKp$QVO(SZ-MDRx{*(>Hyw&%0#pqE%ClXPE2zb-utM?p+hX2)UXze zYpRgZ`tMkpWyd9Co&*y!(tRT#wb`X6G(L z-2TZT49|VjhpTEcps2inF4fvajPz#-oo?+yAv}Nle9;700}Zrn-48sUiEL(Uzc%f!^j5%ba_%&G{k1tw|O-;nAhN; z3rv2gfaJ{?hJUq%*x#RM%{hOP`d(i+!8ePW5|)gTZ+Zx9G&@+LryS8a%X)}r7t+}( zU$Gs#NAefzp&42`QIEBo;E>{1zFdz2>6H8nZZ^}nptD!7VSlJ77fZ_~3!gc49R3cJ z)8))lBO_Z6D_#_F%dcADB>xejoI_o9X4?0#UaC9s6a{#r>w&)PewUnorZmAd3nNhK(;d#A(98+|qR6=bDV@M9kQ!`^DW@Fwja@AJop*zx5Rcr)!aGLdC> z#3onZR6=PoZxrDrSA$3CQ%+?s4_6qB6y=Jy|CmCoSto+VmqaSQLYFvCs)SDyT+r&W zG92@$0^YMMDLubVyyjC46mL;Rxe}3h>uOhM8w!51xPyHcag~t!Xe&D0dkSw_xdGlbipoV|= z&Q)=t#lDl=g0(x5<6(ARn*>s+oPHcRzXEDfQ|V%MPId@fL9aHA^I+MnN^&#dzYJTy z6UszsLM3SAj}+;?>Mg!OzjQR(pm`Oi+F3*0!XjF08G!PFJp|{sE7K7R#mL-$4d62p zQG=8S98~8DLIuC!Yzb}rP z5t3CxTZ%3mi7eq-bWVg}V;~&E{pZnPOJ%u@cRHBll-*93^yAc0p4jgPq|qJY?A) zd5f=XjKLfl-oU-clI zsdYlFrJsbY`;I_J*L7H!*z9->TF%*P3f;Pr zVdQEXR_JxLy}lh&g=%N&N=ixv6y@%YELnkNMwV&*xIq zUR)qNy>1J)a{im)qhI^O(PNHy<6ykxj!_TV!PzXYtRyN3UR zJp1V+f!KFSAQtJ?ubif_zB~D&Ee0;t~hbecNS%=M=u%V;?wDu zSfRysdO2yB=#_biph*CnUuA)dxu2xGrjdU(T5;#aUgT2T7EXFey?Y4OY7 zsPgIEOZ&b4a6`)x168_{!iNDcBh(JhVLFR?Nzq z4YwbFvQ{usF^}0kGNcV}%W%}T456^+EFitrWqbGm?t8DQ=KrVt!ddY!H!?cSLzc(i z9-%;$bbn*FZB`P;xGwZ**Ctf)4j^-H_`}`Bj~neM#ruy-=&U3=)0^ACAHnx`YaGTHw;@|O|aIpYVaW$z^U zi6Jn{k8>?_zOWvyhiTTVapL>~S%T!?N77&XZ=S#WSO&N3t1!vdp2_DlgG)#iUU@Qw zbbW9L5~^HLGpm5z`hRAMe-8h@pPy~f!;xqR^67lR3WH`>l7bY2;{qh5rs{O%>c_qTuk=|q_ z&yTFW)`NxPU#Qiszz}&>a*F7$x5`g;v2$` zt3vU`-q5{2=O=Ks;ZTEOIByz{$HWwNi?ao?=5js6Sckj_bOOb5{qWW13YNCejP4sy zjIR4WNo*eG!CUTgcxd{JRM1B-_|1LXAC$tP1tqF1{~dLL+l9^oiGdDgPk9R9ZlObpWG_+x%NbI3aYIaV%szT~=4yxbLzjZ4Fvp)%+Y>&W2SdZK1XR*?i>*?oRqr}tRayFyyzlRfW0)3wqFoVfv)M{%nx}WV3 zs!q9*4aJ+KhD#qvLT1)N2G0&ee>yJA3G51QN`A?7l_Q+NZu{8@TT?CAf&m(|=w|^A zDN!X$PS}J0%t5%Vt%CK)BJ{@#WwB?f4m&o&jCNaFj4`_diKYK-NOHN44a48Fw`c0% zrdb&-F3K0~o7%$T+m?7DriT4GTTd-vE!S04-B(2<{rH&j#E_R8(lHo#Pz8sjPlLg%xP?HJ!bDWki(~s&M0gO+u<+4Ebd0Dr41d zKdMgWzkPt;XQ#3`#hK74<{=(6Clz|0WL21>^t&WeV(zR>-zzJMjiy6{;yV}Np8iqU zJpY`P2-cp#cwu!Od$7)s?rPz0z2h0eh3J`3nWHY-$!*exQMG5eDDgVO*6|%6YPF|~ zon^RDf#y56W0%)fk|rf3nqL16i;RzvK%TSP)aZo!L*m%vwf3BqH&Xl(79mU+b%b0F zu$A3I_ZTVAyFL$anQbcD$$b|$t`+0VX_n-0Aiqf!drGGT7E10&<><7jJcku2FZ6qw z0R1$s$owtcKlsDhaXeFb^)QpJ)S$Tw3o%afnXo3&8jSB~$a*Dqvp#fLYA&X2ieO*X z@xAM6F-j*oki0?J@J+J-H8(zFnh&br;@(31`c#(;=WPE^m38>=s=^BsT?6{dw;6ku zZ6~|_o`Ou(b{SWOI{~^vs^EY@AUmeB_GyG9}87LH0W8>^J;kbhriTUaz{W`k` zvx2`+WK@AR!v$uwXA88e6AWEi%!DP8^!92eag_H%n^i-2R>HIq|E>Q>zAcXivot$w z;-0s;tzY0H&ma^oTS8)mGjMFdN&McK%?{01qGPsx$D?M~gtYm+!NNcZr`k6%8}B0M z@+%Hk&P!pLd$@ki8GVU@@boRNaqW|-0 zB<;x|s9G>qri~kio6$FQ#rP@lt<8CU-(UI8OKNjCknM9RhY9>UNbXu3%V~0f5p)`k zKU2zPJNBag`nTY=JQIcww^5Jeabl**8?xlVIVkO1jMK+uuo08Y=t=JXS+L=pFw5VS zXdm{Hu~VLgeFxu!N(^~Dmp#!r!aGAZV9(20?D;@LdcBJKaxLPlmD^JwKkWoI?B{O; z8{WBWUW)febP9Whx)J4J-qP)!4<#dK*FePC5*!wHT$nzlE8J4}E!(%N^yO*&%RJ1y z63t#lsMAb-Q;3tO62BSt@Mh*<8Rzi+L4jI-R2Dmob=camX7mr|Y&T~Fl6^;Rfz7%5 zI3qrV;jn6WwYM1e@5m8?_D_Yo^GD&>h#EHMj4FMww;Ja!9K|e4deK{zEqI{Smh36s z#hEjcFq#yy{O;Fj1a%bG>U9_TxLVK&3oEg0S~20H4QxVCDC=(uvem zyxg#zOu4)nqTd+F_U(8oN5gt4iBbIuZI&%-fauLtm~yp@SPl}wbVM9(9+$%AC96>1 zfmJwCLy@>i&EQnH8t%;a&W_I4p(D{p{M=FK>|Vf( zPL{zi`&#U0sZB_-CwWugEM*VmScjQ1egA;>o8(Aey6SSyaNJ6K)|}2#mm1P~&O_cB z>LwH)h#@={X9A+7* zPES28#PWkvggwoN$$|^hWSU9!ae11h{1A^8e_**DTr=5JihZ70l4&h&r24nF^!T$P z$(kC+$Uh{Wia>E0rW?li-7YeX5QipW!)t%;sw&0;9U0y^U)}YO1 z#i(Mpf%wx?@bb`d^yh4LMXe*eH^)lUipmiz!cxhaQAcH($-6NnkjA}CqZX`Y{k9du zOtl>B+GiZ`-hT)_WNyMsWrYlbHK?&oG1`m^CtdnVV7x*w4nCX5tcPr+TgpttRQnNR zyXRtfrmTk757x1o!d95Eyc3^F0);1m9^{S0iF2;J*{!rDxZstK<~euxov{neK3<6@ z^vp@|p~dk2pa~X^sbr~Lhfxcw4qRu`hlK}nZ*y!5j?oGt2U{*e;E4rzR-gA<#TI~% zX9Z>`rwV;fdXR)nC+X%5dMrv;jy^bBgW*?!sVjD&4K@{68fixk#Cb!l29HsOO!WnS5#H{O#DgIjQ@)gHej-e(&vG9gjQ`_^lhk>Dd+$W)2DRNF3I zawtlXdi8I_qzTuAf#F7=J5U+_&q%rbrvOsAB;bT!$?SHb4n4CfU$$er?{WmUNdwSe zPX!yszgx3zmSM)h&l1H=xsW!l6oo#3w*&+J$inI(nnJrN;EO)sKb4-$Kru}s# zs`s}@XABBrsm-Nuy)z%T8^*DJ`<3W;(`I~g(Uk0Vbb(UK>A2%*DJ$hX(*A3j@zL2~ z?17dqy;E)_N;wC037i9;#w9q%kbi#o8zD=cXS+V06V`rnB?m5Sks6#gV3xu4u*0qr zH$9%iuAkJP-?qq!{p20UBDEu+ukC z=tbVKn0K}-*Wp$}_v*niZ=tJ+4IP`OEH2)m&5mIC?-3*`FQ*l|5roLtllaU!0SsHyXC>tTy#LOMeB87PKDkfE z&dr6acj+~H>9LbIbXs@e_#F#6-Mt!n_A4Pi=gXm9k9TMe+a>We;O`F3V?U$JGX-TA z;OQFvUB4)ssode&z|d;Em2h7esy>5!d;H%FAF;R*)}%kc9b-SR4ei@#KkpIZvRq%X z^|uGS@b8Vr(dDep`!~>)@?z!NY?}>5-{8~bDvVVqBMsvbE``M5`toE}xuFN0r7kD# zj?f~rrkX+27_+*O?&bD-J2-ZUbBUc=rk2I{4SBBI{xrLVKjc_n%iHo6uOw# zA&$`|DSjU0(sXC(>&$LfTp08y+^27~XIv`}r;DiT+oK zF7I?>`+s6+ZzI7fHVXOShn z+k>KTIwJOqb2`X-e`m@ybKI63Bg<%XtS@*K*8K8%69o z-AKrzt^8J4EHUe?!1D|Iu9vSU*agMIBjGCc?){FO+wd7iL?vL3@Sgc5tJB3iC$6~s znear(8XCrH%KYT-V~pri<2*F(AI`2>@ck{T46BqK$!F`Yu#)GJbh#h6zOoTI!)h_; ziXr)uq(;YAb5`vgg%>lwsngO-zMm^^AV0pGgfK5VT+eS17tU;>BTYw$EBC$=dcXfb zRz5r`yJ?y@7Q=(5)w0=s_i+(eW#?e(fN|u(!b6Z_wi)YY6|rfwJ3V&h2O6v!FWhy~ zpbg=i!MG!wMESmi4Z*?q(j||beCJKKSelAHX~Ri)_96(4Q^T1X>)5&czp&($k{I|q zL?=Q&5_Gx$6jyFAM`%gJ>Xd95YJBwhgx~a^s624~$UHSMA z#*gmJMDA_=cjX6m-xEYG9=r%7cpi*aW8%7{m3t2m51L z8t+VhZ_~dTlm)=xaz{{`rmcRJ?U$qdwg{uae)s?~#vI$#66w7^QdenPKJ#n#kW!4KF)| z)M8hXPPa)v2RxDp#qDrJj_-BD&I$@MRpIK_cInU|O-w=j3o+HaYtrc^%hXb%yS$3< z%s&yxfMTxI@Fb8S+^iEx|8p3TVk`!basK)QEOSho5-`n zH`JZQ1#dKk);$)quDJ$7TuMl*LJjm^)q?VM`y~l{kGlRP9}}4a8D@0>8eg5n`@OQ+ zreGavr__m7GhYfCbEgws+W|72yu-5roP8f+Mdy1KSo(M5WAO>I9Dm$*N(^X_+++hOAlHk$8*HJv`N|S5zrK( zj_=&Qv&a%H>cRcY`mRxI5bu<+8!|$SNxeiW1CPPBd!y0(O+H(0TME?+>T#C4Ht}kA zCm$W0rHPP7B@qwLp`2ta#n?2phoV=dxMh-|ErQ-Q7lBpL}Y4Damn0cv>U^zJo{yaS< zyLI|MiHBDoPoi;nF2kO^sq^`IJRX`QD4(AJ9|TQIT3pYT8V;qJhj?F7<7t+7)s_5| z-zF_+Q(|j+wZpN=KX7gPXvzLGHEOZ{9~%3dBx?6>LeG+uxNJ!ddtI+aoxc>Lcw>rS zMh=r1J~L!WFyf4gEgZrrYoWI=V3(VmeCFR0ImMT{TwSJ{|^_?EcF43fi`MV~uq05U^G3vBK zu@pyGZ6LLyPC_{6f?l|g&c0Y|qw7q~#A&zQ2}h27Aj?l4llc;JPZvS%!5Z0|Z<|^G zd)u;cD2^cmln=qZxt@4(UlB{qR;2@>9zVs86jG`+=qa^w4BQ?;VlTXa1j@;8^I zFY%@`jE9St>xPpm*F_-Ru8uxi>R60RCoEc`B$h7@5gaq!h}SeHsfn2vvm4p~gL~xT z?zr15$+!!RKV8MyJ7#3Stwk`=#}rkERES(I$W65L(gk-<&T`jDa7Q*J97l_t~+E40txT0Joi4 zO3Yifkm8A(r5oH5B=K(z;e3QL4jt6Ueyz%f8S@kHnPoDIF43bm@08%u4|?S9b_YmS z7>If!cwc}9=b1QE;Ht-;C55Uv;CrVOdvtw9qK+iOYt=Zkzn9FCdhi_{6~ygrDui8~ z1u?be_~T#|i|)(2ckkrlB+DzzEW?PlS=M7m(`>Th%t08CJRTd*7N$V zf?;eSpY3i;cRaPM3Pf%Xawm6Nllbj}y*(md)%vxtCSH9Yc!atS^7>L08stMzP}^(z^R9 zOc~~ae=a95zs0=2??4s$b^9kQI^jyrU)e5AXn7=AT37~O1o#@)NxWFuT@vU+p$B@P^@72nuBPAb1fbgIwT%k|8x(l z!U2szWQk2Q+%AtrIg=E&%cBI+&ljTYvaiAgk;2fuW6?uoBcze7s- zL$nNd&!UHV)B5Qn#NMN}lQG4cK+CePY@fe%r5(C{P!y}2@@&)=SHg|WW!QIN0T~d$ zz~n$Y`fTE#r8mm7@^m#mvQ;2otw+F+wHnw({LaoQYSGapd1zmHfxS7nmFjZeY-#*u za&gQtus=Hn4W8w*Nn975zF$r>z1W9b@^&K~`<TX#X}=S?D>*ett;9^`q|sgE9`I^p~Lz*;c2 z`H4zRglOftk_B~6Qs-}9B=)vSlnncUKMV{6zv2rpd7VFANGT+%+Tu7z@f0@A%4O$! z&44e>|IPNwC&sknZZ2+}8p;Y3+<4x~M|$e6GMjX>9rhpig?9hONcz>zq}%&W68)B^ zk-ZH!fNwQ;MKOovZZe>?I_;b(XD1Y-`jLXkGi93j$f;N1bha}-ntG5$^Q_je)G9pN zV>Gdgb0c>%e5ClTMB=tjjy@GTu}fb?q09C-s5yE~rkP**oeD{siTJa33e%5KrEQ!K z-#Y5C@W*yCjC|HzmLbYsU_c*h=Hcm(bIgKkq?HByGsg4&Q3ulD;l=`d%y~rBK}9fA zl8;w*X_3#h8nj;S2WIS6elcoMS2{7H2rIPLl80%*V4=BEHrq{m?xorv$A|`dKMTq` zK9E~M{xZ$nhwt!ya`kBS&7Ns%76O^dd;OHhksUgk^rylvyxclYn46$ZofFD%_o;Al zqxv~CY&nU7n9C-;JWN-`Sc|XES(DxE3n5~nhD@JHRa#G#UwDX%zQ_}o0#|al-C4G` z>uG(1(D;1(V{n@(MRC?m-#R?&IFc+VS_lqbhvWJ+mFx=djn&xIf!l42So1@Ezux#8 zN86krF&CmBKWMRRp2zkmg@;Ywafd^Oa8likXjr?*=K1f-zxa)&5^r%P($W_y)YIe} zR&2Bij*u)muds(1He z65dre$h!nBe00eIw~dfwZ;X<@6>Q92&a~-TgS!mUB^xcXAn;rne!BORlp6DQXjvRy zSd+}j>vfQmz|96AiUlw5d6UJfhaxv+@kfAEle zymh(~-`j<1)G@qAjO(w!Pc2u}+n&I3Ht|fv#v06i|4-Ou>qb8I*&(&Fd?K;i{trTw z{^HCZ;X+51FNt62EcKMGW{R92IJ0{`E;hfx8r)Q=SyK_t7^FgSf>uJGZo_2$7KH|5 zs`0aqGwM4eeV3Ziwkb7udEyBYy7MNCTEO2*zmwU=7bVc(^M5~BrZCTNCpoplMLM{n z2kX45NCWp&VsMigiyN&@C;F9R)vR&kZq^RavlB4-eIYye?lQIXa27+Nx(U(GE$E@F zZy5KslxXXff;aD?>N#+iWZje!u=rbqsT-Zhsj>(d8gz;?rn1<;5qi}6iM;qeKq|cY zWJ}6c50rTnZw&bcS5`j4h<@+c@C{zHmzubf0UdE%CV0jO&E$$~53?E$S61kTnN~!;&`|vc3KA$nNwg&w5OE zy1)iXwooy_Ts(2^GMUSd1vuJtXi#xtQOh~b4}a6M`bj@8Ow3wR&g2j1F)ELm*dpX2E2ei!}D^SILv>ij+S5fjNb}gaunJz}27r7@Ai| zx_Jk~gDfgUX4cemlxaWPLhLzZot{FQ$Ok!)M;R0y7@FU}(RCOp$xWj-RSQheM-@zL^_oSKJ|Wo?0r|tlb8S?)=0P3V&@b zm&U^KLDyw-ew2AC&$%Sx@#bW<&Qg`eg%;svgU5op`y|Nht%Wb)8{3i9i&p;4!=t;- zv1`1i#^`(v-Y|A1J^Q4=haCkt`9T6x8eIyz>WeWrL5D0e*5sU-HvFTZ@?y+nbvlM; zA3QQP5MgpKxV~J8|K_K&O73-u;>h4`4|4^_`|ru;ZUHhK{=|zySi|qC0}Slh%@^N6 z(cv3zT04~lWcd)U)lSmU$G%GTckfPz?rq0;DH8L7NtE;C zy}Egxbit(&;=QNC$%^9(q4z%x{C|(~M=LF%n=xUd{2mrP`5H2t74!U@&f zGKEzKJYo1LTRdZ0!mv_vycvo-sEJBm$dDEg5-@|7n-2M?_zIbgr{i+uw+=bHo{~N!9$F^HV_x@U zrvA4PdhvT@^3!U;ea=j{YGsMh%~fpnl;bdIsspA>8N#fu^rCS+>M?A}OmgY+0T?xT zB2L?%&oXy#k4Hf*cC}8nX&v&8wEKRQuAbe(o;T-nrcePEWZYw}P2b>1R1p?i8j*Q@ zoxrAa7CPFLvB&Flsc@?W+aias%*C4Ygl|6X0T&WC`3!_O*kSV8bQZbIjJ~$4!xt;U zg|q3dM1TEGX~TOXwtsRJ=mb`wRrxHIV|y4*O?Ks7BspwSTL9P^IiUZ~e%2o(J*d`? zDy%ZROAh&5f#kk!xWy@f?eXPZqGRh&XObLIobE=Z6zr6yl{}FY9%_Y_udUcn6ees7 z^dY|!oTWx|H9K?vH>3>Uf40-tS$b&z6!YEzyH0<>Kx-u!mJgHZGsCYL(>E)wK9ElYcov-Gi4kKJCUNVmlB zcjZ8Hru04l4u9T==YKsA_ z4WeZ+nHz0@wSUz@#YLD!L@ z#(>LYz`mo<#eN*-oX=;*R!xw7RZeu2_9kzayAw&YyVT{79P7_{6t=hj;B(bCFI5?5 zTYas=#{*810}jU^AbTy!EzMxFH{B#{^SxzvRf(f29o_r{fA4?K(hldqmCh79ncJ)0A7N^>U;Nlzy4I9p)HBPTr8_a5uDs5kW+)Qpd> zW&07B33{Myl1HmbAyh~1jmGEUb;&S7AK+)!!OK~@xLMirgwaB}BpvU#8@ zjK8r1dl-~5wPkIv>2@174*zE}$R-w&;;y4tk9Q<-$_Hre`2f>yC9|txJX^GFBdYJS z5*nvWf;U~YWqW&KjXwQq%kPhkXW2yV-+Q!Y_XkV!RbDs+27sOOM)ZGNEY!X|0W@kA+Kx_VZLWLh*MH;0wSPVfzvsRu zd%gxp2WWm{-YW{hf6zBXe|xsdsse;#6__~2n)tc+kb$Aj(#)K%5=Y*5{8FChTr>q? zqgMdLPTYvTE&3$a?inO3K7~@FTvnyxMFW-1MaLN<$j>1Q!SO>kS+?lz?XOT=Qid__ zeTDamZk$c;CcCkEY_A2foHJ~H$FSKJhd_FgGwPS#7CgEygr4dD&GWc>{irJUNDnvB zXIhHp^!I`e6xvP@&-WK#XT%azUXjk)C*?qMY!&u3_#kXs>`vUSxl3crd$3S!hP}q+ zxJq{-dun+IriD79(&(>(fww0FG}xlvyb_ka!hq-czoFy5u{Qta52h~@8*oi$61mFv z_J+A9ad&7w3)5_d+j{cipadT>z}t&_5xr!ZjQ7ee^zG3Ol&g;s?)eyi-dq)&G^>$~ zIu!uZJU3$fs=dsQ=NDpmE<0zO4%s2y0KXgt$@H0~D*o2vIjkpE8Ir4oUttd4y9Td* zN-k8!!IOdUIPv2vm2Ub*q zGspENLytScZ=Tf(SyslTjtl@ZI|p3t7b#hLq#GT?^9}<7oQX%mX|U+K0uT00XAxUC zo3WrCuf>H6p+82#uiDADdSM+a*i;5R_$~X^xEYM`o?;TE&%H-hcY6!l&z-`NtMXXuA)eE3t;feFKK6P~NsAmcW;J~^K=wXQRVaRJcP!2yRR_zQg_R)9*piR{L@`ulh~ zWkwfqz;;bGga7>LE%o@mOEAg&dL8_J$Dy)!GK+2Jnk3KTKN^}T6wlsHx@fsb)voI? zw<>w+aJ~{tVn?u`A6J&G3>JeQrnud%LOR zii@#~-_qKvj}I zqu63xD+m%S?xyw9_$5$)yKCgCs7iTDV)(3(5uwAIrnoJyp08rlQ zfY)E#W~*KsQIn=-yy>1J+%cF2TP|zKm|b56^{1Z`xc5x^6njuL9fB_}L)VH*cE_$2 z_Rsl=QBy}r4AZ>nyf+S_-k?rW{QesBSRcZ@(An&QN&uMlbil+BuWY`GhlonkY?(gu zpsfQWu}^TW>U(zZr7v|dF%jJ#9U$RfoMA=P4s5(q!fv|!fp2b|xaGXOQ1kdce3^Aa zc4I9!eh-mz9^ipN$t=4|0F>)F;2vrvOg%FZP8`sdF#+Cn_M{*Az7(|KEc3c*MlJjC z4zHOmksA?8!;_epVY@ag*_inVNzudtJ`5jlNHL) z`$>^tmb?IrPHD>gjnSUju-&r;TmAM3IXm1)thW-a(jg zmUnC^^Ug~31(4TdCi6P}xYCzehPL7IjGk;#>Q=fgYn15tB#HDGaRFW~ScXmfJ(4@V z0X#J1#VLbJh56&%$rsoxEo<+=bR~^2q^KN?j$5(fsR!XwxD&>_{vxCu-wZtuPe&3^ z!X$4Ds8p>9!xxUX>2iJ$J%5V#3;akT7NO~IG2j#ih37N5q$UX3sURA4_>#w$yhvTz zR_VWsi4tAz@gSLn*k!36X_8pdfB75OG9Uz_ z`{yx}eLhq_%tUPOKA!i6ABCl_`8-^i$*w*92Z71*B6|`kyjZZ6+)U+rd(uia&HpEK z=RPIlz1P_I8h`GoaKs7k{e?w8>|ltisf+_qeRUk|v#^UeEUg<`cYya{J^7A{R|k`~ zt=GVJYCMvD$!x&)BG8;$hUW@0g;}SzlF@1|(%X7^Y@VAO^*vdEcGkn$Q=VJ-qV0%2 zyB`RS^L@dbP^=tX#KJ!L(lFlVn^~P_6IWqDk2r9q?imi>D=mbF?Tsj1vQsi8Ityl1 z=3-gy8j}3)JX{e&@Nv&97L=q-JLV{e!6r;lc{_!C)gL6A^VbY{UsdsAZ0nc8{MGg7 zP|U&GU3-yztK1;pY5-oeD`!XgZ=>Y5pBPbOCroWB0RI^!IAmfrIrrl^bZRByVe5Bn z#TEV?J+c!$E~t|qyG_BRLKD+e8d%qG4f>LMUxPnJu+@3qG^)^23?6%h*rptTYP|^< z>6_2~RelG{A@XAJ`rah)h&wUX_LTP7C(jOyQ=$`V|6s}IS1%pI73oP*hbnO=h=0XV zI52Pn8esOLq~`s*5%!1cg?%ekMB4aG2)GIewi(34$#IK zu60cQTtB+vbRO!}o@C5=I(&3n&Ug?tiu@rJORquy zzady`mCY7B@P}EP%@R5Nm5tWJgEF{wl{4|fwPqlaCDbscAb0IwRzU*|2w?? zw25FfUq`mX>rLoM#g=@0{_hN%X_N{ea-ZIWc-CiI1LSG8;Nj}tM0H>ns{gJ5-7mt<=Y^ES5TZzU*e z7vP`TXjZL$5JDx+czEn>A#wM7=y+%@(_vzH57ehmKR8cJkKI4Am2PhyEn3QRU7<1( z5`vba&9-zF*ZB<^XUdDKGE0Q)E^g$~qs>x(X%F@~sR5=1S8!Ip6*E*g2r1}{d2(L` zJ+;lyd1wZneNw`%PPC^zuA7T}CLOj}H);@7mp04xc2~bN$SpgCBb4*m9{DsdH!VZ$ zk;}>S<(v6^daLwaP=e%nYc(Vo6ru1cOgKKV7hHd*D)X_+`}jliZ%3TBU@zOUQ-h8z zD8TAaO%h_a9_Y0psK2Cwt+@{L%THx-=979!#i$HuyaO%KKn{ECFkFyklbC zcbM|E9HYNg3%ZHZVZnjX*vqP#os04Z|AkI?FmW(j{!yE1t*ONHG$6yu_CxqAYuP;C zH}xi6X6z&~8!FWFeoI;sv!o9Xw6F{Q*)V-6XAv0RWhL>IFn&=1_G{KBomU*7^Zi`h zmsiHJmij~6aNf7FJyJ61k_P>`uMmBfa1HQX7_|LZi6{7OplY(6HrJVmA=7h(iX3wo zv(5$sdGGm(vBeN#R)MO?(^#{u2hF>(QT&+ynxuc=yaHPf+`{`%vJU&h!re|Nf3u%; zw>Q10)8i&QAs0`k9DNPO=Rz=-``_O7+fI*Fn1~bhj3b+S9ffsrp*+i($xK|miE4zi zbW6$#cH&bjl=FE$I`1lba>XBX?>b>nt-p}k+YUzaUey2JQhUuCOL0LLao^x>>{JNf ziy|7)MGPkEM_z*?cjNIy!#k#~Qw9eNtMN*7u5ifLn|z3NmNw4TWp^|G!i5bLDD^gF z1CINHaM%go6h07CpZmZ-%PFWcyNEfhjiRN)UB%0a8bam^bK1?S8Rso4CDVr#!mT3S z^}KbbMDD~_U^93}lCM3HU&1rF#-Zq&pUL9=xu@vdcMM;4Unn>+g$&jmEYsU9C)dDF zzbDx8Etw5_tV>II_HeX*FB0?86(sTlF<^E%`xUo?rfoPTj(u$}q&z5qPZvwk{B<^2 zs`ngL?n=a-ZAnazXw$wD1+nyUcXF=51T?pH$F)DdGj&gOdOM2e7MsHvemp>X<=BX| zL+=ttwjg<2?=bYuO<*S2ECVfv8<=s1P+u;vI3)29oc?<}mG<(>6NczKM9@_;qrR=kMmdF2F}Iam>BB408Wf zigOcG8G84fu&p z+w@rSw5{~H)fh4LPZGI#EfS*Gax9#d&bH6{0=TAUch93m&<1Q%d{3@(??!l4xGqCn@2^+u1p3a{zQe3m|u+1*{K{WecvrJc) z4oQQ@KTqM!4|&Y&;U}0kq!hnvEF)7Udl096TVx){@W@)2%>C7N4W|W@IlVxkXIGi7 z-ao@1_WpCiu4en#mXL0A6u+JAc-Nh{k@YaMXoxJAr2CXmNtm)|^s-K}<9QlfSjq1o zsgFtXvHLLHDFL5Yyki#mgEY_@ z!*zJhclS-olAOfp=cu56>TW42(i>#d z!&i{59*W((bD7fRt@Kh~Q_=m?SR$M{0!`kb*x2@!?YP+t3t#_6*R<0D)#SP3T4!mW zIV;#v?H0&gl8@uYUS)S4Er)w0!)5w;aJMnk*uIN6CP0JLa0X-e)@E!Uc#^zwy~=t1 z+>grMG5xew81wHBCY`Mpp4NL3lN4vEb&d|Zk<_V86xw&EU~VJSdFJRM%~gNVq68T9%ez>mb;OypK(^w{kXwZ!c#rX2e8=-FeR9NSs!}aYtmW_Sr<%Rhe-4e_KBW%Ix zmK~nXu4F!Ynjj>k4GnchNpgOB&@t7H;;zeo$b^V1uyIc)zL}oIYPk>RK>`0fU$+&$ z6&)mF+UCi2Z?}ryP_z3PX7^2DXM(oVFrVR~(t!g+v3?_XRP97X`(oyDr~{0D$cw5c z6@?Pzd!RZjT6Pb8aqt~XlRm_2F7MdBYrUxJD|yl0^0P44zzV+X(Zzpeq zzu}O57l^gnV^}#j6eZjjG|EDcck>mX zv^-OIJaInkf1oAfE8dvnPQ2!F55K7|tAAYv6Et{tRs2oHMk!KD{-zEeWKNbi&x38# zEwJKPC5swjK;1|Gz(W~2EdIDJT@zs??zR6we%+0Li``dX<>xfkR#^kV`EugBm?A-l zb|bx?Y>|GRq|ct_e1m;8m8fEB#qu&X!HK1_u&%0viTQ>!N~I0khEBA(H_w=UY;TqM zTU7Nv!zj&A?0-6sbqURYl2J9t_N^k;v2H{^bBlD3ZoH(&>spxhuMF?io)P*i)Q8ul zU2&dQBfD$F-=w>EC*5C7GWz#g$l(5p|9e_4ci7NpMqR{$3$+rDpwE!gT!A_&Pe{|4 zdoXlnB1Zp6V#AEexj%&aqMM6^FJq>``u@oG+?+krjg`9mKOg1w(C! z`l@|!yv_zAKIXGSv#(R*G$-+7F%hmEeod-6vSpgdx|d&}i8IyD4Z6dWlPe&Vvw2(A z^ddjkZG?p<=i^uPa;E=Kl}7fgMe9$!+3pZ^`c|=DZr0FHB<*OSe&_ zvf<*6$Xwy-PBYjNDB#1OI(GaXVv3BaCNsSH5ac$TQV*N^lMyF7`+nU1+^S98gIsYT+Jp8GC-!P7lN-`5o z4GpEG(%|#l5ACU;G-%i)tF)tuc2;}uv?+@7ock!FAFoTzP8e({C;9m4vT)|L8*!NFC{Fykj>QK42Gs+( z_~`X5hBb3Kwbx)TeyEBD& zPu~f~pUlx>Oab#yxObMKe2oz|!a( z?BlwLESVDq@AZPvH!g$aFOjE#0lzVJ_;cZg9VORx=u3C(8fShlj*8~{LlS$HtWG^6 zd3NKsHj(jlgy^#)q;uPxvy7u^_}reeNpQL!2!3zRVtRl-Ip-Y>3tb~{U{C_PGFycf zrprpM1oR~bJI26{a8;>hGV*mVDleahqN0mTwOX6*ur0-S-6iB^>{0NEn}r)Kb6M-r z95}zVk#qgjNcTl&^1{GNI=4Ofonq3-7WDiQ6FZJG5vs=UoZ7f^WY@yuaOt-l*9Ozr z__KYex=f*TZrgspLvZ0P>5e_`t^)1s8G|N?Nz7Wi6i#P#;{W}Mj!&J)p&6cHtG?Ny zO{+U#M?e$aCYplm$dhnN@gRm(ClTe+CxGLEaIN)ER)0#3W?uV+QO;k54`>GF`WkrO zs+z5K7)1T~9(!E<47*Tb4)5%&q}uq28NWeasRPAFrieB^bEPKKUNUN6Cux$u1wFei z;F*b;Y&KP;iSlhIR4y0xfA%8{t5%3(lWSP8>K{04{2n8?_i5=sFZxTtKr&M85OHeV z3WqN5#dY%wnfjOx7<*q<^8Txw5O6gC_Dz3-9itN2lbie&V8VBmz-R&98^Z~rDb-AD zE~(Q6cDcCxL=amx&zr(e{+a5$OBSjm!I^(~csA-e^DM05e(xrv7Y360CM9ZoxC*lr zw~=}MPlAG}4chijW%g>i^vezIIho=o9Q>3>M!;#QX424*0(;N1=J?0rce8WmH7D&zZ+r(10xGX1}K z9uZ(d6Eqbiy&QjudQ^P_#k_L#n-E3DT82Z!?bqn@G=a^uDuxK2FL3V27u0j+!q}VB z&~SbwoBmyf2J=3*xO>-_$Xtc`JmhQ$zGDw7JpffLf>bB@c`cf1Za5;T_gF7{lKVhJ zOSPowfpyOZbJa-Ywu= zGzBm}F&ot<%qAAR6KwBX4}900!!pWx(X=nMxG3_r$&gQ4^e^`z%#eFdItNH#SR3Dq z60=ycf(PA{I!@9gHsaiwqcC@NkaV6$`!vC(;eT;v}8tZt@LadM6hL zO}WM1o>!zc{VGxDr$mlbSb|o>1k|@HXU8}@k9KyUoMsQU@a6=Xr`w9@IcLecTQ}k7 z)mP}NmB<=Ob6_&R?~hi_5bo`BC3l}Xi1)wa&)(ZkptcowsckH?Yf+%dvK2VF&s6d^ z${Vzj=i&p)0(Q#rGR^woB(dAsTgZH?Pp9xa&WgY+Qv3A>cxrKNvyU~2I2#I=e1i}I zGFav<1-kHg3+ns46av>$;&y(tSkI!K*{&;xp%dR>f^HI9#4|f?{qpg!!2q(*#1TG) zjg;Ou-z+&q*EF1#%v@qGJiHkQ-mlN$k{$u%#Lg%f{3Zg28YZwnJ)ND!s*r^X1rZ&V*{7C@1-`KOwezPj6}w_7`KjL&;>_<6s63=%SF$rbTgPfl!F% zQ>=upMR$na0v{>2qHQquNj{Ik?fa7$wM>UMGip(G>@-rX>P&{L^cG*5mLr1mGF1Cl zC;EIHAbf}mgw`R4u$RIoQf>4E*!3X1GWsVw{-h5bmc)I(;U9(hF%&*}YM@1I6F%w4tsRz`#-RSlPt3~Ei>e(SFL@;EORQVAfFIe1IlOcA(c8aZ(jYIH zAFdz_c^eP+p1i>oB|M!`uT8ULdPrXENfD+FHiq9Rn$rGT9$ugy^9%6S*bo*q+nW|> zPmly`yhp};OMuq#`B=W}IZK*U2(x-r;dv!3Qk$eeyW3lEc9m>QwS^+xaH|4iSKE-% zi-9n%?`G60O<}q!gK0&2Et)DH6`B_(l6B4h&G5s4DR82=0&ksI&7NeWLDJZKsZR1j z!WYzsiHtP1@0B$8rP^vg5qNZntrGpEp0=|@V}AJtrLU~1Anq>I_^~M%QVRv z*@>jaWf@#ttS+7BX5r4nyxCi9|JH~7TwMe|#krXD_#S)3Z_|EOP3Y)3iAWwVh1qMk zALC9rTQg3Z+E_Q^&^>BQJxPaJ6<4D8$3bGIbQu~~ub0kn(@)vZI=>0WnSB?=4R;}y zJ9dig=m4g2vKkt&932de+1v#SsN*1G$rsHB#9^%~^iEui+gBE|V9rcTz3>MM=q%Gc zvvjCq?@Ih-8bdDKN`^c9J>5W@&CZDOA?#@z78yB`Yktl|obcZaHyzpyuR7YWY1M7v z-JAa4b+Wf~5BJ!_wQJKiSg#e&rhieU->#IPjFBp78g2vCO=D19zKm6^97X3_R-yRK zXOY;Z0Ma(MW3*yC=QD)Es#CAg-ZOzIbQi%Teseq(pD$c|Hy4h?{WrtGT83tA;+;H` zuCXSbYd#-VimeY!2s?cM@;e3TPF`emkXns3k{CYJ68f)+Bm3WFi{Ga-vBb*naO@?| z5Dj|FLXMPxvUefwD%U1^25p7t6&7ePr<8fGQlPWAZ}3&N4!gUx7k&4v0Bug&5`(?x z;a0^aOiWH;%9;D=i(^KTGRqQStM+&p9r51`Ke4v}K37y>f#O1T&@LBz+_KPh<4m$N z=P+c<^~55jTz3D6GVRNGg>p;oo8+qYqjq(bcvT6&$Flg3M4 zEuTi@*b#VnJP2nWPiNXL+=uz53msKMgxJ3>%=35XoRG*$ywqu+Z2>;qGJxDk zb%4D`MoE3aZllJ1Cyxo(IP0vL|k1$qYr$Jw*7hM$$_XMjmG#gA8{^+)C2fk#W7b zR#1pLeynu=Y+T=MfJO8s`SW2^n9hmh#>8G5B`{;ic3}=3J*l5B|=_OY0=UKut3+OVpHh zDh_MYp=vofIOy~#<~Q05JWs4glY8aNB)k|b%<9m#V~hw+-hlNlgU~oMgWU~Mr4zI| z@%9Z1p~}&hM5tMaXYt$3uIx5gr4);`Dxa8he-9d_H(sJ>bdYRJ+zg2k`>f3O+LPN%S`raH90nD1Q^{e*^#2}Jww87U{U$I)b1NjT$a;VPE9rxMCH zHe-9VInnoWAqy5bifPKBK<>0@)Ze)$>CD?j>1D>6b%8rGlz?OGa z*zq|@FcEmJ;lOV3p9MPX!GcQAUQmwVuck8<(LAbGY%JLqd7m^|xPU6}&XxETGk=u< zG(MU8LM@F=tNU{9fL9T|-5W`|3~qB?sw3Jvg|i^VWaz4{z)@r!vEiM@pZ$EK9`ads z|6uWgZgh;lD-2Qj4(B$##a$I2S?jVsbUSCHdT;ATPEECjl5OLpy2|3)GpWiv1!zuR&EHg=9%c`rmhxQjn%Ks9^#sA}(kpiysUt{CbdA7H$ z6qEeskRu28gZ~SV_P5}~12ipTnxrIJOSp1hLSFgih#jh%n44QF7(LI!mcU0$F}@KF zP5h0*{o%xz%G2N#73kVuhn;z@L=Oxv#OJ+iiBi%zNcOVELhBT!He^4&VmVDx4JE=6 zUjyjoe4_u~C5w6%fTd;)PT91O*;VGi*xlJUBy1*Gbk2vwCfbYrQc^_s-}I&5vf6OO ztcNBsmfU~t@C&WT15y|whV6|(h$dM~{@)QgyvRhN(ms#;nRNsv@z3V}XZ4h+d+B1A zqmo0f2a*qbf7t2oEPirl9dmwL!|#&0xJT|L^X2+R=uW=3Y*Hekx-}4EKM}Pa@$Y@@ zQS{dRZk#nsjzxc*KqLSB!CtS=k>r2Z;m(rRm~}aUGpZWF#$85otgTikedWI)-)SD$z;S_4v7$F;Ncjg67Eic;Q?D%golHy4z~7${!eHu%RQ7#bv+3`zBH1&KH z2%o=QKr8J)GC1xHXr7Nmqc`zP?rk+F^NzCWj2fYz<7kMqRhQl<4_xUU8rnc1Jf{dv|Sl~=%b^C~i^~@6`iCSPG*SHM&Xb4kc0${nluhcj0as3he zTNR8Sy)qe3p3)(_KWfT7i4Yh`K{HrO%8yIQ8$k2Rb1N0-F&T=_-|VQC*C& z$J5)MG5v>WFh{2dEgV(I5Dx|F{ka|0UF2dc+>St7o*hog$q_>D1i<}QTTuB{3iBSJ zL)R{>Mq>{@A=f^E^mIKd^^F%^`U?5HJ1BI*DmGS}3%eix!np@$lh!~Na#F@wJfkC3 zq;p?^&NlpmZb6d;BhJ>m7+#6?7eh&`-5JpLb;9X(kJ&Zd9klG(49TNu6UnzzOJU$o z4ZJ$0hFR~|EanY+x&pbjc}72u`8!^n5l zC7?EUDmuI@XO#)+wEF9B-esi1s8c^0v6&o)T2up+eq8Y=R-C2GY)! zVfzPAwe!3qYf`M}>fRJs=30YZx$nrk>PMha5P>cI64+Xvrx7tQ}~m$OwPXyd%Yl3L$2!Z~FL z@wUzti-$F{gz+ixpga%L^dGUEvIVe(`)4NAYLWBFyGX=K2eG@jLv+qxj=$TMVc}_Q z_DLoXbboEb%(8Of+~RXEeVGkjn3=-%zBxkk@=YZ%%5}n>YvUjnLFyYfYRd*=KDV!L zpT`Ow6aa7B!WB*?WQzAra*}gomcIEWD&&lV;aA$RK<%N)oVWn+JhF}7WrmadM+~Me z3&xj;Kbf6)2R-w4g5>7tY2^5o!*FJ0Fb-ay&VG;cqOq6!B>hXYNld#7QC4@A-Z7u7 zsD{RhTpSm2gZ2J@N2_Ty-kGmNzB;dgt+OT}d?;tO-NR|noGuKjl3~X=4@*C(6Ib;) zPmZm=4x^J_qw(nkHqtf=f}<;NU~9T?g)^+P>|MmukEpXXy;|W^dpTai(d=d1VVJ}H zKOUQ32t)L|0OA(lzE1@#jAyii%xdvUNT8`f&=5NAOBs&clS0Pr$bh1wO?YJ2E|JxP zLfGt6kL`MHr03gU=!_3Wjlmgg2Jhi%tN6=*?{9?NoA?w8K@ zVy634sm#R!3>?9IU#9jjJ53+GOiP*nfLus#{DX5#6HO0X2!z9tLHK@eAURqS2}&|= z(BVKlOP*T|;=EiOVo)o%iuIu|OI?}?s^Zy))Z#pRR1nIdc%Q?a2mHQZwwMIC9)UMr zrc#}}{d*SJa=t_8A$1a>P0cjeF%#qgE4qiCR_0}0Qv`SL+c20;le};8PH!k+sCaR zK%XY?&V+=MtR)!WM#g`$ec#?fI5nT=K|;oe>SL;4a7Goz9@?4~-Cj!J4T9}$|1;$TzBTl~`+&wTf3&__kGl8eS)gz%Ho!6oLu+5YNuKe}a1 zKHibLz+{$t(9J&$C6BM(C2`;50Jd_5_|K+{;;xJagkyZGs?(? z(psMD?|YZ|TQtCy%SBiy(j)u6EQbDjr%Lq}yP5!SPS}Qt`Nu?pg$jLWnu~c++ez;7 ziy(^Hh{ZW6Y>R9*3wVDb+QRbUuGX zgm7oL^mrM@B^I;#q5v56W*g=uJTT!sw)D=LV$>VT_w${%Af>}e+L7Ds@&%OjD>3Wl zT9Vkv87qT=an_$So>^;#J~x`N$m6=u(!P_7|79;GL+3G@rzueP@hz%s{K(251;Ayi zZRlilM({qf32yB8Z?<1vVoYBJC`fFQOGV@2Q#dcO7KhJ!PiFW(g71+LXoT_X{K*P% zyjy{3x5|aLTfIrLi=B9Lqbh%Q?t=3(^YQ4fE6gD*090mk{>!j;0-3WPV#b>x-Ol-6 z-g{^;Gm>m-(-17VE&fQKJn3wY6(z&<8s39+{UM8Osf4#Ls!-oxFu79fO)7mI#7@`$ zh(e#q(OzFFP-)5l7Bq+F4yY~um|rfeO*jk32XDs4-YG2QsyqF6W1{3?SC;T8dn_CV ziqEE2voG@5a9*(rM=zhprtd6(Aw!CAU!@6g+vQE}=sJkIPk$5j-J?Q#bIqjI;IYZs z$pPRtiF4UT3@6c_M3DU|80prZ?D3zSv~S>4iQDQ~#7^xn6pMp#kwrT5o}LN&d+=VY z+T+5D92YX->UQy&W-Ipj;V;lD&Bc|S*O_~+B7HHf9`E$*O{~tW=J!+1V&Hm9Qs6N9 z-LwPU?*A3VCQhImUUs9i$9WRA{TeLk6M=V(5?EQUED-+i-?dYQV8wk+)kC+7L)A4{ z86pTt5(5+T(*)&jpX;o}l@1AwDQ7VC!NAP^M9bfja_CB{K)nqy0*8 zbmdoa*Xjqjz4?ue#a^Oq3%&#Lyzu+?HY96uFx*`nBAx9czy5*)ig|c>{x#v;V1c9` z94qyW&m0#3vq##ZqnRi3mr%ThFNg4+ux3>SH`**RZe%EBs~5;cj`-f{s+-F{rv zTEN^K+aZB;;Jc?J^VOe+bWJhu~1|?TIrCfJ6gZG~Z?}tUU{$m(yR` zZT_sTKV83u&yXL1ywi_B_pXh2_GCFb(^dwV;T1^c>?XqTYjCG37*m_mS*w#e{hTE$ zSu9uz!%iL|_l~aq&ri6b2`X;IVz0IY=4tFfFRD$F$c^B-3vPnx*AC#BJvGdcb2&O$yA31H$;2p#{9v`7J-)Qg z7Us94uU$x#*LJaO*bmYEoE|i1=^yM`H%S=(NP&iH*5dj(7l|(fK;t5w6PbLE#b577 z7jbQW?~NaV>(9lInxrZ1RCK?b1LaG*aNgsi!kW9qWU6hmxVK#sd-yLK+PTkR|Lr?W zXLSu+b}K}$+M#4$#UfZ0Z-g3O%h|F5f6$Gz#h3e!iB@yQaqHK7T=~Y01fC3on+vS* z@Us+lxhoT{%xOo$StL7(r@*jQf{wA(tbA87JTxoA%zsl^>n$e;o4EpY+lyIkCC`Rr z+2T!?2PT_4`q8mxi_lf?HF=r%2`Jx}F3iqi>rSSF-q9A+OWR7WmIOfDr(iUWO=J6$ zn_zNfD~@luE<7;sB+4W0#io~-3!4=+BX!r09xj*G0gq)4!nYegX8_@^~MJ;%9L6ZN0v^d6=*GJvm@vI zVf6=F{QaX$Fkg5U;#)T3-7?NtKkh>}|C=Vc^Sw~GwRS9w?QMoiJE~dq!k=*D%P-8| zGnZwAXMq~;3{1K=lL#9<$;N1V@n^4O(T>Qz^!KoC)J=M1a?-&cdLFdJ(r`WUn|CjN zGY!EF(|@v~Iy>myuM;JyA=607Y(H53GZ-7b@b5~CG}v&s3=^&$6Oy;Mkcdxi;`jyY znVn80+-lCnaF6Tk9B24$H>kq}rAp+u)@n$&HCd{?Xl)xx`E$6N)2V-YxISOR}f$%3I=hcus*DeSuLLQIr)i0_Cr*vsv|foAZ$PsAuTi|55w zSMZ(O{kiaKnkQJ~EkX;^LN=ETpsQ2rQRhdXskyHXEqPajyVF1M8)XUWwqjj1Jm^!1MVZ%yug6Tu`my7rbNe;#q1|0-%RNP& zEc0VOx<0xHf6mY*UK8v<=I|J4-e-2AJMR?_l>GAFBs|Va10$_+j9->Ps_i47wg=x2 zXT-CIid8V}Q$8-=Q!DiTI10Y>)s)^n@5lOsxr!Zb_S9uv-OBX+2JUk^L`YZVVX!z% zq&fW}S_tl=WF;;|cB*ymI}AK1;;0hD(ou_aHa)md|9vKKR36 z9Xm9clVzIm;udMiJ|NBM_Z@fxzP3Bzyh1OQx$p}#a($q%eiHds=nUnh2c$dsL;W_G z`o06Nduj=Z{MneA^WO|drw4HQSO`Ak+1^WuoaHghPCCP9DFNi3(3Z~dz4`rV-`qUx zJ?tdQ?oD9U#7$DYC3tcH95nllBZ|g|`dH?}xidw`e!3IeysNNoO$ge3NM~16d9L=X ztfXiCYGI_?L9#_>jkJShy+R{A?TW>%{BCt1#e?4dGFj4|;7gi^Y=Y+SgFK5@zznW< zQxBt~l5Zal3zB{kI3|k1P?vaicdihsSc&lTVLlF*dCI<2H^BMna*{6n5#)=K9PJy@hU!)_G2^%S!POxS zNWHR!$vyZ^#dB>d4x}=-P*s{CQ-X=EyM)UA@nqTk^HQIorRo=W+p}8gUD2s;1dXLV zB#$1hAcad^$>euC#I;3fBC|#Xx`ua>4DEG^OqKXUsg@o7Rlmpl`u3%|-aJ3zm?DtP zi(zYkmb5Q1C3QQs4hfKa6;w&>wIWjYw^`get%)h^&w@R7xK~;84zqWvfC8?Wlc9r& z#DX)Sj!(nt>~eO;(;t3Zx5IP0j)~TlD${*)IA=|HJ8{+v1DB;XxZ_?5YmUu@&4>Qs z?9QJ;sm~NRnFm;}S;KzZDum}UWw>p^R5tLHJKbPrFG&dcLQ?)YLdH-F{Lqi*&_n#8 zsn(8bh7U}7YpK#Os}hV9zb3CHeuDe1A-GvTi_LqS2HWPeqI>dIQob$#VuTR97m>#F zY@6Wf^md#|ZU~8n9>naMz1X0)IlDP283KnzCy)9v6z5% zze<_JYZ|rHSCr`G7K>J&OafgG-u3k34e|1R00(=%!Buwg>~?k|922);>*8i1D9(dy z^mGvSe5cB6Bii6LXB@k2z04X``NQQ$cGz4KEu5>`3+cM^P-w|x+kQW%nL`gt@{Lyt zn(rAow=G|~hsP*~-ZEJEiPSAAO!I*?Tct@VY(*a)Qlp%I0bodFKbD zY$->DHekWu)8V>1zqQHDAV4B;BSetsoMBarzKO^k%=D6Xc z*)A4}SqOgb%w$~^I@G+Y1XtKp32R^ag7w@G9Q+}Th|u^{HEgN2IzReIX*8&v4|93 z(2H`wQk&<(v`Zea|I=dJ$GIl~%QsLr`w5a)`3a`TJ0YEQ^3m{CJQ<^%0xLKD#(Aoq zBFEfskY!$sf6}Z;_SFkul@Nj(*QB$64;9chF&|GgT@{>KP00g(aX;o?&*r-O1CF;x zX6wmrv%YkVej!#I(jsqP*h0gWvC>{#^VUpwaIgb?eG^Qr&K(EUeHSqK-wBc*@EW!{ zzs0=vkL<|P3Mk|Mo;8KlLU-^eh^*Dbt4r(I_yB+Sz~3o!pXf4E?#&*vfcHjv67u1~ zVd!uH={*0W@C}4voGVnNOx}H82n%0rkk0eT5B|XNKL4<6J&O(KWDFUGM{rqd*eel)_#f*y?EbG2Mr2E^WZM?bA z`!azg3kFE_mQAw#X{S*>?s*=_D$E5qkp16mw}>f#ho_qGc->ghk7b#l(UOCUxOYZ} zT!jap_%n7logEycM&}=ulUP1kBSiH*NO~@@lQAHK;*aHqI3f zCdvah^7oxX*!OY)yU#NYotKVEY+?@!acT&!`$yvo)p!T$3nTDVkc1csLe zNN4-3FMa4W)jZVQc$RHY6~mtRe0+R9oIQJ03yC(el9R!Dimn}TI?GIo5?6Kr{D%&tlmBzG}VDgq-Le}1oWVrbSapCw{);!`1Y)`Dg(7tQf zH`4})mdHs;^_G)Y-(ASYDtGaDqjXW>ksfs8m@d>*oh$@q%hRmRI$Ugak(3AdL#`u# zHrC!_wg;5y2d)bhj7kwQiWWllaV=C^S;dB{c+l)GCnd98)QS7-A`&^FMeH)9i9O!) z6Rh>~@cD7hXfP`WLzat)#|M!cTNXjC;&l8yp@P+Y_6OSpdz|q5nCO_FGF`%-e~+84 zz`RkInZ3Soso89p95mHiyzPD>`+ zOZqJSLOKf^LEGB`cZ@D!HGlk}L(>6uM?N%}m(q_ea4x}`bFayc>q$_zIs{im@*Y>a zPvFYCvTv!cBWbE!(=!UeySvkv=ynU-Z|K1E+?&GJbsi+&+CjX^(wrsV_zI_fM`54E zAK2N*e)O|@BSwq0$n{ejAUbq{)YEb>!iet5RFG^`FBWBQ{S01})p+S%6q#lG02cDu zeuTdx7h1GHuj?K7x2aVa?czapx;u!ouc@+~Zmn?Q9?$qczr;MEdr^&bm6+Bro2-7f z7XnS@;jdqu*;??7v)BD3X?-n(Vs%Eg3@H%1&TeKK?tFslD*4zl^Z{!tEQXOQf8qP5 zy2K&Fo$PjT6x&p{i5^CEL*~0Ov>B|$Qv7<-4Wr8O^LjfndJOIogE)D*0PL@yfbP{0aMm$vQ#gPtQL>={t zbl`?&T=Dp}iCTD1I&6D6K6`(QoVy%U)0Brgqf3N9bzc~BIt0g` z<-X;pa#)wvg?r{*5DY9`$ai^9aeUkcHf4VqWbDdAtLN8Pn7JC&@$Vra{rZy`!7Jh4 z_bGU8Z8>Y|sYRpb)uM_;o#?~^FKQdbJy(0ak{E+4@M&@+8oZ8YV`f)_Ebj@d`CBEt zkhl<6Z%?sp9?zOJG(hdqN{sT-XA@d_&<`zj*g46F{H7j2ik9HH`-RNf`VJNP9+tSz z*WyfeEjnAj07pHGCoko{0gL&KTbPIF=)G@n|6~c4Iogo2`tuN}8H%6O)7d?b3Xt%7 z_odm_1mg%3qWZx=dMC}#Ql`&HA;$gIB>oz{+HI^^>1IDMuUL=HZMb!OSvDle+P~&_`{H$v$!z z92QdP4Bv9>3mAW|!}sDoq_uScjGws?J2lGLQ;R>)HAO~J#aQeIt?ktDi>+j}sXWAG z9)(2G5ckCT!}cK$uMGcgozb3J55qX1LC4v>0O){WJqi)8Zf zszm@ZUu6onOs&y)T{$DQyx(vIQ_318R4utSHia(Dr&Kj1?@ zT|ObXx%il%WFZFOVl=L*`N*bTmZz8b_nm%ev>><42z&?YNLdx+dLKGr5%-avKFcn- zc~ZG=Mv{rD4@kyW5g^wV!gRt}U+#Uq(At3KAL<@Dpp`h4J>-nAC$}5X}sxr=BjrBhIcQsV)S@M{JhP=jCY`V5-}N4OwZz+LB4o?=zL^Cn*la z@ca+&hs>GAPCPAwV>#J4R0GK7WCu7}y%HN1m9Ss@j=WE^9A!5~kY%ok@W~_;_gejA zNp?Q~$F_4e!8US!xIesU3&BGUY3%5p->-qn_syvBu3qRfcL&)#)locpf+~A>s0Gvl3eckY5^FrBNS!`%hURf& zk}lyC)VBE;G(4XDI+UpZbHat2_h? zUDB8*zkM%p?jczh93~7s=|bviy`+7%w`P?>^yfTWv;G11_op?f){HuIpHU~WQuU^}>t{%UHzbpV%P+%K&U%>P7|({w)_{kxoFpy0Mi^`E zLOkwziADXj*qV)Xu!7$pCeIqhIvjh@TX*YmR}Ujn9Oe!~vQ2`-5j!b?s)NOuR69jIUlM|iEx{00{c{}PIazU~5Y{JYrOhOTt&aXZPCiSp29brc3}^uTRl}zP5CZj_Tu&C(Gr{yh%6Cmq3w zm_!U`-2=^sp&0lzogMl!fGVWPNqo=b3D+Y92#D0d!jU!1hWp-QxHkCzx&1=R6fy!h zUx4?eTn?{>uf60X9hOF-kj``{x|E0I;7p8)FT>fRq1ewLofSCjCoA*TN@sPWdC(5m{5HPwKMbCxFtL3Fsl=i5jTzsM(zv}d%xq1zmM$x z^B(l@s0Q?z94%CSmP5!V9ixW>8yTd(VND8&EwkR zcEQ2$1L@onB)*qY!^&pIgVE4mI45ug3tjdDUQGOjohN6ISHoOMn!mSLr87gcLLy7+ zr*`4Btck+kZwhoW=fzkrzf6q2K8I+lP;6GoU==6&P(AKRkYs%mOfM{ii*DL@UcZ`U z{K_YLhqOs&_1^LPotk$7EI56OjlbOlC7HF@Ph&KBKW8CKUTut{;wzZr3MG1Yb`=VK ziabl(ht^jVVn>QAF})iCV=K0x&%_kg=9>c>B4s5to4GDDbQ0WMVTN;V@+{%}LNMeW ziKwqejKl0W=Q8{d~Q$fO*fsY#XTM4Opm_p%RBQ+(T%<$_16+$ z$GcFJ^!dqFvjSLbCNH^o)Pr~(KLMHRLeXe$8hh?h1a7aYFh?^)usyz=h`84aE3tLH3Ss)|;d0hQ6wfPTl}VH7uEmOy3I7U2rHzTu_MjFG z4n-0BUiaXT{#)+y_{en6RDqj$Gg|r730;QUi7L;1*E#fKVLFYF+MS0v%Pz7#28#5{ zr*bR`GbXzR?Sb!w3$SuRK0Bm4h)$}i#+@ziO-@SY_nby zkkj3$-l|U=#M{ZTCywH9$5xSzd>6cStU#T9TCDFk75eL63-6QkB9^tMz~ss{G=87V zsyPEikNcMlpPd#$j_5<`w7GbcRj5|ns)j3J_2I!hbeo~^RZdc>xK6i979A!9bFVbkhF0$(OC5UQ{#E|vzY_dWb>^|}r z1J0HUp}Sp()484E&k`*baHbBFcK*WkwWC;?UJtrEwSoJnjfhSA4jA}+8LmhwWPc}d zE=0zX~Orx?DCAl)`1_HS!)T1`WK+POO>GCdn6d%>@U?xZt%R=8lLG6 zpAp0cnfIkzMwj9&8UDFoe(=uP99_$E*^7y3V6n6lFHck_c8ll3#l4%*xUP(OFn%|A zBqN!m&tfYEZl|kyJ4%Ex3ZOFND1_hiM7g9)_8~@zo(QbQ6KsP}KKLdHU*ab=j;vw# zE?$P(KTg=;w1erSWx>C08Od;da+fu-hwdMT(4jq_xrP6O_7w_}Y2OA3`T@tG{NaBy zeD2e`&^j#)qd%szHGI!Zh8_~nEqTH}1pyjCSE`c)DyY*p|8lXvvOhBqGl4UKo3UYC z1yfs-1M^rD4&FaT6l#bjqkLJ&$91I+O#U9R65VA>|&s5 zSOGp>{e<1zXyXCtQS*{~>7&=S4$2)EM z(EZ$_7(Lcq2y2Za?-vD2H4|N(53rAS{wt1J&P-Kuq2FoV^IR+t;ie0TkLC=QrJ171 zsed8D`VW?q2?7Qy(pvpC-2CziaguuuMejo~@_jmc&NCwo+`rT{>nqPTE&$u#+W0iP zicQYTC%wbl#J)?LSj?(4xU!w!F$dpbdvuH7;-XxfeOj0F>ah@Xg8rN5!&y&yEBzO? zYALd!vAyZNkp&og*_kM{2gB8!Td>Ui8#9(Gfv4LQB{IW`1<;!W>tf8LI?4KPg)qgF z_n>Z{#!{vgLy=7$8gHYd!rTGQZCH)&ktOVljS8JhS}O)eKs7fAMf+yP#L+LS#zp#YG|&cEY(4GQ;xm%jJvgo~k0% zXy9zMv&Q7N+8)TzTZlpC`7CtPAnN|024C95nC`k4LrUd}r1N}0L_Fkd&c}6= zK|E#DXOWA$0#!DHiwWPqglAh2`S$Xo01y z>T(*qs;|X92H7NC;RTdsN8#9#4{T6THLUcm#5&t1VOPp<7<;-u7SFF^%lO`S&7%~z z{SIY@7P{10o_F|PUqg&m`@yv_bEQ1E;SYbnfSo*JwOyUuelZWaHd;%)g~DGLj*qt_5pLe@gKjW6yL^4Yyr`Ouuwj*asgO&8pb1-qhm=s4~p>wQ3; zHpsW2>aq92YKJNCMWicbz&#t$m(~SyuH3o{?2T=Ix?ye^ZmM2Ej*WW{6{ZE88~B)w zZ_bA+NB>|B|{B1bz{1MY>fZcx%6_ybjgYvkBI;K6EMfeMal_Ubf`Cdv7iWV ztlA-b92G~Nv0&*={?{xHH24nbK6E)dAkK%lMSn2H9;^2-OL~F-0{yiRs7sAuo?M5ZKCyr~XqrVEja~D9Xu8x!+(Uo_E z`t`Uj*$X2`vSA)s^`u?8pJy-m4li@^aN)_D?An4R@X2hzkDa4Q{uTuq=*7DT9Oaoj z|6W*jxDZ`zI8R_)Ff41>ie9t6F{hS7*pQ~k^RPw2v1j@=wf4lKL_V(vdI zob-{Ms4EBUBF<~@s}YXH@{YLcPGa4o{g~&+deCjj$Fr$n?CEI*TKTsU2jm))SO0t< zA$t*4c;qwF!Gq{sn|d7eC&u)NP7Kj%DH6xKH#2Sbk1+FCK2~nI$5Ixj!OSCtsFABq zzT3Hw^2<)*l@D4(-kbhFZ=*`o@YH0Xaf;N_y&9M2*ps^VCn2}m7UlGlnSbzLdba&H zYHv9&glmt2#}@OX9>P7D$>1^M7Y>~btdQ?=Pwfh^cZD(ORCgwK7dcAzaJr`l&jB@K zga1tvD?dg0uB!^CEx1j77N3DHTF$t4<~=q~UY)jZEy8SGkzlrHAH1v!#ecGC?A-{? zOXYj4miV+V>4qz5;#mNR(Pk!|UI@4S@=;`Xm1ioOVF;AquJ!+f*EK6(qVIInTT;Oq zeyG#dzy^HlT`Rg9r9w}P&cW4ly@;FAML2uw4W6y#yKDbk&P8p<;mZmH%Pbf2#$}JV zTvwY-H>ri!Zq>L!U!VOw)BqnE3-HBCeG;{G2mBsrf!{6_v6^IU8vVK*%NL$9J=9Z^ z>Mkph>f8A%KErJOU8B6!Lxk;Tpn6IeLh=uGYMBg8dH5F<-oFqUKhGxS1%}ex{gS!a zF#fR!3lcvt%|>17o7s)E5u?cYqAif%I)UHFN?EGH5$a`oP4cv#kD#lZ2WonMuqdkJ zea#VJ7vTQR}LLZVW``%)Wq02`D1n zof3+~cfNW50iK6>X7=58?e$xWcujZ;E(>BYE;5l$jjIInj&e+IYUFe#A0<^2ti-<@ z=2L}9vV1%1OU?dpl}1D<^S0KEgELr6+8bQp!ark_eVRx2v8<%jXk z>isps$-7C|pOy^B(`I_=>ifp*aDP1T@a%RXt#bh7*zHV(hiN` zEP_4Y_homCdHb2H8y5vDD}vEu{CE0y^-zAWzqD{b{FD1AG60SJqa`!^2Fu)=pjU`) z)4l0}0gJ%1YA=4UtfYST^Pv0rAME>My68<%CfpGUnKo-nGM|X7P=Kl|vr%u!CK&nB1(T;S z-Ev|+Y|#IU@9LWkN5;K}sVm};RwmM22Yv0qpq1B&+yj>5^fDOB*|X9tq%VK)VWsZ94X>{GM zLU2-75VYKixsRrrtfRpgg^pSpa4{F?rfNLhu0=I$bKz*(FHBiuNUBC1A+js1#LFC8 zMLPFX_`@-OP&R*#VT_?7Um8)0bnjDAH#P};M~9%bN;X|FJrm01dhuAQ714a?0lS=n zG2weAy<`0Ywl|jI_-z3k=gxM*7CVWzQ0nj}czZhzt4joW?C?2=EVjb4+x)oija%S$ zv=)wQEvNc=lX-j9UJS|pCStHD(EaUb7Zp!@-EYBVt+#l#UlJYiH3y8ZRbpdNA=k}r z$6q$ti8}`lq=SS8P!24_;D^DqO8XoboU=l^X|K5-4o5*Jdj(bo7EpQpI5OP5L_A_s zE43Ju2rGOF@L0)hdgEaWd}dwbH_uEZv)Jx!)L|>p!^^lo@Z@t9K3zPN?qE42vO*oI z>sgab6F)eZZi(B6q|%JeG5mwCEjU5v5~po72};WTo8e>sB*U$!DxA+^06IoyfopLw zox<-TUM;72dVF3Ts=+L=CJL)lA66KR=wv=iR}OIpGb` ziXYZpEUZT_QDoR0-YgmAL#( z6L&B4FnPMlO1!vi9yQXH;jPA&qlM;GI=saP8pF(Sy^5Gyb=8ICJuZ>V^M_&Iz%!^D z&*=>&hxQx8mZ5v_{;>-B=TH&!_G?7fw5RdL2OHq)(grkG=|xt#93sDrEydTaeHI>L_a@ffbH=j95Kz7?L5IyULK4OM`Y30?Q;B< zoqsXJe<@d=af~FE{x`$zm;1ugnHH#EzmFgdR^zED+cj(Zgb zQjI$!_&ut1STuVhDT#RtyN(p%Bh?4=Q)Ui4V7gzcmnw-W{s+ac|KZt7J#m&n4*d4} zdjyLwsbr*$7hEwofU%aD)KI|}vg6HhM@ggMn^6LBAAMD_hxFZ7D#-HC{ z`^*MRpR7x?`#OU278mAoD4@C;Z4lAjin4Z7xy{{=;Q6c&Jf;1eCY1TWZ+CP2gKN08 z&z8dA{i7s)!cV>yyc6du#4hPi(q`t7%<{hyKjB5@v$Bg|Sy*?kQQcJbA$aZW52~t{32NtiQBBR7xSD&wQp;e(&`f&y z^bg3kFT--*0B+A|d!oP5Ug9}fIrR^0+6owvv}CQ?0}9LQiirh{`KH(T4Ds4Cfu zT`bvmAhix`nQuhb>niQ>bAy&AmiS@ED{h+OQMfu`C04vDpr!kU^G3I-u>2CJor+?c;iz-;Y-`Wa<$%E1BYJVO72gDO53FpEk!jg8GJ_8;H_VT zzVWmnH>B+(K9h^HW%+N|fy)=&G^kIL=hN~U(Ccm#dG*5w{wiCd+?pHoW&eTveLKbl z94h4S*)cf9X5HA3OgfijK%r?9zB=s9{1{!t-1Wa1K7D;YEPYpiC0sbYd!z(e%Fx6$js--TfpgcF%$% z)h%ehIfpatoe!5a7vtKN8k&>E^!6p?c<1pr8uXZfJoi@qwJ?+C5+t zt100$x8K>zTORWfW}n~0g%o~+!=;UA+K@v!9UsFDnRhsDW+IJJ?0^%DjZOU`Mao>9 z$*m?!aaW@@onI@>>&~q}Tz-|lCq68L*8;nvD0gtD3vB(nRHBW)v`7cz+HTw|HJIo) z7(supJrWP$pPnMPzoHp+%AUoqU)lgIpBvHai5IC|;6xN-EyNQnK8Zf98_cWRlop07 z9^h==MG|S1bK>$`mhbI+6%6;~k>@=mUX--kH{nNA2!6bhMP&yK;(N|X38|*vxz*u|pdw}rrr)ilR}2R5 zMUxA$tIU)ByPya5Yt7N=Y$ertod<J>~nJQ&faKlUBMi1dNu~fFuti|mk;C`vo5NKY^L=c$UB=A zVPniP(%0h+ctjLp!r--1!lRVg+{7pT{EyEb!awCHkgxLy(k_KyYGoF!=X}6sFyp_> z)^Ji&mcml?(UN&S<)S%1(8N#pa=$;ZiTg#Yr~Q-6^Ngvfuw)d=j+keY0z`uJyKF4qv>-c!Fg7tG9&?HHkSD|r|9qPs3rc=jdz?zp*LdOkjB4_0ecPE6P zq6^!}3$vKls2t5K12}24BYV#r5Jxo_(FyJ!;F05d9K1xJ8jQDc9l>(u&3rk7;?1DA zex78WPrfsOzeam7^J$t$?)?{Va9}=%;Ucmk>js1ryv0=Ze9zhWlXd%6WAe};WQ_C)Ozh;>N*7#3Fk?ML^G4mK+arI0>Bu@18b*-R>vqKY;{gfpQ#JHU^xN2ESjM~x zqyG|mdS@v_u$lI2y9t>%(1x^W+KV^6O%|EIzQFH$kpNJmrDi8{u@U}r|gF=jSXlqr-YvB=L3^A zTcYjBUIUIF#LL&0qKAJXG1L46{qD74#><1Elus2#&5wL;KUo#`sF zZLnd*A8hb=z*#u!lA~MaNW6kI_kX~}a}>QdB+w!$A9!bCiJQI#ax#^>;rad95+Asw zpBX<^+E4hnZVTtR{~I_CW^;A(FA{kB5v+7(_qE;xN!FQJKm|S+(7?U;=tzdtSc+Xh zn+A=L;@4g*!(X?r&?U^X&1G5O$YYc<(s6--vzOrzE}!c4`wseVWP~GS!^p$9#gMmp zFIKIqpw~Q#!1F{4mS{eY=a#dbe0eE8pYB2&l^n?c9ZRwMuumd|y90R-6=}gy#h&{X zA4!sX&PhBf{{n&lAKT)1w5967DX?`#7v4!(NS^lH3%A@|aqOA`Dw}$((dBR!H5}E4pLez%>BdB^L1PgNbsGC${*@MEx77;q^Abv-kk2lEZTT14+XWkJ0 zq)Zj2-dsZ-Z+i{FOvl*1<33f_Oo8{Bj7=ySKnCk~!PW3y?Aoc2*h4td8NxC>vS?b4H*8g~ zl+5#`7nZ>952Gc_rWnll{>S|Utwa6ESGiwAe{7e8*?cCO0_k=IxGet~t({W_8&+1~ z=FjRRX%h2@Y_k%FN2<^iLmA%uNHt!rkfB5GdBX+4603gJa$ZfBplF~K25nBINq@6o z=0;h;a!n5R(qtx#U%6DWpUtRJQcHszc-T;jYgt#(WTtn; zML3AxO&>&4N~-|bJU?U`M4z%>>l+1Y>~kQ7Oa5>eK4z^(y*`EX(C(4^ex(+?`6SLz z#W0rm{w@E#w6+O`Z4TEZ{ z@ba6%^sBNfTq(82(r<;_ks03L=f>C~HqX004dT76Dlospi#uvG0j6Fsk?iNg*M5O4 zFLo1DBvfQy1*1N8VOQ`f68yl1EIf2ToYR>iYSNJ5^NjzZa=)7fR)_oYSG3zu{aG|o zW6qAa<5sBCahf+SV|7CA|?;@06n}>ESA)R>S+dx_CFTlHTz4hRfO=Y}QkQG{|^cu{+Kah{TUWPkO5=q>*53nw-4Hu6%DEfIO6PjkS=US#M z*|zvRJoO8~!1@f@JFE>nM|YyK=0na-N|*F#%oT4bX`sjBzC*pd7_C(kXggyr9&1_Q z<-|aaH{T6!JmyF|hf-(u@_V=X39{T4?mWxG|G2mf6OZPT`X3KLt@IrxW+u>GUy9+G zZ3PY)S4SF7e+5D$5Y-{XvTGKc(}w09f~P8?c-UHS6hzLmgmzQ zo-7wAUrKnrbqKNf$b($+UdgTVPu~(4p4G#2R(4+kGr@F&FLZBw)Ar#I_D|5d*Q)_3w9AoOU^%9v$-&;ygRiPru1<6&DNbit%_tg;=0_kDHS;8!pw3 zmF(&s9^SBNlojJQ2hdP!W&T+?(}-e>$+9W0z^|+j&vx9S{hTv_sJEe3;ZRcU-wkz) z{V6>y{XXiC1MmFRQplO}jjUhk35lkTsChk;ey{L`?IJ6dSKMS6x?W5ccLs~61=i8m ztrTK8rcwM|L+^Y`gJ0E6xId8TEzSGky16ULtS_J{NgZ(SXBRrl&*YSuM{Ci+GK`Ns zPj*H>fIQPsEH=raX6&~)`-BxreP6@rRvSaR`53G>s--g*?B%;>`U!3_Y_|L5kPCCV zB)htxoDA}{`S@)8HM;RpImqp0nb`8<$);upayZdayl99DjdzgZcYm%xdtGU&HnuOn z%eEX_rr43?v6morl@;z-luCDIGp@u-R?s<=!?{nL2~C%mqQ}HK`o}8^c1)_o6XvsN z=l$>ST=5q=oYp6}Xf_6nyup5;_`92EaQM@4>q5{&ry9#xZ(dIYNQ zah5%}AXJqsSKSQpi|0%BbBlxO{Oitt*tMMPtF`G&pJ)79MIs5wzYfLgVo_w8NUtr= zfmqWzY#va;`OLQ`uF8($*2Y0}ltUH72NtltwjkPYSdMp>Yry^@T_Vmr3<=ZMV1QO3 z{l;?C_4)ti`J(l2Sw>d5SS`AhzE`3ku=}Z|eiVJTI2UsIH({RVDAM;g^JbeliAP@S z6z%xY3~|hlsLZXNTu&TZvH#j9Y{0zE7}R7p3fvRl7t4NkaJ zB2r|GgAw!bZX4}HhQbwifATF(9G^sA))j!vFd0GZbp=P}&V#h2#wev%OXCNY!d1Q+ zGcv|gnY;DyZ+JN>4ALO6PwXLX&?d=j-{d)f?`7QwA@s+Qy)I>7on z9Fs-7vpazr%l74SnC~?8(hxE*Y!~w`&Xw@^x%q_O-|HY8eXGmKKh6M;f;N1*H=nHg z_W+Ew;&AhY1ZsM`5wfJ)CEoJma;zi6(NY|LZ7$8r=!VG4<+yt06`JqVm!I!liOMqx zNt$;Sw3Sxi`aSv7V?++r4OS5PD2^g=raXu~no0C?`mPX+T3Ru%;CXy?WFy#XwBv|k zAEG65fRr4t6!*>jAnO0DFCWePJlpK|aK%3&NYOwK$===?9tf|CY*D>wA05Bp3*1Wj zhdcM_kgI=pf#(=E?BAz=YX5NL@0z&_zjZ=5n^ot)vBXp2EpK>p9pc+V@w9pt9d%NU z_qo%E*^!Cd-G6$}8l@)DUhXUz#2Zbo#Kbxu+Bi&?_48WckI*U_lbZ%HS6Z-e(j<{Z zLk7%itU#K*pX{{?g4E-oILOVe0zK-54$;cx8RrvAFML6imC{m`lAFo+N24xSbu@G&10^}a5h|YQIpK@xt0q2HBmYC z|9*kqY*ga=KPfid7Qs0e@FxktTNUelRN4S4g!Kte-0;TXH8MA=HcKfa_4 z8kO^K)y<{EV2me>2yw#QZJAVVftcK>3z6igxUG8+Us#X8g`$=8mSr()@{|=Sm6ww- z)%LLVnX6sCQlzL(O3@kA^e;H2Zggazd2)_pJdG0Zi)Z!(DE;E`V@N?u8X8eds+UQe8K^I(mF*$3CI5GL5vyyTMzFP^3FE zY3P(jXb+PWq-$<*0}E|Qj-Qiwqwx|NmX!dr65~7y zWZ3)o4f!*#Lb8*8%8G}%V+%2ibyE&JkqZm{HRBrN(d1N`9U0o}EOs{iCrZ(523vKO zS#)qP4a}D1Pt0IE+7K&}Fxm%Bud>A<87VaQn<78wL;(iQbmMOK9}hQv{Wrsh*nEHs ztS?FQ!+`qORY0>+4_a?oMKaTD$cI8lNfy@JxGq?{u?_p~i8M%<@Cs%oh2gYu-)ZAS zC4Op80gjpbiz~KqhPgif&Fz_aw)}TFU%{w!6wz1sOO#FeN#?fZ<7`l5|I3;Kp{$dl z9Qw>C#H7t_-0E|y;Kpoyv|&8L#LB*Wz;EVzUsfy%tyJRQ>lC4?xf40*76@&HZ*fp> zB7HyqJDdpa#ODF|oc~pAxFfX$A8o3oz3+?Ru}8IJC$AmS23soY(X(JCF`r=%IiokD zd0YvdJ$wM4>fVYSex8O^*9Y;gX4Mi8d1hWBJb2fRQ_w*~RsA4$TPQ}yWl)WezhUU? zE*x>>A$RSI4q0oXCE3HD9nAtm4@CC~33Tpi1^&&#N}OjfggF1(2^z)!&FaLe-Mr!2 z^TOZ@Te#6i8SrL&2ToxFJZ;beP_x(So$MgFDi9KbbYcN}PRiF0Hce zf|&Ah9G4zQO^(X*hd-C&$z}txuICIWY+Q*G)AH%gr%Ym{&A5na~!q^-L3}sA*aDq6GwkIRCEXC6slSJjJ5yW}7hlH=6F#VR_C27Lw~9c7h$_=zHGf)0}@tcn=M4LBD?lH#5x*icP&Fy2|pu*Pz2R z4ApWn=>h#d{M(l;SiSuN_wuqHxZ0{qvQu^oZ1?W1M6+)`w0r16PS^Nh^a?1YhvLO4nRM$qDgF@i{M`J!n49H$n7qBcTjDuX zPArE#>k@HTWdhCeVc9bJ#n|CHihQ287RDTB45?#2t={tn9=wdlO7jHTcSAXxiY&nN zfze#wVoi8yqAuYypL|l_`>`EH<6!`GxTD0sNGX);+dnd1K$Th%?$NnN=h+oP&eLAqYK?9aa^pm`8-+*hY#9}W^y76Epn55*Q z$y$AKyVRc44`uy{(oLefNBsHyCtZc2rk92bixm0Fvkk~CdrA5ZxC{nhhtE21(m%Rx zaK11UO|6)(;9?W}W^6)<+ih-Zs~tJA`>=R+)lwStN`L?<5%w8@)HOwxAJ6hJU`v0- zo@|8q_jJ(pCS#MAkLKs;bfW6XPog4?R9M;|Ef_>4l3A}JLCxkJM&u??huClM)vF3m zy5w;)5^c%9g@?qMrv_7P&ocNmq!8Z?y+SJ{$nlE?wBXq)J#v1{A^6&0ip5cdbYuHS z-ji{r9j)<(PiMa&n+z(&)0VVR$Ef#U$^5RDU2f4ytUt(m?LV{;k0Zmg?MUjA!{SMc zyF}3+njmUtEjm0KOy?|9(E;XHlb(O8i03BHR}Li)+Yog#EWdaE49>JzHYKciH(0?!}{s zc0~snc)g!Q1MkDqNXKdwV&$I@svcVkbHfYpBHIV<2d;#&+xn6nd*zCLyqifK?hP*y zJzk{3_w8hzl4gfV?5E4{eOWA~F;BH!elC1hml5pj$~pfuEx6&mM6zQK?pFj4+3a1B zF^(Q-Y6f(v!_Y-DNMp1eyq>%TSGSeW@{#@dT^Cx>xR0mdca8ph#Nl$xJ1&suCkb#! zwgZEAI*0<9SG>fp8E>p-xdhI>;PW;V6)$JdaG4h1#xQ;9`vcCnSBK>1X-j%GnCGm&9Jhz+wFxX$nR^Q4koq8XV(&Mn8U7+EK zt?>F^4<0X(CWl$iTJJhbaT3g-ZoZw6l2VRAa{{TuL3#f9u1fShZb%-+o`GLiR$;ML z0WDecjdAF5!m^BEMZ}9 zbt?}Y$ltqIg@-Tr&;pO~K+9HOMN%^DbWee2M!(Vg)s*1+*B()afY(qnON1wN6X?2fY2J|aC{0Lw&zak5LQJQ+gzI@CtH6)m!E|7g0Gh6+ z!Yg!?vJ3$e^5MyI$X;HAbwzh6l`n@!K@DiLzb-EDMgg>6&%p#)BXZSo2tQNYjUUY1 zxM3S9(X$JacnF8jjRm_T)!UPBC&)!W&oXDqkgF9g)$Oywu z%;v_Gv_ahVCL}JG$=XZzz&A1s+wNyl=gtxQiYQs3#=nM(Fff9Rd(}`ppLLbWWs^nc zdL;X^#mY~xfMuR9pB+iJe`tXjRbALDKa;fAvHkeEm3aCnW!l=m2i_`FqoIs6?ZbL2 zJ~1BQzBS7by&nMKOlze*$+Rvo1I|_bHlj9p(0?L$GZn9&ejPxAp!6 zL8SzPSw7FkEPK+&&02hUPLt^ETzUS|%yx{;oo+aPwIV-KzJc9IUyzrZE0^8d%~|dB0l3{LSvi-m^w^^pQVs`y^!U5ga4b! zyF)j^#uOc#aixNKC9%%CjK4Vl_eYUUP%2C|ml38eOd`(5BSFdP9VWj^pb=~@YG&Nu zeZzb%Sks=g_d6oCIx&Pk^kChT`wGy|JCJs#%kZSL5r0h8B{KepSU&AK^y?|4^JPcz z6GQ(XH%??2eCRbP`&%jgzNd|vJH^4QLxt!!`4(NXzZi7-cVX1qaYT2c9f>MDB2JI$ z61@m&VBOp`X!>gqjgV91J34xBiIo#M*zOHq_U=cm>{RN~)Q^A2dbPrbx^X49)nWeM zy2dc-)$mUaFe5t|9DA4EZ#pR3S=ieGOU%vci4 z`@Z{cCbvYrgu+MR_>tX2G|wsVt5Zv`P9~4*_i7yIuV0DfYtK`aa2tMyfuDezMiZYo z9VBV4BAQw@Q{~(&Sh|A!UtS?};pr0a`(1!!$8YXI?Fz8nzDP2Yb+Z)sFSfN9m|rAX zC#}fKZD(CYP6x@e{+FTqMJ)O=ueBgm0w%BIh4Pd-E_bXJjGVeuGLuuF2&O|VKDsoX zdKou^$fX`HZk<7Pj<{9w}s0u&WqZPj#_At~aVO=EEEVscjiHz?Qz`48w zcLz9#VupN$F~eJM{&Y(+FNbBIjSs`2$1`a5wqlgqmD3i{-ES zO?r<9p9^&EkXCryM@sPRmL?(%TViw8N_^344jrN00o=wi)&qWtPTtCTb#tolZml6H zA9V(pIUN<3F;Bt()=gX?CzP!k&bmzq*q*Y)ys4FR+sGWS7qy^L#FKaf=FR(ZzXWCW zoFq}LHe@vOB`!LiBualS$D2=RL-Y3S+;$R9bbLJ}EYHeQ7eTJf7JoHbQU~AdpqJ~0 zb4>H8yrDDyy~|6`E)C=MyGBB&Qn+L$H$AR}S( zBiz9i-0wfmWa_rPlKpwdvr^c&HVGH3N}$VFp3*+MG90vbG`SNn4xUY1iM>l7(H+_D zeEIfkLf+7;oYT!$@W@AmLX$w{bENp7huwI;B#v`GBF{fjuEz9n0d(>}W&ZffQdG8G zN=5`dgY|BVxwvwdsx`1@Zd4a4MKgb(N;&8(Yr-_s`Z$G*Jm|AK2N$Wbd;{eH{KonY z+$@~tzJ3vr_F>_Y`8-pU!yF1Mxw9 zgc&=vxvpXD&|=VnmFj^cCGjqlw};`YO_{WJIm+C?^-pwJfqDPE(JGqmxbO-DELj=7=!jyqJbOSK^aUTDYCBO1Adj0Bceg zO0?*2$4Byc4XkHy`A5E47qloyoEzwziOq?~ZTXZV10rn@>;qfzrX;h{WZ$4Q^ z&^z#$7_ggydcpx5HzSSS>lw@^CNyDNUq5bElN$4tvF|_2gUyRYaClIKyWi;3&6kp4 z3d@gjIJuC#nP*Ejxf~U5(9aMpwd#TA?3R=^;akb>IEE;i$Dd& zyuTWx$S<5+f?DRkxNphoFz)qA44ZYH%G_e?iRv{$$eK-lNVk)<{)&=&Vh78dnP|n{ z69ZAJgdXE+&XAuA8y_r{+!J*l76E5pk3UXNpz?DHVUKA()(%xCBU)7Wn?F0SEymOE zjB0C&AXGg%O9n3VfnyiLaLgVyZ$B4+k3%h{ zJ742o7SAV9+viENi#u%Az4Q`LT#j^vg#sUERfk8O4<)g7JD~8~Jk*UTqt;3K{4B;? zcMn>~t^b??XQp&uTv;wjaJma-k?--cpFn*+wZJ|TDZxHPn#3gTBW~ZU#D!{eXymar zNZnV4tb3+U?r0^5zOQDjg>4bT6CceTH9UCER9 zlT%p-%|IDJED9hOmfH{m))jL8Mv`d7#Ss2>o4;TwbaN9PgpnqBFNt=MfBOQ<1+~FD zPtED;Og%neqk~Xr{fOLS?67^48%BT3W0^Dga7*uC0)5|A%XLSK~x zI?GFuzfoR-SZhO`$aa;{uHY#P;Ed33=#mWlWwgJ4ymZT8UqFB#Cg-Kz_G;7tVEX;hfLMlLPwUV!K0i z^o{=;P?=PVW0tL;ulWoZc>2T*kM+%`qok$y&BhAC=-zqU+yQqX!YLeA zP0OU78;A3%oUAapv6A~dWihB`s7r2wpWis}^^3!VAMK;awT3LBbyy1TJ!Bn=&PlM~ zKp}n!iJ;qkYvHLvk61xjF;(Tvqx^?J3aC%;Y!y~2Wh_mcDUQ>%L8|;bu zqziDT+y+lrB-6dWHK6PDa!I$sq|j7&lvj;bD>dmX#=B+0*_%r)EaD3Y|L!a=z{FazTeBbk&Tw;93mJ%C0+kB0x#q09t^&Et6<1)#TOc(g# z7mjmMGO6lv##jOC{+`W zWRK`#YX1tF|6>I2$Y$o*z8^)(M&S_b6NmaM66m+5sc>do4c@NFdf?fH@iaI_vSKPP}~SHhl_CbrWvI2j}t6dw-L2Z7SRUTk$foIb(;@}3@1m$kn$nb z;?pzQs7uFN5Z)DH*4~@cIE(rJ&vs()8#S_KwHyb;tmtH6iacqZ-Z#Zc@=&}#UB*Kdm8S&?gNA5%`v6MfCMWdXtU0;|7#SE(OKZg zy2I-GIg#UT-tajm41LFD(7CU^!(;nW{CFXR(;3csc{Arp{CnjJ>0r_zpyg$xTYB7} zev=heue!+X>Dmtco#x}^sxta2auI)Ex3kdnPL~^eI~oLqc(m9pFdteo7;lskwDwDr zlH7gdrsqEK_LMnvZDcd7wkko_Z2`1zog2JcV1+kz;8-ZwB`pQi8%We_~s2Lz04RB)7kj4}y7( zu@{7G!@IdU=`gb0+DqcQE}G&8rGA#EDBeXq%XIl)xemhPwU5Z7KU?6~!gIJjGLJ?X z?%+G ztvEu?u=|(AwOV*3$(^Zy-&ro@qWS>8YOYaL!Iz z@F-nOZcMWVlQHKonRRJ>vgrlmN(JGI;e2kgeKag@4#&Pq%*(Acgg<91EiC;~$~pYt zK{{rfgj=t4P~o?nT_CtmdBZ*R$s)?WQmA(2H|<}N2#p&H84nvlS9In;V@D-=YKUS8?N|D}axuT=<0)Z~ z`zlfzsR5fr%Q53gEv@QGg{{do82w$7=El@Q>i14`wOmg+HrkVey>=3BUQ}QoK7ifh z)(JBVC!hka^11=Dl%A6ZEB!$CizOax52uT>?Rl5v5VkYO!%@bF_4f(K^|vzV;E)XP zD{Vm4(o396i4t_?4aI)7jZ`(BLfH|DUhBlP^H41;x|xRy-K5BL?e)<9R2L_Wsi5rx zec=F_kR9Gy{$qo&2i!*oGk>S#2+Mhx;F$V zvdlN{G}^k)2h8VNpxsLu?)awB(2%wamyWNZdLaUM|Ea_5v4+%Z-8axsY{Z-ThQwm_ zA&C0whI>BcQTLWEm}As~aoi1qr|Am3(-uh&teeAc z8>bMU2AaLABs#|OU~}Ft&{s(1M-un3tt87#NwPmrc$5zR{0i~7b}()ERSbvvmZIZA zb_WbQOg=xf7QbP4WQ=8ZQq5{C9hxU98O3z+m*%*qxrwW*3V=}^tlQU}=@`<>d6VA5 z!rHBy$Z+PNS{iGDe@koV>ccs3qOA&@?9}L?&;p2L9Q0+8I+=IDnb^i#ikolMi@vQ; z=7(?lgCCka3{{7)-WJ9xE_-4?TAxyI?)Mk3zB(WpZvo880imRvf^MIk_G7zycJ> zl+(|*mHG6y3xuP?mAG5^cc8!~9v5f}G|#jS7EbR*kyj5lpua6Sx5Q4YyGo0`sA_`E zhNT#~H-N6wbb}dAR@naX9VhqT6r4&kMWe<7`s4U~-XO_NxM<)`N-7Lt{qcQxX;Kxv z`{*Z}bm+hbo1ew+)o+4}kEMj-RsLjBp$*xlY9}^6_ECh2wGi?uALquh&YI{@@}b8| z!myjI@PQ?A7U;Hj2Q}mL`D`O+!P4{zQ8(KH7sTh#yfTkAYzv2V(<5;EjSPA_q#90a z$&>8TJJWRF_Ol5R?V^D9f${C;c-LQ!K59^dgC|#`SUrUZcA%uC2xuZI9?Y4>SH=osV!l$d%jD?Y$_;byqF1bvOPqm`&)@G)Fz7Pn?bzGUn#-mpc_|2 z;z^iBq-0jV`1~4z7#BZQcP0J&I}6138Q1)FF%ccMg5;~`B$`ITi!SKhrXbk2YIB}_ zUHOkOuENa9(a`VF9nfDAf!k;XJ@Kv&|0%W(Z~Lclv!?RU!`@$(nb*>XA2Z0sMk)M% zZ^Da#2~f#A;is#@=~ufJSnDVw3`I>+a>ABu`Cu<@a8;pXRtJ34sX_hR9+88o8{~?t zF?Cl3m%=_<-R~Codcz0WrKHPC-E0PE7$lTp`JBU3(xE=2h0A>$%zV#IzPz zy;Vjybr{h61(bAKjr%u0phDI^nf`O`!6;6m9)yl84=nkZ-XWz3Pf+K#?~r zyJms2*3K|2)_O^ZON~Txt~&o(;?E3VT8-@|_O21|8x5^T5~*M7;LA~SED)8`wKvM( z_5MnhZKXmLtM~J!-FpR}hnYn4h8JjmbVS^mMjx`y6nS# zh}N7)hjGtYzrbP#A~I*0KQZBWMJ|IX**C*7T^Zqc*kf+V=6PhA{{o5Tyk|iwkm3Y< zJ{D``XP$yJvEmx|KCYf~|L-8n*x$FYuP_V@qK zHXgZD0}+f%>eFe&DOZFL>1E#HLxId^o6NqG>~}O+cLy!}v>EQLcSi-Lio>sbIayCWNb<;z%L~SxWAG+sq2# z(U^}I^%tp9iZ_VTEwH3-D0gDWa!_CBj=K}{Ch=O^}-`EgX}X$!W9q zal_;i{2xhY8CKQyb#agoQLmjSCMqg+E9^D54Jgk~Sp?0$P|2~b3!6LLUkJGuR+jPEFD$H&##sc>d zL~)K8DW7O1wEpN%4M(@Z@Qf;!A^InAI;+TQWHt2kzyFMIh1NH$?}m@1)((q#(>=DL zStd_x9;pGHt&0z?RMSg$6IsuDHQN2upu3i)!^W;se7uz-dVLs+WSF(kpw=u|IZT1q zG^@jT|H8?|8?K-cV1)mT4WP>oor48S0&!zq8da*zg}!VLTqzsCr7l*6^<~2_$-bTj zu8D$v0Rj$rN-1os0Kc+4tdIT2nfKZZ4H_$O*5`7%{DLbixNL;2Yv)UxYi`1_(9hTr zC(^&~Qy}?pBdWhEO?7qUYtp+ENx+@ z$xh4}RYYs;TtU{=2sf;op;dJ$f|v)_2u%%b^v996@O5Y*-d!6)Rj;OlV!u|5EEq-f ze{X^u71mGpu#B1}mcY09m1z5}KdnDx%{zA;7WcpYNp2i=0r!D+xc7cC9bo1PZ`pgq z=}WyhjgpZt@$!0n>|0Lf-W6bHb1gni)ue6NzhD;2sZCecB^p&nVM_BQG}6hZdxRO-e-FSD(X2af zxB=fR?;)lXjwB<5MpE&wFV>|tQ2na!F#AmbCT(T?wk`Fr>sAZyn^VBQ2+2>}# z@#3!~k(<2akbmefcC2`cxhk(oj2qK42vnp6;y`gNmsz1-KMx9qJj=&9-DvH8gQG% z({m8gv8mqXW18ygpSzQ`0yZOiGbZE+C4v<)5NCQ7ax zPXjff87)eW5pI|-gu4V{duJ+5j&6rZzJF2m8E{KAY{(#qQBNkZ%lH@UyBmk?ACVr7 zW*vowEW>j27WZ+^dU$iw2^S>i(UdX+exkF77`xq(yUo9XFMa|xq$5phYJxQn+p!tm zaE*T%m;Ux)VOoeJ12P3)AwA#a)vSP+aJTFmpz5c>^_oI@_-hwe3tI$ z-r~x_apcwRGN_r}feE9UBIl3Gg6Iu-7_pHjTVrg9ub#0mYt0wQB&R{V)16-8vB8(P zsQgHxyZla%|M^f_I6Sc~N58SFSwC7LOmOH#->4O2jsIczyw3^0&dsORUO!=hOeHQ| zHj3N3DhIsI{X)Y;C(=Rg!+g~sJhCl~W(`;1zt`6FFtlrH3CLfV*rQQ@O$vu9mW?`O zVZ<4?rjqvOvOOBL7a*KTXFRkGx9NmitP_*<5GhZcNldKF$g_4Up>yhg^oVl{)Rsx{ z6zP(9G5_j6b;hmQYfmPeW8FhlEQdQamWDnFhkEu~So8KHXJxDgr}cDkz@=(BG9eKx z6l(C`%vtoa$e4SwO&Huun`AArAPw<0LU2fn=(C^FTdON!&n(75k&_{J8aBc0qbo2cqnw83xk7}8Frizsd{!3jIMviTOlHC$SeRpL{@x0r;)4wZ!v5tScC3gr1a{@TqtCEQPUtc&kxvw z&Xb+!Jg11}vfbl17~}2m8CuQdo5-o19zsi>EA-=%H&DZvc(-eU>9*6QjCG(O{>hj^ z<~wbI*Mwa`~2Anx+C<*w!3u@>R)L2zU)1_f>p_1i>4uos%GrI@#Z%c6R zW2B1a8L;|l6;}I6IVsE9x!BkUVLKPl!zU}iop~VNO!lDTS1Isrbq%OqONdj$X*iR+ z6^HLHpgP52aPe0;x}1<927i`=cD^aPdsWc?m=9-ARwK55dm7ap#XPi(Q>q=|Ode^N zk}-R%g@dvQ66Xa~P<5*aw|1@OY-3N8nJ*266-PvRvz3 zlSpRrHt>~kM(r{Ablb^WFx@o>cWS56^lw!VJhK?znMZKoya?8JO~$@uUL^W=Y2r+Zy=^ur_yIl z%vZ+xN|Ngccm9Jlk*hN9(WRXxGUj1f9EL7KI#;nb|9fB=j%pY|HVs|}@u^PO?^YhQ zswBKA%LFO-AK)xkz68h+Q0Wv>|5L4C$#Q1_@$b0!dzPf2^02VlSB*~mF2j$_tHkK1 z9@J&8B0s6I1jj$(N%e~-prl)bYNsF2&kw&b*2h0wvUE5Zc&z}+16t6yvL*h7dh%1NK_s0n*jLoM$rKkA3SFWPr-w5tRS~f(p9Ocn&ClYFTk9ETZ;q^bM zv?6pcZ|Es6Dt#>D(oG1wS~v++wpP;uzc8@ztiWHMM%>R0DWvzTUOjvDrz;euoGQew z&Hx%!Duu4gGGeUTbfRc)M*L%Kg@XzM=&;a6NK2OD`v;wpiq-P`yJZb{lx3Z#CwoBc z8Y{foo=8tvhQUx9#_G@c$b~9ShL+(Q@a?*4D)fnimm8&+s565qJ-N-lH;=;H0f!%#aU|V!O zU2GN!Er$?KO{UaDxfW)-mf>_$InuXCAL^4e@p5B1wPbqKpIH?+aM3fu8{UBa=1~}b zL8Q?U8Spx*6Hh8jxnbE0A!*<`3`v#Jr(RjG$gKc3>ig1eHZwhKar4d_|z zMyF#%)N0u#Vkz|ybh#_kx%D;l)hfgT7lP@Pn?Jz!QwPQssu0yseVCqOgbVA-s8K`_ z{Mf+W#mxItV~=967IK;Pr9)2FGd{E8CG4E^iw5Zo;M3DuP)F*psBbF0q?!wnCM=h9AebA-&m((QE)gO})zjeF zi7clagXKXGKHGyPZ&BjU&Hs(k&ei1b+0!83 zxec#|6wpEbVURhg68ry@A%kle?`Vk`yTVjZ`}Aa(J-!78l|PFr9GU@@xz(8b>H_Iw zVoGXP*$SGq36cwgyTRLn@%H!ZH%Pgbc^JAf4 zb_c#pnIuWBN`OtXYcagQf;@=vX8foiT=^`Oo{eh<^?@?t_dzSU#V(el;fS%Yfq9CS z>g0j0TReUpjntI!LN`lT-}I5uBy{px_&wdZXWpJ)ZNT@M>Y3?+rKSu>}e6F%lkFtI>xg-Eh325^rgE&<~3h`NR5USg){>l-_s@rl*Tg zSK|R4@+Jksv6uKee-yFv&Vac1eDqn*lPQxeNmg%TAt?kU`5KBm$2!i|5IfHM$tQB) zc(8D&zJ`t&`5M;EuEU?twW-S9WYDOR6>paT+2?Ht>jygb_%zNPvgg~=UB!~?5!~Z! z_I$Kp|3C3=q~O_In4cJgr{AU0v^NTTp=C3cPfX*UEhW&na5B1mucm$9CKH3GUKo|r zOnpox;1yAbH^KwxT$K`-wYw9ImQ5k|9L$Kdqn#l544{A5-(lAAYP4|tD|tCafnRm3 z8Bc0kk=2|Bd!Ab3L`r=Qmdbo$ z)pmleSF0r9hAe;P!C#C>QrD8yEAji>{@}sbx9tA>5k71U#-pp#sr|`QuxL^csu`ux z(KpR_7bkboRd)($`lAHxZ%5$RK@HUU{U=zaAmUS1N|P6q!rRNgFtfOen|DMXHonus z!YLJWBlG7ZF+RM3|9eS=^L1!^6@^o^*q!&q4+tck==QGCoJg{Uw99+&(uX4YWZ{4O>76Z@Hu{a$Z{^J-?TnXTc)^c4 z=DvbP#y;{~6ijQ`yYtwDHY~n2iUhsZgCc8VZ24M77iO~iLfj0)_Tw+1@(WT;2~o?SOkngE~VndfutHTw8u3miN34~s|lCRe9e zl4_S--=>3t5tND$2ZXXe}PnJ3$t&^90wwpHb`+O@9qbhdJ{V#JfeM z+<$>H8ShRP<&3JS-RLx!q#{KZnK3jcCj+)WEWo_BG2~8|IeE<(U(G+Il12Vryb$jo zKHAWS3mWntuXBRsM=r;a-ulb<=M&AvLceSh+u;N^^n$Q2+uJ3MIWWk&31vNlxlX&e z#O3{x9*^AM`Cp;HF$R@uD81t($4{Hkh^@DWkn<7j{$;hSXRaEujCrThGO1Vfd1A zoSJA)Qn#8B;~G0*=ZQqg-aS%S(o}*KfonLWxhF|!x*!J?x5rKRGK}Y3Y_njqUGQ> z+zQi$V7FlkhB?;I(_<9*7s&cLtuImdr2%i3o1ydlGP)`<0oL67hl-U`Bm#Tp{?=*0 z2dp2@U_Rr4M+f1Yd#N<5cOjga&oWJNbGcJ%tjHw6r01?zKR6er{)oo`4+YANQsPHw zRN=URqsjPDYhZ|tGkV+S(P0}7@NSi!;x;!&?r&f?{QiVEcQVoy*^O|6cB0myx7@>X z<|LENOv71fRO9SFFwvGGP;-Fw9X-ys~*T zS*drCx8LI}M##E-9{wgBJohsXfH5H_r&^E?VaCG6(+s^{CC`6&*^K8t*>Zc&d?Je0 zAw74!O-EjWDr0^=d$pb(Je&mbn!QB5Odv`p3}EkGXPjD)NAKz%<43x>h;+*2@zvLU zggco`?5ld=+NNe2<`e~|=Chfs5kR%v%HZ15f7rf!8ri}+^4^sl6TU4RNULr%K&o6d zs(k2_WSvsxtBSku;S76XV&(yJimh?Grq-rnmz!H7!4)+`Bq^12i>j0$kq z!++f6k@}GIMGN!(mD4}0i*Sun9eSU5FWI@Ab^hLp!bg4ByW6ik=(yiYbgFLPawjf? zC++L7tW!#3HfDhH&;nd<<3p9Tjd_*kgJMG2Bl1|!28QeI#Th$_X~XmWd`L_)YPv;e znY(W$pK`s0aqj+f?Y)=q+ocfA((ceb*~xJ7E_-KxGK%o^8)4nTBiNVi7?m#z;NNNH z1E1BO?(<{aqxCuHcz8Y8``H^FMqk1qZ}RCq+Y!9QB02GWs2}&XaTFYq>SMEO4P7(p zBarpgI5cP}4QBb8^IPS`@PduR<_cqbu5rdCZy1-p^fzQ2?IrF~3DxX>w-EH(@~~y9 z4+;D696CIMaj0n;WqxG-_b~RpzpaofdT0!)4*#3UyS;7roRXVj)T$|D#nL)*NZP;0 zcTpA*5AkfbSNV38X7{gw8#e9eU)PIB2bq&g%Z><}PxPU4xBLU!_$rKX%90$8Rpjm6 zr6@DfmZ+WcfD1ZNI56i6)wN9p$FU0HVwF;E&VZTV^iLP}-C^8}{;6Q(FU6>I6?$Sv zIXtstZ0FKx#Lm%-7_r~Z`cqO#@n)?ASQhD|ZJ z`w69`?sEM5Urp#UW+=(j+zEGfFUS1nWz_I}AO3yGGV!`nKd!ht1R$090j493dcba} znpL>JPX+h?nGt2X(@%X;VO0MPjNTR=75ph3?)cVVarSwVB5Ow0>Kqr= z)Fet)%ss|GpKl{h@l4^o4VICO17-?t1y|^Bp&G*B8`j+tsC&yszQ)2+96c(QBx{d{ zIzb0VwLPL6i4}jV)=SLS3*yq}+<@0-?x3l4Dn0yA3UxoqnBMY+BQ*=)fWlO446UJw zM-=!b#>WVrbcsIervV=_{x_>rAOZHJccTTFDhXlikxudtCt98*bsN24RdEmwnwUye z78k&#&i~D7^HiRg-sObJ79uTd%7*9j6VQ8&K>O?*%4e|mYa6R+S?_!vWP#xgo#Ih;#2Fg1nv@?Of6Y)nBCe zJkXu)^s3Vl7zKcq)Ll6wC;8LcnZ~?Lr_RE~47k9VEJG9C+-|Md`UpdRFBN><^UU;a=0}Qm0?=JF^2_Pj4Xn6?5|6WP71& z(r?KOmZR5u(S^Nr)wTBD@5Apm=*Iez_oQRs2N=C71h=!S(36+?{A&Ym(Lkk*Bt(sa zhf{Phx7vj|KQiHUw|VsJ(nddfL(r9xJ-TsL)d%Rx5%K&}30*d{1nk`l@#+45+(4-k z|Al3}BVFD}_E%p8uR{`CQ;hWI&;{^wyEbm&tLVY`8F2e+QI9UMH0>AcFv-Jf$0w0E zC416;rLiE}Q6)L(Hh|Zg@CRi|-f1a)*+TwC`3lQNU!yObUO?>oLhR#whi+u=<8k_3 zX#Hsn*)o13WYqp|K1UuZgdce|I7sb3S{;zbSPeP2bHh5)FZdWaXnII!x*?HF9x;Gl z{iXvu+uXU9QKMjy4(o#7TSNDa`T+CZu+Bv5rF2DX8f;*imEoAxWRs&Mh!)r8>*F%w#0$NNN3a=bIbtF_d)|lk`u-Ob zS@07y(Ev(Cin@0ScP00g&#;w(sO3sAI@g?akD7akIvc2DzFMYvs zIyy1r#hnjeXz&+bIax}q8dvc76}F-n_=`-7yaXEt-oZqxRO+je3q#yk7I;M{Crq0| zE;ldj*`IY4;=z1EEV`*vI_Z8ZjNDs_)1#EhcefpoF>nRO1((rz{;PSvzAoa{-1VH& zvJfx^0sWPcz7NU;XO(t*{=12LZ*NNa+no?599~3O5fPk@DM5?zp0x5%FMcfB+Y9G% zDRO_PIVn`L7hVN^mrN_~gjm)mHKSk$=doltdD?H5utCZorxU_H}V z)Hm{zt2{-AwXtNW;W)T3Ko{rXBO2gm!CTdNiH5m>T)>&@(4BP$!AQ+RZb<=- z^9|=xGEb24r;UU!O%v$*!ScNE>2ln+)R890%ml@W=IF4ajMgvz3Ik8bin=M&B+)`4 z49`>)2b^&x0k=Kj(!x9FFHNCi3;%(Wv!d9Ur_D9Q5^}XgOJL^)n*AvY9L^+QdMbMk zYWC*aWoz(;!e}C^x(d$syNm;N=Fz2(_VLF{y~HD*9Jv=&&!OE%#N}TE+9Jt-wD4lw zu637tVs1u!7nt;D#b*thVc5!IbbIVf=cy_4BZf3$sFyZbs`~(J+Kbp7@IG}PmJJK} z7918NjkI5BPPQtW_GrS_RONXM*0I>|)0VTJ@sU_u3GLB@pN)6|mQyS6$IO*9M|U}I z{M}l#IQ@$F+8=;fgD>NBA&<7L&xeCuzfrqj0yjaW8P@5^h`(-MCqAwrus}W-y+))` zd(Uc^_a_Ihmwe*H^IFinXiAS>F}_frcd+vjn}mMk=J#*J;e%Yy{ciWIPheYLh}!3F zQEC5taLDgKvp18-{^90iGE}E`*X4uhqCd#1Z6I>~ENfhHN_al7L*fM8 zFm~8KJl#G`D^>G7$c2UAoeOEyEO8^hZM?U*QMr{&95fEPP#3LRT&TC(5x(uAhqz|m z6moZFZ`fQuvd8l_wBtP-U-AXN9+uF{CavJLuLa#}`;c{+CyCM>)?FK~Oy#nA^9K5L zc<{+v$@e~2feV%3@BpOq?HNz$h^#o|Wer#4J|9+2)4{OQRWz#h2e>O1W6WP4swydj z(EI}CAy*?)beWHxr7iaiuaca;)}Mc2{~MP#ztO6i8%EYS)CnmATj{#J;jkmS5PfFd zq32hn!_JM}`1m60fVNVNg`KC^;2ALB3-loExc~z4A z%M|%jn>*3^=q0UxOndoK*Mb$7Vo3S2_aL){&Ez}_$>pa@`A3%4;+W65qZ80>im z$DT~3efOusVh6^DnHtD#aGXsZ`Y!94$@^!-!Qp4Ic()g&XObG=k985gwo@WS(|5r8 zL7J$``ey?x_4#j^?6-4#J7=I5453Z}W=I4&S0@RMBkQ%CSjJWK9tokhCt$o;9W}XF z1di-C6;$R%;}$hAO{oySznnw*Y`2G&MZ2+|Ng+*k(dX5!`G^A<%UP>f6_iVLF>81{ zJ$^h9f*8L}am=%*)zJme?bU_$kuD_o^C^)1?1bkvbLl0Mzpyp76Za0-#YKEwMxuVr z5-zLx)1U99@Ob}s^ivV2SL|lKX#5q?>t!N&lCKIAf9dw@$vbo`_+7Ey;?QkDT-T>- z5Ud`IdQBzv4JIZt@}@DAE!r_kv8S#V0b98V0^;5wyRM9*4F zn4eAQ7fB|3?nuC?e(b+hE`g<~F?z&Y<0QRT!nyUAF=}QWU2&;Dzx~`IG5+~fuBz-A z$j6Jg#!#U4)){bx-RA0U-{lJ0O^K_4soNVJ z$JJAM_T-Xhn|QL{R~+WjpQxYtMjW&LH>)4a{{&LGB0P8K7A=@x29~+9;#PLoE+H#G z9J3Csc1Y=%^jgqaR*OeW7z52phi^KnB?b)oK>S&kiUIS}>hDXWMTx8V!E;?j>E@lJ zjAeOD7jMAlPb%qKQ-t_WQuIBhPHh_)BdfU$bJuB;-nBbH`-U-w1eDRvL7ni}<_`w! zpQ5$zS0h}qVi`H%CzPOdx4;u%grflfZI?}rj^G*BQ z#g(3u$#Lc0;2=M$XNLa{cn`%hzM#V#2_2(e0%|vkvE8?uiyC^8e9${0NbQxW>~%%H z)wu?TsJ@XrOZSJLY=&oCK$_A27d)7uD8{U8xm~#kPNy`mysE$EvGQCVgmZZ-hN6;8+jPv5ExUDvBaQud(XO|B3TFe)2wGvPJX_Mzf9n7mY z^z>@&i%5cmglcRlP@xyq)1kAq2q(IXAt45)WZ6zLAteTd-+yFt@zlY!auxyhqbe zv5keVd>pnlN~q8HYVfg4@SSp6#DIHF>DMd!R)w~+`C=JNc37`!Fu}y`u&<5-}$W)Eu0;x-|~3y z{wFIY1Wl8i7?BUR&MS(44>^&m+dY79x`Rz2DYO87Lc{!0wEjJv`|?$b?7hkfU3&%E z?2`dw7Jfy`v6L?P&k^R1G{%22*Epqw{yaZwiD>m<8W%m_8LXf91wYLYs0`~zb~kNA z41dNQN-`toW6g!x?NjIl8OH4y#5mH_ncf)U2(KqF)@VNE*76H^t=;CLPoOKYuFnGB z6YUtq()!}NeDEZ-xYtgXWY(FHVHM^=!MHDyxf82l%*}jE@?(r{@`3E=`ro|8bIbS> zYDdMkRj7DllmXvE7P^+{<=wzwwHp%Tsg6C@pR%^ zwTyYH*P+&6Da~oE1qYTxtZZXD@K$X;#FG;*_4z@6V~zztUt_zO#<)S3Eh|xE*RI9zj)UDSa2!2_NMDVSe0HtvHh!kd&}Y z!LeYH^7$>adxxS!?=-45!UQcd|a{LuwRML~Z6v6WSX zP0vU5c#j`yzk}Z+qA{ztgqD{V!3o7uRC?CUtvzc;+MgKr^dHbS&XgBwRR(gaFSt-N|<}1I`1Jj?w+v!D^>>or`&5}U7 z_Aic}u0l-z=s?*PGxQi&PB-t&0%fMF*ZU~bwQboj)+i6ZHLoR^xz=RT-9tjJh|d!L z&_TS+XIZh}gEzND`7I2Ot-)X4me9}5=`fQ$2TLQ?k%|a2$Vk476&`uCmrEh6Ze~8} zGya;&yK^DyTRvue^dctP$Y z&WB7eju*(9?-D<)Mf}oTR^rjV+N5UdG~icm#0JAEn%DXrvI1&Qt3ib>Y)FB`DMi@l zgbI0DZ9=r1&4sn2t0hlA_v7EuKUnxEo@kx-AtuM;g>tey%6Qxb{_Bs2;@^!U;dzb& zn2Zg^dgWBQpe~2)x1AU$bC2uroJEd~T+!o6Gc$<+r@%P8bw@&{=t-f{EFW9@E0BE) zw}VZ(7FMh;r>7WrqV-F>aK7%UrsAU@*sOu*v4v%bGKWLF$Hbn#@0x@8;GA86r5jvn z731nW8(fSEyXKIS6HbEH)V=8Tw2)r=;6o~79f-n zFn&=IJ~g8>-NA>LosJiry8Cj|!ZyN#DK02$mq)iSR{8VvU{pAlLhH^B0{eg6~QrG3R4T@t$Mgaa&i zVvIlIuX04zhkT2T6J~Twq+S2|@%hF}#59j-ocyMzu=Vj5^cp2FXLAvJ{oI5B1D|s% zUYn6peM{l>sj1XGwiWJiQaroPm3mq`z=$AY*1t))#l}7)b4$F?$K6+=c5(rKQ^7)9 zaMzV+&C3FneZR5Ds5)|WYCc5tuE*p08_1CF7DQreE!gjmk*qwgz~?c3>HUuaTPN%dlWsJo4r9{7^HWvsl~NiL`nnn!h7?D%ElJ;kS9 zZ#avXV&M0;ppmjSd2#p-=&Fa{f3_*~_Xa5>nC9co%1^9gYXvxxX+5{O=}&z~&XWY; zo5?CIqvcHBRLy5P_BwB(R1hcBD$d{xX4|qm&K+#2PNDm94fsD}J;ccAlZmsV0t}fm z8nZm=Y0QeZuzhPZj(!kD>tc(bF`u@y6$c9Z*^b70F!-5yWHMb%`eu`NVC$cyDh zGvT{$F1iJdCug5olju)}g)egD5~Z9Cyq4J#v6mpvy?^CJf=%ND?L&z)e9$w<-&4eR z`$5zv<~!VMWVza%DrES1U5LJFf!y5+Iz>MdVjfD7SSVB7TNw~_DF?qYM)$Dq)+BzW zk+5W4l%(y2JfA-Jeujp81)|cXf?!($PRr1f3JmN+`?44zKMON8|x8Ztos>BUgYtWI3Yq! zo}L`ZH0>wlsN{T-8@o?R47&d}pKJaT;V9#1;YU9z|D_mK4q@CURT-kc*_`+US@+~V z&h+{X0~Bg8`(}ouaqB?-^BGz3=8#L|r1WIoH)xfu#f_0FbhTS5)Eksw-uW@awabK*Xj%%5vNaO*RX6x~zP_T;wP76o z=)+&y(2i%uGv-@`7fE;%CoCPlEXv?rIQUE}$0xpuMzk@n;!-9Lhl_O+(S1lAEo45K zefP_-c$Wt)9Z&IAIXvk&LV718wZ%MF}vL+&{n32#HjQO$ia{De*ASfqN99*FWHil^g*z+9W9rs4tti_k za6u^=WlJaxzQwwYg3Efe;&1t;M2qFr{(qh?X>5ju2~zZW??OwY7a4o}2p-u^xz$SE z#Hu7tn2_%yxs@Fbt=r4du1lVjjbMeSFIitezpBV%wkfcFUNKI43M}hjPIe8q5vDJR zk!)ZbhK&kEcvf#WclyQ$(st{CptZf8hWdMvHC&v~%WsNg^N(V%PdfPyOlB3~`9(LW%Y#xNE9J#&eltk= ztYxr4S-VG<;Qh)$KaTYrt!tB9GqdEkmKlm()mdchz^icohZD{%%%gtyy@=|LIN^y} zkk*n3N&YSx`J~d1I$mUGPOK2vZ#wtT*#;I`-oa(pQ|MVA zL;lS-53x_~WU}(O0+qSc?Qi$zUheQ5qkU5jB$$pQ+!ssVul8XO4$!Pyr!By!i%UM5x zq2@(+q&ko~9?yn3YQ4pqMU%;%Z8|Wj(gOXUg2rvmfK!WDhpe75O&ON~(|vMr)z8&r z4D)jixp`RlHukfmc&t1RAL`Iu+mX|a@+5oQ?%j)B_}zfJ(a}b$iSX`JIq%AvX^-<=J-+H zPmE0()`rdUGNg{TAQSkb!ivHDX*RaQCYw5J9+@c_{ZXEOpHh!^(rwA4zaHegeXKB8 z=c`2eBMi)+mgC(EA{TRe3Um$A!z=%!^ufMFz{VQvwN!I-7AayYQ{=Jw-i$`xI30)dl1G(uX*jU+{ z99P)}A6*D;_b8`YyS&KpBk_V~t-og1=P-EgUXGH3G33IiKu}c_(Q>Fj|2|BHwGEAE zxTT6Ke>@BhdQL*?MRin&X74zs%CY012MuhihI_+HP?9~H%>8%*9Lx9P#WzLNtjm+| zWpRS#(QK{osCh7amL=NEWjfxWcvv%}178_Gi@Jv;us2*@jNju)ZcaJ@e&;Tu+NNCk zFI<*?(jhOZYZ!8~BA1iEXA6XPKd;eao6De5BN_XoOX!{)PvRXBC;a=O%>CS~3oCqG zP`M?S{v80kL%X$D@tJwjs{CM!R|p;$kwPDxZG@ztcKo_a!qq2R5!W9^LM1gLJv z!S@;8M!}K3rJf|lD^93hL0G4G7)(qp$6|+}k_7W47_weQG&Va;sxP=f&3rbm4yI7W zqeuBldnYmUS~T}@j3)7tLeGBg5x{z)A0(pLehIy_&XdHI#tOu40v$e><&`?i(Ni`} zOV;Z#Tr!A8(}$EwA__s)yA_8vJ?HGy&56SV=FOH>r(v~>AN7Of@%y>3!OeUl-y3j+ zPb#xoRDYgBS~rxgAZBEJ5eW3ES6D$MiMBOq@P|}+s(NqkFg6jXx@HJVx zz|YWy3ADMiA;6MXXMFOcwXe9we^Tgv+l}+X8QZfy5PYgb(7l`Gyu8a{W^q3LZurPO z{jnS(U#X+zs2bXM(~}r4ix(yj;kC}6k0*fv3O#$Vx`t^Wy>HUfY|o$YOkUi* zW(FC&YAKZK>0nTxlv=nI!{n8W4ZgQovQ=9OmyQ?VG~Mmw@KS%sxZ;duk$E)F*OOF1 zyzpjOke1;}RWOv<(!*hHe-#PU2345wVJh8uEg3%lZo;HhtH^}1tx)mK6u+)5qmOj| zLPUeCc(hhs>lVusjqNT*pZZ|(=V%1f^fq+Jghwy4(ChR(>D5@AXaoO8v z!>ofFaGr;hzKi|_M$LuT(a(z}Z} z$dGmGNUAaW{wNv=bJHUww@u~v-%9lu`qzQ`?dw5`*2D>$a38&I76$j)@Dq(ozIW4l)TnOv$~kppE+TedX0qUn;C2?mUxFr~?p*xr5w*AL#s_d*J7 zyrjU-&TB&LoIK8veg0DR`SqLRXsbmSeEv{@eGE@>FE>??g;4{0d~^rjQy_(fn6KhT zx0DouwQ)P9%F2-XW9DR!vR%&%U$m_q9D?ex!7Njvu~(j-FE-$eQd_cL$%ABGiWU0( zN|4;v4}%=P3e=7hxr$ab$bX@S(tcIcYr$8@*Qmw!^`mL&%UpJsZ$z1mYUEjtDJe9x z?cvV(AMV9>GCzEFf`isp8xOK(WSmeOvLq^VaTt8Dt-!61H<4%DMc8sa1pQS~>B2`j zV7x*`tQPKb{hrMrn{rn4^nEY%W!z@wxgD7oMO)960`ASn*SF+I>!YopX#)6ymeYED zPtvh7Uij$lubHHO8v^%<$W>B${%{g39MOaWlcn5>ilHzzc@pcStEH_Mvtc)TXL-Mk z<=`so!G&cF&g`2{^i58{#nA_G#mHhhDaC^f35^pnA7*KJ7S4r3&n$8ENaoYK@C`(1 zH(tB70nH_%cp(_MG z_fDbbY#U+Ck`6rAF5z~^SP*$bBcY#(D)kIwtm6Syn6lJ?u1WMD69eLeq+fEYoN1){SQ+_9VH&74TXJ&Rmy5edhdxVwWl$cwU3cIJttPx$!--`q{ZO z;A;{wpd*UTTp-U|pK8FsU89J7um`!mC$491YxEC?WbaCJl%{Ew2#?@XbToFIq4ah3 z57<17@gdFcb5mL7U3%F<2=s^NH*}r`s zXqouLkRH*T$^Z?5ZkJy0rur%j)8>r&8K-su-UAtiqa^ zEs{*e(7WrHi!r5ode}b#Y zRT$_qmF{_12vbbt#o=qW5ps7cj2vu^p+zk37Qnoq)9O%bzKYgo`4Z5S%f~_Lw@KaS z*HE?R9-6T`RR8`SB;jG4@FPH-J6C7{!&QUvf_w^JK6@1#)o3L8V8# zc6#?3lJ3Reg>g|db5;we9q7W#llzfrvnc^erEUHgSZub&5r`oQ#u zmA+h9fDdrp0?M}ubd|;rfXfQvc8vz^fn*k>P1xAO(5M*s9i(N&%){(OKMraK!(}pJ z;>V?Aa;7=?EgA{qZk0;@D_7)$unkLtUTCSFb0^J<;snPJ3G^_11WK{Yo3}rZw!=4g z`jPD+jPIAVWIgytSfcmKa%%oQ9R$xR?0D3Ns2q+e5 zfW*$uqI8KxN_UE)fFR#|_xBIn=RWt&o_*)MCs43<8s9N@FV+-dU>nme=Cm&mfU3^GBIawBw38~>(`*xvQPZ+S6TY zUxnv)d!U~BH2$S^q3BhcCd8=Pk}I7xxbk5hte~A!9~ECE@7NW3 zaamLGt?mJ^vu`5V9T)N8+aAb};-{M`gGWXsz;*U7$^WX%eLS;@tue3`_M6qBuk+lX zsVtb>r;hjwRspw_2peDX6NZuP|#to`Pb!Yv&i^!rp9 z?9P`ISoyBR?P1i@H>8dnn6d^fG_*zs9v$NkrlfHLRL3&FRg<0fcQf$iII13P%6DCT zgvW+?pg!9)UeQI33sT*}#*Xt5&Ya6dE)6Q+GiDR{#f9O2ch0fe8MlP21db{Ak_%>Z zmYZ?y3gW%)fn(GoqW&NcU%b}_+UX7C!W+Vr#A$)Fl!h3qjfy;we_|SM*o8zV-O^Cw zIvHYT^b5b9{R&1FRFW*S0G##VBkaxjLwbyq(0$bv;P_8Z%yqZqRl?->Ci3R}Pp)%D z1t`2MCMw?y(D@DiVEFeMX<1u}>t1^xP1iJj-t7CLqvxlBT+bGwb*BYSo|^zdcoXq8 zoQ3sm@?el$7xC3ti|(py1v5!2v1a4@ynnzb4i@qTG(@FaE1;mbm<&1-h=P{ILhFi9 zVn=t)V}E*}M-^%Ot(e(N`95oyJvxYt{FsNC&Fk22e@+S7bH|{@Iw`o2KUwU{R+$$I z4u?Jvl9Yr4)-}U++DSBT7M-gfSfe9fkMKi8viSWW2{vy*GtIe*;_f~4K+}$<@lC&J z54DpoY#T#}b32dw{TcSdaR;Gn*e;}XdOjpiHW1I%xe_^$Ii;H9m3d=7vo_!||B#Ta zi;>DtOO&vTW@=SebCz4AX@9{lGA%MfRGI0H4#)n7)eR4xKz~goIXL`2?wU%u?nRP< zvDZ{IW7K+>DrHNm4C}D&r~-Ip(nNBm48aGp3PAL@l-L#OpzRq6iTl!eYDrJ>Qfs3faW3e&WeKElda^=uVvW3D;Iw5l@czC)}yoGhrmk8jTkZ| zSYP%cTlK|9a5vWw?N$5=d6VgEobQFM%zOfsTA^h9?tDCMkPLfI^AFiDuAEs(KR>PD zKdi1UH(=9NdkGC43h0MREmDpdP4=Juftmg!IPjn&K=1UO`S#p)PVgLn@A7}ihv64Ri|KoFY(+KA zTaHDyBi+#<_cY#q#){;ZT}Eus6K`R)!2nvk@jP^yKO*(hDd%>*5T<^T5GvimnCNL5 zXhNe%tmRO+#ly&38RVW`GEQ7x19?j-$g&-S(Zrt3ka&v~bKOeYJP@Y)zI!eH+Ug~N zP-vV&qSG;M5lZ2rv6P^v-p3ru9t#FFGe}rRD^{y7g^rc=#Ma3JM`o5mL`@MX`#BTo z7#xGS$drt5t-=z2-O=>!G=4|-H_^*wnvh#>E1t25ZWgG@4HCLkqmvaEHYWFli}>^cY}nwg)@*a%L7TQ zOy>jks$hAgq3kDimC*20ojEe-33#9XKu%d>_?BN;iix#;0g@<>}-6#$g)x z+5+&J>vwo1!vpT4Sp5ZL|j7+xo;mk~o*&EH?!j(lKC?u#9F0Ymn zK27UN^m&s5@)v7K$uJh33AREup~v~?#x!m_>7#sgH|f1-!|XkO47pjG@`>t?aOe+r zbiL_6-2NtS$hMhy39p>9kXxiOsPyTP7c0VWvAH#SB-l$><`K($-IWJFw$_s^d#<9} zv3Fr>>m!n?Me}}@=)5|yl5md`n84HS$YEJJZxW6~Nh4B`eVq*HJ^BkLo5nz}h|bl0 zw{hE~uaH?yeL(Tk(Rz*LP`W{1JXi1OtAMNiG#_}!FD|9zJJh$A5bmP^TKU`^{qsrZ zVat6{q16=VQr|{qSGHi!h%zqN{M*hQZPHKYeYekMRvTJ^#{Z1KVWEULluKs%{gJQu+w3v@P$`td0ypVyRT=ZvO3beAJV<7C_sHzu9`@*o4> zdPsA9HLGa1)IBUwod=s~SC@*JGK$pHg@LEGBzsLA4n6ddwkhP@0vboO}~nF_0L9k`$XcbW`m~~oTW2~oI)}t+gm{@r-{5%9E!Ak z-H{aCvwth}*G{Rp13OQr5NWE%cv51+CY|>Y{+PR=yKBY*a#j=1(ucMd!gyKgZ5ii= zr|c_-2fd}FHBKFcH@l%(Eopqqk#C}g0}G(;s+|~n4QFS94nuo+I-`;|oXdspNB@w> z9hXoO>i})8t|Ujd7#C5$z*|=t!6Nq{GxZ^$QCy8%q zr}Kx04rS!E)`NC}8!5P1g8h%$v-YupLf(_dOsRn%3{edsk38~lVcb{H+FC`TVqP$N zX->PItT}JwIt{m9=!5_Ji7rZA#0Q7FqmIex{DO87E+3W*DH8?>Hr6w^`&U=9w}v|i z5^oyN_#zj$cKs1)c$_U7ciWoDK>Dcl6qV-W{&^a1+CJvd`LY2qg3=3ZvPEuMQ6q zKJ|7aS~A7(m};Jiy~4Vs_Uagv`gC4-x~bO4-B_mN8>_RRY2&gff*DbF+qV{KV? znpd38E3Z-GZpvfzSvcWod54FB~yH8m4Tk zB6=aW@vn{oxZTiCM*dYnyU#BJiynQlF}@MYCVqzrh0SDVMkmL_7Q?X}Mdb5SJ*58P zIC?Vk2!Gxnk#j-rsQp+5Zxw!D)KESJJa_FN-LKm4sI0e8Mg0XKFcY7dSP1JBB?a3= zLnO0v3w(QMOa9KS$G=zBgGB2u@^@d&$$j<~G zFYa5z?ihAf=q)&aa?Z~Mqhi__MDv*!qFbE8U?i#{8!p_#BWJCHg2{Gbe~RL}JW!IQ z893o``1aT@5KVKvmOHLTM)NIDw7$8Re_obFy8t{(3CmhDn|$0*e|0*)(R?o+7WNcI zN;MGkuM6=4s<-dkV$D%_kOku`3H?lFQ82_j*ftI{(GI8HcZRAdK<7t0f?`dx| z+AR$H8$(G5pNFMSHbJj`39+?%&%`fuLs=&2yzpKUkKI;{(#^(*_lEHW2_R`t-{~oS z_;76ww0AYoJl;0u<5TL@8h45>d^Q4C7yp3zA2d_Q=L=_Qq{EJSxLgQ&^9F6XN3rNn zI=}TuCU;=pTK4RFSD|FMDSE7^1d$E@Vek4&0_}iqB0JqCV6(JRNY3sdT8ZlDi-9E? z{`Mr_a;=m5acvMgcgP??@%3eqO3g2Dm9Hh2&&Ja14SLSa(s}P;E0U)XL-uH+k5H>3 z0bM0Z@VHW+goR(lhhHCJ%lq5~vTOko+GnFx>yTKpXZ?+XVE;^lx|48cM-^-xUqzN& zp?f8XW9Z+k!@TKZ863FV4Ydc*cejDRc2HLUOnQ?-*3&6hy=YGc9n z+)N@Pv|+u7uW+lpn$&u@;#|FQc;)<^^f9y1sCUOu4Bf%`o7He0?&)_dFDipn$ zGaoiTup^dtYw*EA*|2q=l;FE7HhHRZCB)0f30%H6+H7PGSAYJ8&*7K8!2n-Figz+h ztsbD5>xkzY?&DIK3V7}QkxV_BjE5Pxp%d5A`8yFqn0>YD!11FSk*2(sQR!J$>2rv% zZg3RS9P0~bZikTm(|P#KzE+s>`!CsXnPdDsEzs@f=3@T2Y{xIy?omS={7&LsyWG&k z+yCKnkU({1`F$iJK$&xxx|+SS)=_Xnjp)E$7x+anU-MfYo^-AhqE7aZZ_F}g>d}=b zAzMexZ%8=i(w$chc~zT)lVaLo{zB^C`8XV{J?w@ag{SknKa}xs6=U{XiLY>8Ojy&@+_!ZYd6r27YUE3=wo|8{{N5T6Ew3CSD?(!pP=Klg&VYcC1WURgnhA0|{ zcZDz4mBV_8R$>(UlZ#C*fx%71NFJH?&hHotMs4XQFqRL(=CUnnja`t<)UYf%W%< z9Hk}bwZ0@AUi}|ddwWGebx*>U7t(`vxExK9#ZlV_V9F=z z)90eNN{ZFW$#g!f_GL1cd4s90K-PrwSnKUdR%f1_Fl5y>H001+cqwfp)_V*!%7QS; zSxq+a!GCrYgF1Bdr@)uZ1FkznX|1M!Ommtt2mb7=-2S1^R>ty>GHrn?h6WjbTe8^NBiTOp*s zUdvQ}@qs&h2yv0m!*$<3LxD#%d2r?hBj;p+bm((5wRRdlO7qal=^T6c!ErofqZ?|K z%oOhs8^W)_4cibB`!Ek*UAhwO?^!FJpO={Bz}DfpWXf&&Y?igcqoEb#<>KK;>b)yk zw>pFWA)|u7*oT7Jqf~PI9EXnws=}e%c_g5y4NuXm0jZW6GH%did_>d+hDR#sT)hO9 zO{e&fnZeJ=_u&#`Y4?H9MD(BPponJ|z$lEK`7I?l`H>W>GGee0^!pT}vB?32uQTKI zyMpjYiY=O{8T`?5HExiS63AN`ko%v)u=-*%_VWl2ffXW{i3-i|p;cOV{Vf3fbEEgB z;h|!@je6AtKb@P2o+e@9jyj=2_Ap=BJ{gm8SL9=wDc<)HAp)2aRpe0PE&M950Q~$U zgtiIO(P&`_9BD8RYwC7x{tgEc+DP`yUtIj~V(8^c$jmdF(BaRH=o{TeM4uh7UFwnCbld30!#1E{_f3&D7DK7RMy#%95bp%YAA>IS31bZIf|n7 zV~Xisql73urhOTukzjoJF}d57hiCMrT{HF$c%ofobyGj(JJ66p7 z&e4m9Q~s6YgtQ;tPd#_TG+RkTV+XV0r3m^&`efhDMy&Lp4LU~rAo+7YbLUSwP<_Z@ zVddWn6t}|_St)1o-|lB}X7ax1_PaD*!tSxi&QA%BpEDvR)9dllHVhWcO=M`!cwD=+ z7KT#3vE{iYI(^9mjMrO}gY`AI$+I6E$4CfOpDv1OsW#xPWG(Hdh(X`yxFY+q41U0M zMY2+j59+><#%p&kWb}TVgyEqfWahDayvE*?9evY7c=KyM8e*@Ge(Qo5Cru=i;gWL} zdFGRZcQsc+`6}8W^=&XxS9C;%A&2>SZPNINfh)Q+CX+Xe@z;J?xvw%(BFsZE;dQ{p@iY|Y!`~~fyb#ZCT)=5D~d|?|C$Di zXurUGuXE_ddRu6J>qd;{6yqh`U*O$l%7q?f7XAW!yM%1Y7=mrQm#i9g{TQ2aINg5~eK|f81OG6UMg? zxt%eLiMAzr6>802`lo~+75#<<)0>FJhqE|<3J3#YGx-}s5WYhFEcSJ2{Nt#;q<53A z!Gx9&^8QI4cHd*qPHb=&=B-I*PF!4x`XhAt-3XFgQHM@IRfW%Mpk7WztCCO8Djho=$6T^!D2bD<=%h2$%RGPCBW!bsow zq)4$H5586j=RQ}H*!GL~hR_NLGI-B{bKyB+>Dhu<|#a#U1 z4IwXJCS+6ufX&%Za`Rj+z7_rpM6>@8sR^0PkstQxiyQ6I`mTs~Ik}?P^;x{;2N2y= z_d&<$-q5Hp7Mp!}2{&peN0D_48x>NHvF5LMm)ESm1g=CHl8%dw`0&K8nLl6rx=(gV;o*+^Jb@t9PF=i$`%E~wff zQ>=@7B=3W^(eFIeOakwXmuK;OEkWnNS4Q!L1W0U~Mk*h+Ylg9TSapQC*E@9ndY=i}8y^(Gc3-@&G zNy)rg?0+y9X45<+?&uJ_?nw(AULzq4s2)Tnug%fUBx~NqCYd{bP@3J7{g0^kxG;_H zT+r*pO#a{Zy?DH<5Ar#Y&R@7RksFTpfxezQnW|QdRW!cB51K_EzuI4WiO)w+QLiS( z7GCJ&#t_g{d`xyt%)^SA_0V^yjBHSP&p6Q@&6c1{u`aGp*9T=&U&fE`#-i?w3Us|? zEO}D>1IO#f!E%}j(_89`cc$in^W+XvGW{o0zDxwong*o0wh{Lhw!zZAPLihjg}Xv* zS*ziPgcS?R(bi@cG+HK$FB_7@-M!(1X1S;H(_O5pj0exmhaHYyF+4by&EljZp}xbR{>xOGYhv({V^jZ$ubx$c!@QCJUk(oZMQ^TYe&PoidkZh_TMAlAozSEv2%CF*C_9;u%v`U z4_8AM|JtD~D-QF~Yb&|)#;zzQD2v~@tw?m`tPkz&rCzoaZ9L$U1`9V!3AQEC$qE^1 z5U~C?X}EqK{n=sznkw#M+_v)6MiQS9?|J?ncFQRR@45mK@0NrOQe4p2j7)wkJCxby z?~P2Tc75~4X?XdDDA*cHyGwezL^>zD;q&QGawRSo-#p#`WBchDj!0te=+n-NJ+}PU zyUKXNY}!X-S3~sP9>dIFSLCaaCC2LXB&jMNx-WFys$%Z{S%E%ZT+eS%5b!#^EclY2OGJH%m{+O;l2bxFJmkC3%7;e(nErt^8K zRie4SvS5hyUy@*7pE$j;3`Q-H5SE?WhGw;%h0o*M$>4{@cxqiYG%f8Xq5&Hwz1{{n ztv2H;$V1GIaYc_&mRRR}<(D@){49;1R5OARNzqOs4|fuOt{9)0YsxB_dkP1RMKYHx zs1Nk5w6HSbHaa#s08&XP*)}H^&vC7XHhTWETQGCg+zz$BIK;0$tccf~bw%nGS-i?T zRy2Y2Mh=mw{PDrD*h=Lk%=N4yvDUZn-y=CNlYX}g{YpqTc`gtP=zm}2JH!Y5OHJd)JutyP zC8A)(mO9eyuYxTMGhx?Zx(m=+i!?46!r}}&qTf@C_x(G;9<^{0ly1KeHN_Oc_7i2~ zp~4-M78n6<^Bb5D%&o5qii{<@0FLpe`ZDjT&p9Z;H%8_XbBh} zHcgy6cQ5ZHl)XwLPaP6*T{nHk?Ii?N&0**=-5u<2w&PtwhhSNSez=(MgY0gO;xj(FeO37j|W*O2$ABj@YqqMgBe zVa_dglHFH?AL)OAAKEm7f@1rV7P@1#|3&89zm29jK7zPIkBJwbix+>d2afim-7kF4 zEZFCQViL3Xf|wG-c4^%l&4cA$j$;@q3Lz*u#V z9q&4sO`Emh%5wwa8P$l7IJLuigDz5R_m%s7xe=W1R*>V;CMaIl1%(7=@k(l0+!N~2 z&`G1(o2Ox-`zk8nbblL>^=roWs7}v*R*RUsxWScyHPt7SFPV!bY}pOhw$PpFky`x4 zs0U713=o^y7etL;o8iT`Dzb5YB)Vnnf^I*}68lz|6JDr*o}b#6n#}pb$02)jD5=xR z#|018v3Yln3mO@U$YrdGt!vlwT z-Q2-g`lk!p`yiW7FS?;^Lcf18J^$>2a3-63Eu#b+j(#GeHznckM_tf?%q+g*;ZUY#x)*xmpUTG{pNf}I zkJ7pib;Q)XOZ4}>7o>j*C4p|axMb81*m6Tk_;B<+WBS$--E*?%V~?reukr2h@t>66h$8~M(7P3BeA&(3q_DyW2su$l^j%F*XWycvJ!>O*`Z z%mvxZ%;vX0oyq0pd!aN>8zet3re=lg zo~3y#m-E2%#2`T_OAqZR(1+%Dd$K9E7B4<~l1<;}CNvF=5KSK_guRDozQ@%&G-vW9 z{N$g|dqEzqXX$g4l+D+_n8U2t?unMVr}CwH{&8DwN5GSV^<>rMs|;s1fNokViE+N) zBQtyCkZimq@{f1m%L|9#i9NsJc6J+yiF(Ny&UZl#(b>G( zgzL;u8&7mEDU~lu5IFz+5ipN-raV8B#f;dZ4uK0c6Sb-aY;`6DJTq%Zl)EQ3rFy~@ zudB)E$I58@SxaQ?=fKA%Hgbl`24H0IZ({HHTqNS0QA<|>Z<+QEZ+G!TyXL0x=N7th zdyh~ro_9U@du|BQx{5$4*`Dm!T7&1QWW!L@P70)k;AE{lFv+bZUE%9c_6c*u7TAe1 zNZ${m9=+Hq^3cwfDLvgT6QJID+TG)WmcI>#hgpxwHt$^AJH8es)s~Us87WMu zwF}yLAcyZbHyBTA^+aQE8sFn+Bq9^bk#?5?Y2DO`(-hvqwdiV6tmcQ0F0O>RJyL=` z4auTYjW|WS4i>t!5}meOZqW8B(9tR(O@p?f4rLd#t0kMCJCMcwZSh1E z9M$+~g^7kfP=>9ix04Zd&A97W5~M$;eUyX7rdR&u1=@_FZD*fy!nK=q;L~R@&_`_o5MOwJ^?2`SQzWk&73$f z3eIevP2SFF$9=y(LI?Ge){S$;%0{%$ZWis_shWx2hS{Kz^N;WcZdPzGi*n%Sa{1x| zB_d~kFErr=-KUJz#u~K4s4=ac+<<$@(hCb9+)7G#NaxV8jh683nL9CiU4&)&KZ6|Q zLt5S-hWn?5{x%?f;No5UC8QVz-hU$Fek9^uZuI~4$l(Le4P(~K@+$cLQn1634A}Z1k0|-m8Gdao93AtWeElhh_{pxw%PN;Y@nkyI#GdHVx&N@;WLYp| z>_{gwx|8vcK~)gxFj!D(dCh!@Qi3jz1!VfnHr%UG1%prcZ`a@iy>52+GbNR(u>ReicCwg)yjo&>W&&UNB zKvuguvHw$qzg(?_zKhhn`s_B!ICl&1wlLD`pM$^1*1#T7Gx>RtW7h4oMx$B|@dq3y zVa>&^bcdVAr(f0)wfT6Wrwh_~kHxV#?!Ysc0M+Dt@l8BTE(=V@43Kj@N@%{{LO3+W znE3y0p!e%SnEAbp+?xM`Q&0E=Q>;oz{?QHS>RD^lH|YrfWnmo0Q2y}er#xQR8zkDG z;)%>2r}4pqcVj=}*Wf4JNz87lV|PcI&D->sNXM^58MT|>)(!`;c6y(C8Mr3?BC+2U zMN_0xB8 zzF9wMwv7}WJ>-mxm6F7B_)U=qdhjuoFAQ?wuH9i^g`oq{SY3lBnr6bd>Nb*dL=I1} z&x4-OT5>H&7v&DKKnD~Z`F#TBPIXJLdjkHF@n5enxijUVOMe$>SDZN1uzwil}wmTO`*3?4D zstV$C{yl?QH^b{aA!LW-N4zZ41KCnfS%0RXXx#em=)r|?WP(>GPFeW|f|(lfW|AMy zIZo#R8(AT|Q5LyNtcDULBcfl}h|MFb;OV($(sv@8^Q*3eo-L(B!*CngV0#`e7Nw9q z*96?X$rGK~p3WaJ3KOZRD8s))JBa1R796oX5$<$0(=O(5*eyE`?&x-r+*hi|a9}4W zuCyn|Q)=<`b$y^UR7%((ds$?1yb_!nOUR|i;YiXW7{1S>`DP{ix#{U1$dUTX{*S|f zH=IDRAe0^ubotJF|T_ za{fj2v1&)eI2`u$0Yt}9AMve7Q9`%}`f8rW&l&ZE8E$j~E>ayrxf6%uA`0Li_3iGH z>|uUnjs*9F+2VP-es(@Qb*LkGjxN|Om*ykgqP@vq=c5;stx<&D5q@-aId^N1Cu+A& z=P#M9#;9%xJNW!c;ePR-WOl0s^~Jc89_1pusN@3s{h_zeX4b$=`J#pDC$Rj}*1P!m z^CGA*_)I*xM2w6)kX&;rPyS57*0jsU{liLOor?~mao7{yxQCH|MY(v_>(6lQWHXr= z63J-VTcZ13PW&f3RcxHn3bhUOL|QnGqt;G^9ZHTwYeO|2b;<)JsHO2rIz372kNjrU z&x(NO&HlDorgDh*|Cuayalc}lZngRhc-}MamDc#ENhz%iYxMoup<#4 zt#5-Y=|+;TITA@(FM$h{9^}rO60B|MiEds@=O-A)Xg{$Cf;*|{*D}R4y{8$b;n#lERk$w#3(s`LOuTZ{l@U5BV-Q1RdFHj3KD-xskkqOod~D%W*5v#X z;qCogW;s^_^Ce`3s~>Koz+t!G+&~yH<#TWk^%?C{X(7GN9JABY3N_H)+y7(l4CzB? z>7P(O^b75|>wF4M6mKWS-^8!2a%exxAVGbyDq6p5AsBBrCgy`1@uz=ZU|(Ge(Q9kt z(nDyzacK$p>AwN#Q+>E$#9=-(_$@b>a>9b6uOMAyf^f43dYbtk-j*zV1HjWxz$dfu z=o6VB4E!Ta-MVOt{U%st7lFy>Dw6p;5N$Mg0Wssl z$(`t2JWb96ZKQr-CEtE-P@)lQZ%VxqI?6~z=^yfvRTk@?{T4olr8Viqt|9?z$9{yr zw3lt(ydLH$^$NW`e~j-oABLyYNNB$P8We=>Qx}5QIFKltHjpl zQ(zORBWkO?aQ1^bNZB+%mfJ2yi)rq$&*T5_cBaGtOnlc(CQN!E+MMKw>Xs()Qx+xQ zG^$4}?n>oXTDWkJ6b)F#Tb=^6hM`fqDscMBCL+_yyl`XVfQ%U*1dt zO7+keB?~ky+lj9{%X3mgCD=5(zeL;c3NtcvI9#8wTilrveBB*&BAQL1Jf0g_q6}Ai z^+@E}U_9$p5xm9otHrcja)~MwP=l=@N2r%NA6gaSlq--jh!RlDUEK$1|t*TN=Gxfv2PqcC6^D;%V-y#%XBn9aR(f*FD40LH+ySW7g*}y%(eI!cNaxWSvF15$Njz-bkVDefC1Rh1YPdJ6jhr%&Lw=Ji(Wa8a z{J}^myddZy9RAxyOueH;nrZIH#V3t#%z4a|?ed2%tyEGog2U%iMeNpQ2f^Fc6t&on zgmaE_$jJTexKSntuAHkOI*nIxa_JY)2`?wzvu7g52bL&v&kr!)w?sg|%+Y9l`wdJt9pqqGm=rLn7wGi|6 zKOA;GQwSYCpUF|`E4)hm0-iJ{VO{(btb1n&`+lF6aP6fIv$4nnK2l8hKMs#F{s`OG z(sZ)3FBwU7n&VyJ%m?SF;-0KVnCe?g=Gi)7^Sx8R{EQ=sSFOfB1KiQ%jns=#-kk)A zzt~BfT1wt?no|;a38Wmu$kW%kxJS~K)wA*z;&x^-iO&1bkH!wX`6m#RjG&uEMlPK(H!#1Yn;CsJOtm`PXD1&21iio6z23q^(25=*4$@BUkJT=iB z4WYBN#qaN;%7`3DGnW)Pom&$ZRTqHVy2( zidLxk+Yx^6z(ag#P9R*k)=E~~ML1`Y2bwRF&d*7eXEyq5f+#l+GA*|V+pt&J9dY5p znOk|x9+^Vu+)Xtboj!DzcoUk?WAfTL2PcPC12?jb+&PLF>))1W*6SmDqTeKZJun1z zSx|56S6gP!0#oD{7$(MK{}thoa)atNjc(%Jg*h(r}|xZ z!I?;K^rTs5k7nSxnmO=?mlQ13HlcOjHo`=aqc~e>dF=(Zd!w)LjCn0GDEQa3V?XO?Fh*J;aXw&N2Pm)7^&brN!RD@C(X_`}-H&e55S)4DQN*3i~56 zi2BO}{7I8~xT0vjbhH#&s9=rQ1tBI4kk3Rv2caS+tUUI=@ZphC%jh`STa6?xr zL($Gnq{F`gi_Q|rpxldGt|vb1dW?N~%Uw9Iokvm=sV;ZHasFvZGpCW!4YH5Bh(}wv zXu>K-v{)yZpH+~6KfG{58|>+9Mlm@~-H2T;=_8EZ8;)2hWw75*GuYQq|I6YJP%YU) z?E0l~75z>6*4L3gzt^FtEi{Wh{um##hj2Du{aCxDzQU#9-(g;F z33+^B3(}r`7V-yuAV&EDc8POGl7G^9c0`z{$(QaK-|Qk+Lt62gQ3;^?xRnG98IKc~1}J1m!V5bNmLl4`)Xx`UiMZ9{*F3MgIion)?libzBt%$(IhhF;&v zjo#&s=Gvt5KFc(jTbJ!&y+Rn-Ix-L6iDlT6-<*X=$%!aFY&vS7f5iL2ZP?H|4mt*M zh!dUP`qZnTX=OVZcR~&w^0P!^T95L#4-dwQPXl22zZRky|4d|~=Z@CwqR%Fsjjw#T z4$`%$L|DS%$2WD@(F$jTBYP~-but1@70n@YR<~pQ*c@0@Tu185u3__|HNd!cknvL& zp~70KAqR8*-Kq-C{+v5vLg+i|)hc{#J%+yXl7iRyh~!N5)vVWMdn!xsLa9whV9b0E zvg}bIUj4lcj!X2AYI!}zwQwbR7Pp3IX!~;HrEo(esG-sWicJ=4Q>S6!*zsp zcEVc@PKNwEM{=OO3M)jqp>U@(Ug30ilDync_EEN4$}{8pFk#Lm_}LvsvjuXoN{$(u zV&o?5IYl!MPwYXDZBFp&Y0dbAT`FYtI{@ozj1M7x96Ph2A@LiOjrNw@_X)EME*qQV)>?5qN z>m?gY^wB(-lkj++C)seR7}snlg#OfOqUyDoiJNbQ9=MzH3V}gb?-bQfzG)#duQ0fl zdSOiT()ppm@=W$-JrLe_ko;>!Sfk66l@nrxKVhXzUT7{%HTXl64XJO&=LT5aeM}OV z99*YV1z5F>D1GLb1>0#4*Q=xa_^3&E!>LE$8Q4!e&)71folQ}c+!J1o_~VDNPoSCV zVDJ3Cfn#O!K#uBF!q%#xGPwm%KHy#QJ}T1fYhR&G^i0mRQPCs)62L_NtC zNNJ8azq;`)H}2&!_Q*wFVOa2PwFwiV8$ zzC)6x8{oq-N0RPHHLeTGz~e*@@wA*GGG12zDX!ni#P(ar;Mg@9QJJxdn4|E~cnaCuGs*4b1Z;4l4C?!O$eN+j=$5Y) zdUW6vFSlzrzVWmZ%r$?ItGzEcc_Vt>rce**a)EpQNryEa?JA7iV}<6}(%zPwO++|e zf#>W^g8gw-q~fI;K8nhq@J$cdE-@c{m~4rbww~Y(xEAhZXE#*1{2_OPo{F3s>=Cu# zim_T4=7ttXr}MUFT(|?%4cRHXeFW_t;mFom34&Gh$$V!XKRulSdmc0s%LCGQUqcx@ z&*>#Mq<5m89Tw=&@e};g2?D1uyC3F^rhAaLml?GWLqWxDH}U_~jPqsPkm*1gfA-Hf zZdTw9*azqq{0eSwm67niBLlYCKVU)QJa=jE4MkRV3}JH@-CG z8~B6{5}f)Z(9WWj5IlUdn7d$1zSEw9W@3Odxuol~gEhE_1Ya~lW6DlLmCFZ0Y6NWb zgKFltXYk9qLq%Qhra{x}-Q?S~R$LMp50h@Ul3M}e@QKAapt0=_ITWsnbh5U=#1IGK z{jUZuuc`s>#7-h}*;Zupv>a4pz7t)Er$|@L4ZWF@&R6;^U}pZbrROS)WWCD8s~T3Z z4T%oI+Lz;ybC)XmVyPp>WPI{1IIPMgz1<18IHD8mBPE2GEo0CJ-U1nO=3-1f)^iWq zf@l`O?;&!-eznA z{zuYv_*41)@r-Eq)zF?=DwT|s+~<6rv_ur`y-QYRLq*CSQASo86hc!O-SeEMfonxZ zi0r+}*7}{_?H}-Z-22@3`JDIXJ>0;qIFei$nS(vveS&9{JJLED$JkF%gmfbna-ovW z14i|bu%nJJm(EdL=u{YU+KR0DRgE9~bU~Ne{$aJc(RX%N$^3V3`$E9j#R2f{NbxM~ z>35V(_i*Kl*7A(A)_x>tIWOikqHI6FmNR+e+^uB%XJjYbmh2$qyX26*gfh%O^bf0l ztfXGZ*VH>O=b2XYmr(Hgm_c^2Z}HI9a?leFbCE6O-#o}^swZFftPphWR+F9#1Lp8OZPb^xj+#K{}63Jo*~9)e$W}Q_QQY+15J~DA~HL}i0WL>foz(AZ2c4mJ4eESYc=FAe+#F~ zTg8qKIm?%u`Jpp;%V198c2eQeh(}rGLCfn_ve&0on8oLVvC}sq->QRp=-g1Shjw_; zonVk=C`=sIOZ0V8m~ZK>Xw9??@hojQ@d;GYj*?MF6mazSHSEhP7QFm~6l58{2?DFn zk%mjXgNCW!rDNPrUsd@04l#}vx{^;Jn8?cJ;KsO(Y}o2BzO+CBj7Gbn ztFr0hxq4sq26iycm4EehDzaAjiS%#JA=(EzaZ=19$_a=_)Zt|8zpxCZJ?kTfUP~eO zMeE>F-&SJqz7g+k_zsn2o#bg?tnfU=z3M;z=IVKx>)AOTE_|Sz3GzBM3&zUn5t)0H zxO5_hP@1pHym!ZAtxG|zzL&&yEI~QNM_|M?b0YGp#Z8faV6W$I@-+B~pf%kBy&H?U zReTCAqWckPrF8C-wzE)JI}>bc^k@$eXd#Dd*vN}4LW+%nme4Bj*8*%Dr+xUoz#L=!d;M7T{@S#NnSWIXeNwz&?A-$Bd}L# zF+@s9@#_)-wFVxS!F=gKlA#ia^!|hbL_Z?BcG-B($hJ$iR|Kt^u< zg#Vw-FzGPn+_2ZD)d zGvI{HUfP-7hLwF@!t<=go0cC#`thS--tT`{{oX1YbiOpvzv+xm z?JI#(vm1#zzZj_`8l&7DXSrSBRl>XPXm`vfUw)6;9pvcbikdY<+zy?!xczk;B)fEy zQ4{aJeP((Bnve(CHk#g}r+$TvHwH=luq{l=paydCT+h9`AA%E47ee7cAvt;{84ui3 zXGgZ&{i6`k(E2)( zScX#0MCv5#7vjNh8v2o8pYB5zqb_o9b6WAUBkv(EDUWyvlJSJTZio)+A>WE7pnX$T zKtYNJ>77xA=c~D*qW2lxZvLs(beT}_Tp}WaGv4CmeMeah-i;SsSdAo~Ooz1XD~T1& zcbzc4654e;$cZv1Jh8S3<~lVKsa|yy6MGZZ1lEymwY&JmOBduzHPsFiz6s7pWWbSo zlKidKmXre@a^TgFpTwTiMXA0v@SgJ!@AX=wXs(5KE%{NkjhP>`4lSIa%|+23!`)Z> z=?=7wOr65ueWtEx+GG*ut}%vr5jKYH&eY(ilpkd_6lQ>$WDoIYT+lG&2a|212sI4g z-l`vP<(UM3@k$P}%ZO%8bQyD7xv4ZuAsigf(>%tLCQS8Dd-QR2Dt9k95-+S%X9J|o zc#kc&(2QawSlw<&&*Da0^E?-3pK2q*39Z6J9hxC;T}c)t>L3^6Gl)o^SziR5OMA$wd_|Poc^GzHK1XIyKicAv zKVj*x-{ih(tl*HP1)8GDaUJ%lxH8`vU7&uw|L^Zk3T~qRsP}ERc8ef>U=6(dZbcTw z*5JgM?_tx^4&vG>gGc*if!C>KV)ASgI$P@qpB{RU*2g9IuF`PO(%(nMrng{Qs^glp zJ41}CTZi66wz=tCS=V?*vfGs1b=sGoRl88|Lpcjf2b##7NmM7O5elb&JR)bysJozfsTtg$ z+XF$+v_$9%Y$N}Dnt<2SY?+05GQ6zO3Y2-w5UN*MlF`d*aqWMVphmffvK40qQ>4Fw zvs?v+e;jbUhj?e_{a6Dz+}OaWwuIouD+O@qViBo3n~Y zJr}2EaNb8|;43vg$bjbNr3B|`m4GYsI7gAKZ?kds!XlV|tcN@j(A;>XMZjgNl19BY zd_SlTI#V0Sq5YP)@x^42oMTN?5~}f>Q!Xf0TEtyx9Y_s2coX$($>4q;TFV%OT!GD# zqKLj{4(_12>nAMT`3c4Em<#TEk;j>f;`#RDwRfPiBA-m1kc{81r~+r58ZvIva5R6{ za`?5#lguzG!~2K3qQqViS9SWCR=4d<)MA>!F>7;}jXOd>BU(gSCcVWM;TT&};m)_( zu0f|KOb6HEf4FKsn{t@5>qy(1OZazYD_oZ7AjeBrBkPwwU?!|1+kS=PJ#H@O%_bL2aV z+WCLD+DFgU%46+h%v}cGo=)$Z<1@LEz%h&?^#T3rO6T4mpN@<0XqM^J5YM{LUZsKY z_-^v+fHRT^^M%7DQRGr<7T&k83)q*`yK0lmM9}@as z?*c-TQ#iNP5Al*#ZxppQox7&uDAbWqXBSXj#gVy%Y^NxJmYb0nZ#DIEVfFoXV(;H7 zWHz=#V+_^YJ~~BnzRw_9vd+yUZ-nEhZ}GK5|}ms$iqA8p3{f-q#^@O67nqQp0Z66M~Ks_=GMclVR zXJG>6{m+ZixjS2$1*mj2xM^7v-<>tMY7?PZzHLOyV<k!|7c5y75en z)ef))Pm*?_1Yh|fg6la0 z0iLfE2ZpbmfUSd`dRdTK^(y5%W;B&UQE%V@bRkYjEH#8+J;^b-w?g1XJBm z3O!dUNY1<{bht1GY6ZRIjlzE6$c@wkvOkm4R8VG2-Mx{F27Tuh2Zcd&=T(re%KuqV z!AzVo7kN5w4l7>=O_sIyOi`ecF+!V z5wMy~L_YimZmp;U534TX-=mCP|E1?ektsKLsan`(zq=XKWWLo zkB8*gI&waGDr`x0fh*%5k#_~z`0LLvF#gyeiQSdRJhWK|U$>}{hs)Y<-TWH3^{t+$ zL|9;h^ht2o%bGa*S7T4=JG&Po;+BjVOkGcVp(L-TaRR{_=HX|1h?^ZnmQijb>Bdnu z;*1BsJ@P%XKV}cISb9l}^RY*HIA@tpf?g)!jVCJM=UVCzv&a#y7cPdM*_ zZbW5@{VWn|y-@`{Pm@MwF=l6iVM42ju!X7kVz@SIC2h$!NY6!ou1o_-a}}{pBc3e) zpR78f7oUTHpAXPsBm}4{pwl^oG zV`vV12&C=Pul3MuH!C>k^bhAF0^8t8=n#JMYh%W50*j2-t>+ruZeVr0+n}q~L9D(q zc#4M$n(;1^8+bd0SxLN6&-HY!C}tX7YncE6H|t4v#wg}aZ#wKf&_~XQTu|SyoA7Px zBeJ_Z3)fGk@8s?w{IM~aOmYIv2y!#yw8l)w`Evsy^;#EsvFjM4^ZYzYZcpY~emub5 z)Su`@HObRc9E4Y?_hiP;I--?38fjE5g`b&5q_(sXTPNkvdwM&0%ut+f&WD&?wWMsj z9{Ni6Wr-c8oc{JCq02`VHtX|E{=@ivXu~BJWEh*t9a*#w2W|I4QrBqz$h2X?`Lh$? z)x3J55T=YqhOY-1#)@?6)L_LKMYKzzkE}X6MR0okXV{lqOBUJ(A>;BW_omYoMCUY!SE2{I8Ii>W!?Z)+^Zlu%P~BA2NRT59fC;j0DronIxt@ z3412yz+cyP5^wyI*(wb%r_VslX~e$z0r5|J$)D~xp?aPNn!2Hi%UK%6EbDegT9wpy zM*S>bsJ~LzFr8~&6elp$mi{#%Ugy)&KB`9+yx56ejzZ^RGK{Fe46!OOoIpjq<|+kfeEaOq4t zVJ(N^?9rJ}(BDF2@-`t2c}HMVJ&8+K36@urWEZU;%9CBLjKW1(c>8-Fskq#Nj~;VI zGj3*zwapn+CwFfi&CN?5$JCrRg0P5x*uLgW28??)K%VdL(aPE?g0iVCglqOhcRvTi z#;nJruQm&hAKnZ1@_&+VXNs93EgdLQc}Q+8`-H>Iol)fdOtFV0r`ii0Pow_L(Ghq{ z%M(bhs}=Lot9qzrZ>lUmrCAy^zE=nNlSbmbAxiiPTkdp{D{HcZiF3pJ#s@Irr^(l|w@U3i;iJnU?#CvVEfVv)gT(D)_EOYd2X zK5p9vpOF>G`A~zcj4rSHsCw)+?|Ri!*4bin%z8 zc~{HsqjIyC+{7_kq#9w;K_BiTgoym7^~bxY?0U7Pu#2@78WG zP8cKuhvd(tFH~f4Lzw4Ub9!j!j$In3te(l7@Vo;~kV(=Wrec!~ zN7)gqCqHYQCd&Cd752BOhPsK3#UR%@%EpOcCR}RE8(|v5d|(E)GK0Jr2&~)RToTMk58+CGhRR4s!Ha zBi5Xm4KM9F=zgI^=p~{V<3}vGsY{cEi+}nT zdf;K4tT5(g9Gq^gCxgby=VD-f#%T6{L2##3Fe4;&_-VcqN&q~bKgIJ;WM*{ zgfIykIcL!hcdFTT9%LSdFi`Y&8_^AI#7A4(q5N|X`DO4#XsGRueA=tHLo#7Z>0)P; zZ=S{1{#+=?*iGUtHe_cZ6U}+`41Nz+lSNpZ=m^?vN*2>7h%4JCwfA& z6q=_s3jV8H1zAgN$bdu*ZX5mPS7EP?)O zP=m%ABe8F#a&9@;XZ#>trrE;ht_6@eri|zrZbd4-R&Y!|jV$%#aoS#I^!mSS?vs3^ zAl<L@?OjrQrO{%vPQd`y1X&SAQiV?U;-Jf^fy{eaz<6I731^lrBV1YswhTyzg*5-?Q^F1G zqnitRgKEeP+AlLmd6@h*3ofXlMi@*c|^zs|HhL=K!(qGc``VDh$ z{sQ=UMx98^YQvis(0#OQ1LlpfTJg+F95@<&CKq**aC1dB%s57W`&IHt{lroj zG0y8B_i~-?LyK~_ah@-Ty*}5PYRgp=05>xTxZid|!XU;G1nuXF=P6abN zRWVkF+{_1{zOzs6m++#{a_~D-OJ-#+N5emRLdp4hQfNazAIhC>*UjN}6;})FGUK2o zrGdN}pPQmSH3vdshwxYY^$~VH2lYF=$k@gbToIcO%XJ%wOyV|1elJ3Suz@?Pdjl7& z@P*akZREjwEv!qQIgdWGy5@h(9*QAn>}W?b#p*+=;^D)VM&dJNG*cU$PWwA(j_!L` zwBOMO;=3M^g0orpd(&q)8Qn-^Dif(!lxiXNS#r)7XW;K{0U*5BN48a+V8*A}poLdc zx$)Z`V&hH^lx$1S-xChP(wFM2`v+^@ugV|AXe@!Q^qpdlx%JU3$k*#66;oSe z$CVnfCd5G57-e0wF7Ag46DyK6v=)ET8h~?)CHM+54YoEAHFB&4+HD!2&O${T)8{?&yse5NjC^qi_}5mnhiOhRE>XBq{0NM z)r?Y=#^VigVA0Yp5}BxnX69W5_p@GNj^)LZZfNZKO`2sK8Snm~aO&57^2)OXU+@d2 zI)OG~_GvlJ)AT?~=$U@6Mve)bxELX4XV}+lE$yzT3bTO;Q3hzK7k5D zr<>gY?FZ2$J0uJ54yb`At6GWSi*)8tC&DjyY-Qfrd|` zJI&N^{OnRR6yL8Qv$lKU!&EOcVZJo~V50;Yr=kX4emlfGxoB4zoO1dh=E+A`l|pn% zHF;lXgl5dMgvOU?VsFbVC+cN5M0ugEop|ZqS5S4Ui|{?vSGXe!JTDF5^{Mt)vw16& zR#}mnAvO4Lsso#{!<*Mt8P4P#E}_|pRpjmaC{(T(05hNWkr3(q!kx1`5c`Sx>+}1B zXMc}i<>S}zogOvJpI5VxLCGfZyuD=dGpJ4ZM7+wA@S>v?@aJ0(iBlMkHs+l{@(Grl z2`h_za=k&|+d?FkLfBm8Lnp71wdxkaAeM zr<;^Dtw09qXHoPVYp!Hwz0l_6W_I_!C|;)H33_NZ8$M^+5(}jo+}P`mRtBVTD^6TX z-SguRBz*ED6D+>qnQP72fnT2d*LhXU$xp6GT|1C#@^7a7XrJKXt}kRKeb0X#SjkpS zyTzv+e1|L+X~45EFVa(4O0#G@kbO1voTlYyJ9_x>T{ZoOvq zU7HV!|NO&Y%Xi=4F+=er*c=C{PlUqRw&M9&eQX$v^8QX_MokdjcJx384y1FZqE|B$ zH7fuzf0!Nhoj&K>4@}R{UC7kpvY03F^2Feg{+T3CO~P8Id%!#K53%DX zp`Hy(ppEq+qD5sm=t3xTP~GfQ(@%o*W_OfMd6?eyB1XA85CSJ<5iPS+y!^fnoB#O= zzjm=AT5CTA7B#Ap{E6*YI^h!>O0FlSa1rNTEQA%e%1M5&B3k*ugZ4JolT4*>{HkI& z`*-PTK6=Fb)Y^(1>LsT-;q}|lU26-N_sWYj7L;JGdj;@#QVY?%XvCbgXOIrwAfA~6 zM&1P1;5HJlR|^lzU&9tf`|y|R(@?aR2TC+c=en(@V$1(VuvzA-`I3agjBTYiEI;*_ zJlmgzl^zvBi$*J%E1$$z<{Kl)WGn7Y;SBurkU!i#-b=aQD))EJLwt&M z?I}y7b9q0n3Y|8ovqK83`O9hkD0S0ZNS&xlG_A_9PKgLQmLQiaVZ?BD|7x3sybpA`UZOGcmqn!6Ros;rm*!fOa;iv{63fxUA4-y&)S? z<;7cUC_!BZ=RzFq)F@YZi$~B*xf{c1Z^%4(f$(Dv+z78FO+5i6ktF3B)o1>6N9!oBe*Vir0p8S&7LJ}L=DjyQxDUZDSw!!A z66RJG0^aXD^y1tVXo&J6Ff?)d67%?XM{rC#wI_k-A?{~~m%?;q5@sRihQE!Ns zI|{c?=Mo-;q@Juo?MdKje6oN;2rJnPPXH5mBVUQ0{iePCr=_>>XG#Hp!wBdJF$c9OE|u$ zn}oH=W8#_#PwQ!JmDU2ZEmRN2$yt*Nj@9_Cn*;l8h7Z5_#&D+d`4`x9rJC$5jY4A# z{9qe&k%Qs8gado1?@~FPoA|6xIJti-ds)(xuUxel$t|3Pb_Q$~Yd`WQKc!yLJfiQP zgx^Pgf*A&l6niC*K=#x$mr%Cr3Mbv}r^!^LE zw>AkM4q3sv=lbz_H+i(|@G5AT>`nfkFS-@n(UZ|sCuW_al|KCj+z)xF z8!JeI(ayJnm64B#7oSbNQRi6w>>xg1ZXuH}Y6rSoXU`p6*Mjc|g)sd{0m&JWgbT{6 zA#WztOXQ3~zg8>;!9_2zMtU6z0@WUx?OB&8Ap70XaW&edeo4fvn;!^^u4Iu;{Zt&G zpu;*zJMi1CDk3fEDZt-X6Z=_?-pK`>`3*$WasmH2T@5cDwi2UeRTTT$9qvce6I>UD z-$-h(6#?G7^n_4UK{IdX&%MDXyf8`inv)FyO%lAdsR7bcGKcVPFY?Wo<{`ZP1_qM` z$PAOijI&69rWkJ&WAZ@*ANZ-=PR847;pN_%?0-9bd6N$rXlJQAn%43UlaB?BU^hEy z^2T9D8GW*rT{O|0uS=JJ%6Z=KDfuyZy)X-pmB|C6lt!{U?G>YU_$=b2Y&o0snOJp? zKg^?Dkk4M9WI{Grp%m-4T-fP{c)zSWihG{U8JAoYW^bDfol?5Q{@_J z#b=~YiG>!t9APBhIU1YPz@x5qVxAW%WE331?qCKvQjM|qJ~xDZq;WU%Vgx@=&w=I9 z`^Yn43(j+X1r~_*v~F|720JU@zeH*N_-$2GIBGALF0dvG*4N-8HwPg#PKs9vju)Kw z52ByjU+(wKKAfU@3*74J$c1--xQS}=mp%E1w^Kf-g2F*tBHCSzJw7Kvl^n&)HBxvD z^#GXKUbw}O zfYVuc^@<9R``Sdl9Qwd0WoX0GYB~dN&c!l?!EiO_JCQfGVf548kX3m)7vUF9b4?$C zKGh~YQ1ryiOBEPfxKlj$w$>Fx@Pr>kw^1bgSoaw;WxtWQUVU_afjQJ1NhcTf^LUQF z21{Cect6FHXej4~4(8GM>iABqHHz*meA|iMB4~kYckKU z8p}N@1??q0M7qRSu)`o9uF$^M9GCmZ(Zdh=Z}pH7tM>?}-r2~G{2Ibbtd@atM>j<1 z{m#j(PdF|?pIz$g#m@>~f?T%FLT}b?;i?KcF=LnjtwDK2nR1@xK^1T#aDY76H3H>g z>OYxa$4O-l!{_Eu9hd8Oav(ZdU{!b*mW2lJw46jW zci`qVvFw;nvBrgudw+v6P+2h^#OJOCE{$+QZ4ank$R|fj>EU(gSQSmw0|&Jn>36blm78 zbwei!ho-tBqn%V2oxh6lxoQhr1|E_1_p`Bz#5vYDlQ88q)_bD&Qx#$OGcS_UP>N%Jgu=<`J;cxGv!He>?S5LC&eil} zFngB=z?_6EvPdEoPnoX8u4d2iT^nYh&$^Rg!#H&@U-6?Z7uHX2B74|NII*M&j?C>P z=^mQsSb-bJ57d*C>@e)OO~4KfyUoAZdLOAw*Jc+!xWU)`GD#gPSj%=(&ClAI9NIM0 z43sx`lbdI$52dCYM4A0W&gKx~ktRSxvp0z~c!ieU5SB>0+bp#3gx)o5>u+CPX^jYt zUhR%PInvBwx2br^gFUS0*4upZhv$saJr}lCHjaP3OB3c^@dC0Snn=lI;blw9A@oll zxi*yDpAkBJ>8I7~a%XWWBT4`q3sO&6KQ&6a5LI3f2e@FDg~bVZ9*ssHrB6=9N- zK09idH-F~t6Qq7{7JQ*IZN%>~?Bn(UUM*@PvJwr#Nd~2GE5C=_RNRBoV~o-2VdpvR zTW^KM`4O6T4bQKzdR($yl0%`!|<^W4koJ z?A>rw+OQV>mKl*>6^*!g&Y>KNtv_Z$e#VAyRii`LtjG`*Gx{zxZ`~9a@sXKlz$biir!D(13t+V!xd`q z2lGLgaao%GIV(ZXJ~{}s9~?sV%J<_nTm7J6aXtC(ZXljcpZ_ey!2k0Y_LVA7`PG)( zMb)@1APLqVZzmtZrEqY1F%*gHP&db$SSNnLeb$8#zqp!w_B+OWF_nUA z%?F5tJe{c?1c2MGR`O!nGW?k8gpX4$QMc|t=HxbgdS~<|Yg9_G%B3~z6*qG}_P(s3 zHLDP|MGxVX{syA=X9J@E5Ih>&j4?>-H`S4x;8`*P9AFb~)1?`%D^K*Fs?XurZb)GlhGfx*%pZnnqZi3@Z{7f+p zBxy#j!qRcrYp5oxrfI=%qg`n^kGH^xnKtD3ifWwP@fF@58z941m9~1h88OWnqJ^FVz>su{&gIP92MVAos>^C^cIRaX4(C4gNiJJV> z;M8Yt!t0dbSQqMDvZ1qIW46|o5!c~(NVJ%9zFk@lzZ{41L&wmJ&BqF$n5rSxgsjM| z0Ne4cWZu$qSRrH_d~pAV=YnUUG$*H*^iPx*{tjQzC# z4rs0UK^C6+BA!i%B6Skv-c=WCLSBsd z1anK9iP~{{Je?_oyWgwG^1Dk=O^GY0jB6lUe8O<6sV3`ec8k}Fi$F7**0ICPo%u)k zrm3N)wAcb2E8cWAkDMb+pzee>(U2^`ji0~50qp@2uW^XEcSj37uh}H#pJj;`*zf5e zr~I_Aug@yhiTa5y_@|*VWj9o5p22OOI~8{i-^2Q~-{zery6@jmCA@j%RoV8HF-@vUvYmTV0nuypBj3Rskv&2`mm5YJ~|R_ zUg3uPs2=kF9EfSdR#tt`i`P2!1nt`}3nm2Wl0nt4IHKwUU`0Cr;|AePnx&jVyOaEG z>7iHOZ_pfgFS<|sg1hP>K)*6Y8uNqXh60_vV_Z?`W9rMJT=bK4efHyR zZ{GU(7u0=%_JUzuLN(ZUqo!>#g2@^xAc&QWzkYStN?qro9T&W!I!mG;VQwdlmNy6?g!+iX&j z`v%(-RzS~W8U9Jd2vicd7JRFW#2W0sG#A39zm4YFJrtg$+})Tz&D_C;dyM;12MB$b zLAE`@xRdtPRc%V=Y#+o3x_8cov{CyBoNvLeE+sMNszphv6=N3g9JML*BF=V0F`b z=7;)x13+IfmZ-L7;;!Lk@ZnVxS^euB6XnZ-+U-d4Yg;aMkGcz;(|(h}k5`%bDz2#a zQU+&h7><>uN5Tf}S~8&Hfz92tScTO#JT^2%+fJ?oRc5!?|B`v;GpHDLlBm_`!ZPzb z7-sj4oEWZ;{G3ccV?zdMw&3yRh!D7y+)LtUhu4rGSEMK>;>?nF;xf4>U{}*d=61>9 z@Q15d**m8EiC=-J{(%nY-m@WNCF$q9w-kca`^l3XCW4Yu?rv1+M)v6VL-fBi1&s&<1lRB)kwTfUBjV)*|3Iw&hzFiL{fiFK-38v zaz?Kfx9*@lbftD={(Q=VJ$FGlZ~x)8=hK-m+dz-VO$x;;yN|Ie7P<3}CY3TbY4+)1 z<2&3f$rc=aB?~4imy*8^-{2!VRiUrTn>-&(a+JkB}i@%eO&|Jaz1GFbDDT5mkAYzWwoY+b( zn`{`JisSFGtly_gyu!ixX#B28u-|eOiF(|Qjc5i@?X@Pcu0tiD1ZF8Vl1cBEqXq3Q zki55nJTVQ!R{g51g|!cF^fv^J4UGdE=}xll{pXZ`G<9~&B@^CcSt^p#J`3>y-elO5 zFSzjRSGaR?kk~#u#HhDuq1O*|xJqef>^0d7?B;iptXwU8jFFpPF1xH>mJGXhl--$8Aa(EV==hy@Tucdhd^K2%1|1vNhv4(`^wPAMc zIW$(8;}$=U#Os&1qFtu6!(z6BaLJvS(6(qRDR2CWKd$`%XI6BQ^pHm3gX7s?_LC*&Bt7ZlYSz%`#JBB7Lnqi47xB?l4b?0HCF z@Vy;HOk5z=X-vNp4!^hNknHDgaM;sAIHxMfODW2rQ97D%QFf;oV`avFgNNE3#K8Qa zu-L{OJzCnvb!Xpa)=6D~eIX+9EC=I#8nk0fkRhI#(ZQ!s;#f!gsmEcuPy|aB^%0Gv z1<0^;C+rThA)kG!ssD&-eP2598eL17xoiNEtp7JB+nU^jMqE$U?hM4o={tXEH}xgm zZ4m7Hl?WcT?c`#YBvv=ffexBKpFV6m8X9;3W|eyrhbvz&(^3G=A8X0w=f{}{ECKIA z4w6Tu&3Mrge|T)vPJ9fP;dwJ%km3pIeNd5O`eaA5^%<*p1L<6?OI`U;@{VTC2m;Z% z8h_{th$Wplnb?7L*+guV;8)E2!pxWiu>N5r!2>z?>$d($xrJ!ZW0*dQc*b~7BPwIR88s<4W} z7qB<$BNY|Kf=vHUU^%mrtmwawGT-^aQTai#@!LM(cg6K=rehfI%gX?vzVGqvBJN;H zztDBkO|&qc>T2B237qR^q66dgxnR>S{N48n+<%f!hBdvx-qD}n{kL|qL{$peE?ZCg zf(^;u9gXS|&7=#>ECNWj+l??mka^ zCRgJ$H5YV@dcB)wUQ4~Uj6QP?^=h5lz%<+Lg@b#%N%YrZjEs)5Ul+LZ0X8Mf9PEsO zAy_;E8{WR^^Lo%5m=|1Q+6c3hW`1^o7ABE9J%j;Ee|#lw>PxA)p8w84cvRv|{4BrV zGIcX{6}>CTzW%`!t7)O>dRxR;Iz-VElFoM$gLp0c;y-ov&pBUSRWThM+vJL#&&lN4 zpHIbk2X3N~|51O3Pp4Mb3lGTjj3HGLSvX?-7pV2`Bi6$(bG2Ft0t?p=!!hkREyoW= zt^7>}6;CtLqG#w19z%ZL>A~{!j#F!vN%v3=!a3bO$jmB(3;pv$AY8W);)m=b+eS9y z+NJNoGMMVAb~g&m7to!{y(Z%Bpo@&RU#DGu-elLxFL+RTJ*(6g&8OMhqg|s%!h|D- z$mzE&_)nuV%3UB5Yvjg1^FenOWpMVNCoztzwBSXd9hsz1js2~Tv7Ig+{POz8g0RFE z@C}gVC-x*D(dh_CRf!{i>ND}j`+Dr&^UwI!fiW=ETpwn~N0HKR*|@~h1^r&0$$6w7 z5**m?gZkd5a}M8b;>fHpIK<}=zmPZh!_8tix>=fk+AND^*sOsD|D9sJT+o7VFmBj) z0@EXfKP=o(nPD5Z_4a)xEXy8Nsb`XLy%<~49)WP$l~cJdRuHe|gYdm{u3*^?-1_P% zDBo=$!SXKn>aQX&8G3sXw7~vcjBK0FJ+=G`J*@566EEU zemv{C4^+xGkoGl!m}6bgVg;I$|Eoc;+`Fv8!;jVIu4@>L5YmrSQp&YzQCv zn;0G4j+E@qL;Y$Wa^vV1Jmq^482L4lptq+O)y5&9)OC;yrZ(ftqo|htSUb`Dt%UCt z(T);&PIW$(W1d)eBdwA&PRe)^F8KZx4i(7q9rAY(sQN>b)Dsf>EEB&}X@WgQzliUe zd`4>pf;#H|-9=f~d!hiS&ZgbjTdbKR*Ndoab}HAYa0@$Cc%!{m>D*jnE8!uNRczjS z3%Un6h33mELsQBgA}7&|>xy$BEWCr9H~A>kyZ8yRZ&i_o2l{CDg){KBK7*_R9=myk zz|Hf6B-i63V?_I;o>R}l|21-^hTcf+X&N^&yX&pP__ge=N?ZQ(_%QV3`X$rYmJ>0q{&G&n)MQ?5&gPn{mnHpMyRqO=p)mIPs z*R!LMpWRgW_2xXu{!xX`wbTBiha%3<^;)X>0&nzz=5a{{Ycr%|H;A@-6BDKwAH;{* zipB2ysB998&HZB z)0~kv?LzwhuJBTTH_{nH?@f=SP~FOFba(R)+pTwKvuY>L@gl(z^gD45=vu51&&i64 z1@M<<-|bm@8b28RADGX)K%Tl*WBp4(5a8THsvRc?<){z03O7_$z7e6$&~d`t^4vcE=A#$@S|-4ET>&#pUwp^sBR)KdK%=! zsdntRISYo<-P!xhi`Y$61HKn}iPVYJsPgv>xFBqxxg23wS9>*kX^}tw^YT4}>3RKN zOB#2)CqDW6kpw7KrySHOb(-ycnsz9Alc>MN*tge|9kh2Gs{9Ax8RL};sVYhkHjhSfkUl*h=$l|J(O~VgPdLzZmG|tMhUCT=~0a)ru z*?GVgU7qa$iDP5MGjniw0l@4Y^42Gn`P07?1{P@&c+rNRIzB`HHH{%I&wB94QWtbY zCQIyXu^UhQbaXFZxwcbq(smJ8%sD`2Pie*BhCGKYGZMk$#dE-qS;vNQmnK{Jh`WyTrv;h84FK5O|8B}Aw21K1Z zNmO1VM)Bn^__c$WDLoW!F0}_;zfAIc6^EZrbU~NDiMZkSVg-`Zy^;0NG|q=J#Q!7d zI{a$<{&-Vah3vh`EGtdj=X{>X%-*44j|fRBrL?=%t;k4PNYbDvqkEq7pgoW#8nkyp z6TkDj-+$n~?(5$3yr0i`f8Jx_vv}y0HwnZh|cH&{NXvBV=uOl)kiHEi$PZCNysy9 z9rY(JSmTR6KcPCt+Oy(ef$>!LRYzoQe`S{5Ukv(qFL`6xgx8ULa2Vb}`ZUtTq5BKK zv#XlS*s=-979541G1(+}2#+^rEo0|Z2k_D9M^Lf32YUN8ms`GQH{LMW7nRXmHMzzg zX{mPcQ2L~fJUKK9t@Bz9^5ZWOyOY(pcUBqfo;*N?RagqruJ{3K(?jNn_K2@dVcENM z-d>7+NTn0UIi|s@hfU<(br+oB`yF0SkmKc7=%b$P7BJ$j z4cV{r9kDn^I8vMi!G)hmxn3#`*|vu5ii+pG zqiT@t*TpoG$Dah9D#s6!Y3EK!jzsfZLOmdtX?}7`whZdMcf&EQn=J8AcYIjGbi*vbO;W>$l$ua#=q>}7!R^kFTK8fIa1qw6h0aFleYyWSapddJMpO(zbCwl zv0fOB7SDaoWreokJsLu&KmL=r$s)XGxHjwQag8^3%R!+uKV+~;p2VN%NYD8+Yx*ub z-)a!PoIa;J>qyHu8{{MOhM9q}lHDSCSqh6H`^oQqjyqQh`b9Zdf7UAYK*M8xo_GixmNEwKEzx9FdLB-#qi1Gg9v3~zT=4mx5JgjO zNWP~({;GZlnD7G1xuxPoy+shcRGuF`MiG6Tsta3Gc1!TQ!}AN(yLOT#C+~^%P3++M ziCpq=C5QJ=&-GZTJnrGM$AW#4)UWZI_A;E>hTq+fgJ*4Z^+ zntGxae3(fH_=_rDnUalRO;~oj29HZoF0Ou$lwYoAN zfAd_zZe0|>i_eWj1*6ZQ*Z!&8-2{L9`HT=P?#tkk@0}HYNr(frt+X@!%2x(T7Qx`n zCPdw=3H!XvgEHR^@7KBRrd=FXZvh!@*!b@Qa+E!!s51 zP83p+#|4Xb;~EbiRGmPx#4S40?CAI3M!)}weWTEht41JugL1Y8^!%(Y1?`#vQvcmj zaGmO%QufsnOO5;J>D@l7gqbuHnDbAD;Kk z6QYFR|1dl-GY&?auP0ikr!q(8Y(l*n&YWIIGtS$d3ZODDCECgs8C zhhP@8+4@U(70aqy(D1mQ%wAk9Xr}i~mD_pTqJUf`%*O{UewNN1c%LK={}BhHV(ZBm zk6>o}{m~G6NLRwEG|x|mfamq(xZwpnxam9Gr97KqqaM<;qdn$#={ekg7jKMR$F51c z&tHH16q%UNdltp0#2fK1BU|ENTogTTW?D$b;t1@C^(VW_O7QO^r`d7lKK#&%UyN?o zedI9yITxJXiY;$>!}hQ)k|D$3k>i%L(c`Z1wGP>+ve1L(X%=we$jNv_uMbk(lEFnM zw-^}q#ev{iJz3CTgL>Y20rM%A)aT~lHPfn~SV5NGW1h))Qvcv*ofVRO;sI-h?V1zA zpI4uVEC=Gz@*-t&yXqIdyw(H#+*rUhNV|w_vV2gbEY<&*gKo;s=Yr)8|p?MFw{-Vhp1tr3ae_YzcR`8keaeHoe@6za$h1)N9M&zPuDa z?ZG`{+8GMo^Wur3N)EmnV8}YOJ?39K41oyG^&oRPn)KV|;m1KjH&F^5E=VX@1?t9mwRFHGCK?A~7%NnTfl??p@-?2kjV!PE-$| z`VnT5nLI@#g1Aj><( zOc4C0oK=fq4&HgT4YJc@`FECOjO@A<5K;7iMCRpV(Xe2s-qTHn7+qux?JgjL>#sQ{ z`#}6j*9Wbm+1G!Fm3UII25b#CA<;@rSk#aUe(O8QfPA_**zG-7ovb70RkorOlf$q_ zH%Fr13l3PvX8nG^<11H@d)!E9DKsV9r!?dIWwc}HX$JRC?nj#4B`x-0t~Ec|^ES%3 zzY1j6*h=vE(&u8TZ~Q}|)>{fZpBKPA_geBK{T^~!>F#o0O==3UcD<&bs>>CvbkogwuPsRAnAHaWM@?hX_&i z^DHjtd9vWfszIPQQ&WP~clW%83AbB_QJV|S^!oxgzDV;6y0y^8nPyNKdy!lef5W+{ zRJSn6j#zWmIO^Ly_`LHEF&-J2wrCPP8~${*TxG~qFW3R1KYqmBuNe2bn6WOhG<*Nj zXXd%QE82T8M8cVLZ_0$Jd%lwC+f(tihZ+$6%b$!>r}>=gZ$sAz+F3TMLolG@jXthR z=k9q*qXqI;pidl2UVY5P(~S}PT6C5#Z<&XhxoMy|ZH0swF@ zGSp7Oll+_z48P8Flf%iQ#WfRr&?VmtPH9|+_~DU_$RWyE!gXujN`VW@N{Q*06ntK* z4y+FTCCiqpAfz>ucGmcl$RFjnJv;y`M^MhTGDo1g&IdjHn86j8CySrX84Y76>yhr% zHeCJh9puh!BoWFs_$^yQ`}hV(aFaet32*~Bn$38~It*L7>9S87Z}QWf?jdFBjoLjs zlPftE|8nyBZLG>GUtalE1ya{J43~TS$>5|CtgK|oY6ki6diKAVsUz;A$ivUMeJ5J+ z?E){@uKiPzk9U91Quex35I-z16O9Viht5eNVsBrDl^VU#aeAjaJEp~;b&?m<=szaQ zo>N@vs)TW0WciR`S+w@vP>>%y{Oi!;jurz$nq?j zNc~e@Gcvgy{af+tj94fBR(HL^YRLNW z#(%Y$1@i+@WS|Tg^`QsvdE^5=N)5z4Fc`1+!?BqfYuCy%Wbh{sL_xn%|{iiqv`z!ovqSWbHv7-zgjchxE+I1F2^G z*~A-__GEBnZ#vVAa32eByk6x(-P$QK#QGKEj`!CAJB zTnxE~vQm9vF6~fWaBQDg^E61;St zj)e8QIll+}SbgS0D1GsX9G{embzDEeV#NV+$W#$|*CEJyxRdC|*5jxUZ)m&MO7^+`|p2q?|vCSulw|z;nxL|}fTYB&!AKEYtt?*HS&c}LWbygcT;od^+jz+T1?E*fW zT>y9V>WR_I1*kU04K5e7k+=Tgcu4UY_Ic?8-fL14axnHrDm5A0m$z{*dBF_&j^04F z9leQ9&9h`zMhN-yA-@^x8~2c4ZVFc#-HI3N@rH#O-K2CdU~f(jiUUMsMnV~$Hk4t}|$68d-3jOe9VO#ZKV5H`br+?(Hu z?+hQ$&i41@zy0cFWH!X1kIzPsjXQtiXC*-(98yPW@A%`fH@wjFPxO5{u}!dvnGH&E zrsS1A<%d(naPagGTC-6nK4}W9+QB2dbzC}%Ti^^*M?_@8%n~dTE@$6QiQ<>EoIxaL z5KJ#MBPZWAVf#MngP7JvipNgHeI>LrXjLX>zGV!v_pdf+HeVu5qpI=N!2;Ic!CAgc zS0t!Yr9BOIs!6nuZ+1BCg>^WIw&P@{}CI4#{v{tjxyyXTcbRof48J3C6; z^!EZ7#NMXaQ+_Ea))kvJYO&ABF<$l1 zZPYn&GtAPoB}=QT@X+;F*qZ_V{Nmp_j4Z{nXYc--V>91*L+Q~5^42~Wk2ld~gBAVx z&yEr375#kAZ&YXQqKR7`CqYZ_PokqEhbI+Kj?3jFe{wQGHY(>JL?j~V8YTF};$C#{ ztQi?Q(1@LW_)$GoJ1MJLi1*NJbGr{1HYTXd$bL2oqVO3&Q{33tr_@t~CNWXon#8!JTPnJ&$0mSh5o| zzvG1}%`>?|Gb{1i1JmK@{td+QW+~RT%7z`5{K=Zk;Xm?FsjZW zNA-BD@+kt0Tom|n|4)pr%m_$}Gb5XSG~o?ry^!iGs#TyoL)y&gpgD2_k)NE3rzE?w zwoZ5XvJ4ew`l)=_wymDHE8Is;%0lX68j$S%Dy$+vbCCkCXnqLov)=0lOF@R`4Afj>!acJ2i)YV_hT#LB$b!NYd}wVUD4PtBFRF^Dcnbmtw_P-A zs2-p5bcGG+`DD`BG~8qBjmAdN9PIQYf$0}H@cg1lQfGJK4#gKRKDU|JymiKQTk@gl z^DsN0M$=$OJmTK{^v6uuftGphF70@8FT>$6#-C zQaXz}u_gXx-1_NYx{CTM)o zjEK&`gK8?lDp{U)c$CcuedmF)j6lL0NL?Ju)-s;FSMzUX(cH&qQ~d~{JLfm{S`q}7 zxpm~`8-LvSm}(3EWN`K`TLo_}&H{(v|1j3H`!(3NcM?6mR(!;Z)<6w9%J09Qj;g$_ zfKRfBJZLV)?H}bq@qjsz{?vqfpWXnQpRMG3*c7a*?S)J~XL9Ebk6{LuXhUF(9l1Wg z8sGNPXN{Lw@p9dMf>*mkVB?Q?5TZAQ`XeP}K5zIqi)&(vi_Yb^QF z-*?b$#ZB-p-j;Yitiqete1+3yz2yF^aKTM&5!&7(LtcjTU<)rV*tM{MoR$y9X4|~b z1zVbEt)5h*P%#(6zoKuAAR@#A?W zMBI&P2h0c!cf*G3{J?W*2YEhT9q)_NVGpSX@Ph~CqvbUBJ6$bPGOwCmUC9nlbLS)F z#t2Rpi2!TI6Qf7j_yf&mS2)r`%tz)h&CWWY=O0b99rJN$ayXb$ZxQ0$8ROaK(d1c} zn`aw@H-&kk)mE9DQRNwNvC}j#da;3MQ0+%(a~9Nn`$5q4cjEqkU%}6-kBnGrfn=1; zfmq~{hdX$z7aa~Nw-oq9_7meeTp12Dnvt+aO*oNeIJ``yJ<%?mX}w1_u_l^+e8`-q zs8w|uRMKamBRd73aI#|O-52p~wu2Z0+WQtgrGYq(zK`0heL!pdA2K|`M0|ZuIC$?; z;4>E-Ldx6rfMdxck~k(G?^p6dS}Iu_-)Je2IX?q^JG7sR^7)5h$pg4by$Lr%Qt;Jf zh469MUs4*Qh^|;MaCq2mvL&@1%c+lH)h>DP)d6};NvsdbPjBXW54>XLhFygV9r+|~ zK^neF{e2qdS=_BDNrGc@N`Leh4h@kEXDGP#4+EOV)23nX;<6TfZ6 zI5f!x{n8GVaJFRJJ4m#wASF&I_~)$!@T6EouFfpSQ-0p0UF02P*{@E4CGF#I*+u=i zZPMt#S9^Gn_?VpApNr7}UG`Y3CI9h{D%zJm1qw6id_{9Xy{z&;wXB}h&pv{k9t{Dn z&-P@`j&FD@?ddR^-9s9dj26F0Tg|q~h4Kw9!=Yb_dK3O-N;m<}uZnD9ygt9s*pVsM zTaQ>v7m3e0WAHP${I-mY3rxYDu3y36FZD%kRz?PWQ{kJbhJb5i)c3EK_?!)1$BvTybjta{oL&7r%b=C`An+e5WsnT$Ody^-opmnpG7T($V} z@p}Xl*Azoil@$L}?H*eD{Wk2(jVGT{v#`~-)$r@tLsA+=yJ(N=uqS#%{K?}}&=WH+ z^w%egd$7VEAHQ=GmKl8@ql#1T=~;&C+lzL5d%Xj)YhMo8rF$j(z)SKToNhFeYTdhH zm-i{`=`I1XFs6R&4>(PI0*6Ko-}}Z^erfSriunS|6?%#MhcLmhWB%xjp{#_P4Y^JIL36P;(O+Qa;65^(JI^T1_>JbTHJ8k{^^^R-IHi*$l&ND9uf>Kx67e%Ca?$Z3 z+FwI`AOD|q%g3)|D-U__J?3KsYvzccB`}^Ox@F^#XXOxP*F$D|XEQ~swBarnOu5VM`X55@RVS_n3iJDw%TsPD*htHuvFEG3{vz zPQkKQKGHn)zr>R$qL4QND1W(|9D7%f!)sL769+u_y<_zleK{YRKhVO>_IbrT>T-d? zBL(Eok~A#q?ujY*EqJkKcu3S8Mp@quEp)uvo{ zHno9VOgoIbng>Iny@SN-Va8p9SlK^By1ViP6}41;JVlE!CI}A6!|Kk6RlGq)>kCq6Luzw z;QqwlH=XaUh1CJ!}nCOw9xnc#mQATxZKQZ{)G!PG$ zbGRTm9|B66$bydxk@0wUu(ta}JSN@4<~KZ0@}5ji@yFwrwjZ{!_n1Kbli7EaF@73M zxMNJX{WtNV56zbT8``Lo5qTCIaURiOGt<$OFug}KAV{{OIdTiRF9S~-Y6a3GuMTrd~9lo_(` zXe-t|H<~?q$CKX{{hNv69-)}t|FC!Q^Z;;@sV8+t{`lS|4nGVRs2Bh6D2AphGQ8t_QxtpC5gOM95YDj}M{kjXAKNU*&2LTki10e> zpWQ~3M@_+tFVh_#^?gj09>aWNmqXPJdvfi26>f+h&hAvy;q_bg2&O*IhOXzdr^)mV zTJY)?)VL-PQ;#gH*|-YEY>y!)ALrp?bG6xJ-vjt-@28+54<{u5IgJ~9&>i=y(+-QK z52T;YHrH}AK{RzA**>}vCw?u2%YB_>WNd`^w)Zpkwb7h6_+B;G&O8ej4&@W+R~VZu zy9Ezbf0C))*-YySPjufcn{yer4S!UB0BWD=h|RaF*tQk1C(`YBZMpl%d$=+5rd=YM zd#doS{bgXhr-xi|zblY8^+OYm$`U2#9vqqO0Y$kDWMAQRymF*~-Ij2JU#<2CwY>H~ z8^&aF4qG*`@MkQrn(ahww-insuEl!wpW>b0ap;ZFY1p|bfEZdAV_TV@sBgJB5!y6j z{j)+Co!3F06feXpf|s)?O(OpByIj=nK>KXyj^_UwhPRF)#L&A{qt^Zv0p|WtQ58?- zuFu8}ry9WHw;ZoNp_GY1TA;4=kPPvly|-TjLHm6_`8W3x6LI%ET5^i#&g{F6x6_?$ zj8-;h_RUJ%#7~8|n2luq+A_@1p3TJyKgg)eH{xHXa>2Z&k(mG4f<7r7fHhsY31(!C=D#SCd)Mb}I$7;VUU8$|PPd>D*W*aiIU|1dV0eot*}+MzS= zv|zIt%}=i~=S)(ix%+qTLH*idg6vYTnNB$@9WBp)FjYeLqy;c=XpaPA=lvbUj*Io+ z7pm$pdnv~|_HYZAI{6hdUfl&!(+h~wv@|^Qw+GsJBAbg|o+S8f{v7m=w-TFBXKY6O z{>*DxKI4ZLvbEa_=Xx%YGLveoGe-qpY;=&!w?iHV0mL{dF#XYTAw1wmOGF|R2v`D6ac>#^^q?hMvLW)jaZtv!{3lqg5AoVNJf;+iAy`g z^S6o6jklRx&29yOLijqmm%Ym6N4DS>2a{k>ZaKMkGzGh{4d7NG$LpUShgt_ufz%Fq z=Y3L+8$Snux9cBrYkZL)mFhkE9#wN~{$Ckgsx7})oyCovkSvbu@kbAhD7P^8ilEw< z;;O0vnY^zZFC4)`?2{HUSK9_7+eUcqFVCm;8lnwa?hq{QCe0h~g za>p71Fj5r41%Whwch?%c&p->tSp|^Aqswq}r3X5?miE7VYB4D6^GDCtW^z7Dwle>E z-Qd8Hc%ti^gTqux!RMVU-#$2dp)))NRE@^z7a-A4TTP@5Ut#BG`~sPioKl z;~O>ZXwv&Eu2Qc}@cgzvy7MBFtGcrV+w6P+4TpY^`v+>o>d*991L-4t$@sU(5IMq_ zsez(lufmL1kUdUlXL!d zNc?)L9(yJJJRi~=hE7h{0B$CB#G9?ceYAJL;;S5~%IU+|KJMV{+d$;^U&lK#ma;#y z{Q18f;i%~*?J7E&BheUqo$ZH$sYcgAw(6vx4CGmcQi3 zbbIFCfppaCGmY5Y{)q|oo9NQMhB>p&io5>#qXW4#7osRl;J9T0c!g80*rypMcJk0h zbFg#g5^+yq5$rVoOcoKbg zb3L>V!sADp`!#>`ad{S}uhl1*c8h^1ZF{msP=$wov0xYN^x?D5N-^eC56}C_@b0SS z;xpbX+c@nZKc!+A4EeMJ{QLgH*!4T;`$Z;)tMEE4Nb#77)ZZTDR@ljKi<?rxGHfM0`&#QQ=dosL!+Cu!QuV6dp9IBt`B~!<#qup+MAR?0P=vP(aWaClL zRp~&wtgEp}%uP@V_(d)$hNP9!&Y@DjED48jm-hS2zLCKtTvowO%|lt!3)+0wB_R{p zdxe6%To8f^KXzK&TuW&`d*dn z!cLxj3ZIvLCf~JFsBb!tYGzu=^Ta_YYS3hOs1+c=+s)sE(B<4k^-H;eSZXyWP=i>Yw`mUJS+gp;W40wFD%2qD21c);6T5v>fi-4In;M zrMSS&gXZbwNVK~qvk4uGk z(@tWr^t<@+_xEsb1I^F(-HY7YFT zva>zVA=7o;nbc+W=+&{;oN=!!zMJ5O2LGZO;JxwU6)6c2 zbf}J$=F~C4b2MRs@qRMMsS!^Mc@JItI!JO~nE3paB=(>3oHy4?s~}C4zQrHs(^(W_ z6^9#eispY74asKYe|n%xYC?zlWb56c?RJpxtmZH??9ca=W)4_RX;) z%eyM^hu1W(>{<`mKK`!2SK1GqSuIa$C-vjl7B>jr+eo5Jn#*;h$59U{Pdf$cMg)?zyNhwx=MHpN$wD&I zx?6k0EvA!b+APFME0?hbn*#XJR=Mbfr8}BKeTDBgjm6jMebEux+k3>qWJQQ59u5lY zh`hyBw6@k4w)-ZKAuU<>C|?YLn!V)u+AOAWizf7~h#^5T1^9y7J9K=~bn>+ACq75@ zoT-U9+-BFa;*RgW$Z$(0SKaeU;N&?UjC3iFL9sW_^bJgzbCW@3QyVUf%bXk za_a=ig3i&tNI{+UL(RO39dE_Mw41am=e!*@d7T4?l?RB6q6Xs5?1oG=d$OA907sRH zz~Ben6SXQL(}N>n_V&w?xtHB>11fg>B96Yd(@s%Lb{(6;O|dg%Zkza`EKvq`e3A-& zeY#D+b?IfWuv*Q&rTZO}mNj&tB`O8|K% zQ;wr)wynQIJ2Cs-CYW>B9W9%g!>Lg1vGQ9XDtVdC-T%@c_M~U;4Ly4!CWkS;#*-jv z79tBRTXDsw9N6yOLQeD^#g`2fAma07i7t0;lpl=u>LKX{D&nh8{E*T1dhT@MMuv>= zK!K{c-09n$;&ZQkkqgxrbm|Tgd~{fYP9JiW_~YtEJpn0|&m`sMb6mfMW3+{<+qC0W9h5LtmDume%yx+f@a78|Tr8RS5+Cy|vph7-} zbz^@8KhUtGoWpHD{9_31C%T=(#pt&SUhWqnjcFO2Oyfq}H!L3B|D;{&XG_H{-5)^n zvJ6j{{Yc}VJ(yGnlAv$J82|DIr$)MGdGwBQ8qyGP;2;_4(}W-71j3TF?KCrLG9Dk` zj;7jCp9S^Db%zR(fa>~0Lzm!TQ{$m)dOcaiD+q>Gyo1I;zsb|k+vuS24T!T!B;F(w zcl_~(=6}=^?Y)!wVhv%UV=So|T7W&&ZbIVZ9&W!C^al;`6r>w_GoWkz@W5hrJPkksN+>9q*;SyveWf zBwo3Gs@MJbF`Yx{g=st7<3NXMfQ{GbA^BY=AvY|L7>MZnJg*&%*>6EAb~ob2Aa9su z*+u$d)$#d29d<=lFt43hh?J?W_}}0>u6)Nh3~z);ndb66d%AbUu>jgzL49*W46Y)R z*}kx>GJzCQUj5TUn*WwS_r-L64%)p8DsYU%@4Wh%fGu*0<}+T;rhcNgNYi;b;bec& zyij)}7Upp#^UjMS&4oxOhUTT$z7)v%&4WcEb24XjGhWsB22`j1Bun$&h)oBwVDr!x zQX{h!X}{P51*7tb>NFl7*Jar6UD5ok*)B-GntEoMEJ%xX6J9~R6<5RZxXYrSX%Etc z=sWG>TTQwJ0}292$#Wq3wpF=>7EN{(Bs90{&B zO32O`DY#=b?c%&5&o|#4jxipH<1p&k zJQ9-6sYO2%m>USu!wVT)-#-_8_;no2rf2)>emk0ot!5tp!lYKR{M7ZdO8PujMrCkWxufu$Z*g#ddRXQx zSi%cVYQ2LE@ZeV(YxTYWuRH!cN=F%|6{nJDUZAE0~t5!T| zNe)c1ZY2vBAHz%64+2KpQL?9d5B^|wzn`4V8ZA!I_CsC=8aSJUo0xFQlk7^!;|#w3 z5PvWgqNoQMoYzfx!Qo;fbewhNjA?Fjm1-hK9~z*%G*d;^&n(dIsrz9 z1`tR4ay&9h2&zN7N%YZt!4K;HijuG6Ld~iet8eZ|WSPg+{&^<;S48_?HqyEMf}=oo zwKBb93P|?)c05ii4O-qdlLGbg_)N<;Xt^QBPs&4Rm7_bf-S|stS|8%03Lfa|{X9ud z#SNhlZKnRLmhuVAE?pD&@*#j|ek#Jdq7f^nY{iFe&1dfJH$v;)ALWAdg76BugZNr2 z$M=hwtysJZ{O^c7t4dAv&F(!AZ^B%;;oXg^G;{kAo4^~A~64>!5G zqr>0xxb6Ep1vNK)&>iOtZfD*`eEo17*u1SL!I7onm%j?&@B$fr?znwue7qf~s|Ata zQN=Xd%^$|@P~_h?zGIerm4cM$gJh#=6Mo+i0MaS#4&)bFPC=u^w3n*qH8;}373=);L7MaFZh~TU^1e98{9aFV z@76I67nZ`-08{c}B;D6P%7Z&$okZO!O#CJyfnC0T&Kt$CRd9X$NmyM}Aepx<%~Zg+ z(453-HB$e+56T#z_W~meakOC^RF%-2%Y-*_`%?Tbj-^K?O)7e1k_DjL}pt&%#&YWn= zHe=5(1Ws@0BH~-T_|%qiIA|-yTeTcSTJv{9*3NuVBg^COG6HrkddQ9Ea5bUR-3XL9E7~>2`R=XF%yB>_4|95axXYYg!gB*yKV-9=E6et#?}&7+wQ3|*n{AA=UtZzXZA!z8C&d%xN}}^R84C`n z!lv_ql3m-hu>sKE(nb_Ew+hAwdZTH6>0F3wz4*i0A#BAaU4E_eUnWFlBIq0dGU`q% zcAAn7-{v)v;>`!~17CR<-R&sp_}D;m(f_^ZC&u2R#hJFgNVT_tTeWHvQ(t8cdRybj z;6=GOaRv2Dy3j1#h4O+(B_oubkjeRo>x%m+wm}? zFn|;tF30wkK5(`9H_5BX6NJe5qEEUFT*AJzgeCC8kbnfXAu-r`N%&Vn%b}H?0sBb3S9~Bv2B_DJFWpKNO zZDJB8U4_>c-cMhYTDbZ{=7YAhRuvY9>^#+#r>hY6KM>8*8JwVn` z|INVNBYmN0Qv=zM=7$$7_dz+dH}KE(jo5X|b2z;DC$XJVBOYg)4<7!~{6OhmbaJ&F zOkEvB`fe5DIS-}aSm{AhL-PSHycEHpoo&P!Ps01B`=I_k8JzCM#d!0rA?(4Ix;#2d zd5KF!Q2SG!_u`{bz~W%A|+!W1~GcK;EF2jJoE=L>#w4A63#M zIO*%)gH$RqIM+Xq#afG<s2RQR;5QPptF6BkwTaY!k8u4-Z{1W>7{vR8a=gfrqE9;5O!(@DXoDZ_9mnXh;eRz|b8%#OU zM!whIz#n~d*#0@U_^9p}w6A71l>BidhHX`N%64xQnn-=MF@;p z%|HY3$GAU#WVxYw;UK-Hlzicz5Ud7XK=-CE?7SD5&YU#M=~^R@#^;mY((1` zUSst=WIKKb>RXy@$Ac3`v_%?S-xl$>4t7ABkr) zD6&3zIy@){nH6)5(bpJfE_ALKU)k^)j2BfBdE;b!Kw~zn2n-}M;%Qe4)jT-rQI1RT zw;;%X{_m8R`2YO5HCl)LjV|$_Df3ae>jd~doF%>4lsB034#e?|M4)yMhs4Oipwmtg z%-m||2g79kk|#IDh&}UsP|wf?E=y)3qj<{<)MDaD-PBy{&v>KGKzbjql@mNDS&1%` zyGnFoKW*b-hxZpUeeH8RXTv906wyywVK{Ql7zfAb-Y3SY90wos24;FU*&354I7M^e zyFWH?rfT09qorODKJOE$ocIb~Yw<=Y!c4B;{j%VSk`l}&jD$Dn*M0$bS`)FEZG}%g zErWDfX}-xp4<-F|gMorX_xeBKS&dg{dc<7_+W3n^7r%d1^4uHEVrXW# z=>%rV@jYPhntq?*#aQi=5i)&rlGD$=h6{4NV1A68gg1EN#Ij?f;`r(F8qlHq#c=Ia zAgQH!l{O)_;HY;inP)SYIa2P08l~v(ymliawswKj;}glvoNT;4k!97#+wfMqwf;xa zbvRP>#c?V$G!O}CQ`#vcy?efwwzT(Bp*>Yv3WaAADwU*^%E*XB-nr)}o>3{1R7kQV z*$w^9@AU_Cd)~YEbHC^NStxqQ7_dFd%l5ho`gc(6tihz|Wd}av;02DcHM05hOsxm< zVwp&{w^-p`O-W!Vu*|w6UnQr8&El;!_EMue&ym{w6X4n}h>VCX!qJPnQQ}G)(mJLN z%kB1qt_@A3twb9i8RvW-8Mml%z;O^0%9$Hrzm#T|tm+A5Z!W zm*TQK4qhyXCQGwkVvmw(e8s6C`Yb>f8JHbKAHSsw+E*{&+5!*c$nZ`3NVFuRa0KMo zSdxwTh1lFb7bf`sAO#b{Bv~2J{Kez?8I?QBVE3S1;NX!@&_0ZPLMQWA-Ud)?eGm=J zP=UbQ?IdtqEmm~%M3xhn_Q_?tMD5ga-e;ySRX0sRlYB>jimoMD&+hHpe*1X($D4l5 znacWJJ&;PN0-3z+C)WAq3ZX-riTtV%{9a`N|8Qd@ZCvvN2~S2t+o*Hol21AA^~eL& zF&_5+vwy?jwfuV1i}cr|I;7ug1e|`dn1mDr;xiBT^U{w#)P0{4iW^XeBFuNlu+%}( z6F!{iBxrmpS{Vd^$y_V-%6StA4n`h6ptYLs!s zVy1y-xg{$s+eBQODf}@yOI~-D;h>Lm_%A7kY3zOKi&9s8t`4oheT;u*YPciu8(WTB+WLd5?>U+G;rfb8 zu-1`jK8J*+uT@{j_l>zuMTgYkREHQnnvo@R?@_@UcJ<-&icD$i3?FWf!xD5f*G1U2 z2;;T#X|T?;jNE^jh+ixn4FmpOB)z}9XFRemNXLF7^4|3#t3Dnm+$u}xKd)LcGQ^1A zxbOs(zcC(ZWoW`AN1i;2YQ#5xQ7{&2$b+D5c>R^0FwN&2aamA-D+;|~jN2cwwU@f& zvwJwa(q;aXJqOXr^;=20VATDDykqV*9kMat*?LQpxEo7sHEvg~X;V6>mN7iO#Yd z@8JW_iW-=XC5J;YTwS;22{_0#5ZHMbAB`%2vr)gv!ofypgtse{M#4~yZ|6ytIx^)n!5lA$872zT33y^ow0pZK~OL+d^6u9_wI=wFM!TNB4 zPwD!HrD4TWV6$c*@gb}SaN-qE8r4Wj>UwkYmUy5u@ma!oXDhBxs58XOi6hcOIXI~h z@exkPsNt@es6#v&^o-199*4rCchK7>>f~i%7xpyuglzj7lGxi9CleE1ImVxkJ$?^a z{uQHKw(q*p&kDyHK7!TL+4*{1rDWQ6HV=&0PhIje(b8@Q_?!?#^8PSw((T_UIoXD6 z)~Lhn-Wr#tSyK|3aRprh>FXC$eSZ!5{qR~{CG$G43oZP%=cplCC?e( zVS%xdN;r(TtVAP+mU1F(71(oO2l-~r_OZ)6(CJ#Kuqk$%M09O9^tNW#?DGg8OFF=( zFYu$)V+^^jZ(?*zTTzCqi=Mf{!Mq>DLgy;}QhXDX!<4A_vpULc8Ur^b56Xd4;k-nm?lf`Kb(t!k>%Dooj)3PV9N!&guqrjnzONgKCiVydC7{ zSJmEmAyWNf~^drARd*-*R7}>KE1!>+xb-!L;tFgyll$q>5$=W8p*Z9pwMK8c#t2CD&Ssd0#4V zKEUx_qwQ$tM%MFkekGh4`-(KB5Ipy)3IAIhN%y{VLLZ%!V2HB~`TDsQ`&C{BTeokd zJOkd`ehzv$&f!fX{Vngnrb7mRP zID?~6Dz_!4tStD6;}Ynj3uYEGu}dq6l-w(pC>R~--yPhwTqJaorIjIIw#XEfppdM4tq7E0$} zKi_fp2U(#V!!HPz9tn8y_a`9dQAVoV6Y_Aj?L6kC)`!1bk76I^-*G1B%6{ z%2g_xV^4)G;rkbO(-(CdQdQT4Z3^ZxjEz;KpupD>)jiwr$KoE~G}cMxDO*0%8v-1= zN#kO5iGhh1TK2q7i1%B{sfTWXeL1n@m3toc$r7W-`=tV3&`Z=Y+#EUFa+U2-gWpF( z%iT|;+K};Ib)TTyMuFB=4n_-}s>6so|K`|3>%36PsQl_W~uNqRg<&#S_>gJ0*UvWBHVCdAYb>> zm@eOOooj!49nJE7Dpbce;9T3skagXV+8^-1igQx52n|A z1tv}W&NN7Uxf@r-sB8l3TVdF{K*t&07srvQH*#=!&@BG=&;4}hmMQ3N+$d-cHYf56 z8?jPn1Umd!ouuCB!k^E0KsNK6Eb;fjJ^LE-u2dd}ZFi5UJ3?Tj9}diQss) zomB6sl=vH(@OCrz(a|5Cqxu035aS#q)7d&3MDfFJ>1VvCZbm<9f1z_>Hl*jrTKwUU zFXWAEW?YXBp0&W3zgpu*Px!w^Grx$@oJ-7OqB|A4KAOvav~#D6mxPLj_sE7VpXI2X z+D&w{JrMSOjwjoTv#{%85jZ9On{~O~;qWt4i8|i&=RV)JM}f<+OedDYzUN~0J=;x; zmOKs{4!ZG{ElS`rbmMuKnnNLbTNH8?tgv*Ia zG-+xnx2kv$=pNf4+nvTP_dvr+6xyMqRkix}5&U|)tXp8Lg_lQDo+o{ zxf@R||CD0&p`~!(s3QGo`<8oWIvK2oMUz=5AO9V#&i6khru`awq1~Ps8RU*4o9f%} zt!EcuiFpm#S?rE)Ze{oL8kU7PGgY*ucntJr-_>r$RoVHc!<%=lL@$xq>Yu!WgeyJh zIyqbPWylKX@O;I#Fa-O)N#^Y>^)t$?}~%3-NwZz}-?5BVXoI_aRq#hKTDp> zF307Am7!#clZ@NCM%DNRgVS`RNJrujHIHwf9!itvG8}%)v=GeeYIRWs`yN@xTdxYH zLO?n9bnZ!H@$06*jjzL_qf%h?}<%++#vChP|L>Q39 z&In?39Y-nfgDGMPtdQ??9ylcfppIje)Li>;L8-eUdB_4{b*<>#nC z=@@+J3?k~2n3lMfnPXn+XJi~{M)C8ykZ7H)40}%>^?{#>&1B<#9enqzF>fcjNTa6~ zA|F#Rx~r2T_&uA7TV^cdRadie*q?VrUyP;DTq93~TQ|`z=ILH>EP*`m%wk>VX7GAl z4C(#(CGNBO2x`g}gt*79_=y+Oqz&UN9*ej_0-#_qkz`Yu(#{ z_IgbwOC@;Vci=V++`>MOnMIE9Nq@VfW2Y{JBrPF5`A68& zaU0)m=0S&r8E`?yOs5^IDANo~PjH3so9!g5?HcaV7ztiGon(81#)0nW;aira_W4bE z${1a+c(8={^b5il_w3*!uX)mW(|RJ!j!I-a&_*`XuJZ8)z1#A1#s?$ZLplrkXavc4 zs97JGj#nW^sPtKH)>x00pxf<*7dYuGLMOWs`HicB6a zV;uKCYvhznLBcy`d`$&nx3=@8y??Kuwe+or(8bc*m6O-Z^=KE0O z$thR5dh!fzQtok(ZYUrLnNP7xo)K@K6hIRT&Y+o2?&!{$|MjjeSkf%w16Q1&{ET}@ zdU-i)ay%#7ogO*d50-^G$?{=FTe&4pvl43?%+2LN{BuxkW6hZ`Oe1B^IQ#s}cM06fWmAkcU1y@UU_6 zu>8(H+yiAl<}dC^6HK)v^R~|8t1Ir)q$@0&pLae27k05S4enj=IVRS^B? z1;}rxn{aqYJtiIxAV>O%Y}$~7CxyI*0q6db{G9%1evKM9uK0(0S&Q5tSfhyi(M!X# z+5L8!-EZ%^&xj=Nlc71ck&rRclC$1nxzdgviubS8=4V56Tg zf5a5{G~o(tzWjqYr{tx%1~YHS^=u)gQ0_lQoFq)Gpj*?heLZYlz_yAKd)Zkl)?yN27!8BFBC1C~H%WjJpqY@I%#0 zq(YcoO1fN%5$`QIK&J#}qSwLpP^1@3R=;_RJG~?MrW*Z>L6e%1%GnMy@478PakY4q z730pLn#lnT9emVuChsB&paJvWpv6p!p1^R%&v7aq_rMSBjAVWXpK7zQjO!nU6NuX4 zEbKC5Hk`W?Lyi@{#L+*1r$ZxYRF7#$^W+C~r+o@(@@v7X2Dl^bj%?XZRXfHH9hXRj z#_(q%_s&V+bc)SFtLpID16gosXDeCne?#(cNF-l=ML#27u@rV6-Uf44y(VWLNw9$p z#}~Fo&|!<+P}zb3uv}zA9$l-!Gg?@N@HVDVEZr_izt6lLc?{E@$#FM+^02z^IWqf8 zDb9Ot%?D?B&{Z!DI8_5TH2meiJ-{@HD{PZ?lE;dnSWdy5Pug^kmNlm!JYWRe2y~Kh z_wsjGCTCiJ)?ZzLF3Q=E z`6Fxaj~QMt=A=Arns0<}#4q9V0vTWPqz%PonSgLGh^&;n!{I@!OND75gXe58%T4h^ z36rvg^Y^T|kVRtHDNZ1*^-?@0{T<9dz~+HouenDh6QC&iAC@}WN>JC9F=WZ|4s4jk zG@@5)$Q%cEyf%ROHHPI1s5@1(be=!n@(~7XU-V3#|8)2mD1R*=-^-rjc z^<4`w7*fD>eR4zl2eHr0c&kUjzQ~Maw{EmqB{5<=;Ki~N)Oo}`^uT%F37 zw>hejykG2x41-x0(gSyqIj;eW3jbkmracC?e)Ys|);9coj2wg$Cz~DYc{*NjI#|M(Gk0sdjiYsW|E+P|WrD0pv_mQcXEA+bWD5~AQ=;m=(xx9+2NK;=Tn=}7@h=Jg^$+SPy)$jb4 z$cL}j&$u438Ir0dfX&VzQdU=tD<`n~ocTR>onFcfV;+G6y39{^xI%K^QeS?*=S*sv z(hId0jDWBsb7gzfkYnNKHH3sB{ik}4oYTTr=;<@ z!gl+mEWd(%PUaElNPV3CBzHCMsN_wvQ)^Jw*CSx06-?4S-s04TyZqY}{fw7c-w_?z zfrgaWlKn4gamXq!P`>z`_%6`Klb6rnTi^TBpBG=Fq0B>Sx;a+}STPN2sk5G=1yVt; zwaTntVgP(7OCUWgvheozrjR9#k?m1!%FTHlt^3rduOTYg`~e*>nM(R+x8Ol$Og9*s zBh0UgmZ<*nMI*;Z1^fC8QEmJrIOM*Aq|d6un(Lo|$$(~ZYyNdf{I$FM?w$G>Uh$tG zB-wm2xa6ffT6yvxu0HI;x^I}i)W57- z^t6r#jaBD}sX`fkv2i;;yv36SkDJJKHeW!EM3KDuz-IL#SNPoj7wKVe1ABkag%j7E zh~xJ%+`Y&R-Al_6@+u0_*Sz;ZVkN0CW{NHse`gy!`4q%*gx=z|0Bb(2$dev;&;y-3 z`x)&Duwfph8hns>{ZiL3zn-57UVCdXuQV&3hNripxJ+YE$`1N>e%E(LGkWLAG^?!x zeUZ;9sZguGl`|K+!@|M@lAa>Pp(l!9)0JMdJT{-JV%~v1AESxZ;C$TL><<%vDAB^` z^PJ{13DR*JOGfx~;;M;$u&1z^w5Pb?Oy<`M$jcS1r>2S475SiLEQ?s@uqC!EiiOm; zD)LMvN%EHMKebbK(fE})Xy&;ku+cJ~fEfG7`;r(z)(1W4lO@cJxg*J{j|J5iRmA9W6E`Em2-dvaM$+{dkM^o3zww$YHBL3;f{hdS zPCfmM_2=bz&vK=L#oGYbBM9KIj5_UZ(bT7d<$t4qFW8%5(yYW=i0~ z)Or&3#2U9R??$-NNycHRKlcX>DeEpDp(~jm41D~_dvqI7gU=T0A))Fap#$>p(=*J= z?2#vwFIE)o8pENP&;QN0^}6@r!`L$7bS?>}b?3vqnewzUWB@w&O$Czb1IgGoC3qY2 zcT_Yg(Tun09aRDS(MtUw==jn^R{LkC)sAyVQGN4- zo0?kOx!p{QzB@~}F>fG_&W;6@n^j~_CvexsTt$bkNQCi$4LH*$8rrHSQ>&T_xZtrr zM5eL5*#Sc|^OFH|B>ux;RqgA5p8X~VHV@)%S-GQ7^E~0QbQyQHj}JOrktuYCewNG) zjfK;;Rpi8a{4K?Sh)4Pirj1xp{XAZ!IO|+ zG6vq_^VcHybrt#+u}?_VuQWvU%nwzC$$o$U#~x|&J&J#DO`IEx>6;}Tt}`yP3_ zG0%%Zo(!KoF=hjDZUGD$;Dj_{M|&aQ{pq+4v_DCtNgv#+k7sUGfsE z?*)GS#{1MNb~*~3_Z~HVpGq`7w%{;dHx#xgPZ)PIMxwRD2lZh)OzqtnqM|7iq49u? zOsA?c=Q&tTYa?!xZb;O}Meye?>Sx?B{RDxUTVUMd*CceE1iwAZ@#_;J>9J0C^xH=n z?)J1L8+O!S#jWm0@!AXF<{}$OhO#$0@*q=i^!y_lxD;UAJSQ1e4~(+r`zCnN9Wy3! z!-icz--jxZaVpH8%RJHMhyM_ltzkIaXfbcIIDsxv%|N{d>Vi(E6G#$=k|jZSbPDQr7d8U531hZOE{xHMnz} z7yJn8Ne#kG@XIxp{OkpZbk>j#boQwcRI_*J|9e+K)g5WD&Im4bquF(H=C5JhC1dt& z<}`k|!PE_jWNVfb_n-0>JS4s7lU4cLr~BhU#VLmTcFe~ElKtQZdv;duInQ-&WnKo-Bn~>;Umcv z?|h&il>Q z_y>M4{fiRy`>_S}9X%g1AIFl?hk3YU`!s%aI?Lhd7>fq$Xd~z5y+YN4o`OLSZ}h$@ zQ~0WXN0Rm|2G+M!k?q5pxJB=cpetzysbYGavwBkcNIb*A8bV}&H*Neo=CtRkXu z+GvoH733{+A{txDuySN?$VSdGO_x(_Ah=wVrxp!i>DR`1p?sAufB;x_>0B>3 zvZIx_y!<9Qyw(jFY{(NzifSc_5#A^_FH4X=;U+4(I~YO(=E^j&j*p(gU%7gM>$c)k zdB4#waF+36#qa$fZ(whlG)`A?)5x56n-@h_)~bWY_q7l-J&t&{=VCnEo#kr15WMdw ziky0Ls5IVP=G%RA@*eD~Du*L{9GpK@Z&^a_VUbPXFcyexrNS zx*KJp9R=s%^N4rEs5ljSv%H9U=?mdX{W;O{_g?6Abf%#7#vb?Th=D0a)g+tj!n&Wc zL3{Tv;;J(pB|UY8Z?rd63{SvUOZ?#cpx$(XFPq8pSPsMVW-{J1C+*%w_RN2MA;^!> z=6bL9M!CJQ9J|QT@6wBu41@2L>VAm9CJh^=V(|gl} z$%d#Qbv#Jxg2?CGVtnzz4d~+_PqziAaY0pHC=zE1n`_D?Q`t4|vupYq-Qyl@9u9{b z=E?j8;V})6y5F7#J}Tlu({3P(4h`a{*@d4)xx$ne>};~Z7r#C*i#Hs6h3dYDMLUr^!{RN#=j_#o^l4kkC`-{Ok)2FNP3rzS>| zQR9IhXjGIPsXA7RJ?%ZzDr;(9OE%*TQD7Bw>Db%Swl=Nf%g0^p2!af@+8Z&PKEdFdmQfir|OEClLC$T;w z^-#&X_qTXuHvi}M`ve}MO;DBgnppOf;OJNpZ)9_iTAQ=3O$yPFVffv*CWC`1L{Sm2*MG(w*gsP-ctf+!`J^w@W%?CAZ-|F*dpp%kJx8SGf z2K(dx5_I+^wiq`I#3E-IJ{R_NM}z;o6!O=;OMmm*6D@DZ6o`iocXiBG*taE^%+D&s zcDFb_a`Pb?(o)Wy99fFoC)vt&6ao2OV7oM2F zUW3u>nrrJb1&4E+xFkzA_>r4P1_)A|bhZ$Fn=8-)e}>6R$3fxU7*e`CAD0|TLyioG z)4MwGx*0yuz}1jumh-bZ$qU)GW(ixiEymuCF>sr4WX|i8B;%?~`LX-=(4SE`=-r7$ zFz0JN@mx>vx(z)b_~JRR%zD8|%Tm+7CxmdZMK4OyQ*NMAk3KJWX~rq@xb!+DO=LOmAklkr)JWuE9Z%@ka3 zMMyUEG=jO7HsmGKNVG;K!)|*s8h`t@XuZutex8+nhM&GXzsT<}ER1?fyqBlr{y(Sk z`d$IlaO){{R%k;z4a{WS3Nb9pJ?~SdkTz(AM2lq&RbFu-4fD&eU6vAjyx>gA5`G=XC;&>>X5iHA2JW#^!jq%Lm{9v%?^=o?+KJ&J4Vo4pY zd6583bIZvLt#~})t2WF``Zw#&`Rxg!@;35G+9dihkLeP7CXmr)xp>A#FSL{O$Gxt0 z6}|bZ29rk5lW7S`4WB~Fzy>nZ(i&g?{1XN5b^hn2os$U%ht8p+cWsm`U2V=k$cmK~G2G|d6A=wqW+@+{FNHfh{rq@~*9|<>|%4L|@qx>~&WbgeH z`$4Gg%Rulr8YJ5-=vZb!rM8G}f3MBO{BeQp_U}mTlT_R^*o);5WeF$Z?Xk5@91PQI zAUfLn@xY9Hh-~OVC;u@)YSIgEvil!S_R+Zru>3o59GIQfebtO#>E%zCt$dFrcY7l9 zZ|vSM9e{hhx`NUluq;qE$2ywchp$&A)3YWQ@O-Cn@U&krsrD(x^G^kU;ru32tJa(C z^gPkR3!ZOHwmYHabx6ScBu^LSWNy7{UD zaL*x_^fxcWox|(kkk4WI_v}P;GqM?-K5s|bCf4GItoOkquSLd59UpGRuRMRB>cqAn zyO42UY~)P*v&t|v_CnFj%fP8tn#JDpgXdEp5yyU6cul?$L~V~H<4?WBCjCwM`hW z+K5B%8A;FC0W4 zaUy16rTCP-HD4a+O=l-hL|!Sx1K=a-Ki`&UysO5k zm8sC2XGoRjoyMofSn#U#vGmx8@2D-5d7_hpWqa53>Kl-EppERk?K0=bUzWN0J5w0Z zXA{?c*A=wqJd*7SLbh;x2t7<4?wO(0BlKZpR}6{YkdODaXyjwKZaFW}r2c{=U*R;19j z0K%ufCbf$Rp0zNRZ)AJdKIgiT)&+TpmfJ~O^lS0Hbbko^(L}VD^uw($=J0w!7b#0# zMAEk&Xg7ObM?9E-yxFv`%GNZQkD8<-tQy?7@A)tF=9a(n+3(rFqNn@Xgkd@cGkXa`JILwz95; zhNdI*M8GKS(zh5sZ57)Ce3#>unh(OtpKr+$lXR^AXbK;HJAigEE^JL$E4or^MrIT= zV}a#++dW|TW4l5!>G}#jy@xMN{gjSQ`;UYT+LojyF%HkJRs?^kvn?RSoW9n z`hGoq>orgGJnO3<-MyCc{sM3_EtssoQiSDuc%h|CoA=vgu*jm|2)dqjTZm&BWzX)% zL($=KVv6JN+%7G+HY8Zab9I0Bf)7`^h;P#mQTGQsxVs>M^i$8p&kuQ`FE_FTA>LJV zZLbsm_EosDSVp3qHRV@h_v>8K9C)(!YEZYNo(a8j@Dtb@TQ}j!TdtrwM?uDOEib+c2CfUGXc-=%+71)ZsIG75#Dbl~hxsLO zm(9_$QsCU)LsxTwtoE$++`oLjz_d3|l=pLdPT=-n#^{Fu&JE&UOB zl$?nN_|JeR1?>E__9fnCrpbGTi0Qex1Ceg^J2YN#207!=j*lmM!M@(_$pOR1IGpu# zY;4OCUY#VO_EqDd=9(>uJ6y|pGczFKO$V9neM2%Rem&HDdLui(9}*ey&oAGm$sf<7 z%f0%-daxrsCe+~F--4m7yM`E?bi&>e547fGmS8aEk7&?z5zPGSL@tU;amkV`yuYar zJ$rW|CmHCBruiumhr3;v?sA3fBl2`>T{w0wnaf9fji>5o3G!6Xh6!xmsJvE&H78w# zDmFW5x^_yIkM}^ze3r1TpAMIHYZEws3?_-zh4>pSK`xoLD5GYWZXR#qSwa~gJb!aHOL@+T|KhvbO+Y$%e0GsYl-DsH#{|AB|ktC zK^>cekx97+B8#QMO35O8>)k<^0T@zSN~E9j%)@0;a!SOwM;a#BRU8LKf@HT3fImol;kXZCWm} z{#@_pJ`mE}O+M_rp8m(x6Dc}W3$Y&SIK6ZPyZ!{r`eiiDm>=!6ROoYXu&7G&Fxp9P z3$My+@i)&nD7;lpmh6thXO*=W*Ap!B2;?2Ig%Lgpq@^(jA9wRWo3pco*we0}#pS9n z)@?o+HS`-kF)js;tz`LBdpF}Ez5|t&{F^gRI%GoMKt%Pzw@9pK%;hbX#nUGXw4k77 zCD`G(;Z^joN1(W7gk4nCTm&FjFa(eP|{YQ%jT&d z>-_#Ot@YoWspymr>1D=r*fb5!W{We(O(-U3{Zg^zx681A^*A5sdyzZj<$*5eX9>oK z?D6_u58z>26?vXuhaLKw@pCK=QcsrcL*&lG?2taR|LX+Y*Z4BXNB<@UE^pEbOhvqR zpCDRr@e`{0;(@eS9+8Io0E`v-@V28(>EFhy+*Gg2=wX2%JC8rOe-}u9b{-#o0eeP8 z^Ao)EGZIQSLPNYBgnkZ|@mU^cg5Vv?Bw6aB%$;Z1)Mm_g_H=r=^`0<$!P4Qn?BqE8EjPmT$Q!tFIvs{~=^`Y9|(2-N58e3$Z+S5$_uj&bmsK z=xiS?)YFi0gq$6jIJ5?jXk=poDV{~vF=)W$*oVB3G)<-7pTTieLG zhU=2KH*fHcuk|x}s(yq|9_ygPw}8C7DZ$dMGx#g)w6}nrrx#7`11ndXOR;$2X1?Hx550VIBG+o*g!JDjkT_S=KWnRD`?Ol!Sw5%2Eaql6%ex| zp7^`wV(~7<^(<>6-_dX`ewQg~*&~+Cw3B#$d+4S8{P40}p6O8vLCQBVt@z_3>LFLQ;xn2QWM7S8;XPwKd2H0cO zlzXuLa}{w^vcsR&vD|)sAC2+2gF;nYprxb_y;qWehZtXkd*gmq`ff_CpqWY*(iyz6EF>-A_OkFNLSoUe&d49j3VKDb;mZ1Q~Gc!8J}POv~z zdh5Ws&iUly#Rk0oR~5W~#;r1ZywmhxL;eCUk)YV^WBG?+n)xihI*%J!n`=kO{~N9dP#YMgeBBl5{oBF|@c;cm8*)ClTDo#x!Z7X}Z7 z%w}iex3>(>mAeAdx$k6Ha))HibTJxTES2p=7YA;Db&;2d;+{hM=bD_kLodCIFVP|B z^x1bP|D+xH_O%+{h)9Bk%M7UsI*C7Qod)9qE)k8J?{L7%>#$b6L$)_CUL!{R`m>&$ z)J>dI;(6%dlSFcENwIT?h_C2#oRa+_B;Gt4G@iuDw6BxplTp4`trcvq~4~xD^+W%}LfL!nEA~&%M4A9zpQtPBM$t2@Z}i=Ie*9+ zmj}EdilYg>EB}DMP@ta?yZH~QEc=6|sq7-J%WCiq3ty%mYbGn!_rpaaXYvMP{iyhO z6k6F^jHXX_0Z{(2qQ9XFLQwl0PWZ zWlb6Dg@8ykQLi}%k>%G2*-rJtj93UP zFDH{D9^!LVtoOEs&0{RPyW*J|e?-llwj{Z5lH=Q9QD*`lnfWiV*>Y9I~enq1wJS!hJFSmw_f)^Ho1b$lk?ZI7`0TGk`{=@hkK zzeD4(exSs-*Z*?{emN2ldT^9;(B?jjbb=@1_vCzgDz-}tg~3)`WYNM9F72B;I&_qE zEHYeOz4soZ8L)i&Cw6%Jd{bU>><~3oyoWMhI>Ee*KD7H#0`5BO4-uwqWashRv@C4Q zUo#4zceWLy_&s7IVt)2-_5<*S3-fu`3m)_Z`N9p?y@bX{iEP*E`XU_6`%j|bEK5f| z_dXvOs-LlS@YT$0gd!LKFm^l=@J z&J5IM*&PeW^>Gb&dPEKMn0$&Rm6UKEnjt8s{vWRT&2odV&~|d=SRiKM(|qryJ5=@A zQ>1UB0?SJ6$Wqpe)T7%SjkjkR`?X2w(+}#x)tyVo8byB`a)6L!>*DskY_0Ggy z!>56M{X??E>m`m{Sb$D!nn9Y+w&Bt2y?k#}33a3%VWXk@1;dnC^n*v>7PX5 z%g&(nTD{4z!(F&)jT`iQtUzAaxOAwNyozTz=WC4lq}Bj>@aK8d){DI_ z{?~*LT#WlpW0^B{2WgLKd5CD3LxaN`*^K)0>OJ0y&8YTGztLf%-$>qi7a5yT!}v;X zFgN>7o~-JN6T1!hXN&!4&xKK_XtO)o&anOe{ebw~J^oL!e#TT?F_`}0VBeQGS%3HH zm+FXfJ0RPgy0eaqqf9^lKQ_W8UD!X|iugUt$9nhF`GZHpX=dyiZuR(k{IqTQ86#EY z__JEOq3~G|X*LT+9e0uW&&fc0s?`*D4*EW~~epfD$1g_>l zTI7uOE$9mdQ-VqHm=YZI@-bAm7_t5KU~bv3vv6LsgyauS!zVLXPGCf~kovkYx+(oT6&ozg%w~O{jV_V z)d?z5nu^xWu0fLnb`izO8eIL(3k*Z#>3rug_$0TCpEe?qPGh{ofSsekE7yfoJuG9n zF7BxHN{;X(r_$^~oIkRt%odK!x93)*dV#+9AMUw4nF6B*#L4!hMbBR&Hbl}H7+!LGmqdlv$g-4N#@PzuO;QX0o6qsL^c(`0;UM>BMePchs z-kYl+Lia6s)d%DAg^Ex!YL{$BnsDPH3qGnNlkJ=^oODMO`*Vak)oxKAH9sWJ_D*is z3@{$0%pad_Oz&L$B$__s6xuMew`@MV=I9Ffy%nj}nY*}Q%@8=?=t3eK%JBX#!SLt& zcQW@|JIirm8M#bP`@gO!ax=@c*T@p?Jm`nzB+C3PFroDi?sI)L3Xy4@9ZA1djVD+p z!Wg9)G<3&FJX~%H=v7`KRLpO1G&-{=M!xN{W zpClE$DZl)^J@v=4QR}S{Q1CUD#6Nq5+oBT@`ld%Z-?U@S)E(shW9ho%a{T_c1`Q+? z$zG|fXc_6b&-;#Kuk4xGq9kRH(%#ZUBnb_rflu|E`Vq9jqWf9L!7{qNQ5 zagXbMpX+@Mz4yf5+#Pq_HQ?*M1ks-buE@v36ODgXB-x>3*+AsekIge>kvZ!tH}bmX z{&df_E_5>p;2ka})j9+pFo@@Knf{Fr|Ai*Z|ACgAup(m*wqemtUx+PZ{hqrN@xzn) zd`Q0_Doqm54O!OnGPp>Xd~!POS`vho=NAfdHq18BX5B;IuEkKQF2{OTMet~Ss$`ec zxOx%aIN>f879;d}s~WmLGJ))X!`n3Xl{Q* z{u}!RuVi|dgMmfDjW27(?g@d2viye$F|wRlof*WlxyxW@1D;;h0QaLEC9|UFpfo_w zKb#z}nehw-B6?+ATaM+x1@NOGj9jm;#O+5sk!gC7g#Qefa1dFR#YxWHgZ?DI=xI$X zlOY*vKN$uaEW;$e(a59{Xw()_sSR_uYmPf1&@7Dv{w%~R!4tV#6$#bf-9@{^Oq!*K03TIr&v|-Ko7nbF1m%7un{UgOrL(=)&C0elR?~`8{#duI|DC6o*=%4%`$_y>^1xKJ0(VO)6fX{O<mPLDp)PdkEJxQJ!j z9x4*9S~%e+B!F@K`9g!;BC+l51-$PsXZkBS0re)FhPV-mbmyx3c;-zNKL7P8TKIi+ zcHU+KKI?uEeUw^-mK^g$CI1ykv`IJS1fsOX>^!TeDKa{939UImCFkyj%dxO@q8_yf zb;lh8;`xyoTDe~STVT|_iJd2hg`?W3|8TYJz9($f z{6&f^!*J8#g?yyt9h$8zAWMB^xVYy4DGg}FVkSPi5wqZDsG*@dDvX(L`?X z`U4PfFr3^7tH1?*&2ayYGj%#R6aC%PiqKLk^8R!i4o>ogX-}l+%9zP`OvNhx)a*2> z>F@`6=}dynZLTCMs}cWx;fXvK6$?&#-z`|19)O0j?6S8@9k{FeeL?M9CaK$!hqDHb zmSA50g%e=rfy-u>bKWWJ{y$q}84yU5o zr2(k+KI`LXHpl88vtYR#!=mWR;t_IDd~TXn?$+WuIHGL_2a%`;oaly-0}SZNat#SFjD1}SgKTk4|-roNBImyW$VX*l=?j~_wG|XbwVd( zGmY`l_wTsbM)%RD-YF!-x)Ep%)i%=-OLVkw|KcE<9@APa0#}uv>x(KW=&qmAbZ``)@}afBU>vuD;`6 zfV2C+TBe$0{mR1W`XYYox;Xk|I?K=A^AQDp;YiB)ZoI6BX+%ZE!uILw#Iu9^(PI02 zA$Xk(=hC_eN=~_waTX1@I=%+Js~(~WZdT~kH7N*Q?j|{#SB(q?7v`;KG>OYORX!i& zmBY#D#7gYVuJa>yo&To`J??9Z;=&~B* zu(SMAw_4n}C>W|o%2VOHH0LsZ2dJf{kzF!H_)&`o^0qD(de(V}oL2cGRkeIUDcT0h zlqEx;TMNnS+<^C~cOvEI|K`;PlOBP*mob%X-yrrb34&2~yL~cGJg<_7TaehgQZ;y(bewbUYE$ROs!C2 z=~~NtqmO`_w16(&ID#uyIt6>wUrMr4ZBrv5&aaP5s}ASh&Su`*I(F|)9L49DzWmYb zd?EAfLa}RkGMw^mAwSEpDTPa>cINLZ$jcK13IpsC!Ta6j`xq(%GDXQ1q?P$0C(+h z3D0R-9st+P`^XR7ft(f7*O)?#Bav1 zIib8nNHlI)&{E)s7VTg;V}tCuUDiI3bmRen9TM1NHAp>K^&46w0DMV^U z84g<$1X@Go>Fm+|oWhW&C|1RgB!2&jm$!L9%8{4kbX6vvlJ0?iE@D{GLPZBB`6C;~ z56|Vzv8*T=t`BG>wobv~BN^d*#uu&J(`V|SC2S4ElvI*?znG_0CkP&Xm!rz!8t#Z% zf2ggsBJtg=xawXYOs-((dbcw;ggwt&Z~kF zVYzwEsHj0+q6er6W*ui|{pN0w*g^EzMO>R>&|IpyEcJ1~y_D_YfH4&_&`3 zd&G0zc%TnmC4$kyvE0Q5U$odQPk4P%5x*>B8rp^y65_IsyCghAFOJyn%~PyX(hk8r4)nPBJI;MzDq3!)CBf&IdUu$3`2*SI z?~Vs%%;gt(gi)jU>_xC? zP6e6#L%^2XZ}P``*|)FiC%XK-7aiVYEt!GuOz?qTwQlmCzakdxH{b(gLa1SQGU{{l zK!&^6GkJRk9&W+$!}OC|HJ zm0;Noi0}2jO;3OsYK}c6eoUnfOTY;;_0SNf8_R| z9o+;(ig$Elw?iI?IVdH5tI>=7&@J_RVQjuM7aF$^)<(IKJze#9+MH@AOk?>f#0s6i z)(=)WxRIFJCYAXH{YTe_P3t3dO0Ut5# zK!XOjNw|fGOX(2oHJ2uhT_+y|FGILYXEGr4<-ICwfM!a2k=&A0UiER zo!fu!1n4EaBwLm-5A0}9RJ^!U=(y&Luk`q$AF+9Y!7)?ush%VtLtBaclX0lm;W#u~ z{KIE2#&Jo9mkL)nWn4SYAL%fyTE&*hqG{$KX!ng=3Aa$p#lV9aJ!-fxyLeRsn>f~>6FK+tj0hJ5-(KAL7 z*kRNXezkTgE&q^@cJ^0-h}%}A=UgiejP*d3A*F(J$AcUW`5{wTwlmr`f%6aA1Iy~d z$>X$g{8jxW)I~VatMjL$H|{?Uq`KlcG?mIYDiGX?i!yWL)tOed=MqTl}G zp(@Z#qQzQY?t#{SDwX(NJ%;*hN@-2)oGzm#we_gDwPx%5)O@_DXEO4SdE z-!rd7_F{Z{YZBymwvz5W!Qu{!F#hK+t=t!SbuhYS6{NRTO1ReD7J=|?1M^>W)Nm@( zWuaBmn(SkH`OSp^Fn87ma%cM)T%72ECNz`^Cs*|2ra1T_5t}hsV;NS}Wq;qYmCPyk z5gkl%LbiSXxK_<_4=DVr$a3rxu%OL6BUbVh*{h%}L=C=LyOE*kjCW;yH@=fUlc=9P z;u8(bPjsS8XdOO|%l+zuqV6%R-4;bm&L**L=r*!n)q;Dd`xG5ud-fK;R%}1{F08cC zrDuf0IEVRFx7*26`;&8#`K4))9TH9wKUCqzsll*m{U<^!PngtQVi^hwWdawylPiw$ zMN(Ju1;v(H@fgb_`0;~vj_9XyKgvc!8|&v10-s{1HSfXC&w>6v_m<Wg99@a;&i6(Bsw^MiTX@cx%}KDR ztChUZF-2=)I&o)AB^LkL&9c$vax(&C*dBb=8FT}E45#KyH zk8j=-K|gz^quWEL!T2w(Bzr&u9>{W*q&o72D^@d2xY0@QBD$4ja7Ci#nA>o-XaT)B z_^Nnd`VIb_SS#1a&=V#X&j-U_siZZm1UtT;$7`G1q2x7WBOrPpXiU*4c?9U^~w|fz=%t` zq4{k!xicgica3442w&srQsxyV4j+(oAR_OKyRrOIU*w^~dNIyPbE|KgLfczcGOw;4 z>snVskj`Pcsn7;VyZl9MDQ*(&mLBWHxNR>_Pt1$U@!!Jp7WWgV+Rm}i>@yc8vHSZ! zeAcVJ3=Qmj^y}OV4#ioccM99V8Le`IFNOJJj)ZbbWFuN*13SOqatBfr(n;`i}<%2lj%5>UKHIl4l>uck-dK! za76hva8G96m(dC$={vs2f@RW@#6z6?4sU2Hen6aOj8#j?aHs%;)6TX|9nYa7iHqvB3~3aB3~#jF~d#=v!E{T2Z`NzRjk+; z%HJtuxmyjjV6t!(+)Ak=zt4*CK51ESGx>+H^T!23z^Ha|0?uN4<_CHEDo+SLsg376 z9>^z48B?vruSM|-9g+Jxd4k*f@CQ>5ICXa*wO^iy7nP}kMw}b@8Q+MP$c4ZN`!B?^ z_?!5ADa$vQ9zxeIZblEs_@KwkQy*=ph|fBgqAEQrGT*)x&&=$a>vXQ_o&U{OCAT)W&2&xsT6gHkhUS$FSOw^tC{{slrP+R z6rMu@j3KtSLZW4T659$2Y#y$YGe8Af*&g|oHBnb@!%r`G!<27dNy@E(xZ&A){*hEF zwOjKXfy-3*dCHCaKGcB6wlYn-dV#Qh;!KmSEw{j{-vVl*bw%9&z&w~R?LJw4umt}O zn!~?56H8~To`cGwhaxocuw;jYPX&Vk)6cKHl7Wr7e9&*^k>@WKirn5zgI{+KkRidX zc#=^ZT+f(K`&Raf6jfsQ8*D}$YxD=+4z+}WB{dS6Te~jA z!_B-V;vSZSf3&Ofk5dxpYokikylp6C88S|3Z!NxIl>?7tjp+N?Gr8D~&2Z2votSwP z;@4v$VX;vMx!)eeW!Um!#~AIZ+ENy`__ zJj!x7XGV+P9bL<3SNKz9##uTA$%56hP@=T47H=zg4=?qP(0LzCxtL2XkmmY|EL)U? z&(&T6=_9?QCL)wuJ5~nV&6bj+w$FIrSs&EPdY$UFn~D{mt>gb@2T+CWkI~`0)1bP4 z2u=9&04q<9;de7los$ylE^Z5eH$i`hYud9cr<6r->r@1}!2FozCca3T>5()OCW&II zg3;4}#}YmvP5U}D|23d?O&<8c+!($-oz1Swo1sj0EZDR8@PB*OMFwdN5RF&#K~it?g{vPAayK@6fm-H6@@RP;HtHVEuV>%WX-}o0 zVX6-JYNwLA#!~DZQiR&Q4GE|H6<;}Z0W|NtA}^9MasN6CK4*L!tv_)E&6(zd1~aZ^ zlJsJHWyK?~9s85~ZoDFX7#hNFP}0uLyiyBgQOhB2dlm8b5aY*=((v=0HJK3Iiv5{} zHd3yGC@(pS%Yf&v(lGj0ISc8ycq3$(FPJE5bR~!)Jq(Y!3G5hXM6vH z3MhB}n>i1v2E*o2-NfQ!k9dHC3IAFYLZe?dp=dL2q-2~gtWj3P6-n#(@YFzhBtjak z`CN=N60IaNXCH}&9MxI0x%M!=uuli7$FOInstPCE4+DLcMgQ@StI3BC-sl|jF!njr zipR0N=YWoTUSSzDaHF}4yjtUhmCnxOr$+@- zqaWvyZOm|ZsbfRjHJSF9X}0HHV?MRG@SHi%SMz3qKTYi4iDsD3hany>$cRM*>+vnD zyXP=HvCsgi%XXveU>j1fqYeAM@P>Up--v3>AiUmt9ly>sh2CBI3>~|r177uRBs;hP zzgO}>;_U^($uBcZZXEi`+ke!|y|(8itVy^D1@*>scIjpDlF!%psz#>Uf64lb#?J*i z=lkUQ-V!|dn>wH1>_tn{N1%Qyl#$^x2ciFaX(90z%NK2UP2znsu+#|FCt|~LW40BF zUcZ?NkqUT@4Nwno99u7>aU_9|6Su7nRf2KPru>lvYilQ$9h|;vhe67Mtn_5 zEQR~tDEewEaxw*pFTgZ1oatuUiASs>t{?4#{v0k4f-#lFGyxf_m>o6UM--q&2Msoh8V$s58;FxQi+e;h=gsGon&9jbZ*75 z{b-OVUf3S-9w*t|0?+Oy61OM`TU{8=yFN^yu^lhaq4mn}{B*eFyuVX5hjk{-p^nPB zTua3!2=7QI+mi~h*V+Yq->!?a>mr9b&wHbZ!A$4bW`zS?li@)}2YGXK3%1$Pg39;1 zk@BV{Y~$Ysg~OcayLKOORBoLCiAFdAV?}Lu6DiDU;yDDC*yN1{57eH+{hNFjjWT1Zw^L~!6#b2JZ!MHU}^z)g8 zoJI3dFfM&1$ryB8dINfFpN-%n%{6vDQ>s_NEuF8O>`Fmi??rZ$d*IK#$9h)HG<7n{Jh#=hY8Z2!) zmmhLDjw;M~$nCcAMVfco1oQC+xGCM%U{;+$Hmerk8GYUeFDMXHSNe<2rmI6t?+Vfx z)`{aM)Iiv%W3=*a6~{FOA-OLjh|bh+IDM2S^d`&DJx-VLO2>hq{=u4DUDAqIv_?UV zbhiX!_Z{>`qwNYL7#q~I6I|0GNU=#d4%4UrA4f-e;-e1oPO3-IlWj-|n^lGkd;o7w z=+Ty;yD%Gb_{w)l^!${sXyX1cFkkgMYf*J z#MOns?>!q%f0_iMW$V0=9sAAyn?%hS92TLCXET+Q!!5v3$HH~O)# zP?))9rpd>9-Fz?eNBF*CeS^bp!H8uX{kcC{oHC5fen0O^xYof-mC@8pM@cTqho(S~ z+uuYCgEKJUypdE&fzYd2C_4B}2VB^BYNvK9e!V7|AD*O@J38<;T)Dg*%x~6^KPg!_ zZ=nHyXHG2LEYCbE`YkB&3J`y}Zrm?13@YS1$j@Vr_!@gY$Fe=$k&DvYBqt`2jdCNR z_4WAt*kQaBNuXB`-$F+!z9Y|N7bIG&-zWzb$;_jvRSh{FI)<=dM+Di8DzS;h74U!e zl_bBN#hugHhaUUH3z|;v@$S`e5IDS--%%MzjVg?h(By^urW6Pfa@IH`iRtHAF4^%l z7I@8*x9AxDcV>TZycJTlj?(nyzG7Y0wXx^8R_>>PfiNZ940e~Lk+Q5Je0FvWJiI7J zHzZ8wLRagdl?lF*oa$Zd+8(*b_LY%W#Rhe&`LE9csA+jPirFg-F1leP$moB)2CblY z`X~(;y@*@Y&k4HQUy=21|HBP~V&MG|ImSQ7a;1Z%Ks0SBNx$EPZ+!JaI?TiJzq5Sh z+m-yN6aI8*3_&ZZk3&_{5UMu#A(nmn26CC7V#cYXXo`gz@3`E9-rT%3JFxRQ*lv-d zCFW*mkGm-x(~KmazrDb2ir#3-?gAnF(L_d}SsIeDw(K!}cjBu(qhXZH1u{3c0S8UE3IHrFUZ2Lx|N}I-35te^|DeR^ke;8 z;X8W7IzEPc64P+%Ro9^*Up>+6rELD3sEF$qt>HmChG)kt{Ft*}hPCQcx?_ zez%BqNqbSzgq7%RraBlNOp)xfECbp=#rGK9R1FRU*^uL|OnlvBbt5HhA4%#;$4V!97O&g&I(FcRp&bV&S&1J;BlyFmKMzK zb0Z5#J@yavLZewngVL)RCeMF&@rkU@%WPL2sO)ToGoBvw>(K^rK#C#QYp0Ruqb2y^ zRV5Vh?672xJ>C%jV`7@fjm;T&W3CqpI$0>_x)h3*sOdmtmle@dYQ=*pu7e57Mwk-O zBkK5Yg+I>DhK;(v;rNfO@Z^0B5r?zRyZsM%*F&r`eZ?SX4tt9h7XzW>Gv?-nF+1!> z@dubmB~Cw^r_x z8n$m=u?X&tODEZBMfguk5cH<7{FaHMxmd&5DCxDY#OoTB;)Qy577FH%uZs6tt>#k$ z18Ld32t?;d!5`BwV%4t}7p!oE9D{lypZ6a&S=|rZgO-xLH@dKjF4J$v6bPkCref#m zE^z0;5UL;a0H?{lfyuFsG}6);>5A3(TScC<-}dd_%PmEj0|BiZ2gT4=d%Y zkGiL$Cbc?rhrNUU!`0#=X|PXDkLqRazzeoz@;8rYmS-V1E!L5(v&EO+=%oHya&oa7`YNWZZM^*SieF=29 z)-9AG+lxFBE=Y2yGV3sGeIcSN@ye6!-k*Y^1ZwUvN6}5w~q*-yO>$317;3gwQeey!ko35dEFn56+za zhldB_hw*EyV(8u(=Q-6y4sdx!JyF^BA1-1A*H^(X7X zs3{a6-&C9y5rhUMGd}i)JQvgD1hixb{l51B7Fjey_DCn%?&5+DRhGdhrqkH*Ze+H` z$yL17s#I#SQ3`yP@z5_Iin#r##Do4aO=dmochH(73VIcQ;uf*|7KWKW^rB#dk|A9( z$^%b2#PjB9&#BV$0nmF~1BTy@AWKHq;NwB&JikAI?wO+lvD*8=c-RBdF|q(_6?>xC zAcix>{-V2ghw=xShDP5%6<%PICie)C76$#~aYF{&Lh1I?OIgNov9h=ofl z-uCT2xM=9p#M?V@eZfdL-rt=B%xlCJg^`f+r-$4bDKGk8*T&hoMZ&;?hq$jYL1<)K zfq>6fig&LV%KxfMpkd0=(8jz}FIis1|NQ=ah4K6Ywtt_fkccJ?e2j)h8j{sJyYaQ} z=KwvaCuPH#&-8CN6wUiW%$(kG+qZe54?~J1co;GzfKN5l&Ruf825zOBLCTwIiN{|z zCZ505qLnL5mIb4iztJPkmK>VF@??^{;3?ZHt<*n-UwqQ%=MD&>^%GK&j0x+`_*y90 z-Jcv4h)y#fLBC;kCV>rBX!9UNqCVj}c6{mwZx(9MA>LW|w89V&<^4OqPkiDFrO&#E z)Rk^=^fe>?%l?aW%;g4TbIpT!a+ueKVPJ@5Ao}CXIE^g^qLT%WQQj(RB3;sgGe+Ek zcSQztaHcbkGS`G0yGZh0z8Vj14uF~&y=2+eGbV$s1)#pWZ-w$EC$8x^^X^S37Ggu| z#JDXG{nRfMwr>p=1&td9{mW8Fz2;NA8Cu}Ub*A^oZs*pi#3Q#GTI2`Ip1mV@fcCT> z$=;}Ml_^szkKD<4Z>MnSO z_7!Ntvz80w`Njskl|5to%l={Gi8Fy{|Fr^P*)liI)bcIJvvXFhQKNXRkv{x>mPWcx zmtZDr=5qqHa&N2rhenwVM(S2agfRl#I(@V^1* z??={|zGe}=G$D!?KW6?)=U-5Ba5J3IsUwOq+4ySlYZM+2WMX6&9#a?s3Edr}wCpgh zi1$Q3%|*hd!7^NCYXG`hk}s&^DL7PaD1ZJ-0)6o&4yDccic;VIn=`w6WcmA6EW5R8 zoLK(mY%r6LB%>N$;NXBzNGtqAz73hq{mHXLwDPuuFLf^pK&7$yLcV{vn6ntl`XUqQ z*qtxX(>nuUQU3_C{Yee>{F(`N7w1rq@iRHcv+LlmUZ!Nu?AILyI}i2|q zuPzdfHe2J@FPUyUJ71V~*hqX`+<=}Byg+WoG+|>_SpSY`9{QhOFSeJ9=flFaa?k7y zfYr}<7+jSuIoGebcM%@__luZ+9mnlUnvELl1BAEro!Ft)6Xi@V7E}&Ji~q|CM2d`` zTp-JEb><(`?_L-Q>8Zgp2CDK;2VbY5d1twlXNO>Zay>yV|KVf>mhI4Vo5p@viu!r{ zMh8rmk%^XFc=cvaG>-XnE;pHqbq5Ba342-ZXP!KFJ=qbw>xa;8g9q5kv=N+SkI*H3 zN0Bluh6|HSXv`&zY^h_c@A!TqEqC~de2xI954$Ys0eoM`ycNTWg;8XZs3|c3Z9BpE zH`W7~az6rO2O3h-7I(bv_*nkcnM69vp&mt9j({=mBFLAaHF)c8GyYr4UHaKl8{~fO zh47#Uj)pZw<3mR2{8n?VT(jfzA;(7^`jD+;{`{R11{*GaCOgJdivKYGY1`gn zq4&xJu3vrtYGQtnU%Wgn999l`!;aG*4`v`7Q;j}n*buQ*EB>y04~E>NO_xaQsxZ-UFmq*q}bW=md#PjBi zTdQi9fj@D-(Xb=7B#Lp!b8dP;qg^{0>~ISE&DZBqav<%ENkPhNCV%s;NN94>!ABwj zPzl?uUv;rH;qiW!HKRyWp7&vs$G-6Em&s}7jS-1G8 zl^Gwm;5u!Y^aVMO@Id~53nf~q!{Y)_?nssq7o{)CvCKsZ&#Z}iUkm1Ui`)EcOR(v_V0fx1Pmh&_ zaYoMuA+-}uk{LD8&JX54Zze-0W?)}WPjo@MMB*uEjPOTG+5I}ZY#}}&eh((Ee5p>o z5qJAp1pmE6D|h{bUod6uCOBVTC+T2axGos_n9eyNx|s{8Xhg$T@RE6TeN`~*3T!7{ z@9c5Q0hYtuS1cqs%W(a-`Xhq@Z0DY#i5ngc;hTRaP<%fQonF?>d`<3>zJP_zGW;%k zcPevvoH(9wHTz!4(Oaur&^gapFi#Xot_v^lw7w7+AoYoaX-?xjxm_r(<+hMM?L8hy z{ShCYFQjOPi^s?-^AEQ%OxApXencw5@!1hXKcxnTnPkA~opWf#tr=V#tc8Q_nUa}y zhEXIW9Q#JvXI|$T)jiSjbH&1%92G^^Ik=aO`$K=72S5E&}`LX*o_9z|sh4&9`}pSypZsu-T*4jecL850`F4!8es z+HF(*VC^01oU#nvjs1zV<}V}H8b0AhIZvc#RV-}Vw@|FMFaT{@Ss>hcAjkFkIY4da z5c*Kz0oJsyflId!QrnphC}l!0gci%ulu56$c3Q3E$IVQmr)EjR_PGdFnOv51VJrGD zuh8@oiMA^7l0UNC$gacpc04K~0vawG(HjjO*kj&k-oZD4E^K~@_Ufra{Pzg*qoNvH zjR}TJjHfDy9>xiVi+Bw^_HQ<8!>*}&;rqge#KErsZ`5NwFSnWZWKe+UmYqN9&opVa zC3~;~$9QJ&rS}XzaT?CP$Vho4QDeELj|Q=B!~^nlc_yfO!X2$@U`cXxB8)@ad|@QuyS$0T_t|xp9H$5L<)xAoB(sP?vvl?rFg`S4mh9X zK)0v&aO2n~cDIiaaTRytogrtyZ$krVt;)d0xAl1KiL6Ub?1>6TvR>4r65&IlIo99h zhwh2<1hr_V9Gf$~yeZPoo&LERqB2Y&`dp2KE9j}d$r~{}{0uAu!C^np*ui#W)3{dL zHQW=DSSIkh`KR!v1+)2Y@3E>! zvBko0?SZ(zl0UknS|E&@q%XRAi=ZZX8&X@>f}477fc6yws+@Kdht8b@gJhz}Z0a zwCza#uvV@p{p?77nsEY+`g00h zHEKn#``MB7ZLL_N+!q2mWvG>-8veF<8Q46;nH=khP%IF-7rS!HHH%@N>rtxqtWZ4bz(`(yd;(S0k_U6USZ8q)bqHl z>^&T3-r?s?bGZ=fa6WN!eQmY}x98>~l+mO$jm_()2^tETj9Uh9*9+Oo{*SErFh~k3;zuT`XhG zop_yZ!k3j~_@pQ9^lR2Q@yNbFh^>*M78TA&Zo4jAa)~69V_&dY?h?#S`%FC3r*jLB z??f(PY~ZQ5UYNvLtQH_kQIlT z@T4_E`T0sQG~r@~_|meQ{HOa`xu#M9uyGQCNy{_HYPTYMN5>HTataY%iFz?v$+)#$ zrGj90P5c)8kv7wlDD5m4J^uI|84d`S;I^Lo9oW)jOjq9?#$^`S!jDr8l36;Vf#YM| z$5YyCj^0LpM^Q7Dk)mavunOy3+m%%!Oq;t%oTTTELKYVYTer(`M-`o5kBchZ!)IZ6 z!)kc%c8Gf2bwFXGf?(VamH{>3RaQuwm^W6@%Kg5K@x(16n7jKj8B8kiodi#`^&`{C zFV_@l*jS>W4cCN#{A_%ANhJJ2^Jv#KFTC{bNIuvmfzH|a63res9D1ijGK{Lm)f0o@ zTR(YP5jKqbxoQv0>;H(9cNSo$x1K1-v`qNy6)1YJ%?}M@TF@ASJ$RjT5m;s(rR`be zocC@YWWMqrR!?C&k=SfS+C2OQ{&O%8G>5TgxOX^;*)Rb1?X)ALtp(Sqhk{%87oz&3 zQv7(ZCwd}PChX3b$gN_U*!2tYg~;)8IM{A5KWJ1UT{YPr4Lx0fMs?Z}_1IPn^e%7= zt6f_+<9QB&AT>pvK9Ds*9|U!%40I<-PaCiX^D%un(@uI^q(rw=eUa&M)_Q># zFh5i#k=qA?~67q%@d-I9?99#--i#Jpq;z;L^Z4&%fmWSBhkS++PA}z{!9z! zW`c@oA3C)gngxP!uAb=0XaP+<%`{hRW_F(+1L`{rDEG?=Cr+OT-_}M+Jh_^kzEJzV zmwdZ&+T>(|5BgjE4~PAkhnD7+2@8I`5?jvkL;H6W2$45JMVEICh4#a#Bt-ftZi=V@ z#Z`{fv$mO=5D<&r9n>Zr`CsrGZBO`mwIAJ=7>HMil)>W8KkQvPkllBmGGXA3sGN7K zOJd7umU$jAnfvr-Cgep_5*=Q^d!N06`vY94yMYmM33`W~ANYs8!&`iye7dXzdrv7W z;jiyVrKUT|(C<$Z;o4nyqGH&9O-#H{+Ky+!>>smDDir+CiZKO3p|mUa_2Ek}9^pYB zPI@IC;H<&>CMB>OIeB<9N*7AjrIW)7CD_$F5OTwqKEE!E+dpz3n&Wg-GCv!i_kn)g z8`6G19eb-W{wktO(3n#q8pN^;7V75<5z|cZCzZjx$?QbhergxDMKO%;sMX4))<5C; zlJ!t}^Q9yM!SZ4t7+jO5Wp&NmUE_K*d6p?LQ~iuvw1Ob`LI>GWZI73Y^*}4emkLFZ zGThe{zNku>>GnTP#+^S0@l%H-(!7;%NXfPnP21)!>Cvtgb;6-dM=58lB5vHnI&>W6 zX`8bP3fnRh+A1PRN#+aO%FYFA0y@dc5mUKF*&S#@!5s+?+~v=Hzg@ntd})~2xqT3? zER{(As#l;VXXT-a>4FOXtHFAD58==~6KXE2&;80;1xpq`kZ>AzR)@jGYrVwnOEed1 zBM(Y9SCe%?pRnp1A2jM%p0KM=U;JF77R8sv|DiU-8{OtMwP4dvVns$8%bT-e|YojIehZ`8?-nN&`_5? zwE4v{GRXfEK71((a%?+@{k%Qc_dUy`_{4l1B?GvJm4~4_OqB*}X5rpl)u7SsKx?xd z(VvpXFx$+SZdst7J#<$NpQxsld+^0!$nY}(m$R3NgHt6ATOJ83oj;HlPmHw7M^sB&u+5!Ip!xm_kt?he&pYOeOjfYjUP%s5dp(F> z%=odq@d+#oseDZHLJ{qYG{(`$i>lLUF3U58W5~~+zC^g}JaMsBJy0c{tDKPzltGrLai?V-s z`(lP3?>6lsJ-OKnl?IH2F?;NYk47tgQsaYmTmQq`0fIMwW1@C$y=^tv-UC>bR6}O$ z6yr0a+hOWhM|#D>1kID}Ls;65xLj<(t{#lrVHq8t9|thyNWY_=ig=UcGZk!vtS*?^9n?S$pU z<6+^#C^GJ574CcJ1N#em$@`zDOir7#{Qv%M1h1ioxxTZG5MKWu2{+Bha?Cd&H@`sG zJ2h0~A*&4k`K1!4sxsU-v<43JbE0R}-g5C>F=!&MO-_vag8Tk5FLR(2Eq7*_>Szc| zd}~LlpSNHW+X!fB`9Q`_y(iY9K1k~^({I~N=47|cfXR<4$zlxwYuMJZklCYjz;gpM zAHP9=W9&%kYh^Xl~^ z_jOdygM+M@LKwgq@VfSL-_9zmHzDcZ437l@!3w>tJ`Zalhb1{6@IbT~Ac`9IRwh zk8UnB7HP%xU%a4te-|;)w87S8+PqWD4XVB62|7K_9jz|Q7hc~m1F!U!=ktdrP)GR~ z^!G*=()At0*b1BXVC`{&I;4=-y7-g4EbH)#-8^NM0%6~ons zM>YuZjiUMW%#$#A{|)e5YY2;yo{(FMi}4-jar{khSGv$4o-5j_jpl{~3(qM1#;ctJ z;ADF%S=Ew^18=#bYu>Ei#-Y^c!{>fPLxYK-d@bg~W1vG)pLRGXaoQz^Vbif@QU7-G zMQvVL>ke)5;n9qJ-%wBbD$@DB2dkdC3F%k6h+WY>Joh5YhOjrdnX)w3cfkhqA{A-R z$1MC-S()EV<7wp61oUe7Q)p5(ppo(a<%~im{867I+B5q%lD9U1u97g3Z{cWc2;4RP zNV0zGbEmTRqNA5?3%h#-_>p-qWCiNcJ6diyMoF3X%#Ej$RO(ScnIa4c8pPGV-UM)- zF7@(T#pzdN^Fa)^_iVfatM2as4U$P7HW%WFMtc0q>)v!?#WED;>WDsGZGwbaS3N0+u_N^+6g}#1G|-=Ooal9@eO(=M@^yxUt&y4*Z_w`#AkY zv_Y3?5nskY-3(`u{_uUaH{_4#A<`QqjDAr!pZ_g6F~;W$}!x*Zn= zxqwv37ZUg7Dn61n4~BFyT;&?^Vb&r4b{_ltGF;uHu^T1-97>K!|HMl!yMWDU710gu zP4rMOSmaFpw+mz7<_43KzY#U%Z-RFlR)gLB2y)1x8t?ezhRjA63a`CZH+mY9gR1L~ zk}XN?*dQr_d2Ti7e_!nJf1Z<})H;-uUZ}#uHrs)!Wj3kbQ-Gg0xuF$53xqQx0*vh1 zMnJ}wLB1-b{u*{uTdI`W!nrp`p<}UXBzQ$1mWgx$@)%%->@QK1MT=f zjbPYV`hggyCJEYqyP6idI=0dUE%4& zcVyFwRQ8>&%NuU?q0^;VCk^v^AKk>d@wfB%?w=0UJ?=y27wL1VX8ycPFY7RTIsmg5 zZGgMm8$=p!!16>sAWJpxARY?t>UAhJ(U{2O^kP`#1*`vcktj18oO8&KZ&2{3It|%q z@_9G3^iY8?;qVNsiiYy3v)Rtnhr4LpoeyZAz=`ZQ{01Mt*a?5KPSSCOqXY-{&jX*E zq2%f33hZMN3`eK_CI*aK-nzR3CEkb=@zV9|-|prQw%7JEP_UF6%7>{X(2$4a=-PN` zP-NcwUuHG+-kdLr(r89ldN1hJa@av{<`1ODI{S|-MKDv!;2usEbyx3NPV}Wo(|0|=?<~}4}%kpSrYw;6? zFYfAk^j)MP*Zck;47uJ+DpqIV26<(E&kk3rWiSmjsrDnsb*o9O$|sz?I0Uv>bP+sb zAD-sthQ_(Gob_8N?gh)GQXNG)L^TT!PaDf;ykg!DuLLA_Ko6JbL$zc$xnWX?zYLEA^&#JhOpgh-CDskq-!BmQ4F7;XX9PjQBYpa$(hXmX z9?LIdxsOG;bto}F0fN~LMcTX?e<;cW{p*Iba?Lt!+UhL6nQ0D6Vt2qyZ#U@6WsxJK z5FcHx%O7ODz7j3Vkg2B|3S~L9ky86`Ur8f04e_9h?Yg;ExxbSO+ZJB^NR z%)zPK6L{G?)jV}&UGPa60zWQV5#KxQxc#&*1V8B`0mmu?_l9ZnCu+TD!{iq9Y!kyh zmOrX}CXN5BmE)r{6DTpUMk>o+qL}PK{M3s|fQyr~=)oC#@l}a2aQDz4ep;CLLE5Z- zV%aTa6tRT)!bh@9rE8f$Z-yMdg}tX@riz1W(F6#SOdZT4%=idn7M`Ul;lDVamY%zJ_p~ z)`~QNnL4eI{M(jlQ+@Qop$|>nXhmWejzvCnfxMqziD{h!zUvkZz2{}<3FjHes%9=^ z@y;Y@OC#2-a7AZg2eGt!n*}n`lNb3J&M$U`&J!vkj%xa~4W#&!)H3f1at)J%h33wp zy%>w9u5fSjcQU|#6GTmmhU+_I=vv)XD00FosO*U#R#1%_Pr9L9jfFz1@r#XKDrcjq z7RN-I?f9*?AacwS8u{8Dhi#Yy*L_3DG1k58d|HXuFmk5bl;n(7M7pERt)0S3lha)P zZyR_~l+E`33h69qcu}K)28Oz&*l|=>8uy60@rh zS6I8iLmf%FvfU5Y-5(AQ|5_2L?slyED;T6}yGf}}vcOWCWdWQDh5g(NPU6EH2w=T} z|DFi3QfWCHh+_Lh(-yPsqZUNY|3CH~NQWcx8dUqADYp2^^COohQ-hA@$Tf8`{8n`) zmm(T*lv@bAN$(*t&MS>Nid>Oc8~Zu;T;&X_E1;#>iT2jk2^>tv@HZLu&a9Jxt%V#|wGtwGoe_qRb^h8s$Jui_b!ws#WMZ$ACXJY>Yvi$OZcq%jX zE_#^Wi6(t?BKbSsU@@x>a4WT^>lcm|RIHr~=Iw(x9Jj|08b9`v3q~wIyKp-?mlY?x zAoCvEu?)gNnL?r0{Xl{7Mp@qBay<14C_|p#Bv~KbO=6^8gP&Ee265d?vSe>D9=;|T zW?f-DLf(lSDwP8Bqw7g_MGyA3bw#K56^OWN>XO$8)jE=sN^kI4_xEt@fHUO+f&`Z% zBltpgbM%^i1Hu#aU>`~o;qY3b%lmzcrAH^1b8k9zk=opFVe4vf;RX-pf7sGSe2yjK z#q8hi$GZZdQSB?E^WmS7%a1`#py%vuNc*Elf66FvZ8I&QF0Gjyo|eTr$NEs;_SNLx z{T?h~5DfW=U1V7AUL4-+iZYnC@IUNr)Hw=S8x-jQsVp2hZ45t)b(c+>oPeB@pMsM# zqOSTXIre=SysZKA0N=5NXl*@MXBAFX?5)JtT%)1-`ER25-wG~a4*UK+!Lmz7KH%-Y z10eI5J~gy+!?`U={6_P5+S*-o3qi0A{BGz(C8#4Iws;YTg^KL^- zo&~tC$Rd7Wg}CaOK0mw1k7mcLL|voYP|@l_ktR^@)Cet`J?QP`ZqA_82~~=#kP7{N z{3QA&C^}7}b4qhCyBqV7Y#*U5T?dvP83GgT4PviKz7MGA^%1+8*Mde*ZQd-(o0iOZ zgJzEXAAcCc-k2}4yoBi>_M*TS$SLeNdBN^YzD5afbIBm~_It(ij?Al8HRBN6j#Gm5 zR?Z@AR^2ihto>!E^iU-u1^G36j$IV(y{HHF3T{Y><@}8$?_*Z$5ZZ?7|89O zz;>%s$n^XdI7aIun3kWVZL@xJjVK2x6l;?MPG7M7{4;RpYBNb@TNUS5MMK3U87i~r z7pD;NAJiIJk=MK0@reOf^l2``x0;i=J*iH-k%n5{)sQOqHO&y-B-V;F1V^zxw443+ zdmY=c_Dxr~CG(w(ZoP(+dZWNgU53_=pMget%>_F{XA+{>h&?B}AvKmsk%S|L$IW&i z&zzBccv^z+;tZ9!)RH$!|(0CiB`dYz~jFt z(Dag_kH@V-Kew#_o%{%5=u?F|=DDJ=R|r^b=9f=jV#z;>yy7?Zdni5y@rNT&mGW$no?vsp1>!bJQKLqG{POWI zcxGZv;?vr(urL_x_Ix5o);<#W4{=2XEbn6wP^Ws(6Lbt2M63jpdT0 zra5q$TPk6J597dV8wIyo6nTZpc={?%1~xj*0Tt;qQTI#wfjAyLXSwy?>B!)(G%B5S zT9k1Z70)^)MzoTsiWIzx)8d~z@ut#+o+zc?1-+bKD8gaQ-}R7M@-rFX_uX>U|)qdSY3Nh{IvzRlnnf(U;TGtMFb*JbT z@6m#PCxYO(suI1j*9lp#n8SQWVdR)pC0=L3~!dU54-yClOCx9n=BJH=JptOORl@#w~sf zyCM+?60(u;91FdioPq7 z31D8_(WOQt>Ju8dG(^Oc^^ZjZ^3|s&jg>e}ll>4`(oAr3Cf@h+GurfSH8Cyf!Eg2l zLDc+ia_aqFteeO(HLRQ6V~;fVv;GjQ*{n$W@-uPvR3(th^2AHk>lq z31hBhkvZ0k8$S;RGt=*6-OM;noPGDbc~dCT6H+#^9s_+(YS7ZdrEYOV192+EK;O?4hldMP7)Gaxd=8EQozUKJj&@!B%`K|VMB66m5JTNB_{1f9SghGX-f&Ow zZ&ToP{O?kMWC(H`G8U#cS&vIngr-kOQD{ZvR=4AeVJ_fM%C>SWuj7X;vq3J$nHbM*#C7avvQfN9 zbVs8(+fZ)0yvWl>)3IYA#fUPg5$s_U^lhc`G3ft z>AwWa>sRvM6cXu$L*j6uX&FfVyhXfaEAf~n7o>H*NTf@srlvE$;~+kJq~C;*#;i|6 z>?HOYG6BwYgpwwSDjZi-0+|a9=;jmHP_Eq_O&QWHERHzG6@RjVaPeHSvY-Gzec^&6 z_Z5ja^F9rEkd1jv@Xwdn_I4TTH9AHA9c$&hw%kJ3j?NbO98&H%!}Ui}G+QbF`}NAh zry^?tPup=n)5P3Z4pA!WksvnJ1r@N*OR3@vF65vZ9G_G}Viyri!%E>pv^_N+qk%ME zH=u%iE3%2*2zGx+fv2|@Q~A1O*mX%7KgX8karzL*;E6CV$eF0xHsZIZ!eH|+wmBPZ zX4Lx81toj2obMqAZuZjGu*cVhR!KJsjGYzuQr7e7cvc1~Ce4QRDrqEkX9+eR^?<+9 zpqdB5bo6MHG-^L^TGTN<#@z`Nn%qtM9`Mr{E*Xs-3OZqxXz5B5@^?}%e$T#Vuc&n~Uy~KC zo1nuRAU~QEl!>BJToBSP5^f?ha8s}}zcM?4Di+^G9i^>EV~#VaneYa0oSX_$eL(%! zw&nW71;Wr!CA!Aj2^H$jhI)rE68x(In|FGHws$|7wsJmKoVgWs?u-}m?>cc8b}o0{6x+ z{zipro=mzY95K~_`tNBX?KgbC4%)x|mM}d_Tv&R;2i#)Y$jA1F*u8*xY|M*@Fl~pTv(;R8!S$stLG)4`(FuMWE+taW~k&`l27AZ zSE%OomD<3tE^XNRF`VT}DzWc_V7U3Em%OVo;>31eLhcRO!pli@c-U<(NE)V16I-0H zg{lJYa)5ORZ?8oYmW_mjrJ-ccjA}e0DFgB?v}v4+DL1wE34dUbYF_H1+YtO>J9H;z zkwv68jyn(<>5j=F#o7AjtEiF{eIpIyAyCY-`zt1baWSe61b>On8IKVq=a_CVzR)2c~9`5QRU#rRmN4re;80}kBcT_)m zJ&AcNw-*U-L`&o9P$@o!ae!T7*678mBD68iiVPUAY+7?HSadC+HD$Z8Qb#PW$uzgr z{RhE(o&q$DcM);s)O&s)ckdUGijg&%$^7SE$FvG%3a@iQrbRCwS1fE-FBgREm*Q2O z5@_QmF;MDKhL}5pm^`eJN_8!f|}M83%@nn=f0kOjlW`}miK&Y6?`z)1(RX*WI>?- ze@Sly|I4;C>zp2nlVkVje^%t#)OPH7&jp-+4v=5V9r5>eHFzcFLV6}P;(wc&U$LV| z_~XhE!-vPWqSXoVqAYL{y#^*#D)fF!7S5<@ftMTY>7x5rkkc1w=uvYa`X$YH-5%CO zsVheP+y4lP3Qgdy>n$>A;5E)*J}AvSEJLKR*hraWk29H;{_uS}erg>89al7|@wXHB zT#pL$&I=Rau%Dwl>M-sRzOg#bMc+COQO5?cw}ovnY`9!3+&(tY2;RzpV##A-+WZpV zUp1QFJuHE?M@~krs^Q2zc@TS#uuiZeGo-0KAAq$7hJx`38}j}JyZ0Rr1#_eCBz;?& zpg_R|HIxWwD%fO<~PH!97;{k(Pi3N=(klp8hX-N#EqTrJOczUfkH?25aXq4aeOIZ`9D{pWpYROHwkC zl9r2T>!*CkOdP{W@wsC~p;^so0VQn47s;m;eCc=ZL*v>1#8)GZK(=Z~RDdz{hC z4QjCCM;P(es>GQEez4&DZ}xdn=gydHL7^`3!t&5gyx86a9o<(fyuK?)V6#z*mwA^! z?^u_k(XQfxx9)2HC6^=nli-|LGV`lHFjw$&)I(hYL1e59L3wTjZP@o{%#_ z8$8U@3E_)zV?qIpm)51#a}IJEN3@Za;Fd6{R9v{}iZ^Hp+sLNihgf2z3)(ZiSlFCd zYBXfkN2KT#Lhy$g{LsIf^_hFp1z8r{z?3~;eqj)k7dP~v`_^m7lQTW|r)vPnmUR>T z8+)-F;}WwviiLem(%hvr2cS$!Nu(i*?HSFVo{>P;H^w7lWhuUUjT7A|y*a1 z;s{t|6G{$9Rb&0@X;4<8Mc?@><07tXg99V8Mc6wKcM}?9zmYFK_qlwwuasq5Eb@{) zTO-9ktWTiJ`W28z_BB-cLWOi5?Z-PF1j5SO)99|DIkahI77QOEbkVBZ#{#2 z_?*BC-n#Y^3!e%B$ZPTW*}in?pSNf+`@J2VT_nA7REcC%H{JN z_%X}X@;+Bq!oVn9*fyh{2wn>Cl_iZZbe}CX*`$YzTDp-cvKH}ST^(0wJn@^z3~|D; ze^&Cb0ZH`TopRLjOASm+T}bfRMw~R+1x;@)5?CI>L{8`cK3h5yqPP+ zWy#T!{$T7hZzyPn*pMq>?f7zGAebb7CasN+1efkPqhV>q!ui)`aJoBY!pHa;kw$TO zWEpJweU3h0-O^t|YY~6nnuvX9$L6yi!8S1sD)d=~7p_a;16eO(=5_=l$4-EPjV_|@ z1ue~BQ2W(Kv^CZkc`zLN!16VUO4qouwIv{4??iiIY6TI6Bl-C~jH{^1z&1Jy_O%Y; z@Y%Wdc+{qvH)~cpvUoTIVdc}pnW_@PT@sFv*wISlj-}vdp^N!<%04s}d7{h~XOuqt zx$snyF>X(;gr{Pj^m>6N_tM#upDw4C_haNw_%&lC>`Q4R<9pc_%=ml!0*1p{QF357 z^fhW(yi|n4FC<)Hc+E%hA@>+Q^h}etsPUy)CK)KM-WjP#vrOWNnRs345MC!EfeJR? zMH=5*kk?gbk~riI4t%e`kC_rpx4$zKte&6>*Jg!_y2a*}dO`4=@8s671>EwW%?y_l zME(cKMAl1;i$%UNc_m5y$EZYVxvL!YdWpf6%$sCEM>U?9K7qGviKkk-qPX25rZCqb zi*!RV4t!wD*WP(Ri#)a>NmB`^(b_;#wNTsn2%)>0 zgs?l<3(Uv1lPhN);($hH^jr41aN(RXqd%JOk!~_xr+j31@*5W158GcK2%Uk-@ zA8<|&Q8qE)l7^p06LoWhg-Ufe%zh-F;TBI1wXuxv#Nm+p^#A#=WEy<$(55ernR0Cw zzObm0WpPs38II|9)-EW2Ey4Se5Vl0cdzC<|G>9wGcNbrrx z3G`rw7<@Dz3knmSkeWL$aF$FOIx<~X#C!P-woozfhS=VJg3GTM@#S;wQGM?aq<%pW z#_YBsFGsXvdG=YGvV`TWWKZY5m%74ly{wjZIk*xWc`f*Hzh0z8{L5~EkacJ2t}YH~ zm485YK3S8`hV8g(lnWe~^q0)AbHa7Am-BsbN%X?6GW6M874|o{5aiv6YoeSHyniml zSw{`$-QIx0PstOBH{Wq~`c)XP8Bgbp$i|X>)$lLMnufKXMH6R8!M!vWa;di&U!Ls& z)20ofW4DRpSZmDV^~_(Id=`}V@*o%WjE46DKyY<*zCc;+2_=w{g4b_Dts3dsG8 z0&J_y-s3$b!kPs^Msu#nz~SR5#8UnhzUcX7mA^!e{P~5r{)mi+J_VVT?a2u zX==PU02dwhfgVL!dgkLtt~*GMbuQTwb=eMlH6s9|>pzoaVUGl5EJN45twi|KekN!7 zZaO@ZtQB>MYo8gx4oF-2##@@;$L!76|7jV0Zz9I|F7n{ljZw?9dG-TB3YLQxG_g(q zc7Msd%gc7E=Bb>NgB=!SX!?q!MEUn8ydvKPbj`cTvZu%K2X#$e&B>3-WoDo{mQ|^r zS|W`2J`+354}wLF%jkoC19W3rGn$^|O!!f6aL9-_Fy##BxT}r1A=76;$&GLkH@3X# z1?!gmBnq_)xFNY4(So@N!qC&5IE`~gDCW6vPFRrOlWGtYRW75mcH5zWQU6epc&JFD zP=BGoD>&SyR)Z|fmpx-Oqw7EKQ>UW2MwSHknH8%XDxZrnT08TB1| zE>xCWBAD4(gw7@n;`1vT6+Z849Nl+s1e_bQ1f~aO5WTKq_TB9RrA*(}aZ}@5?Uta- zpa^03Z*gIP+YKn2*G@WBAL3!`Gd`rKL^$n2xzT6o4g}u@`EY~VPDm(eAz{Zeu{!Sq z-k)S>?uSV3b@oTJcj#JjQmY6568gcy`#ogh?!EYot_zyLJk|fp$E}*Q2aNVB(L)on zu=~Oh{NyL?OXR^v7)p*7RAJNRCs4Cbmue*~=iVb9 z*v`I#E>F3RjElCw%IrZLb`QD<`=0$IYWw53O2*CfewGOT{5pV_914WPnx<4O?><-I zdIgPJF7`TkZYTyc%lxWe{6CcF^7u6-?dIwTP4+m_K)BLh&w{4ucP z(i73mE^Cwu|BdZHsiRt6_0~%857h*nih5B;#N4ITP@`l^4=>e4tB1Zv z@APa$`op)0uCQd9IK{hMu-!9L{(;~jT~}X@_FK<_5A$6~U}z)$_Rtw+dA$&IMBJXd z9tC`oCwmV5!0Y9&g4CP|^yB?(Y?Dz5k4vnndh%KHb-W~es2|iKR$uV|KOae2=O}@L zT5@?wGv+&8cotSI0kGT>L9Rc1jsLJMBw^PJVU2>Ok^06*NMJUI!#fWJ!4w;98eVk@ z??@ZRf5Gwe(z-WjPRxHWrZ0>X|EOg74sV#k%hDA=ZiYLHb9ozfUxth%Q25^n{3!uZ z3@E_J&>7uY_(J$hI>^XyEb~O2Od+>lyu>4uT4C8q4{BK^hDzE)kW9@S()hR!zj^Hf z4N3C!c@XQUXS*A%da^VOf8-9Ik%jYDY(?5d`@CS7TKJtb`92XiTDqXqUtbE3FHq&2 z9HznD3$^5bT{_|8hVvW7CQyfq=h5S@l}Kik4H@un$1UIDU|!imT4cdATXv@y!~T4Q zvhfI}s(?D8c&6df>L)DY{o(3a!hKKvz$k72WuT480ETd)h^ww@qIc@kb?n z>39!MG_8<&KR|4jDO`7KBHQJ1@WPEB zK~?+&9rA1`T6M4#{TRATbmLPua|7o;>>csZ7L%IA{1IP2dUAgT>iZl3;hRmVx0)ex z9M5tbmCnTBLksqN5)0w`_38MT4Y_XeGoi405Qo)=ZA8QS6GWbh%9$=`lK)HLyyGDP z#ijrlqHjt&UG30}gx^T06iRFhs`0O|IG7!6MCYzm=cJoV;MkaK5<89Y*k~g@<7X`O z4cLSV&xyfR{|#i%$Zl-i=Y$FbCBhf^O9Zjnh3Ml?Co*Zl8@$eU9DgGyo_6+)fO->6 zc)Bl>96$9Ok4f|fbvIeMr$dc9G@yb0GVJ}IKK%5iC&-^{C#U};VGq)Zk`-l-5^nMlJ=KD&NV9ys8NX!b?O#wieOnP zak~E5Dy}!@G@9Tyh_@pyJ%PpVPSAkI$@u8NFn(EYJhjTNLI0i(g~!9gh(bdZ{*$>G znl|Q$dL7FiX!33&0_aQM73iJBFjy?Hg%Fn>{CMee(35hdcxO9np1p!@#f}%<;4a1o z!X158`rTHD>!;u0*F00r3s=&H`t!e0R*wxy<=gS-ogR=E(oY_5eJ$|U;(4Rlk?c18 z4LyIp9_+S65oKC|-^h#e^HW*Y`0H`xx;qbDHMJ(mnM_l)i3Z=jn$$6GCqB_U0`i}^ zkm0UPxc8R_Tz&kFY*vsm5?HXk`=YnP@8hmzbWBLrg{wBtYg)oiRMhwhL zS!U$&6Vcr*U}O!r+tGHy!fs#%H|dj5VCT^_C>yCwS^Ueconb47Jw| zMyGcvfMv%Z#?Cqx1+E(Xq-uq~KsWFLFR@K6Z;?VJ?9|nSJ1^=*-H*4N>p*|5JuS5` zKyFr@$X?opY^ra=B}ZIg?QL<&)wtlBw#)fP5y>>T{54XaF$-E$T}3*>Z`CMhF8NAi zuX`HJDqoA*-pG@rU*EA(_%#^bI)(a;BG~&wB`7Sjqb<$nQK8BZkd<{6c_fk(++jke zB(1z9fwP@Vc?tB0?$#Uv%5n%UM?{c@@Yn3l5(<58J;ZmC8K)EQ5RG)O5_R(ASO-Ih zyB@tAa}F18Q|6PHXJEU+8#L8rEEp^dCuu#E_@H_YZ?lkjjW)3Dwd#ZLGF~9^4FCNo z3AqXSfn1PZM=-Vv`IRh?#CD@CA?B*=ZONlkrC z@rtqI!2O?#$P4j6A{dsO`AHJbni-|vmgf&jBv6^#(l9i48c5zq7v0hRobCp@{io^K z6e*NrCXS+-&j{UjNeEBsUxS$a9U?sRJGY#d3XY)*W<(*?Q{!QUtql>M(}rhPgr6AM{|X8-)iwl?-Vd#IQjETG7h*S&!1+w*GTUgG~$6A{4owAg0d=n@IexP z$5J)V>0K0X(VO6FYYq_)D8#i&0pP~^qK)U?<7(98L2AnuqP@Kb4;@wr8pxIA@$K9s z^$TcC)*u(XTILS|tV;9Tg*c%wia*T!dj_Fez&-nk)~4AK53_c>f2ljHVfW(y`O5y3 zaQqI#NP5q=A2sK!1EYc{a?hgzJ7oTWwH*ocSL$&je@BR{ zvx{u-UBj(xNkp~SN~GEDS`-A|TJ)$CK8M44#`2xD@l+GHARBfcT%jFKlp-qeoIni2 z7U|OUW?6=n&$4(YcF#RMHVJmFvxLA-0qNH)z}XXZ`A4zd)SvNdq3aMhT9-n8WxvEz zZa2Z*YwomW-al^Eh#<73ZjMOHEsJx4FQ4S;=kDRRtV;34E!l|80s8zWs z?wz9y^($RP9gij!tm7-?2RUxJ&PdTOAAS%Qnh{(tu!W(#fPDtT!Zz2MMV$<-8EtUsiY={gF-CDZFOb;o zLF~Q8yF$>|uOwo`30!`25l9bn6XETb_TMmpeO?S>?;z9Rwdj$Y3;7$-g2mt7h1EIw zw4$j#w?1JSP@`KSufo?!W+=cUQS|n&W1FGj-&#r7{QDRk`GI)PP$F4gjW4qs!@aX7 zsRY@}jYT}ndpgKD7klgSt2FM>b=TG-8HK+{;KbP3#_XSr_9FX zOm4}%!IJbHR6M>xCw&SREX*Ct-;R!_(w-wAO?ENd+LuMPG(E@5Q}SS7jv;lKeT1tT zu8x!g2QhX-lsjB6ZztKVN!Tz-m;XM@hgJ>qM~C;fpwPoNNpNZnK9SiB#};|ePnFv^ zhppyt{L)*IXKcAn2YRc#j$D)K!F8TqFm*>a3C!4q-KQ?)Zw`de_TfdSXXRdKl~$qR zjN`3dGnBu=-ZDA?aVWp06I!31q+2FK&bW1n{50l|-FDRqc1>1?lDmU=dx-UNj2PO> zwwv|2j%W60O<%4^gT2xH2vk>|r0K57IL>e=FVFDyFRDR`=VZZre;7G_zY6bIn8=?z zq?&g-Gz!etZG?E^ToK+by>uJqn#xc;%XBVw?NAVZutl`_xX1q)gv+|phMR4iisU&o z@5>qaCTbA|1ff@+bt#wi5dD2|gFk{Kn2~ z3!@+i)ku#5-pGy=x3}TwqhWA~b^BDj_7UV=x96`%G4JmE3LsevA>5{c+%gy7T$6HG zVQ5E(uhm77$?s6`f40QvMH{|$%>_)}4WZW@-0;ZLJa4z*AuXI(hAg&D2bnro!mnz? zTtEoOF6|+a?Jh=+N~=)lj$uSr{Rh_BcNKQ;o=OwO5xn>27=AYM#}>e26t`R)PWcUD zZ0xsmNZzhN8=@BCr#mzG&I77>_v%hV>>ERvxiwOx1Jn-O1oFC<@blJl3;6_eeuA}# zqnfh!<4Y}ldbH*o&SD+)Qf$w~@?;Ad`$-YxmW317t(CY>FO#=erkYojlL#AX_QRdU zm^}Kg04pBX;W-^2=DS#r{_0DBn^Y><6893T7B#~B{T}p)wiw#^Edb@~%@z50!{6P8 z{R;EwFv!7iKcrys4?EF~EX>^x%s%&%GhA$K#;=v@Q8Kp$+e=aN-NJ)$)+fcd+7kC|TZ2Zj@$Y?dh!$ z^Us!c_8TL#`#CCEwv1e}{e)+{bAgf8{lwPHtuP} zi!=vdTQ}n#XYQbj+pE!Xa~HCutOYme+y#SY2DDPpkh^#HR506gOVp*{Z=ubbFkY>H zp`Fu|TZhbZ5=DN4$5;H|_>?x%_AwU!emnrbO%karlp*~I-w;U%C8m$7@qf3*@Kyuy z^q@{8x0(k?JDNitoGr#7b68H~NDLh}!3^EC{EZ}DY-G2*E?l)X2zwYpH}<=81Ae4+lbGOL*m#Qx@8ouqPTf+3te5Tv z1v3>|?#bT!=VbZ2?(y_Z$pdt$sRN$%+EbS-$hrG6p1*fhHE)-^6>Q8|2s=_D2#K!1 zsb``=jpawuPHf~7(@rA!Ac4?iLme)UkmZXr<7ruNHM+f127*Jvh;l>~4qF=nk1i=u zc}>>M`IYT)hvtfU##Ak$q2;g)ZC{kmt+$thX}`9RS^v863aNZJ+~7**w6$}0-<(0| zMdL|A<5%4M$PfG@)u_)*fiboTY@DCxiNOh>aNNuS#AFi&@A(jOo<6{-Y< zZ1Y#&jA_MV%+LtSHBc21Md}~D#s+~D=3aEBX)m=Aw_AW@R}SK8%aVGzk-lQ&`3D= z+m_h4wc%tE3WA|u$g{&fg379syq=3%Ueoysc)D>RwC!mi7DfW>t5E^JKAxms*XpD3 zW8R^)Z`obUxeY7NbA@;+NwX~6aclWBaJcPCKGinh4avc9#HgECfQ!)t%@wFFc#xxN zMPCM&_^H&Ic}-PzD)DFMvtB-}$7t;iF*xwrl^kqs#<5LlKq?qVEnJANb*J;$tOvX3 z%4ryW&4BH^M3T+}uW{(xD9HBvL#C1)oc)Qnb!=WsX61vo{- z(+zpeh)@McwF@V!bt~~m-E4@NphKVfW*A1B?}J`@_7>>N$DvK(aEW=ea@A5euYY1N z-87Y`rM$%cGa5iP--C7>5JQ(g_@l@Nb4Bm{#0$}|X8Jt3Q8EYbQMNs;*S>z>9k$wk7VkhVl zdlU5IaS<9YUq(#EeZq9DE4Alf;Hx$8l5Og6%C*d7%P#_ABwVx0!$Vcn-I_d<_av zP7>kjZEs&lKGsIgYA@I zyxiRcDjge#ifh|p!kE*vaUGx2u`Q10omi)9%yCHeSpe($B1ni=1-8Y0aDu&Z^w$Cx zWOfpL6ky?*+4cByy$nB|c}JaB)}W)h(op$~_1L&o;ixrQe9tCI7lxN|r-Or_d8`uc z^0|S+qRrTz`yj^3v3-zwSy@^Uo6cE1lZ6SsTZzNO9{e_q!Yes9=CN<*lB?{|#mf^! zp02P_zA*O4Y_?-U*!JjKSm1ktN^QQ5dUt(AXXEUM;~#eS(RGJ+ihszA@@hd#TO=(1 zI>=pB#;pQDeH3}C{~FKm7lLD$3yuAvgFeM&BY7EHaD=cj^;^_ND;Cu=Tkh|rXRj^CD6-d|4>xY z2uKY~6ZyCV(jL%;MbdH=aoCo3`yhJo>$)8#$~`MOohyeZY1<&11_2$ z1|G`a$ZCOyk>X)fRPlBg8R75)&ojLU9Tiil-XwyH)fM??=b6uhao23rK}6u~l#AoS<26j8XlbbbJ)i9bAGal@%&W|YJ^;%TT6Cw(a{PGe1O7hi z8=p1b2%<)gVH>YZ+tg~rQ`fBGGwqoNm1U-p3x;>=U1-|KIzh%+Y5q3*>?~U$4c8t| zgdIg0BL6^`TQgXmv85zR94)LJ;2d6`6_QWlLRZU6P;#%6E(Fk&(MU;a{I!AUgUd`7z}*RyUguU3c6FU)q4N(`z&$*@fVzEqH~G9G|Nm zP4D#R3!c561php4ktS4uCzuw&qY@ojKk+KJLxpY2wIqprT;@(baNM(vq+X20x(0nP zoB4{(r2mhk>kg~&{lkp16r@Av-P<1O-O?L^lX-xuo!hgBlrvPhS1(_P5>9jgx> zlOGeOORw+~^JUz0`&jxkbUj)<@)wfXv00406-I2^LbZ+X)z{dW|j)-pgzGx(SSX zzL2x(x!5VZ4!s_;o}edf_{e)-7(Tayyz1VE^|r3y3hxEd8f5|6)4vn)GF54Kpb&?6 z4(FtT_|#^90=n3t#K~xf(-*SM? z`qS0C#GiI32@~P{pOtvZ+eEnVjQ#d6CgX@B!@2a+e5zPqhE~p%f-$ne*o)n; zRJK!k&*UAian@}Z@m+~(vp(!~%h$nGo`B>zyue>9Ic`LL43#$DhtLmcu>ZbI%yk!x z6+nW42W_+e!t08)L&iHNld_XPvEr@(sMMZE&uCGsnEDwUb?vFY)KwJounU=}*otxZ z*e5U6{qmRGjw}~^PBVq~f5VCCk77LEK>*J~Jm~Q}ZI<27L2f$-v6rWG52EgB(cme& z@ZoE+&}{4_)@IlB6@cS%ed^t9rr){O8wHuR32Uyp^KQMe0aryrMw2I4LQ@|60y2rO zVF8vaQ{*yd@@c2>d=$QjkDM;8BKgpXb5vM%JFlK-u}#3@S2=*5MT%Yx6nG#fySQFK{roV zBapKZ_J9dY_N}J~uxI0O=WeiTSPE#WYxXUz7grT!_sjGB~fBYNCiN z2UsGt3Xax=ku|C%cwyZ#Zu#{4<&~`qAZr=xMdNJvYe};oS zf?zkp*c0}tJhk`%WO5~){O3@J`Enn@YLg!gcN~iTb7Z@vlQqO0I4c4}L3_3abvl-Z zXRnilJ2ULaoc~zQ&jo+j6aSM`T}~AgEZfX|DvPHMmeMd}`UFrd{7C*&CV0826xaWp zPg||dA^*d#(ewms5;Uw4TlL0){f_1I#64p?=20AXm}PYXYV^Qlgc1ae_9A1ZR^dY_ z?C&4aOL|S#=>LoML%h5?p}WO3-tZfbq0-uej`&j{=vgkst!Ey;9-ZOPym=C|_hpN> zdL=?XL)mwGI;%tyo$L6;%T_rr=DjOpo#12tS90ZL8s3(TxLeUN^pSTcT3 zdUnT%JoIbF%GMqb^SqzTd3^?-b2aCpnjg}njTIkrSLHxPBRIGlE(6P7visjlZ+WJA6q%fo{>j7}+X5@Y#n-#L_*o2Ca>iXM~cjj!+} znGDV(NKKR1^P)FnP9vg|0&K#2~C6gtJAdVP2^^D6229q$+bWC zr#Ihv6C zkSF-*{7xvc;M20pOqu>W5>7wMBuA|a@VcFf+|l2OG->pFwBte|iqKd^99h?snad%V z7gU=! z4LM*0-hoqL!5lBrxuFtU?YIM@47ylHmY06Qfz_yPzP#9@)f?ytl5=LzcfW-A@OlNV z=_H?yd-w=Nl73XS&r9qdSU)Qj9EvolWW_?(!J-Y1CBunSMKS&?x(WOKd?ylNYk9|A zV^G-q)8am{?+Nj+8ttX}7jNL6>!Z1Atb^K%UyVG~M}xwrV6uyC5UerJ22Oev-F78M zuV!}|cb9F+IS29KMDiZ!9xEizEuUfE1ML5(w1clJj7Dh2`;h3c{>wb^r z3fN7ykad(^o;?;?+2`|rPMcie2RGjKki0Ku`kA+Uk?iX_;U1Z5yc&&MSa;Q(%IcL1 z%-=|I3NcK(kYewJ9jdTpT8>y}7+6pZiq_1xQz(JT|Lf!F!;j{Su07#&DwIq}73 z^Dtz7hRU^$6umM=6Yo4l6YPvh=DhEC(lt+5`0Fp3X?GrvlrZCVNGH>3sS3tH=EJ|` z-elp^O1wlq4-U@pptr#V9nF2qauc3n-m75I45q()sAT30LG`*xaN

    5tWwU-*IMW z>YZdU*G+O|{br2~y)NME}9j0gG6##p!+P@wtv%6s71P zzL7r0+uIK|gXnpi%iGdH5Tg7MKC!jaSg+&HH!_7v`f= zs^MZELX*G^Ry=7UCH6^psbDGhL4)mA1_Yu9r{ANbphVpR3yD&RgNN z9wuF=CnNvn;DaumFpJ%}?r)bzD|Xc&Dfjhc?}0WPU*^SnN88!E*dDApREt})B#=UG zKDysI4|=6~$*EoUa4^epyp~L&#+wsR*|;RQ9IHo{ODpH^kc;KEvgb>U+i|cpoez%R z!o*r`wu37QawrxK>u<*zOYTDrXGv#gN8mG`B)N8`XMRp7L#IAVK(}Quu|4(y*Vw0k zv-Zh~2MnE>1yuca)1MY%j0&UDcgw9(t-{a@)Vy;Vf zrNI3?muUW`GT!H6mi2l+i7e~s#*xL>Ao%foI(Lr9r1*!3boV)x4Pbg@G zt=ITeW7}VppDzdVG_uHtBL#S4Y70{3x~P`j+!jix!_Dti z;v3ob@2t0fI`fw3UqPl{KcXQ~HYDO$1GahT2_7Ry(1>(@oL3eA1v6ym%JOMQK5H^u z^ztIXvnuiJ9oNC@dK1+;G4APyVPcK{Wm8T2ySxT)zL#nrQ&rb`zdp>dsk z=yI%=IJY~oGX>5s(xPTf3$Y=4muzQVeRFDr6dtfF-|=wrue%t}czPY~hPM;vp%%Oe zSyAYZ(P?pauJ*>;5c$W5Ce~fSHE0x<7L!QBovM+Z>?qhWHiQ_nUhAn&0kDs4CH(I4 zLGkN$L(pj^6W;m?03YK^d;_xW1YS3ibm%~LP6o;Om z*a~AZPxm`+$@B!T%pug}pfgr|Y0TAKen|IpmZ66`=fNRoZ!#gb5C6_C8hM|1T`$AWn!bVM6hC@0`7%%P>nfPN zML=ZnE9`M10HXS&sl7uy&v02cn!j!fxuVsIeONAF+P!vidD41(X+{nTG4mj%(?8=K zlWxO?OqSg+-6?Qk*^o~RlP4UL2bs(B;MKK!vVivnS5>9MgN52uHqw%(J#RiroE;&~ z@K)%$!8ZDpL{%i={RfwF+nEo!Y5a9G!K4IDK0JuY57ci%@G~RYY^=)j=vWJ_6@!@k zcWDQ#46>(Yx8+gShblDl(|RJmu?^2;UH2NXUBvsVB{rL<$&H8&qz}I3qn~PXA$wIX zk+QglcN*S?d#y$^=f-OEpkJLo-dB@@KpSfT!7f#Hr*nMrY zKP)}ePZl2n-qL}~X#ds{;eb8spJe&mU3V<$I#C2hABKW)LNJ+h@dKWq~SWFM-#DFvpBc97trHoTZ-gT!!8 z8rt}Um&JSrIf0YKIkH{Beqi})KCRp?!ev^YAn%JEZPB`dR4m(2@Dw|u@vH&=x6T*T zONP-?6}5t*;RakM^G`1QAOVGo454ju1Q7~~ut|6poM8Hf)14Kl=ubLI**A#KEt$8V ztZ5m2EZBv;iYIUrS0>VX{*CBP+Hgpf@)mPuPxgL&XTA(wknZQ*mi(g5AV|hIXIAEM?|L@@az3I;b3AHG4H=7u&O`AZ7ft5o!V3a?>EkY zEhDRm?h*mc@s#HjnC_80>IynKxq`hX+7O4e4H#y6f>P)R`g248Zn?uYFIYaS$8{QN z&z=MiUU;$YZl>?)-GZ?B-9*~nOaIMP9=aGPFV=xSHQGY3^B_L+wd6TNB|g1Zn1VLG z{fVXvy~O>H%M+8~`gtvy{beC8KJL$+M=~_b&j?joFNddbgPfTcbPM*g{nlQ!jl7qp zk!(VDP@`DRJPex*jOnt5EBMqxc`kwVB>aBJG?mJcut+zA$lWc)p1-nSvZNmEDa+H- zW1AqZ3uNf{3LiA|?M_(uP)KUEp5cJ1TadysCflV`cnMkE=x}{H`8~T3%Qf5tS(bkZ z6=m?aLO*2vc91haSQ7*ux*BwJcrN~E*a}htTY5TsE!vnm1a=*;7xU+=Yd)a-vWKiK zOcAtt12^L#FcPjfE~5o0 zhFHcXic4-*6a6Qn2OeV;!Ct^T0|S*EuBidT#&h)ICn@wNt%t{*au#P93?0sZ z9%>8vPcH1_jrG~$3KnVVgUUGrW->jwwA?c69qNW3a% z&TdcFKdM00*9nj|HI(%Em*72~{;=9uhMw}(;Z+?lL!-4*g-Ka0_*f{rXPsyyXOm*_ zkm|3{&3H)n?m~2U!Z-B2?Y`I-(dpC-hPBtI`=l$p;qfcsxIjQIe0YWPulhsLY8l$+ z8qagT(}m*0wh*3jE1sDc0JlfCk$IcfVhyb`2YP*Uil>`UU8>Y9_x8UrWT;0)!%te zj}~sMM81nQkjK!511@?2U%iX;4YkC9{+is*DL3e$qXM?6s0InlyIZ{B9&VpHl>02? zQydnLPFux7tZ*gWdRZ~wTsMlll&&UPTzL$%ug!(y1L5K<@FTQ}Q<99PQWXQd&6bzZ z?IESYv#H;4&ob5_JbXVLS{H$Dj~~j7%Hq>GDrE>g83IA9W9R>Oy|>7J zeSWaUM1$_WC&Hie%V1iOH4SvSj1JqjqL(eUWR6_}o+|JMi}NycUtOc%m-lLJFWW}3 zdMyEt)Bwn`2$GahgwNS!z}{)@)W3fjdgj4;13VZnm1x3i<8QI|rsdRN)o!eoH-VcJ zlt@qiY(ysx42Q!C-ePT8>xn-oU6P@@g$nxW_aAdIy>mpOJ^{^%f{ho#hm{dOO!@J|-$pN~UkU8~4}+a37)ihVGBa|3xTm4U6# z%Ykd19hu@b#-e3lz`T445yd!0;WnJay~Mg_ z6K`2+IQp>ITC5?bydA+g4B=Dxjnyc(Yy@auWSu#YrC4cqGgKGZ(w*%cdbUS)fN{H! z+*f&q(~P>%W`ztgcXA;%^m+-Mi#_Quoj%^P#@`yyqVD-lYmbOYT1~e8+qyky7w;oeD(E$tA1Z-{8%+%Au## zjy9f=K!ssHc*~DF3nLy$2>&J6L)OA(a{j+GoOpR9mm3yM%Qgig*>z*Vb*UY()33*C zAErZ-v*8FkU)@E*89mc#w`wM4Wu4^JwrfRz>wGz}RdlQbb3_rRE( zX8F^7jqb2_%1}Dp*cq>qFyj7YCDUy|<*0d{I;a|l$Om4W zZzOU1WAWAbP2eJ8ohM%k(RY3$YW;klM6oV?-IfvD_8ELS9f$DLHMQYLg+San<}s-g z&F$MlLZn);WE$fbdaOf6aV_4am4TEPt{Rlq;?9r%;9CQqHrO&&^>74dSH|AOM#)0~ zd&i8`eoPK-dxQC%nXukhkA@sQ%=-|bj)X@dgfFiR6^fo;g_{X26TV+N&Hdn*IXr>v_vyt zM7v!!kP}PVuxuUkBXxC=VH+&5dEip6>hKL(dq{wGy_^kEZw9&XoydRi9`ot)qw#3L zxj2XkVV!0kWAmR^MsW8Su0D4<2CYHrFk^p&cw+)R*XIse#M2KTfi(D+(9~0dxOzF} zHrUMH&o)&fa9`X%aAcotZrulDVfPQo%?J_Ws!w1!q<*!dLmyt|-71OT#wN1NW^^d1 zn3%w`R4ndWnCY0$wei$M_7iK+jv>Q9qHPBm8{LK@EKKici6lFui?PL(bl522N&j1*jaI&YgbL@{in|xKO}hikE?cSK$(h zSr2?-BdV_%20uK#$(N7SIL+=EY*FS>Zn&Ag%Yi&DQ=fI9(L8u(b_~+aQsScW1kY-z zhnkyw`p4xD>M0)%^K-MvFWmw>J-3E!;CjC*m z!S9SgK1><^3AeGMFuPOFAv%f6V>gQ?k3=}wxDAfZCuI1Kr`SRD2AIF-CQtJp@(#TG zj=o!Di23kmw`XvJVTEtSPu}odKB#B@0&+s`2R?q~4!Cg|)M{KVK3DPw8B05m@Ue~9 zWQh-)ANz|4oKpozk;kp-3#F5V{YZL~BK)MEh|Mb@{;K>38f*FVz;{Q~H9>@GZEQ)$ zm`1GH6AnyNrNP7qTU-n0?v$&EPHoYJh^3=JR@Yn1fsjT} zT|VI~)-I%e*}^oxX0m5z8oo9qk25~b{O5^Np!UKTcr3CbUgq^U+AkFj4fUWiedhD3 z;?Hn(7t}@DcJ{!Xzgn=Uxt16W$-_1-6>!wZkve%Au?`K4T8oT{ibOk3yyyvTPb8_S z%O!kfB=f9VCDYMw%Fwl?YM?a9M~umh8ENp}XSQW;?Sfu^e2(m{dJ+Z8T6`j0jvH&h zr-!B(3m(rH&pqhn(<2X6V9Sv4u&61N9RFH^Psa#hT;EFSHT)t^a>H7*J_ul3M7Hc9NGD7jUSd}jrdH@0QC^FR&!dF@Si$hhzl-Y$pONtjFx zc!mF5_>Rdpu_1g*|_cv&N!roPTm>hx~_d!VO?h%@kvR+&ALY1mG9A%^{=3gj5o-Y zVX}!yIp#`Uf?SmsJ-B!a?=9aH49ptHOP3tHY)d2Dd}U2rljYbgu>!p~zk#g8t+>n4 z8%m$|lC;f-aJTakt~v1r-Lg%9v{D zL)Bo0b_9tmD#iM4<2fhxjiJE3u0Gq$#j07F@OI&N+<-ZJSAn6u~6 zjAtLv35!3-`ap=-FLCQ_9Q41`r|{(>5$OD+7K@cvD^LMxOG7!zk5s3Yp#4gXh;V4u4jI?inw_ zoc1{Get9Cb9F>jcR5c;;b`Xbk-{iu9&CBSv2jg+E#%k`Ce=^PB4}-(wIC#81k{JCh z!bXo$;qOXMYRze*)r(TlVozIgXkio1{BjFCZs|~^`2DzR;y7+bK_cC2+K7}tO2XcZ zLA}Cq_%pb$4vBpfhAlZ9Wqz|FhdgL`Vg-GVDVf(T!b8pKK!tUk9Yt)j{k#+$F3Tb* zss*@xS2biT^P#Yng=f2>kXEjanClv`Zp?6#MllY@r1QCz>@GiH{W!=_l7R`54n$>h z1MV!l4s!~7h;Ey|z_s@{!T4wR-t(ht4m{cd~-r!Aguhd}KsY%cgvYdvETa2%0 z^SQW(YN9bq>_BaWCR|F45NpehSrHH#DotN1AK|Ia3PIOxtjU9bMtteyBWRU#ps#L5 z;9t{ZxjF3lGP$M-ok);{REbcc$uGqjZ<@gGiaiZ0=+rZx#^=V|Vcp=16QRd>D;QoN zntJKQDCioCfjE>BRO*x8V@O zYA@EOn)T}oRGzn{zAwy?!KeZB_NW7q8{UW&B)wt5kY5DGr3yBhM1U1Y(@l+=k=>Wk zaB5y9xxzdr|LUK>v!5O;qsJj74T6SWuqEg<^9|;P!}Ign^zvvEyl_nz*Du5L0Ucei z(HI40C%wg7T57->-I(-E_~uLiFQX#`{P%iL*&XGAd&d1Rvy@K@Eun&Xcb3c0na$pP?_$ zJxPgMEw0~C3#(uI(o0un2p&Ee$2}OCL|xrfU}Ek#@c$c1?2}kWM+)ol4$-0UR+o4q zcWh!e34u^Cs~>k}da-_EmO&d4i*tt5L2?t*oNpGQ0mC}91qBoNO=UQ~p$dK(`cNld z7v6JN2CXcc6S(0O4#aJ!`RrEmF0KWS*186dT-%A#+O>Gs#YgDTYY(x{&BB>N%Nlq3 z?fG>;keSLl3W5D8scj)x_)x{zre^wOjCy!j(dz%96e7D=(B3Ugb0;oD?%p%teR?1H zc$wwg_4;8*0n_uP<59?tXgC$6OLvYRn-9uioE+<3b}v5)4*zDe3MKeQQrEC~C zjBNwiYlgz|D~6D>Rw%}8Zu|<)a()awdTtj=pCbV;%y$ygk!{#JJQ?=wai>;XEzdIN z5W3Mhne5xtgNN<)g6E7s|Lmc7{x)T9`q4!C{X!Nx;oO9(7TS}6OU$GDD+k_>Sw^F` zkH_{807h6v63w0>y!dM}EV}7V+j^IwkC&2>#{paM?Qi@<)&;GhLsiG@$A@nzbN(!M zqbAdcQv4-h`13)me#iRfl^KT|GZXZKOmjHVY_=`6AP*dOTfywAL9E_k{TX!5@u~T* z0pz?u3i{i!2sg6;H$_&#*hxNAuviw2uZcp1<8;M-<9+r!q4abk8TgluZ_MO#2JGHC zWb8PgZPGBH=OEUZqZi$PdF&lo?_7YO#AP=p^GIE!f3z5u=1+%*duzmf4gp;0dx`u@mbR~0=ifZ>!|Y`{nbOX(Iop( z;?CaRy;iJqZwA#LC&ZTUbE`I?P~LEuH|@lI)DmYczWsf%d z&uhtQbjVo-9Oj0SpMIryWL_iux$8h5oa@p{nYRV{z7Uep@)R!$2nY3CmT~A4@}6cj zqmHaWOt$?k0*Mk&>Uz45w`++fO3fU^L^X~UTsEi4vvDZbCu#d;Ih*c_6b;ycoByVoyX`$@gOE^ zX@`K$;^p+aks+2_^96Qv+R%Pe)^n*V57lYjM9@)*m-i`g;TJuq>)0y&p=`JM?bH_G zN2@@dTw@YcMz~X%whw}~TfOj+WgoVyNrC9xScs9zBP+w+;5i1J5cMJk5VAc-jnA3(coRO zwc(xwsEf4Ay206J30zbAOjbV3#d&tcAXRHeZI-P@N!#<0v(q3x-*fVSIC&|$&*U;5 zH9DJ{e~fL)%(H;>`?I0xkB``U+&!uWCOqO(tql?AHoGAjNqUKM%G3T-feQ7d$9XdZ zZ#O7&aWYAChp`F_oL7cNlfuY)=MsFQ6vNMhy7WiJB_6+c8#=T0iLkSHh%iRr2{#ut zkwq0T*fP8Z9!^i9%^`(o){I)T<$SPM>##2W1Pc!P&_yR*cr{g;@RntN{@*QGR+qq8 z7OROio4iHK7q=q6(ye6C-4<-#~g6WzP#d7iMJ2Xc>5Tr z&*jlbW99rGV8{u3i|DOUV_<9bEV%e>5TARZl)3VWp7fmdJKl+Rj_9aUkx*3MjOBiY zfpoGXy|?cXw)5!)Z`Rp3Y1RjXKlU+?(4f}g{h|vVB>K{{hMT;MkPt59DSJo$5d!~C z8i3(fA!%6m0*{@soO>D{LqDhQLZ=Q6WgQWNSS>R#84SWb>DT*Tcr};yqgjDd#5cj| zD?FepRD+6gDC@o+%f;?v@1zRZ$YfDH3f*K+Y=<$=*n%vW@>Pp1H>%+N#cbDuWwa;g zID=UQ50(v!5^EjizY@UN$&Egnsf9|s_-ND%TXDZxV#js3nyf?n)%WB3+s1O+8xrZ4 ztOm5RV<==T@ezAAJ`K-<;+NX=;YLoMNM&(RZ2RDBeJ=D&JPegVB4RG_g!u+5p*)ID zYqADVOq~Q28)lP9W0=-aR}DGGn7?cCNHk|^1Zp3xOLWXSa7g4fU^~WQ+;)5$&%LTp z6B(5%gWA^NaJJEb2#p%B)rUZMBHKrfMFt3F&D+j7^|Eg5O~o*E>{JL+t|g=L1bCl< zG#AExN6)XjBE@s>kjU1KNXazdgv+eMXFSV9Oi009aq-+%_J2`6-T)LjRN(JqAMt&# zX=(t-t?VJ!!aVie$`8Y;?io~dxe#}i4d>21VSZ7w6x6KQhK!#K;&zB-BAAS09@N&w z_~wy#ZpJ(2*S%^Bg_29)_x4B+R0GyP4Lp@0NDF$6t#8_L^Ai-R<8onk+NBS{3mb+ zS${(H#bc;*=2x_~eo%|Hxk%xexfi|oyN_qE!UF~AFCaxTy0G)w8^GJCL8oue!CR|q z!OzErjvclJ6$JF5-c@IaeIN5+JobXzxB;?IB3+P|IT8|FE5*7;u_Sv>_wk^~4*+eE z6rg@PJF)I@P(BQfj9*2Qv`n#0-)Fd)YfC>|_CO-tk#M$UkU#gn8OxRWdC)t8N`1u! zZ&aDa2)Xigo{w`9O#JRai)gvv67+!av?RJvQwkg=u+F8$d15VEvTqDGmiZx7N|z&# zo$Gm8g*7;6)nT0Y@+1(y7P3P<4GV)axg}2QGk-T3wzrRl;ie8^-NV5;5zcIOr^6=B zAx$0YZv7YS|CjuJRmCJ6ugIH}A=njzUC!@83%BRZpVT#|lx^vnsTgbyTj`EW;zqKEk~vzVyBOMP88BQfNAk$%Ois7_8#C zLiXLe^|cUfmv2GVH@1=fo)-M%sxO$H{Z9TFuf-3-l2E9er&yyNlaIlAy9X8c-4MJy zbA|iMHVXz^yx`Za8PNXoF|lfVjeq@{i98%4#rHlNPgl@5{hf%Orrhu+vo?~CHLZB*V^26- z)K4_u{D;4-GvhoC^67)(O2n<13X>ukXUMyUOOO75O>7TE6c>j&93tSwH(mO&YD_*~ zdNp^*rHI{&6=7G#ObDJIN%pjt;`;$FK(A{BeS6B6=U?fFoHR>>{4K3`O=>*U{=7=d zR|@cW!B2EYF;tv`{^8UK=M4Sm!gaTJ;j4nVRQ9=L<%K};Uk*y<5^)FnZr@C9?g=$f za!3_&yE6p-&e}yL{b|L0ANbJi!Z^UpFT82{_M!8|Q^flhU#s1~G>Ku0JH@BZjNuO2 zGXGe07W(N?hx(t}6SFZ5xHT;kBqWzp+2iAJ#G?$Z)LTuY{@e*1eD&eL@+k7Fq6qU& z@|hm(N!|D>kbYYNa?!LCb7`ediIDbk53T)p6;J)9$nE}|NR@Xrp#8l=!2kFlCI|LO zak*}86z2KrA9Kv$B$yAm-6a=fLJq;i1`&~M6k&-YA7Oy`w@WS$AotLrkmr#t);-ds zK7q^;KWfk>ho;dmlwqPvmaOQ&<6^dehhh_nf0&LdcRb)$vppKs8_J-?G?VFj&xkQO zU|Rq@cI+i3LjweXL0h9UQRJ!4 zFC4CR7}lE3qGx;vj(3*gstX5s^@MpXNT%7FL_5~tn%D6_SVll6bTPj1J&r42?_UNg zwjimn7=9E-inDu5O0UCx-2u{leGAWP#$B{?y^UC-9RP3qa9aQ43eF~?O*G$ph#Xg6Tx(alN-*vQh;YM(=q@*(bDRw^z-0xYj z?B;bG-S%%l;}kN<7NtV`bPLN|XS>mO%`V=7S?=gx+yc_SzYEW63WRg}H0Ums9NZFA z4fX46=&lRqNFwwn+Hv{}QKb!dbdeYQ_w_H4Fw78iN11Y!OOvSCIceCuWCZ+sQ7OJ5 zDsRjK$xJtTxKJPEXyl{TAUmc*D#L&i^XIQs2qoJ%2QK{cvDfZasbvK``~9 zJv9`n^5!l(!CBr{7riy_2F1Kl-T0r7a$ztzXHtfHwpPN(HE#53>#2sq<2n$(riQ8QQCh-fZ-OvZ2!< zc7;I9r6ZJPqGvsk;%el;XpH;VbQr)&)rJh!2l+vSkLu@a=fZ6a?J+He)qZ#T>SBYU-v;-XLs zPJ(q6>OTLB{30g944HnCR(KDejp>9H7ud%1_y=rHvmHvpeW~o0o%ws;1Gjf-F%_gJ zg5i`IaPMCPnYo4O8$q2A>%gbYbKfHkn{K4LGE{sA++o-OdhLGn#*16Ln-xLaH-;@O zZXxjK5`fZfLUxROfya%`;3{m?L@!oWp~+kRA-xT|$cjg;c*wFK5Z$w<$oe(!{er#d z)14{e+;pI+8|3&h9mAC3<4+X1lgn8K$}J1|CwxW+BkYN4K|Q{FCmU|sYtxjys@U#r zI`?n6nkaIL6P%XPXR{emVz0%=DM1i<#-7S#&q8arB%rAIc4BV)<8&hY{=SC}ufK{l z_b75s`H8e_bOSQU9RkrlKH?4f^B1K!?Za+#-%lTXmsjcBF_!0DKQ|W|Hy?r_)1HXA zv0y|HY}{^7N8C+i?NLL4x@Qw_*#g|Vp&C4!{OQ)M^2jqh4C&w2B|ENk;2SNQVadBj z(qom5?|h2mO7mEr;y-0Lx>E`|V$X;*4Yf%DP#4fkGXD4ro@z{ngaft2C0&5m?Umwg z#<9%KW>=J^!?d{=JCgXe9zWrS!a)fQDxb)MS=pPNauYuI8fhKXziDMuKGs#0zz(!eKM~0#D|4+~(8$N2ga( z&g1h3apMwJDG=cp#XL+G0^K5h~!c^?X@RaZZr%7^j zfr}e94ol;TT-8K#r>=qM$Qe*k>?_WX1V-P5=m`$gY3U)<;~+o_E_e~E>$Ui7n<7}o zg^|<+CHTb1%?N~p{1!gC!Ipw1a^ENhk6cg&>j>+scPc>N*H@rXwZTMvN*TVE@)5AC zKbF+%V7Ol5^D;P=BFk!edTtd{JaJKXW$F7zI73||JGyu z#CWt!+mp10GY?*E4vb&uPNmxd1*NYqaSxr;MVWKGV0G?P*mq4p&bPnD38N-+*Gm(r zYiS|xUFdXlv?WrUkAAb5ZM*bzkc+Dx;UyOOoX7KM>S7Xw6h08NDQpl|XWY$!ieGND zpq}OZj{~&gMxt-RbmLc_;IyMP{jg6KWqmF}5rLb;x^et1FL<|h2sK@K3@<^+R(4IX)t?bBpHBGEP(^T zv_+a87p~>`(sRgpb-6HRSSLPT*$#J@cPp`~6nSs#LLXfQxo+_O7N|YqOY6ID@IIWp z$5}FrEjI{(cXJTvr4C~3^sqp$(pNS>ZtYxrXHOKG%NH~w+=00^yTQ`yt3p8bUcckK(GzDrL=vNM`cl#UNMw5bMn`p3eH z))n+k%OX5(L=0E)K~1D)ZUfp03*hj^D6wwbd&XzTQiAVX90erlLgt&-Ka)RCoiMm3X;`ZNK|~g zuy_4GBCuTO3ZItgqbk(lpFotsfV__%SLb3+l#SxGV>rkc3DQ(?_G^|yH4cvvlFTR zTLBWCl7$y^5PKI117P`d8R~g@xBf2qSTOtLPItS1V7Zl6wvWcAnJb3DDb-Ps@G(#9 zLtZ-S8%#RnOO=C_P%P^JJ^HT>dmXaEF4|UbM~&@fK1{_0S6KhUS83Xt{Fk?Dl{{2j zJ42SJ)ZYfY+c|7lvK=z&kMeYeaJ6AjpDQ>^Jzi1C%VRd zOLxzjk#i;OSgY6*uFo7nHNYLWI0wLw&(c(2I2*NRPG{P_AKCV)67LTxh1R!xdL=s? zHOJ?pI05qkG9R*Oz-@RhYfQ&3see5Gr2^E~4)WX5aU0Qt8&8Ef4~GaZc3p+u315kc zdJO*QQwmy4>$<__D%`tU|aA2{jsgFJU!kDYVl(8R5t;vTkUvux($WjPwP>wx2>r0Z`9j&l!yi42GD?pez-UUeS*KJiiL*3pIiR*lVHv z_%&=g<3JzIy3F$%bC=6$W%nJW5V&_;AI26C^7g}X9OM-MpWE22q&bymr8$7U&E8F9 zBU|y5vgfU-3AK5BSM*u~CV%O)C@a`&EfH zUT`3{qw2A1eHs}5T|plkPryUV{K0&f4Bg9_qXB;%Xucgyq;?dueY#?({lIn`b*)g} z;~2E-=OEX0vb+VIY@cQAfs^`T@5}BvH9_{$`8{Lxj75j?2ll@_IyENT)`!=!= zT0)$~Q{q463GVYRhT$Tn!M<0m(FML&ZftzTX6h`5zPowM(qwSkwlEWnCq^59|SuQ`>bXpvqPjH6oGA%m0b%5Jbt#Suje+R9+Vt$} zbUoYp0H)0C{;nIeu(9%yb(3~V{J&Aq&#?W)LdJp59O5SDsEa~w{eYkU%>%Os zU&Ngio;LEFrz+!JLblE8k%9P|%)}XxHxY5b%;i))AqHoM`@^3VGE~WOHmW-}4KlU; zNQ&$KNV*Qcn!i8XKm%WCD zcGcYxa7;0j7${WW;?NX$xOM>r*)zi2@-;|tcz({S9EqGiEmvSjTL)>;h{8dAWw4I% zqABXd$T+tW8INb3Z=b91$LZIBTVYP6ALt9^PwRq?X$}dqe~yQme}owhOqY15f-Y@s zK{eMlkwMG4u#TTMIPd*VboW`{%{`GQk9D!$&TPW>HwVGuUwdi9MhB7C`m@|rcE`+a zaEGOAJ2mEyi0{Mf<}^4_Pb`&ORU+IuejHk}Fr3d*pTBYerf%pXNr8#jT3N*XFw+(n zs!fJ1XS30_F9Y0oTTmK=-gKjuZ&wSmyG=ns{XMxcI0FaSy#Z|nC#qRB9NCZ(B&}sh zJYII=Fegvwvy`SvbtmxF_{CgFRRX0`8_}X>bvP8;Pj;^f!msyrfYkOldUQuL%By=1 zLr3_~S3|dCW&at)g@?t`&rRKE#EP+C$2(Y7&iuWxW&b4rjMTg#wn zbsT-C*pHUG{6gQPGI*>m*u!!$4RN$ZV=B^(y@PxYoAO%3;wP)2#Q8l5S4&~L@Znrf z0n?cuvQ5quDVWghzlX@;FN1=E>hMY9Ew2f$S|iEr zVtk{e)fve=dWQDRvL)}+vFAqw8>m zu@@}*?<;w|%S|xnKV5Wc?Fe3%IBhruMDu@;_bvf=yOsp^rJLO!mp?-463yuD5ie5w zw-MJ_M8JVULz+EL4-dBpBYUs2LEN93@jJ< zZ@Dwt>^y+m<<{PC|B5cXsh5sTFV=!;njL-Eu@Ysi=s}*h97wr&D^C1M!06NhYSS)- zr<_>CE!9t;GxTI&#OT4GNg9aa>m2;ybuzduaiv?*1xRQA6I5PiOKz}!{^^$2VdU}o zET6at|0q}IGV9n5&TbJ(V4L(3)4h2Q^Dws@c%*1Z*If)0n7f3*yj^Z|QhJr>h1`2s z?##L`dZeMlb0}@FA<4%yLV@9kD~f zJj;Q<*@;evfz?Jg+U7V-sP}s}ckHQ-c)P`C5Ps2tH8L&aWWZCbH+>ivp&Lg>g}5V) z2`T7Kz%pL1@LCiFvt)JY@l%mFfAcu_vDSyoLG?JHtpxsVWO>*x?55G4j)t&2)c?8h zmfkO*vYdH<2b+q{1^x&3HiQy6)-mPjk<2nt3+Py*Gr}tK)hJ{}eok<(M2_(N6&U`s ziv+7hW7mcf*uEx?-d|IM9E!`){{45!HKl5tbh!XVhr80?7dFBQ_32=6D2Hs__#9VD zwnO(YE4naK5rxP#qm?5!lO>0{@I*NeI5FZg-&dU35RS%QVEr4+J8d742Hj&ksO;@P z(JFT*?#EsoaV+cexLc+P@AhNj{jCtYEsBJpwF~Im*d0Q(-ZALak?@@FT9P?mbkBp2 z^k-t7n~1C9vbehz%+vd75}2QRif-!$lQ9;rv0hCIG_ah`^XIFCKch_`|opu<&=e$M_s4bPIQEN|PyBB8Mtiz9}*s+n}ry5w_`b~yq2H`WA zPeA!G%cR`7j7CoFgdL@Rv|nOJ7W4RWFJhTz?^-u%nmPv3g2Tv$qzb%sJ%NwahICW8 z7uyMSK*?rxJbzx?8VZSnUFq>O5jH#Z9(>tNXV#5M)F0V}jt>subJinfy#wP;Px?R{ zAe?t+6xW``-fODkp*_kN*6UC*-m3toEB-{ko44^g#;9#qVQ;M+{pVCD{Qk`X_1KT& zwc?8D7hv$g8B{@$vTXHGZscfoKbn(@lH+U8%H{Utcw!6I+M3Av91LkNjKb@G8bWVp z1n+rUPK!bILmYkGbP)Ys9)`YcVA^tQ8x}eyL%}dxy2msC-&PvRDa$cj?QTZ020zg6 zGv0ijdVx*{Jj}7C%j3@q=AQEdMJai@X45US{mphb*P6%slW(0YhCIffKQ8G<@{-?> z#Ig*sH>(Km*!vf*{1;Cpx^>VS*&wtbOh9T+_u~7bSAxy*c5==r1wUGIpR*j(8yLC!1@#VJbsZQ+x$fn`j&8c>QlwPCzXMky9!wCdCU8g=a2XcU8Y4+vsA_GT3e_CcS;R*jUSiyI~MRzgHbap^smqv84lCT1xXVJd$ytMjkyv z-Dww*Va-e;=g@~&u{+LoS6y1xlZIX3HB_9pqw^21L{bSKkdu}p`MakT-~0O%el9kk zE{^|1y6y|Pmz4=L>k#uHo{)z1c@1P|Ob#|)m;|q4T&bC?5V>Y1qk`FX{GIOIikl!x zH>TKdDb_!%#tmZM@At=uQ2ogvaBGt{f3wqGOkn;FBYH^rhTz1nOs-|7ws=-oA;eUL zf>WX!P5M_QI(Dc9^i;gpc>eb89oT#dlZ_&_R(rz-ULZeRd0W-ODx*b=>Kib<>4g4(#Lth>rM; z(q}k7RvSM3X(m!Do?_)nd2XAK=@Mt%(Xq=(XhYO8{${uSnG2*m7)nD`UGd$Xyq#qe3ZvI^H%=7CC|E1e@} zE3~bg3MDUcNa=~^xb1u!xQ1HMm9G@h2K%?@`@zj5YI7G3s&j{TSzpK^i#2$ZY#5rF z>`soJZo-~B1b`E|>$iiQ|Ca00fo;C0mc)Uohk&~5-Y2x5 zKL)vKMesg~tmd=eRQs7c{Vxee={@CkFmFk_?X1O^J4*YrjRfm-W1aKiFjmcr z`uuGb;?lKf%ad_@Zu&^dSr~b126d35SguZv^O+V$b0rvmX5DkbyY{@kk-Pj69Acd0 z^L2H6C22m0wIWGdX&H{tD}>EIS>`3>AewzY6!|6C@|zt)vgNofnv4%5H={$dzadfV zfR5ocwH*{&ZRqk-=LAb!wt@ZXd}7=$#!aO!U_0Ze&NBUI&Wz7UVO<9K;$DQ!pNruW z`>uBeY4kSw7AmP0@H-t62FpQc*-mc$O2&_4n&G_JNm@JH0x2z)fH^-MiL!1hyK#8J z6|bLU#w9;d?#acR<>aa2ZS2nDTc-p=m^bPFI~_x|^+WJy_W!-+j4HKqk<%JG9)~OA zZb0s4UD|#!0mp7`gDVEs)W69KP0vz*WEXD|db$p~wQHmB^CS4~&4Azuzyx|4=Iz%HQc)onqjCGSE|k zEK|K>0bns}6irqNLhWWtK{-cER=4D0`ziCd0D}mc`)og2DpSSySt=QoRg5jqCVEA zHKMC_NaLQf9M@<0h}yf$z@Yb%;4jliWevWi~2~91QZ$y!kFTgPj;Yjy0lNg0BmnIAn0s=dzoWS0N~F z(SU+>Y1;gJjmV?mEljx@M<*pn!>>qLh_cNhr{s$8&87wr%X`tsTNTlK*(E}2K`XCg z?4GzAinLjWxgZH&ITOcyVA-F%VeBnlDhC_RIPw~@0`rz19O6mmo@d#R#%)}9nU2`M zxeqpaPln#rEo9xgr`X_|EVqL7YmKgSL#>+=(QLGw*D-b&yTFHy!>Gp}XHYy0{4kF`xDsCC0}-s*4O_WI2z; zOwSpj3`=GW1I?IFqWGp9=TBdOZU*G%m>-bH8N1m9T#kPt-^c?TFr^UQ1;^7r$BWSm z)?rbdd6)c^t;Xj*5vY9XLJxbK5*A+9ft~txJ`F7I(R99&so&dNq-8h4F zJ?;HAh?==s;q*luw`js6x)2)B=r79Pe3SJ9hu*;sf8W9c##i5IMC3^R%4aEpU$atv2FXS5G`Xu(9eltM$vqF_iu8pHb$y)HJ)(|4nDLHOifMxf^ zajFlr#mb}Vko)nkXcTNGiv3-(E~g=S28*Ux(3OCU;P$#y0qSYyhjjm=?mD$MH0D)o(N`s*myf3=$hw zgtv>ukoU)x9`uz)XZvoVeO3Z~2Si17IanvO^P2Oq4K3jBYDGO1Ez$2G60kwWiHOFw zVgc(}P1IvpZQ>_d{oIUOAv0CHwzw2>FDgOYnYVoAy7%!fn9#_&C0VBj_g0Jq7wyQp zn=E^~=mwmer%SyA33#7hE0~s^qJ}|U=-+7t(7fVJzU{5U`cIgDY=kRazeq_q{pVz~ zK6yZMR%p@!xB3CxHc-375xm!8{5=)!;y*XqH?>*#Y`Ql}OSdMDi`(!WhTBc%8!7qVjxrwoLDPal z`JUuYZ^Gb(jR`fgO*6eN?GOKyMp2Y@8#$DjLzQ$c*;bN^Z>}}q=9flL>sbeord0*n ztB^((Cl}-36R{9@>k6d?ABA7HoI%HpXYqcvYwaFT7(9~>kIZ0vvXtHZPf@>zOVP!J zooIxV6S-m4inlgp!}NtlbW(v7{yQ(7)3Roo54*!B8A!lxsYVj#n1dI-jEBu9UFmjn z0s6aBH0^J3^Xj>Z}okj$@vvYjJd{hctY%lz~Hu1GsH;qX|@I`ch+C z6_hm1TfP8InXrU%7{3Q!}2RRY*Ni8_tERbdZg_A1O5j$V&1A*2g(5-GErB|L}*&{61mL5l?&$uJ5{}CE;Z#h}N`6GtK zVbF3`m-XaC;*DP)a_d9INRXRRyUJ7|<>@5G_-hxOt3{w~LX&z7N!-2+%%eZ&P$d-W0B?uXc_<{6xBji-*j z#ptn45lU(wz-m(yZPy3=wzTX@u7`Hgb51i%8HB7n`}mf~RUA7?Z>M*%nuof%*$;x}?Bg zSlOk4e#Z{*WSQ%yVR-3RvgLIWj-8#(Ej_L+7X6$Eooy*-L1-|axn3=L1j3JQbfwK| zVbQ+(d(@W6DX~FgBf=vrSuE zGsFT~ZY#m@8~;eXQZW8`;tfnMV|_A1qtPMfM#!!ArfWPlWf4bZE|7IQFOTj*@^?pp z){<~ybEyJ<6R__`ZvmaP%}+S;pf#Gmp*}}Gxetp*D#Grb-^Bj#TzvEV8$e7)mHJSD z47^&9&@zOSs#Rg<^D5klAB;-}Xn~W}d>H?ml4bh~aNW;`oH(8JXg#k*g$iHL?3(R7 zPmT`^gKIy0=#eFz!kDou(SI%D_>KE0X$LrcY6cbWCV0gu8IFd4Kt#7b2V^w{{!yRBW-cj7Drg1YXC_Bkz`ju8UDU69B$&zb~Cqi$#BRzig8t&T8etu{i70_n1-JlQc80kZNV;k}5xot2E*;AKc7X(ei z{NeJn|L9*emY<5=4CGHf?>#P5{D`!QGl+T+>omBW11s5gYr##1$*$Lt#xnu$!Eozb z0<))d5{v2-EPeYec%D2(4==Pt$*+E+j4&sX`K<--dguYs75(JNLVwX&OW@|{OclQg zEQRQY3ZTf#o3g2*E3`dUUlE3x2tiM{HyCRIFgSQ+& zPOnSR>G^5I_F*yJ8~6ZXMFV(itK@`U1kB?76?fKp!p|N(T3z=PXC%IakN4Rok@_;^ zccdK^t#BfT*0Zeo=q$*ZU_^E7r0|&Ishk4ivFmd#g8z&^=(T1eIkG(mU)&ZC7gF4) zL%k5~y`F$f$Jz6`M9i3LP^4!8nbd%>Fp4QkIQ=hDbxvEFb>HH>H0F*X`#* zXMcMos9KxKjnH6yo)Isg)KV3c-$~Pl7HdSWPuBxxzPJbbr2!fSLu6VO+m|WC8%D@* z1?G?Rx~jy}uo_Y(}d;;8#(z`I^q@E`hX@)fa>k7WM$e@Ed6%~@8#aL&>gwhC7?4U%XtlX zUVA9qx}{5lnP5`|z=A{xrFpa1s~ zZ_E+FC_7hryI)=OR!$y{aQDfcA*|=EYAG^GE8x8rZ`@sASiu)^ds-Y0K*eCMkU|fH zRU-DFM$>x+G>WjgY-p}v848V4!X>XJLw+V9Hs_z?yEmI)bGsGYVXlZS`P3sRlP#pS zzY~Z3_JX4;C1}R9&A7`l7{yQaAjqu=KRNvw-h{-`DXf<(bE7IauVvdkZ0GL4`aXEb zx{~_*VuVy@6#8#zM2_rNi5&U0j!>EMm3Z1D;ro*FIPcOZx?Uk11=c2^!uP=>$mTT; zaZZ4~+bo-4x<(kSHxDxZ>)^c>wx&v)P%4gAo#0TpaRK_4GQfvdupSSS8FCbvIp8VL zsT?}QdKePcu}%&}P}w6v`@(~9WNAHg)-a8?B??t-u7|81Z)(3~QwSdB4NoCO)rK6i5udTHohmr|m8M<_#<=QGJw&^+ z`yJ~O<+i;;l=a(BnoxynH`T$8<=(Vm-&JAb7-jA-%Tb!_(Sqi|^Wd96OmsFB;7;~? z7qQ>F)zMmX)vOQUVLM1mR~K$%yDh)HeW{;hm$3BRG88sai^pEEGV8@!&bTq_ww*J4 z2q(+1*I)Dmtu-!3Fxi33AJu|IMzJtlY)F3`RL3js#c=yyXp7|)9bp8^S~`g$iNwA# z{OLy+SgiJ^AsGlAI(i4~*=t9x1h?TM4cU<16eGY=7!}Gg>h56EbBt z=y%r|@!OgH5bH65UR`$=O&q)lrcN#(m*d6w`Q<{evrM6T?@F<5xh^zBDwD_Fg}X)Y zi0$%39FstcTFS!DIulUWGzDHac78YphQ9tu#E}6w zZgd~Wu{U*2RXp=B*Py3+y!l&Ru?EMD8e2|(tzdq-$CJTgcO>t5vnx^JzOv8i`<2bY zbp`IoPTz*-y)n)~u)4~YTFzvdyNDZ5Bica6A$K%m_fOQXbD!VB%V*l@j0{uyZDP8q zr_c+WIT3|%t@vAbCipBfqK7v~;h82+ zxDV&G#j~?6Ld}C;sJEt(_qlyK83ZPowluv&7nwH1p@w4vIGk&$$oCUmt2%2SIEM95t(1lt z0fXS}uPk!8x)2Z6tA!8=h7T{5P)_ecq3VS9JlFluxfOPd_((nuOTs6{#&E60+Tzb< zn($`146IQ;&3i4BF5ZSgj_x#L@N{AQ`1PD!qmEd0avzi(9uE>4ZRDp)7M>74m^+*w zM_*2HN1@N-(AKi$WX_uptd}VSX2j{zUx^XeTPcQ1)_C0h^CxyOsuS6{m3((fN_jrHB*@sz>>*Pw~f1DByJ~0WLzY<;_&MRty zwVQ0{5Ems>Q&fxO_H7|+vpaF$AurY&BS9}d+>DDh1))Sk4|4r@6MiWOg5Ae#>Bq#& zq9cjDaKkK)DptzFu6kt%Igms0?iS+Yw<9@QZ0$Bg7gm&MXMe>zdkNi`VyF`Uqt3Ow#rHq1J0N>>c` z6>c-KK@u;Ta=agW!=Zz3gZ5B&Ds?vp8<_=xH_K3jT)B>R>o%ch&q9c!ZWR`+d=2-X zdC?aS0)+UZB3HIHp3XR|1$m$kceTVMtR)}YD8z7|m=1PkcrB`l`Ghtc*+Ek4yYS7g zq402&AAMZeCG489jP*Ba@%NNv3X8Lr)e zB}yK`f>uL1>V!I$k&fZKlC;Im1r8v+V=hSLMUsLgWq3T>LQS*tqwelPbf`ZFnclSH zbz{roEC{;lN{!Zp;BJ;RQ)k~V#YWA@+`0!XTi`s*$D>9Yt<_3XhYA4G3oVcWAaWpP49{C=s zMlBBpbcwfvLRnX!fcA~i$G8x2L+_W<>&H~!w(}%-79L4{G9Q$+vK!K4o&5jTB2r6l zLH-0gdT?$Cw%yzV{p@ERe^84uwZ5ZMy9O}%NNP6(|MI5)-Iod+EabtR~ z%SG6I?>pK${te%ae4pHcK-Q1+yGj?$>3N8rGki7;Wqynj1@6FE=HuF$jm||$f=9#v zH=Y|Zh@0f$LZ|4y5-eib3dI8~Q)&7F<~_OvavyBz)DfA;Szj8qPst{4@(b~zdbY)| zz@Iw*Rz+sR77908w&R6=j^Gm`x4=}>k3^;|5wCs{#qDNUn}x$Qq0e*(+@E)veC%n) z|E>hVZxb&Xziy^5I&dAgyiG@Zp}Q9vK97T@n{7m!%fbN`gE)43LXZ5XE}Gph1A~9wClc!`u#CkUFzmOXySIl6Cz~%u?;{Fw`esSwtW9-+ zR||fUgJB8y?%Nk&Se8l!_SGmQG7lxX-XmE$)p+5n42bybLb)s}q4lVVFn=-S{crzR zpFrhB8`{513F$4aVY!|Gd>+5X69U^L=)tX#Y&);Pmi_Kn-Y|Sck?>l*DrzYm;K`f++QOxTZ$#{#g#B?c zH=X4f-;JLL-vbhm<*K{FVgac-+BiIKtjU zj;Er~KKmLllk}yv2RCPhEmPn$Sa0*3^iFhth$`s34<~{BI?stIEXJL^mXwhT}1D1r0FS#)gcY4l;pEwtjd9q+H$sFDeJbKIy+MhNcMB+X4{{*Z@?&FHB~ zH`06P!)wJg`46G|nK4c91%XCDBxlU{e1?7+XdhV*ixi%b_tj!ta;XFs{(DOIyq95H z>utz(OD2EUQ@@f9nG;;8%U4PC$0-0Mofq=`Z%02Y1g}wDq%AK6wT^IG_E#P_?H_lZkg{^~!!QZL@ZtO834Tc-IP=}q1 z(f+ij=<@;xJ||)s&vrSP)+aKL#~UR^b8FZw!1YNkQmq;a4KIAiSC=|G{H!k1#ZnTLesTn^Ww1&Lo!wc~wWH%5jXkiW>AjupuW?w-8GT~yH#|4E95xh(7A zX`WAJBFH1iJWC_F6o}*ETX{7j8G0shX2>0)L(jgze3uiB}Mwa*W$mwyP z@!ad4kkmGh)*d4GC(8j1njJ?iUihNzUGGpZ!#5}9Y0)~61|^I?k7<^~YU%zkUP_i) zFJ&8=>%X8kdT&T+Rt{cKUkR7l8*}M38?@=@1N36B1FvIb>>j~2JF*;*LNG zy(E0uluf)u?C$^S1~iN`r|w#%!kwu|D0(@-pM7_20`ZNH#IY$6S1pa?b}@grd^x)r zo@F~F?@#kuv46-7ki6+Zzp3d8pGmCYvft~7Lt=ZudE;34)i{9FIkM6mFmCg((+%B! z@c=oSt{^oJKj4JiU^rT@OE+$g!0!zsxfzvAZ)siv<94XSsyTi6oqK>hy&T;7=W$a47Pg56dj2;3r7*_vZyExsU$)z&SYII$zQ2yN_G~>?z zR-Z0*0h!ty@Hnfty6mH!T}z z{PvBQoJhh-ss3OhAxpbv4?@EZ#i1`}@A4h>&J&~HTe~Z*`n^J^Z9JRx5_b?SlMI|6 zQwZt5Y^h3(9C~L3>zRK{eort+(AahUz(HvEQn|3>*z!M!g z=6e6I@}Hrgm-CP0Ch6lw_H%|a%qMTkQEy-!%2N*Iu{tX82J0SKOoNhE3E!E_X8rtP zvM(SXn_d0{!K-X(m+@Hi@!<#bblXn;t~W{Y4sZ>=bbWQF&}I4}wDsnIcH#F>2ey&# zq}bX6mt(n{qZFU1K(zEBai;{amP=fZ-Mar&ty6bhYDp^cDtS_P8 z(1}Ei16W<_rof#$6iQW;BL!#2MsTIstT(bP6?RlvK-a=&ypB<*QUd?Wzo(F^c$NEZpTO~L+08bSWMJ^h!p5&7T! zie5}UL-vvuY%ts(tW0HT&W9jT!$x@+`SBfp%PX6a3dXXmLu|V_I{GpL*{pHkb&MSr zzOd0xm(J9P$J*K&91_OTv+u;HuuUFbsQHr6V0O!^@PlP4vb4PJnqXDGCc14uz?p58 zM!}%WexhJ@74KZo39V^ybnUiyRI$7QrF0J9^GK#koK7<4{TRa1QQT2IhR@^r(59&q z;Lyw{K0gw2-wzPWtX+oP!b@J4(d7p=Wb9DZBQ!k%TKZk7>*oag?MDY3U~iKhlWS4d zratsFz*AeAAD`)FJ1kuzQby?X|q;{TL^mHo)8DkHj`15g&US&h6{f7H_?+0h4_OK_#3a zn({4p_JbQR(!-1TZks7wbCLBV{Lm3sUF-#|$D^T9{a*xDDh}s7>$Sz7t}lUa+tpyI{Qy>fxLOQp`$Tlgsz=C5 z>H(_%#(G?5G_g!U5Zo!>ODld!h_WLFL*14z;xfMi+a1y1{;Q9rHb+~9Bh3~fqtVZD zGKWg!SarKVTHPPwVVH<7o+*aGt3|Y>{teP!Mo`#?d!*I08XIIW&v}k3U3>GC@TQLz zBn%ak?eWjChf*VyPj#Tf$ElzZ!>Z8kEnCS^-%cD{>kDD~WawtQy?C~3AhP%MAng`S zIC5MB9B2Nzz&?M`o5l{%VVw{E*PmbeC_v!L9P-hm5a*k}fPySLI>|mjSP`v^s;nb< z-DBm#Q?Op}oupVKVJnuk(b8f$3&lZb=cIk+O#B{>{Rti@}hm94-~J4V1A_$obrLP~C4%HI3D?hF)fQjgDAaq~3{scq@UdA@iUP zuE5K4?9rTt0jv(2H55*?OVE+O4RGqja#;6_={d2?55B1e1)2?D_4ljSAem=|c0Zb`puuE_@*F4!F!< zdxhQI!cBGyk!tFI))BQz2eJ%*kb_Yk*wsOjYkd?)f3i)dErKGnew-tZ+n3Ho!O|5A zXs@g~KKUS=8^rF3JKXKzM%FC&<{L#0X_n#SBkTqt6w!x^&Y_X%*U<}orYrii;R&qo zrORzEm7L>>S2+Zw`j9<1Br6(HV@E{WnZaecw^)AarQ=ZC$>vUf} zOS1L7ANzO9(#Q#cf=PQuq153DMC$E#?BT1%Iu(BtlZ#jJ$Fc8W(xEsy{dF9gyt52# z9Ph*H&zV1O!Dois4}w^hq*tBOV!Hq}VSOm|p%z$ie&M}~0$OXFy^oi8e1_y$d{I89PneqW3EMKdal=*%)nTzc{Y z^8DLK-1T$t#y=&XzJ>Xhwpycj$ta`|>%e<3J}w@{EgBm~MH8~ns!M-R(g9ym0S#Df zSQnHGW;>GoIf4dw#HF$K^4W#YVTj~Sh%ED=2m2aDyJ|{cvI*niN2OrVzQ0H*cL1Mb zkOY_67DpqO>!TUnLSew!E<8v3I3Cqu34+-@B!Oid9@~d;9X}Z-*`Wc4yxQ_i;ldy3uIzxRrdD z^0K9=yl?`M?9c%lQd0- zZTM}#Rpb-Rb`s5-u#;aHxNmi%0+Rqy`?U9c*$>#$+xv@43R6w>ska1(Z_DH08r~vW~yVC9-E3%p=4CCbcVyS6K2Wmd92-BP+i2H~Nd|1K`)z9qA z@fi6Jx5{0EMe3gPY97TKPrrm2G>%FfEk`dDs?nqqp+sA{3cGD9fbY9qnMc}7Sghs2 zX@ibUS>IGi<2#u@h~}+DRguyD;=#hoxhEY2}O#VdEVk z@@v#0%O-urlb%cls{WI#Z1li0qW?lU^VF3Tq@b~;&ylyABiWkXjGt#mz@2$U^!+|{ z{KWA-*Ve^$c_!Jz#iSYVvM-8^{$7f=XqP~@yO_H7IioFwSJA=90lW=ZkplB>xzS~z zAz1wH2F%o0NmGqnQRJ6a6gbkCyj{_VlV~L9*c#Ks)ktvM;y$$jsd5#ZCZx-@7>-y0`DB`+#ZTaH4O1OF0 zirQ~mi%3N;GD$r{lFzr`j|v5lcwR`ezrPmETqpzQ{F?c@-rtRhpzP*CUrk<&1a7Hl z)Eq}%ySV4$1p(}Ly*MTgFRWDKoEZ=K^iz!Tie=%ZoiDE^f0{+Wv}*xTS{&|%wjOwi+Ex!>Y+~yzFg$Nc7s$`SyWP|{ zU$!aGySxuwIz0}~?T8{re9Q5)YXnS!jp)tF+rkkmFQP@qZ23+h@8zNJa;6)-Rh@w6 z%x{4J<2d>WYS7Z`59obA+bCh3La)xX!=sV@w6$Db5Pn6S%lpngSGm(c=ZgTA=ob*9 zJ9#)ti=biO(#ZUE#dyc_2sr=4le!js7w+>pf-0qF^LtP39$xTrvVit3eTFT+%X47F zvJVEn$c}kHe|McG1rf}DGBO3G)ELu@RZ`faHJ+;tXLq!<7l5!g(cy`2$onZd`1`*i zSp6=JM%7v)f29Z%80|m;6I!v!mSi}=ZZ!5soN-Q@JojWW!`rr}=-~E#l;r=?&lcpm0QowZkBq>;u+>c&=$tLgP z3)%j)snFJ~6ThlG$~uZIAaH9Bd3HAu8<&Q1zo@o&SH~!TEGd|;aF*AWFYdbzD^~ha z*>kgnDF>EtXCDX=7s`@h z$`dzQw_=oNFi69`*f3tN5QJAlkGCx?OAiwcdW4X<)N@{2*86$|uIWlp*HuaQ*Pkq8 zv1b5pAE+k+M7z*Hg_FV=1!Ex3Q%o}NKF8AKufX!0HU0T|B-)lzjy{)cC4f3{@xvsT z!R{vAQ~a^5$RB0D8PJnw4!;kYvA2wYJk-7z4z7lTq)#fuF9MsO ze3}>QC5sRqvr1uB0d7nxaUw?Bf95cBF)X?R*b<^3`ggX0$HT zy1U4bn;CfVy0>5&>P749Mk5lEjXZ~KBo(z?IPZESEYH@ZGt`3c`T8O_z;uJ2tVk4D zAkS(4i>3R$I?&s>BcUTUf)umtO!;XWWSZW|YYtg&ieLi!JbX7SM|Pr0biy~3od5U= z&z8-D(?VA&_~j|QP29L@p^kXm?I74&p$pgkiOIEj`Ph1O8? zo-FfA6kmhRQNDESr*@%ZnkhQ5VLbVB`zx;BGzs*+{Uj24p1AYCZ$NtSw5>G-jZQ2; zeq)?SGP_xH*M!55??&`rzB)cODwNyuS6h6z$`1DL(S_HV(Io46DGvPaCA1h6(2t9* zpkpom=)x^~@@G*S4nCL!<~ajc>Nw*DEYM#?rx&=Qbu5FYW9mzWK_gy}5DumFMs(C+ zp}_e=2zR|%Tl|&fZd0eOhK%-S#KA<2C;OB@eM3I&UN8duI_uCo?kN$(7U8LFk6?SZ z3$>gqiKhSdLI!IPuQ?c5nS!BzH<{3of))H!xuS2eRFV1GE|2_#TF0N|arOIxd>C(m zsOWNy$gyY^H+T0`vC#1)Sk?{(MU58nF=5&&vmDJjonetv0@~7egI=N#;S6Nvg+EMEAIz{bLgE*rZIxj&JFDJEyhg@k78QF{$eGrexF%pBq3YBO%1)Kqan$tRffRt@yO z3~<+ry8RF%5l?d$x}ot^;mBt6N^-~I1Ku*|Ce*j;(tF#(@s)?IFg@oK4NCPxMJCGd zZ@fQwE?bY&ElSw_djTCcA`Ok2AC4qX4Di_YiH{-eA}g>JtBGtlDOjPzdcvUsZ;1(q z%pJxw`n#jhc@NvnwSAs5f|JPEJ>?4AJ10SFk0s$G-4b{|zkq5abs&4zgYnEZgzv_j z{pK;-`*x!%R-F=NI**18Jz^r6{T%D&S3{(n10A+i8I3V7Llc&5Bd$9;aS_Wo7v>M5 zduz7in>D^DN5+%af&Uq3Kt+}`RUa{2w3>BINBhK4GevobUo;FP8_zrx;b`X2d;HDL)bc)D zF7x2GO1DX|9)PO@cx$3A$F<#$rKkTxXq;je8nSL9x%{FFKQN7e!S8gb$+z41?w&X< zB3N6jYqSRLjhqGvmXqir-2(i2Zz1%uEZ+W0QRsd&g=$4tYX5P0)~OG&oW(Kr_iNRT z{+p=)-$q7~gb5XR-SGDiVPHeinG~Up&MB05x-+NJ;V-_luMjTf#M3;z3WV>Kqra5{ z+JetH3iV%IX!S);p}mbO7rIVI+-n^KD^jP!@te5>F6HBw`Ylj2&x&PNHCXRg8>*PH zi|kYD!Vx*gDd3=_-^?%>@6xMh$b(~OYtz%5=b^Lpnm38P?wKClKwToZ)a9NhG022>hbg* zR_?d~YR#*uPlX#&b!Oy1dP_Ng1h&g z5uX~0TgH}v|Fi;He`o~j!>B{H!l%5S&F%j_)!kRU|43NeH9TiX6VzzN(_NqAP~O@?6dCA4 zyx5*#;!|ZVk*wFN8e_@Mx_QFX!QOtp6i~u)CgZvylK6@jKDHmg}b60PlL8hhhJYz zz&zy{Idn1~=gy7gY}&NNlS13jrD0h}W@|dB-&@SI$`IJG(vt?Ld=n1)yC2!6&n6!F zpYiWtFPLG)QT=5__~&3*P9Pgce?PXW^C~+fft0@^eZS-~ULzsP zsY=Gt&xTLYe>1+L>9xN6CP=gDd&su6qwT#!(D&vcCk$ko0D1;nC;CIoDj(|X(I8r0 z`wTKGTDwJ z-T4lvwH5u{uodOXNWx~7bG#1hILi-wcY4!xxif_)_budlG^UDmlRtsUTvgbt)lLj& zW#Pk~KUkhCo+eIqL!-UIQ25mW4y^u!bzu#iK>@;X*vb}|e8HNUb@`#j6H2U`%b(xZ zo1=CgDIfJByZhhZh^Yy%i}iWFh*uNk50eDjdEvay;2>KLxAUy&*P-`?{mKHQ*Y-ST zx}`);>bJ`<@u(zq*_Vtb?oUViZiMi9@0^d1K&j7-Y6M#gS5DM~ull(>CeJV}hyRgu z9ez2rf0$A!qhX|w2n`~eROkL4Bcrlq%l49$LZyZFUNoesp+ZS%J$L7R+G!C*Q%gh1 zCgOMhPXB<<`*P0pT<7{;!&&4qS(qV zH(u`zSThAIibTolZ({{58=Aq3-h~@FC83+<#5*V^2S=CU4Wt9?Hu;jnQi)9GbQzQp zFwA@P-<<&q>tEc<+*DjNI+5K>-}hFZnGm!o62;Pu>M1=Z_g%ehDCUl=yQ1G^OzV(CZIu$6mZDBLgt@Yo%8SLXtv!ZiMZ0e&`NP>P~JX_ z$$^3k=(SRB-j=6-=`G9)ZrpPxK}YlPxesNaVDp&VHF%A#?y5rKG+*<7{o(pFNA}cS zHQ_!s1R~rtpkqb>_gqkj|1)_HHS}sYs%|>c>uyIwwkAAJ-t)r`CR+HC1ET%R!8$xWGNMF+X1y{U5R&QLLDs47UcHi1^lf z_^u`GOI)~vOn>Z(R6Co|jSw$x#j+-xHa!Z~#Ojbq@kmejc{5zlF5z+5-v2c^;gQWb z`98-v>W^qY2HieBC5l9PsDFq>TyM%p>?x@Yo(g@uU&3_XOV}!Ng@hUHLdRo2pd%A) zxWmEi*q8d#UMa33E+JI{(MApSp0zs7O;p0{0ui`^+c~3G0$khs5YSZ@vZQ(=dS;e_ zwrsQHH<-R1a)Y-Qwa6>(5neWFBD<0LtR%~X=wYuIxNY#}?{U`!&p`bm?IOFBuNUti zOTD8q{I==!*>bQ|Z3LMxKLF>SZG;HAvtVA4gba_CAlDL4F0!);KQoxXUVooRmg#>& zhZ3g3_&2efgVGB;|7aeRZ_y(IQg@jpQddw@fjNJJ+k15~eEU3%y?0kOz}c1b+uXhm zNp*H2);EgpbNla51JssykpC1U^xF1KWQ%7dlbX5npk~8rST88%^yU`g!+SH)*b~Ft zxU`7wNi}(rvkU$(GjAV5-v$?PcQ$^(QlKZ%l2oMK!~wG<*w$pKIX}rpb`syvgF!EDsJsDB5buN%&nx7LEz#36 zOJJvl)BMQiBDksO2{%nV$g$RXfduu2o&AwQ#w-`7xy&zUlD~ipyif1-i#S*y=0XaT z#-XUtWz5U5U3{13f7x`eZpr{RWq%5mz1jkfK~$TH*^i<|i~xJahD$1L!;gP@!73du zlGCTf{Cthru&L_8OIHR!j(+2;zd`d~8*=b7?XNKMYa;QQ>V&3$h(H$i3^_HLs`gwL z0PiF<$;FY;ShCVw5~fTzGKqEPX3eBM#<34UG0=rv7Agp? zefx(VISupSy~$OO?sA#vZ;519`s$#yN~Js>o}h3GI+H}m#i}%{Vv>%``@=aCn_4XX z;vuMKxDfpGGNaY10AnKZ`OOY7>J3t)+v5I5WKm>aIg-gb!0ngq!D7wSuWKSnUS=G} zi(k8;g)`hZ9jY_Suf7ZNBVCEYDL+B@;|5qqvoohkBxzTHB<%#?xUDx!apLS&SYzcw zY~Ca=DSqRT@v&H5*F87lKj;(u;xDyZ9i;2yup#5GeS*rt0)go#8*`tCEtni+GCR`lZRwUOXcKc8q_2*#ssB(Ujp zQ&Po$3%I|T10Vj*CT`(HczvY+!i=40CVg{Gm4pO4lm14e7)QlQpA&{szb0^JhyN}HO}i&V@n^X3m;~*pbuT{Nckr1uDsZZ zNnj#O&~qj-_V=*Ef*`1?H74TT9_YVuP3U~}urA@cGz!Ms>X9vLSiRfDp={4jRbkVf zr?7X&CWz86;X3>X?(TkxcKc;>2`8W9MK~FpC0t3*6H!#v?~I)3#OnVyJE|_O1TT|5 zPChRUhn|*WSBcY%Rd)bN>ghp`{yJ39J2+WxMJ7n9KKK{g@YctbH!Hit3V`&qA0jl9$n!l@>hj9ojk( z#yk@x@JJn7SH6KDL&^_L>QK|Ab|mi+#qTH;`o4uGQBQJwwuIi#ZaLP9=J@(5HK6{( zDv%a0;XWu8;_Ci%G(O-N?|FDOGXgd(_afaMe;B(k6BPGoSeJor8%T6)HGbMF z#=a@1S<5a@l)Lpc+Gl#5*Cih5KZLULI^=KTNW5Gvp3S6OS31E4#=AEm2lp1fgJQK* z7_zds#;hw=9EYY!lb zUL^UR7PDfl9&7tcO{g(;0JJAefQu=!D4-f(BK*>DHCR1%If7Z`CTgZr@Y z2R~RhR+FR`N8vH2L)j8>HDPk)dhlK?3$q%0xU`{qta=~}Dd)L!o)cRz#Du`a2j*n2 zzog*wiq8e&!T+(P$IY6&v@ zBmuqV95?z{DYg!(gQi?}(jyzg=+Lfh^SW3*TPL&U6j;q1cO4)LeL7{(-~InfO4X7`r>0z9S9@J<-lU`jy6X%c&Qy zeH#vDujZ4jn!(stDV|k)tSZ#j*#eVPRiN!B`;W!(2DDzY{zkSrYXV&zQyMOwpU_-aOyif3e{OcQASE zL6&+JV7at%nD!{0tUum}jJnFu7^7hv{ysSuPP;pitROe$mctFU_Jo@7etR%HFjRwT z?Luypei2@l+z9uRFOYsS1++cq9U7r_gva62SG>Sn;7zuE>S5-bUXB9)&g6IQn*5bu zP5U6P6>nPm8LEy@9NYQ?NslII?jbAg$e4CqT^0#KA3gH&lOkSd7|P~#s|rV+FbBoo zY9Qwk&-LxA#?Ke2u?kPsg@@8x&{iLJw6gswpXn%y2!X&DbFzMmH%<<}1CI)f$tMdB zRN>x;ZhrLQp6zMEZ$5p1LhADg*YVOjurQSNg3?ZS>8FscxCwd#OSpac1gD>Pi6V2e zdH=91)yIznnUid>US`TeXQV#~czrl(>`KVLKFo*b^~kb|=#5M@BLE%V+Jl^pZ8(YJ zv_oS;HoOngrnjnULH`?7_R;}$p>tCOl*Wyqy}0eeH@F)iU}0fS3|y8Xw{4G5lg%(D z7gxK(;WJB#)rBV*rpd7j<&#L9h!EXK7zL&my!jhk?AK>7!+Iqt&@I%n%pHf67s~Sf z;T=`9pZ4-d%0mLNAqj$@ICJtL@-mubRe&<4c=1|{7JnIs(L+0U6Z(;k>g6J-ZPBDdIPbnH~sC4ckV!&Hm4zy^z8q|Be?J9T?pRn zNi32FnR7P|q1*+FIa8@G_`)O)Xbaj%-b=m2CvT2oeG2LABgGSmnb)AiMbPx04_`+;> zI^CHt%e}By{V4Xvs$}w}EE`>&`3ZR+_vZQVlz$1}VYiC@zxe8{i-~2Gl4y2mM-g14 z{pKFqJczn!y`XhW8TjX?6H8x7n7OAPbu2fBIAB;u!6qYl2=lXb` zgWQ2lV4XCK&(e*Juw{xF8Mo~KQrYqUJw+RCM?f3Sqxipev=`|y(PFy3u4YdzR2ODW z8-N?f=|)<87uT(pgJUJLz^>7eTrt{;LagthoG2sShqf`q7n0{`lJfW{d|`A5t36Ro zSnIhSZtRi)No`;L26yaqD3WO##^>>4gCS$O1xZVm6exRqghPjDx2lyK%(MTER(u=g z#w{5#>#3iiTOXkvPES!|yD=va@5Nr{?}6kynkD}kgym9W*%7ouPvL_Rm`g}@U1)9C7&tjLme+^J zpP9}U(@gXhgCRyT@eI1H^nurhMTskPDtZ$1qX3_rRR*Ey=YM)WwW1i4?15tq47&@2&*%mr4w z4{gnhdoV{qk37{<#8#Hm*sBGJT2R<67c^4o z8t+4ETpR~!)F1VrFAOWy_d(!|B(j9=)-M0>2DMJ}<~*i1;rZ0dF(;LFVodPSa~KL@ z7g3IJ?L`{Y2=zfrx0Jj7g5cfu709eOn=4=a9Q(XYgw-8x!d`V!7ux61 ze%bxMk!p53*SA)HON&AsfKfA%b$IFR5`xJ-uO0)X6 zlE}&1`iYgNkOz@_NOZE#u+z+mXcn3B_lFS0L6m z%$d742$3Z9!OpnXggaJ9v&N!HWa7~QBqu!uwq1?mJUgp#sK zWijmzcB8x_1$GJ?0ahze1Glq#lOmAWwAd(hKxE z?>d*bt{wY_CcvmNZE|kM2<*6*I{D~6n(^1`utKR02@6{2T`Uj(HLQeOwOmpmcMI*S z2}X;~S#qeX1CI}W0iA3xea9p5tIeY9jK4|5e{(j9UiA^JPw?jZFh!2YvcIQBkiVyY z>$Pd#XLBE@3QK<#f;Eb3QykqZMkg>c-By9JgJGO(!WUVcy=iG+Z$GCv(bT8twQ;T8sRth04Xamo^Byy&>zUy9$B7(%z72h=zl-dWjClV;j+_rHkkTaK22r@IV=8+$ zC6S!AFGZjCNJE5!FRw+UfC{^#OkKEDXDY1U7mR-PxpU9^oAFimSO^lMeVDi81rPc^ zfXulhqPkBG?DqUZ(raV5nnN$~=~wSzV5K{m5|zQs3SNoM7?$z zpNKw2L7~GqTz4iG=JwJ~lB^3%%;QP0Q@eooo{a-(cK3MNbv%pmVGiZ#;jmf;McuAZnaDnmillT+TN@uv0{zPW0^D*vvvs-gGAY_h!81H(Dioa&S^=3z+ zc5GA526HKJ+%$~6w%@0+BPjNcX#d09>^hBX&wR+6xc4vqcEJVWIz5S0Pa$?aQUw~b z1;qPz2Z|4;Js7Ve`EJbHhS}72?Lr#lJQ#y~J9d!no~-Z-h6!nN;N_?y?yq$b{wn?s zdR|^7?P^MBg;5jQ7I%dE9@c})LR_HA!JC*%(Cmh*7JBbIi<|TF8~(1P2(40oxFx1; zSn&KA_+57>o81)#*IV>Re~==M`=-cN&}VFA-A|PNV-Cb#NZ_>X zs_}7~ne0%Jy70~B7WAXo35D$&#@^1a)VuiJiR9i6!xK<1WYO*gx6jR}_D3xm-0967 zQE$Tjh96-{nh$x}>!<*hx^=BNI24#Zv@cU0GcWRjsZ`Gg4zIv=K95L@Qh>1Q& zwUcr<`9rk-N00#OU2Y^!P7ED-coP{K0r#)=BMyNj;7EH0D&5nt(c1CsZ58_4x<3F- zIo5#!PuOy)yD63)ONZct+T_gbD#4WB%Ivlq>cTbN6>w$dPc*)_oja&Uad_TKc-x&s zHr=yDr;k5C+3T&i)A!qPFzXJPQmaVw-VD65U>xfjPBR6MIHdG;Bt%W{;d!#0>N8M6 zI^^lr5SHe9VqJHBQZ4>u;S=JEN}hiEpEdNxM+UWcQuHE4rv3-3?+l~WG> zy9C5D{}wvgcn8VswB$V%7tVyh*`3G8pOo{s+cXeP&}_wc6=T$_)Q3)04)f$U7ZSjb zdN$Hy{PpTfqS-3Si_)JKLcXRW6eQAJ(FOa?od(qIqPh{6`%iYOt!=JL8 zVDlC)vi6)7<50Yuovffvzb`(5l-hWRKi19P>7JcShaVf9h^NI?#Abz}o4q@cJQS87=UL-H!ONF(e_xMx8{9!Be!6p#CC%97Obo>Tpn1AY z@`9Z!dZ6wU{asdvo<{epqM!hNHdn$6Z?ICunD6z0e z!!L7^QAt(=SD#ahZ#;|vi-peQ_U8-C{3R11l5RKrzcaI~z6AEXq54LiEaEbXkeSFK z9-j-BJODj|1%y-d!3(5s(hS=$K5uKj4X*y~ zO7R4mgXkTnPudDkGxKGn(B-Rfd9uwT@} zc8}j<@_Bd%*6yHw^~pP!*y5S6QL~>bSf7Pm90Os2f<8GpvXPl)k&4o;?BULT@4?qY zL!t23d}8kxggYCe*{v0-!j)T$AoT5Y7|fnae8!gGx3|k-%VGgJyzD9R-JTAEOP$D# z*iAY2`~%_RJbhyL#St}ak_2U!VXRgcG{C(h7G&$bG{)KT6uLO3kJmAn5GNq>X>NLE z5k3-I4oOHrrgwIrJv$1JE%k!_znj9-D+B!Kx8A*nZj8nZ8+L;ey{VlDhI6{Jp=Cu8 z-_KTL@eafztjNKX8OYqB0hLuA;g};mSZD7-v~A@qzFYoMrULzM_``*Gx#2l4y5Ycd z`b~N)72S);L0`3o@wwOjE(E;NB^^l$Sn{YMYaEtHZru5aHdf4m#Igjw$5<*`nXN5Q z7v^cVpprFCDAsfspPkHNVC7#YVi6ODAF(~K^kNd(nbM5Z^lOnC#pev!CYMvcp0=E<~CA7o{%TBy}0?IF_NL4LQ7y@!gBQ zr&{hL$w&;HIeHWAHU&ky0uIrxMFm+~G%F(kdAzmc zo-U<+jI$mvZBUzRTuJW^Ipf%iRC{0alS5{s$$UZcPCWvq?g76KLNZ?V#w;4+776FLFBT z4^t(&8+mmt;$quA;bUs5uw&pS_xqItp6xh-UGyV~cx>`SyGB-`h~QyNE;|$puamV& z>*Ifd9XF!bZS>#qvetFDVo{CuU(VyWQzO_Lm9&>TGz-m;=|w?*yt&haZrN{(0X>tIGAx1KA6 z<8C)WTE&yRp4%Y!R#ytXn+3#=cIIUmbfOt%nEPd2hV$2CfYTKhl9n?T9k5@>WG(u@ zcT)_?tOIY;Pu!+)DY#s`4(^;VBLyD&5qbF?>5JKMa_8Fc*G{^r5$r|6qqUfKtCq60 za_YiU>psG-sIgF8-Ob7G%E2%v4L+(kk+nlxP^@_fs%+ZAwd(idq^+KiIzyA}>yE^O z@(QeSaU$9KvjpkS83&m)zFfrTdOUBD5*wJUF5LM+5lk!tk?krE-bW#p5d|mKIFr^Z z@`9+q_i&QlFQ$me(Jl0^NYx{T-z`mA)DBmR+==GLK^9VCnt>&UH%(KC-hIMwnWVp?9*#ysH37 z$sXeRqPuaWQaoIz-l18Cyz#dk4#-eAtTRi<1j2*Y?j+<{fMCn?N|;EuPF$Xi2Kx;n zAR$h;MIxp6z)%tF^LHXA=7lkTFN{WC=fv^+`Q1_z*zEtC@1~G+iel%|48rG$%CKu> z0J1B;$8UcqdEbF$w99l;@-C)wJLT4-pF4Cj3n!f)!G5WuIiN7w_4np6`Wv^0d;Y2i zpOX%OqDH!5q!WZ&&PTB;U#bezejCE~)T!`dyee6;z64ioz73h{Hj$Egs>djfhUnZ_ zKG*zir2;#qFOjU-^@sWfPoVODAM%2y{>77&9APQ#pZ~A52z$F%0)9e>#`s>eX1)-W z=tXf?HowN}7o|b#d?zx-%av)hwPMS>)r5iC!C>7n3nu#%@jb?Et+lXO*Njw7RYW6% zZ;_bzQ7(N+4?bVu40xeGQHuV^1T@Y=LFu!2JvritJWMGV;@(ei$2AnA<~(sG(@Z?j zzS2yjTS~JJ)O&2K_=bAk9Er}-J@}XI6gIz^ZjbK#iHfUL;Dzo3?qyLm7WJIQ>b+4H zz8ckn6gJ#M1>7}mw_PW`xi%8MfHT>i7>3RIJD?_%V#U>F^q}}9`WEQTjTvmj%RI-h zGpKJ?VE9lk_eB8vS)Oj(j7@`5;aYg(`V@_q@fO}9-{ktCu(p; zXaRVfrg@^if4WXz7QsTF5`JsxFT983375#$AQd$8V*=U$nOyIJa@_nQ5N154+UcS{ z%~9+u%jJseRm%Q+E$Z# z%Mp0DJk8_us|xKZtl{;x3RKcNjLC|b6(IgNpFIEMg5XF1T26oC{_j2Z-1!vhX*ZqD z6mOiP`xo-4o`Y?(kixib)T-sfW3o)cefZnBntZMB(>pU1!EU4Pot$bRw94LquVtR( z-iSuQ!Gtz6H5v07^2;^pFxAMFyu3IL2?`c6!f7Az@4$2T)6O+8{^=)9QzQky)T#lO zJr~K}eS6VUg>R_d!H!e2YQst1H$lVHo0#2N#9Yf=#0E@L7v59+2=6~j0r@$sV;sJj z3Vv2jGA}0^Irs~pIVEh-bI1dELSq4!;E>cSQbt?7H|_+ zmf+`e$FSS9=)Ty0256>HKGNBDh}#^{jYq$WrMEUsGIozQj z7^*}6aJECK`2DL0R+;KfOZ;ZQ^%7sSwSO3U9cBHYqK{_f6t*)FoDwu@edH1&v#`(9 zzi{Irs*e{W^$L6FV*aj$2j-g5z%KyiP zR?ywje6nO93+=j_3Ww>w>dMqjIgjFQL&PTo^3>85&6Jb?+bMCp*J5tDJnQi(k@Wxg z&D_a4hI&u*@tAC}@g{`N@Fu~tim^bW3Z6+9lKQrO{2v^|VaWRYYgL*P-$mDe-cbN`PexUg0vmiX;0jK<-8kek9WSP%YD;uO4)+`5fM$MA#YvD_}^M-z&lKECp6HLS3k}tO8z!_oGPb4o+v0 z0Bf6;!D5OD``+3h)$SNHGv12l#yy|h;n@d9m9xfk3nf_@WvZ`geMA#YCP4Vbc&_thHGVPm5OQg@;QI4A@LU@)xGoq$ zEI-V~Un@(&jC#d)JgG&!1+S51Xf#)0SwsD4LU5x0c3+hL=>}vh1dUfT8!n%Zx8=2i zyTe5y{$&3DT&Vg?ZzqtkP zZeX|g-|&v+p#SxFAbImLq`knF*Os%|Vqm6)4pB%RfunQ6+26Fcq5qsUtad3wN?YD> z+Q;+o%{vv4z!VYRP&btD$PcZMwBkJ&>yD(t-d1NaN6QO~$iGLv`+T^U=?ysMS~Sdg ztxfip`s(T24QG2Qsqgwl0mSLs!w%ZPC9U2ln0|r!-lr6ijT)1nc-1?U`W5rOi_nZz zm`=NhZ%-bJ>Q-wqv!?X(dPQm-K&0kp?#J{Ltb1WH`;6{v{w{AS z*J(MKoP82e%9Vv>BLZ886JCn&xUW`&!Jm<4@hkEFa#`#fXsr*yi zq!NclEQ#drdNC^_;o~V+@>JzAV@+?tPZA5b2;~wSUn|KDETg^)4Fj~Zh9D++7?Uf` z$G``AFPot4g)cp^LTZ!`|6fmbO!I?a8&Bf4?6zQUei`IGNG9@;)MG694;AVYuAsUE z&wD0>Iy)z#@c1s{wObsizlzJ7A4dCst{#Ml8AF`-lqXobvK?0XUL;X>j-&H8yb)@= z$0^Iz;bUk0;fJOdnY(!xW4mlRT)X*^D^1SAMnS(JlX47L#Gr$plF_>@d%0{XT6-zhmU#Y_%$BZ!Wg>)}*M`jPiVD{fwPVV&!TpAJ$nnT(|q|$|XHRdR?O6bdb`)3IETyp@l z!<$TATa4$rRY2k5B9b<40Eu-7(4y2RuF#zBeLPPEwA6)EZF6T@_FAy(L)CC6S(kspvv-1`?QE=esn=UV9DqX}_QHh&}j#?qoJ2J&}wJ z`GIN;X2JXD2fTJsd{Kdos8<*ER5YWL^Bs_gh9%z%RB5dU?Fphpb%O$KJl6^y)VrJW zrwQp?u104+4r|NRZ@OXfL_fkt`Rip2`mu$7RD~V4pMcw{HIN16+^DVjc#V$`3Ge1` zw{|_pyB6Mu++q(RJS&dwD%v62oh+{=$%~N3R4iQx(|5HdJpBsQ~XUeQ3XJ2bZKFz*enga5g`gbd9z{3!lXx z^3{qPf36*$U+f7IGAvni1LIMQB&&Nhkudl3(CB?bNUeBSPd*Ud1-Jao$?i!aj9A)8 zr13?T-)35|b`g}AYm&3$=_ZRs38Z{VCKpwbP}{ytB=OFR`|8+)shtZ<*Ey4)PFDEz zCkb|gUm_`-+>a_3%fYhLVNAXi)DGT`v@2s#J`NX%Iwu^~E@Xe^!6_LhVjuHY_vo1gU;-sv`qF${;QS6o((S6zbu-cU z=ooaG&E#%0KgXlxeIcH15LjFvWct4vp{*&y_}ro}3rxG{PD-Z(E))F)r)f4#vD5=y zcP&91_uF#a)7o*<)Gny$b|lO0EXUJ~?y&=(RfUtqtU)iJ7^$Sa5V}nXrJn+ z7qvL%K{y<3a3$+fFEa;B#)D4{-JO&y!7B_#vu&g3c2)dlv|v7mrgR?SBrLkIVSN-# zFPcw2zW2oYKVCtN{llCY4*Ebd>q)X|0tHXCN+2~ondCT0f-Lo@nAs2G^I2&QB9)y; z%J{oXi?JBmxhbCaByV`TpBCi~arG;n(B0KGm~iqE`8eVPdUVng4NME?%yjFp{5>Do zcEgj@P1(up44Mj$T0U|=aTXps3WM0wTjY|D9Lh0CLUX;kSvR8xEh1-`H zz(~&=)bX6&(@kDuj30wgkM0pHac3fO%-C1abdMl22u39+fvjFJciX54|BiV9i=;1; zd;JRNSi&phlzf!ikkyT2if5zuMYH&xc@^&oaKvr|d4JXeE7dhoJ(+HRTBV|8`Dtj< zuVG9Ui+cfosvLGu>Hok@2pYy44#S_3-TY{&iUZNqowrN9hEm*~m95J(hF zWDR1~h1osjP^sC4+8T!O*;6D2CQkJxnX%i@h>%Eh&DomoZ9D(m4J3S6a>N(o)v*%n zKB~#IU*b^Hsb6Tv2wz@LzPYRu)J3llfrSVIJO42~(sDdLe=J%6x*nQj#h*f4dm;n< zk@e=J{F?BJUb;Io`zkT@JC0orORyvFCXr=JJ|gEavQRV_&uKSSWA`=Pw6oiiTumuq zA~qQ#m2FqJ{K^h|XSye(DR~er%_mrCZw7-G}r(g z`n#ALJn|X;xTXxu;X&@|Uk5y3^c}KAlSxIm2MQoXXdrDElVwi6hr6Y;tM}hbEIAUM?bjg>UHtSmSKVb<+NJa7|4rX3uERHdA7Ze- zMG($uu!}s^g?mD6V0l>){wQHb|Xug?=8N-yhQhOY)i5 zmPPBUpkdo(;wil!t(!7{;vDVyd!ND)+ItopL>64qVLGif*zfx4!uqHEaAk%#WGD6T z-VE7Qk3rGWmDDcUi2^qSpo81C^1fw}f9@dau$b%?kHz}mCa|{;Cz0!BB`7g_G-Mz3 zxuO@Dt-8W z{!~;+8$ZBEWbNt1oVr9bqK=~`DR*>wVmN0YQHRIQ_6GZzUSwYFPUg^n0{xa5;6@i_VfpkN`e)uE ziYw$$QRM@aT1NN#3VQHpj{sOHtx2kF?%>HCciCIi+Zk460FXBkzAe-sn@>N-59&48 z@$`4!s!JInOOwIH-y(IkqZ0ID`6Ubjd9N-UeX1E*MO{N8=9ZlQj!tZqHVHmx zjUtv-3i#5cdZ>t|eWwmhXk%R&GN$w?7ejVSK~Pjc^&~HCV7#`8zs>A?bpyx%Qc)^>j3Whpbo#%2RMrb zPqEKYaW;(JhzoA}qji37QG%X5w`XQMUTXdr7A?~wZlx~-eTH&uKs@!r6_kUMbO&0Y z*2#M?!W<&OpxlcD{iENfkHgUdUu*6;`~Pk+Ptbh5fvDRT;B|+@*^dHxr`ye;U*~?H z9gHs*xx5~yGQXLn^M`SG^!)i?Oua_I1%-J2$)_k=dl-k0wI+k9$W_v(aU4$`6l2c> zCy~t!{iyr3G(2BI@26C+7@_taA_SJi%cO*Hd%pt-eXj6#z5UkiVC_r&26vv|{mGT+ z_+T`*OScAV{m22+71Sqh@K^Up^$j+_Sxs25CI*!H=D};~Cw%Fjk0WwgVck!2BBDMA z&F~FJg%5^tIO(znWV?HkKbwCsLWxai^|U2ipTTEb(V_$+I|jLWr5kuCTL7aior&C+ z{pgK&AsU=!$JuGL<0+FOVBr=Wk~j2EP=AU_@Jm~{e{{>B>ZBSQlCCb4wd+MPG*f+8 z&6@AVY~1r1a%Lvcy~Ss!PU0Op^JQ4CxET@!|E*{Kf8W>JNi!Gz^!wEKdp?Y+y9T0# zK1A@PMUZKr#%{SwcML6U;N8DE6mlewi@RKg+rB2z4igs=ICd-&KcT@K9QPT|q?_+U z;X1H>#1}67&toiuuggjg&>xpb{(g7!N*L@3 zb|<~-uP`>gV_?>rLeBYDF&>Z+XY13GNOtdLB-@pX&Ky6?DX;Iw!r$Sr{LOq~Yww9e zzMe`lYJ6`|zl0p!rJ>sR=zZM0r#*Pf4u9}8)Fe*Svoy*+l$|$H zO{nZ-01{{9p#OjdNxSkK`|VL<5q*Cj7bwGpUm@^{Zp}Qnxgux!&pS}nVodv}Y1fgb z2wc>P=l;LJ6sjl3N>gvPf6yTFY0W|OW&FoHW9`3qPQ^7?m*+!DN=xuReKpqoj=FH^ ztId!jOP|q&(Y#(^-xUH=BFssoi6tZEaE_gpq9$B>Jcw3WPlaI5Vs4CF5jGC5hJ?T? z#4B|wnxp>${aAR6^R?;5`>xnPi-kX#zu_Z8OLdT}nhM`p;a(;SdN7h0N_%48>JVtQ zHYaD3tx+3FMFuN|vG=_c#nrMz(h>X}`5G(1stJjF&;0t4a;#LFx-fiaGa4$mipHc_ z^0&PDc@yBar3mT0D38B941wkA%t;i@DjnQVh8`XD;abI-aE!q_$e!U#Vr2aE^qaj{ zd%F9U(~t^Rlk^~cWCefA6N$@43#aGu8in=baF`+GNj<>gD5m)e((fDAjScpzL%aU~ zS0?rpm;VrBuTlP>b;TcbG`~Ry=Gb!yO>Ovl0NuWHTTM3SRSK@;%d-0P{eASX92AbV zBRh>wu6%_6*R84m3+g9-By>cnCgJG&Lu>x7XBzDZeM>fyj>-aDI9{BUO-mvnIvh%v z@dF*-OF6J%Jzl3ciOrOcB(9DcOv38#Olg)Zmyq}a?~YN2R8LKkd%qB8h0spy&*|jr zjWqOK?+NN$-wgtuWl$?HapBoSTz6spYU)8wXuobk) z6>>1PkomE1D{2ZK)+ij;xD%$6YP40>fSHXiR9`w>T@YaJGEkXZj2UZfmp61 zahWuv+jq@@&3082t{N8upSv{RyGR+=F}eWnUfTe_=3gXVAIwA#tL`GzdzoBA`E&e6 z(H*{0-9GR#SN_ZC_t8O1E+im-6uSuXET*#p=Qv$9mBi;*K0B zKL5Y7;)`Z56f~HVpA+nGEewDo^~T42dxny~HK8}teR;jYeNQi3Ds(4muj=%U()`7> zuc|`Rw0v-xco`HMy~*ao&4P41hn4rESiRT=Hcx$x9FOL4Sx|=cS5yD!XLBO;VUSt> zZ4Pt#R6ibTdKRDP(+16*!&v>YMuu&n@99m`5Tx+47mbd!=Q3Be;m@|$AWGJsRPJ8J zjEkJZW}2xBja>SnvQ`A9tMu~R*c*aD>5n^6RT(y*knJ;QL$_?IK$zQ3szxJP1CW!JPayAAPt~&TGqR{^l^lSd1K;`xO6Hx`%e< z4{OVZ)k5ITEjQvi)0{D+TYED$7jk8!7@tiW#dgqVuk+z%bj+51gLfR}wF~9?2-@qr zkjU@%#)cctq6EgBzxS=ub%m{`Jjh~~0D;9$n$3BVPL3^?0qx>1sHBc?vJNG9u2Tw> zjj|&H75>cm=#gkVH;mN-n~gy?=O1U>@C5h%YJ_Q0W<=KRI9l)SguEe~i~LlJjk4T8 ztIv}>(%8x1^^+lc%Vd4sCbX$7{>$YJ9g{9cLcn&)! zR9%>wv>CcyJVgN}(fqydO+*5S1~`*b(r!#){~6Xwpe9T~L6Epq5k6%XbH=|5@hG7T zn@RU}9bWE1)^DoNK;|)eck9OS8dspw*q;cV_cMc{O6b`d6@I6wcfT}bejQ0VgFJED zrPuJUfc9FrrXX39M`(134WH@Tdg(coQEfRXYBx6Ml4hq!(C@F^-_h3v(?D}aBDYJf z8l&!UY^sEY@UsrhE_7Z(b;?$}jxniP8WJr;h{1e$Y`66_94bsAev6urpuGrvPWRz` zaj#C)g2yUPB3kXK*PiCVKHi`v{Cz(a!uRVyO?m}??<@I{j`DWpa);MG$8jlPpg+f( zoE$wG?Ob4n_8wTnYs*tZ=0e$lPn?|gQ|y~6%DyY6T}d1K(OQ$av36;t@eliR*r)Wmvx>W&;s#3M=XH+AOr?JvyN6gf_Q z<}dtynkrnqqe)sE>6VsdB`||IcYUGgrV!P3l zd1a{JL=0!Mtp*34dBtx_Ut|vHR1c0(I6(G0q%WeoO@IOPNe=!(|$9e zu||bvxI<89-Y`~w{<;>Go>;=)`%)XIzewi~r{r=2KWoi|siU3Attb1?+%p6z<=XLj z@^^*NY&1lZ-5U<#xnk2;wece)x~@0i_=Y|hiuWRu{xs-mMFz3P^jo#~bUxhnx(E?X zK4fA+ivX`tVU?(Ucx99ge7gJ+4FugxIyFqurd>8E@AN!kGY(IywH5=e_d?%N# zf(PMWIGG=mKU+w%7IbH7mTm~zy|V{Z4%l;l4!7a8Dc7Kh^5+1TmCSl26;|t#y3l%i zKRjML5(=;PawqraV6lK#Fy{r${tVng!QI|y@uY3MUNI@!18)3VNg59&V!IM)HrFzV z{7x!HCiY@*px2KZqR&Zrk~7--aTt@A9tnaAWp3ooZbiZCv#%gBC5gP3mxam=?Wmw; zm_LV&qnJ$l8z)cCWLVvKDEU-5uP2|CxD4yE#K@>)PqDmDC=w5fH27h+EmEt-J;ow{i3XVDfJOu*^HX9v(VF_!<^l6s#nNHK!&OoxsJW@z{XRE z+vv{U`^uA@;7X@EscH5Xbo8xaP4}q_r+YZU_wAoh#`Ak0mh!tGDD)qva^nfMHL8PgW6zV&Lng?Lc0?ZC63+dsr(Tgv7x*LQMe=9v zWF#CW!s(p@ygzw@^)q-Q;zUgJCm_YebhqQ)Fn<;a^nthMG)e31J6OMOD!VQ?kr=M7 zLVm{MA??yU!djGLga5H~-ElSc|2r~L8Hqw6go@0vqWk^6?Ug+fDtl8#qLc>hJw1w& z(TOOP)cJIOP6JJ;%!&pYW+kKeeZKek{rmiJUJvebo$J2d*H|)&Z@R26OFp54BVFQf zE8Bjmzp^+(f72&ivyXkhBI{wKo&r7!x* zbQD+l`qP@rPl(dGQG9>aBXKrhDV~_01m70Ni2h_dz3aGC`7aaMxqkw@t~)DcN$zh7L64pb=`54s#QAa` z{*DII1O~Eqn#Lj6c{pBZt1BUs&#CaI+Vo{*omFsp+#zVIvlEKPz9;EdgK>?^MVe<6 zMUE9c!z6~u@7gQjduV1>_RzV1Im@{f-B8hp6+1;g{oF(T|b5b~I`X z|1NY5y-)V83c;OISmr2LALewF!ILO<$9Y;y_Aa=A+jq{Qu3?4JZv9pGxeT8V?Jq>M zc@5Jpy%)4~rNp|Z2n$z9X-%~UG+l~-pFU^A+u!3=k=QHLnttrca!+GIaN2-{)Zw!Q z+|&F9QStu5@(-`b%qQ_E+ipsOV;-5Bg?-`PJ?t-To3_-Kqfb#U+^S!zu<J8c3%DgL?%+szWHI3L3%3JqlJ5$ElsCMBXZac-EZLfFIS6_7ad)M@3yXwzi_RSJ7 z^UV?p`sNe0mSBwXK2G~~`@^Mv7{%>LljHMI$LYAdxJ9UVn@Bvy^x@TpNvKWV2>6=z z5oS(y5FZz|I&>l3>F&hMf2$AbiT{t! zW=C;&TX(8+@IFa677jwz6|q}BCN%^*271!V5?gL_kDfTlELU(^{)o87v7AoD0_ys_ zfg8E;0X*2ZU7+h4NdA>*oVRfbRa@mxe9v0Lh}Cj^V@#+k4l4Dc_tS%rhnqzCZY1RGF_WV~NZdN+cyP1kTs@&+*-UDEE zQY`E*-z>b2Z6q7k`C<~g(OggtCGS@b;RmdXr+Hz;5Impx4~xf9ZCXe)f9ddt?ywHk zojN!#G8X%?3{i#s;*7|eMvSnR(6@){VMkFX^!x9IFn9bj^8MKp)Cf6Fs|MfW_RL}! z+W)I~@ADhF7zeCBLA}?-lcX9QzKrP`8`rR2wE1^od}xe#?+bUmhM(EHWJT&lF1BPR ze~RkK`ZR=MN0263?S3pwVA+%1>V5e79um6TY$NDiEQG03cZm4xu;~D*5kER+TO+r3 zkrp)E871bd*P62Z6z%SG@M}ME`(G)pkV$CYg?Hh2&jctQ<{)azSw+G4Qe`21KW;c7 zzkBn_Y`Y{mxec6-4#9{t8l4vOt=^M)b5*eEyaLsb z4j{iim*SQCY&*5M5^h-Jz`oCN&a6-tjL-Tn6!H0UCCi}c>dD;3-@}KqXJNP8BH?G1 zj2sJB=8wqqWxsrnqD@E=B%5Ul7D@#qxHcT;EBer-g+1VI@5Auo;ass3L)~yRLdbW) zz2-g{{2>^pj9*B9JLyCDnKICgJtuU^SZ?dTTe#@Z9J=pKiPXYhnfG9KsHp9QXi@YE zy2Q!xxp@T3{>_w9>pTw#pBMp`&&v7ph<>q1TaM6!s?CIy1fx@*h1Bq+1$f-~3f3ud zd|p2;9_Oi;(v348nI5{^#8tKR7jjH~5fiPE=n!Z~cTLPCYgmu#vei-=#y^A=+Y+Fb z$np6Ldq?K)SX0B*t4QOyAe?kyA#I#@5yG@paL=$?B34ha8O*1%jLfrwUQjV|0aOh< zDGa(-PX<`HU_`n%eQL)#ns(*mR+gvp`p^XRG#9=W$g#R}S28+xaib~sI_9KKvgaS) z(31_i5QECc#$tGOfv}@4hiEBPVP4rOIyH3+sA>em=f($uby5M@t_I+iF6Yt%*A2pE z=1qNT<4mHrCgajSt~A_nBmAw9!t_z+MBJ`vdxbyVxzgY^BXZDmFdv#3PmAC$yrlO5 zZq$S*2X-Q0N(h>f_xh+YBZTo_t_;Sqb&7ONEsctb-}k zUpRZ=4QZ^bM_q3(dRXhFY3q+*KA&l2hni%#Gh`oH&kvv)S8Ak@U5daZCrcPMD4*OP z6NKMcc1h{&Z?2?dBzLgp8_Di=h`g*Y#yOK(g_fp7@-#=4-#bP^Evv%eeC2xxuy7J{ zCI6-D$05H0==usH?#I$${B+iBRjBwGH`o4w_~a%r>zDYZ7;mzEA=_mxaBPS-q({rK zI`oqleq^_1vp2VibE+!ez_@z(^*r!*RK%jKfg+b~ZaNP~(OdM+E!PdfP6sbK@0*tN zYhf`STE?O8+6cNU<_)`VEWtV z#Tg}YKH{?T%qMSD4=Zf`fMdBFs~`QY#fLjR>G!(F+-Pn+%+vZR>Kh(6=VOG!3ChA4 zWU}ip-jVUT3u~8RB^w6VlN%!(+gCx#Rf5p!+;RHc$c|gSz?v^8)ssDa%<_xGc+v2pa zbJ}}i`#S))v7U-k=c0)|>(!Ib{~HmJK~3NzaC$%J{K7^3P+xA^r0H`RTR(;(-`OP7qq zCB`iR{dJ%8_5X*n|43-_y8sxu;VFdwkmK-)PuKADd=vVvu~2Gl(u4PS#kBneh4^ZF zIh@?_LEK=PGB6bUG|!6MIISugH_bRo6Ij>Sp~e63JnMqEIV%h5j6Xr5QGlpjTwQaW zb&$@cH_zpoo(TEC{p_nQVz2S_;duOxAzjA$Fn_TO)JETIsxw0Xw_Wit{j;x7ZC6DK z3q$bQ-DPxAsuxssQ^wHKx5U1S_zP^%uH1(18zAE%FY-{P#P~^i>s|w7#aEzvy zj)bd60-)i~13`MFfF$a<;mQ_&TK4xJcW|mHTyQcH`-qagHF2x^U%|obJh`Hu%<{$V z)XilxNK`W+Zn+$9tyjIojA?Fk?igdDP@~D~JY&AZKb@fAcn@~plWWWVqqKSQM$VI4 zUb0-D-Wjo~mr3u}(PAqs&i{FYr3y6;Cf z?sIq$PqkV1TD%P1P50p4(}7gBp-%c=yB7ahqAyE#JA<=V=EIy8IrjG16@Y5h$7%PH z-`w1C9d1DSH!({xPR$6__O%KNUndg3{VM!5=HpdQ4u>fp>LBp6lTbXrmTc_Yg&DU4 zXz^wv&N)qsU$}?e-|v0G{0Bc_rfRd;&#C^k5XooeF}vgfYr;LDSBYH5*s|Xn6I(ed zjJQkso2l?K)Fia0c^+7Uhyoz~it4m3>NiJ@_=ti@GZ*v#7j)lz+i^Lq?A^U^)c5M&ZZgHQ` zsvxjxy(08p^PH%s2BRIjiM!a_aVq1x;pwG-sak5wDj(lwJx{{o5|y z0oC_M;n___6deLc*GO|1XzMAY=2jEah0f^3e&37P7I2FD6kh9)zD#wFE3P+bfC;Z; z!r8lzNvz*p{CwDz-f9i!B-+2Z`_h|Px=9LIce7Vu!%79}elm$He67j5vAfkn!z*BO z%pP`1qJ+Zt&xwPBC+Z2IblET~E{Ju8L`db>J2okiWlmgZkArHEo^u5{gUm%=T%EBO z`c5>YXP1VM!A~{$t_*u`*%kvv_Qa@}*vYUmtC8ogI)Gr!2_P|bcNB9 zj8)F{*u?P1uBHwSY5roJl{ZD6{L}CqCaQVTJ|iDh%=s)B2(rPtV!khd7~>j^3Dn?E z21!vVz>HkxB`ZjTh&eal`(rr{8;s1sIS<_^O4k$aq%yBPmU$_4+Ti|NO`JDDBJ$*8 zO){LIH@rp3KjTL~Wn2$YTX7nGAK z$-YDx_I>I~Ki+XQowU=P_uj83`}OE9n*TG#cD`5`c3wt$vE=!yTXIb9dn_2Gn|x{X z1D0d9+6~JL=ZV^~6T8K3m$eAJCZv$LLI>8f@5}t_0kC~%G1&KU68=QilHQfE7*b(E zht4dLS`{ktTkG{@Ruc>Ht41l5p8p{B#kI8+q0`M=+RN7u_Ad+um8ECJKBD{0mr*+8 zC~Z5y@HxK&D|#o;%yC%|(!U9oZw?UJJ71A%j|$xDV@p-$D{yDJv`U!PGdLNk>bQ)Y_(oa{T00-j(MnV zgv+_H-USUlgZ10Duk8hu6F8{ea#FyUdXl`x2_1g>(4)Ec$;iqg^dFT+w_5xFm$4Mm zbgzjzhE?l5B>gT>zm9)%-ZvcQ&)wIPRq4fG>FV;qVe4y8HKQ zQ#1_gw=`)!3XB^4)#2KcMJc2Dcg2@gMA~q;7z+gp^M)uGOo@Mylhyvc6l`!an~O=GmnIem6r7W z*aEbOOQ8QPQA48s8ukaoi8sM>du8~$uNz%W61cdNqv5(uQI=xyKl1Isems4+2MuO7 zm#D}9*fH>`h}(x<1JQuJV-6i*$5|wI#j!M3XzlZeY*X$)p9YqV^;^QWZj#~t6ibma z%Z^;eAK#7WL?M8jD%t?MFUj={>s#m0jPs#T9V~tHZz8|oAnTSH>WZ68-$VcBa(&~y z`yE_;!j<|Ig>x4&+qu<0a|(3KO-GM4?U z!PEc=?Jd-SRqPKqYJ5}7Wz$~Dyer!#OUnGo?F(H6H5Om8QYUs0osZUNaU_slWIIQV z>=|=n&seRXj-v+T>)d$X<$5xskh|D(kuiQ$Di-^T7Hm}HtG?>X+E*OKpV#7H zceY&9(0CJw!RvkK{)`?lF=rRh#q-1-xnMUPT%gq|th7pDkMkeYdMu#}?E_%HMlnby zIf^Jv&*Fs$G^OWUzKM3A#Qu3DJwv|a9wfXJ`@0x>P z>qa?lN4Z?a2 zi<n+NJvkV)UzxP z^U>{lR*Jdx7z$vwxz_{lp#Z4%;KnEPJ;!BNE?~~FV1$cRG9_5z(fD3)I;Jw2& zvFG!d^Bs(5_d9=~bB?*54Zn%`Ep6-AzFF-^ykJ%+d<@JXG16zaS=W}HEFB5Drrt1N zcDl&1C8bWdyUw3(IQx$a%$ot$CyfM6ukYkd$pEx7QJ`r`E~NV49rXO^Mzc3;g0)T$ zpz{XP_WRb6f^5@yjBF~`_ zs?41rHQ|gfC%T@D?mHNrYZYna1ts#T^ery>#dye&G*C@1g)w6TL``E&bczmEqf#tr*%7K!4A#mA>z%$!9Z7>^6S}Rb)A=pF$AMe||zt&ctHZ z3~#z-aX%Q=U7Opl{#EpE6qioI-V57=jGlLiA1LvS57`Fs%P=rBc?SV6oJ9Xd!NP6W zG&PV8&NAYvi!^vYJAGN`zE2o8=sUC?Z5I6-ij9xaz9WJD)O7_v=>^!jZ?)*P)9LGl z1q*q)r1T!i7^=i~^NXkY({thK7zNa#fx@^rcC&D_huJH=g|A1d$@^kobhY)Or%!1~ z@1#G*q-S!hE{cBvzDaV9&89K&G|M6O8FibxHdGfpUKNSA!cMDwm^Zv9wS0G%1@4FeV*gOd;C z`o?zNjpa>3Xs_ejxthtU=p6Y?C|j0JV8|VumgYuH*lud3`(;r4U@mwDH4^iGUf4Tz zGTomaPHvYC;KxS9)4#DrklEZ7w_O=ebH)`BpNX3M^!Ln*K2QfA-;c&Q_8!z$-z?+b zinkaMB%!(I>VRL}3hg#G#m-M$P>18*_|pFN#oX0yE5Yi;mn>Ve4r2Ak1V6qxNx9~D zGI)$8AHs5Wew|Cu)$|68UKJ}GxmZD3Cq!ePo*r~df+x4x#hf2lrzdM!&29_t)v(I) ziRiUcZBXJD_%Y2&*Z?m&b3ysYPT>_akVAbe@Rna74Ke)8ZIbo_!~MGAt?%#i=kPO#(gyWhL=&H!OP~jR25*~Cx zf4ut8Js18x>o0X$a~C^3reF`QSh)RxlDv6;aZ^77**Bx3*!@Ku+^fhGK9}W_=d=9q z-(DYf7w7?7-dn=)Ksm>bVI5QR2eb)1Ng+SBw&VE@=C@fJ01w0Sq02HS;p(nh;*=eW zqc(B$`jMwnotK?x&9XD=e-+@xi}}Dm`XKzbQA#p}alC38yZ?IsfFUpZp{(<)xY?Iw z9*Jg~j?!);n#eaD_W6v5gu4@v4*LK`FB!)k{+hTgQsKkPuFy79eXcqG6?a2bUD%cK zlQ^plLX|8-s!wxB9$tfs3;l%u)>V=1sR`JMY-`x(B(Yo_f#QSu9@D`_yt#@?4~@X>zJ)@lR}T5p`ze}O*ifCmBVo0d2P`*97mhg;kk03h zXsFM$R@pyp20sm~qviPQ;;oKhr3%#0*@fMs6VYh%MVj)$fpj7Q@jcF6Kcg`=55vp8xq5JatfkVAEcV~60=!G7qJrU!B z<@o$9swc0RBg<#5%*>l1bie z_B=Gj(skXdyQR#rs`ryo8i$6C(er1gPxUUzfOYq$yy{q$Y=d;hCLt~ohWXX3$M_}dhW~yI>`usWcys1ud>`ULONV%I0}ZOtkS0(!XDw{q z-VbM-c_J7!=Mq=Hp1f@oyG35u09V)NK+J=kf@E?7>2t0RC`Rgvou5-&4ACk|j=lcA z1vqt7G98gVO->0wD!DX9+PT_3;?=4W^(tt4k< znYez48#O%TYWl_cJio$)`A^0$kL0&WxX!XzSdvMJ+38<+aC;eEt$fW zf_##@&>NEiy{S=RchEev4gM+47dD;$N*>v0I78n;vVc;EdMF zIkRHmK+GsKqA|mJ&$GeOaA;jt$voK3f>C1)`AN<3{pAqa=l%>XqDqaw%kF)oOk7$`G|N4)3gxJ^9;m4s@t;JzKs9^g;Y z&xJ`ly!H6U7xiT-FI_O}X(jCAvW37!k4d}fZH!oXky@qv$LU}D!p(2GnYDSMLe{1u zi_tl#3)3@`$=td9`JD`Jx2}$coL+ljds>w6Y{zr*!~6_-T@IkiPd0J3#>zO)yH&V4 zIfF#5h{XAiZE4`)?l3+$5|&=sB4+(&E%nCcJY)Lp-6gUmu0Q{F8|!IlDT0JA?04Oq z`JHl#$TP$Kd=}%YwuQq{eNiOtw!BDJ4qcWpUndf8I@r>Ej#psG;x91r)=l9W)9@oF zzr?>Oo^(gcBQAX7a%i!TWABo~#<(o`6y2~$Le@_0&yTLrmkmf+g1tjy;IL<`m^X=B z_aAPa;z_3md2!}FBXQ>jTl(PeD_Gjm2S;Q-5pr8{$-`+q_5V7pg(dSyKb0PQ4fAi4{jE^AMjfT&5(Mq`60*|bCpyhEko~l-0&dPmI6u!`+^ufg z=gB(5z39LLSIC>7Ld_Z(-eb_)YcTuX9`>d}nt_WloVN4{vsnN`e-m{x$%-}7MU z`j6r+>ilbZyzv#*9cu6cj&JpaxF=tng!=~gMXdzre>|LIQ>qo|JMxrQt=l|yuju3~p|YeVQ0(6g-`|NB`{Ek=sPVSrBy@C&5`5n=8T`~viT(;9-WEF|{HWEU zRI&;mK(=SpVpt9t^owna zKR-c_)Q*Bn#;%aPFkNt3TtEsu&!96OOe1%8h4WV?L+n;#;q>qpviDp+Z1C?w(-mFG z?Umu^5^hU}ESd+33zA_W?Vvm5NbQ=&kRwss?4R^iwqg?)a$6TAy8fHn8z zT7>1S=h&;>lPZ~2nD)-{=2x0Bf6iuh=15zM(=vkSjSKZsS#n=Kzfxb8RAGTv zAujMxSS@ZaI4gm|>O44~^$W&K4-&#Qz9Rjy*rv=qZ(*oM zHQ8o*5o<sXab}F9YKEC+{Ei3bc?`e7DI?H7Yf9FEK)(wG3 z)!Q(Xw-T|}W?vZg_+UgoRrr&T_JuJ0shsORM?0)v8AvB)Mo7z5#_%2<`m!wO8lYYN0qx5bMILv$eIUo>^*8c z1&15k(M(qfIdH!(AHeWovgZ=4;;+Dy>#?H0;;Ug48a(u&@4EPLQEIPnMr#5cwLuF< zo#~B5bx(wI<+&u}T{k{6lX29+8z5Glg4d>9g5$^rGUsJ4c>7qcIT*R?VYf#NdrKd( zz0oH)|7{BGXOs@zwnRY^^Dq6cBku0ybbQHr4BVa9k)>U`@ekPTZ^HUk=sr>nSC}UV z&bLd*wJuJ*?!6xg$CwByAK)N z1B8?(m1O9rG*r0e%5Kdrrf2S*I{q|7*AK!VAwYWM1rGw6<<%-j7rg3Y1COc++L6a^9vV`jesH8yQjO#~HA09bhmtU91a%T!ZphMRSdZ;-F z^FP;;)R{vud}XH)^7A-}^#6==BU#qqtQ7nz-@+5CKw){W*QDljBfd5DqS4*^bDO-2 zxMXWN_BLJUhg+W;(mVTe$enRfuv_9M=0s++f5H>K64v?C1fh*xvGG^DaG`4{xjU>8 zC!2ZEH4ar=&w{pGxNTN(DEIIB|PAgvMc1yc@M_{WIs* z<30SGB0X8V=~aARsf|zi6$#q2b4YW2F=ppFm-?9DAiRUf`8(KJ?JMm!@O)c=2x*vmXB86qBk}VXhEN zbKBobS5NKD-!0RZ^^UN|)kW!WjaYm{Rz8tCK4^=*Q$ zQ6l*fz-}CD7a&C;9G={K2{uRNy!X}qH8{R9gl@{6!RfT9@~7SPWodcMxc+n<{Cd+Y zXnlQ1B$8r0PBW;-J6~{jafaH$)dD~K6IrPqhefZC&_@w(NCi>kRajrasJFRrIZk)5CxKNf-8;YTwsO%vr-0Tb$Y&KtGyB zNCQGg@xe@Ealhq)ss=CMon5vtlXcDYzIz>~9&i^sE}F+QbB|2p#UA^nC-bqUL5{uW z&h_QJ{>9Uv<|s(e-VR5aX5A(xJ(ZW^l zR8XhtiLk>zm)yUo$bVsZoPX8pVfg+msEOVstWs|vdXsxXy`8SuHT3n%Xbck!sX@#` zLZKKd`bz1IbpmYM_#bQ^bWY^DLpHMPL%S8#@R-VO#s zB_w%D6aHCXAhXn{f-Bd}U_z{1XQ-vFIBL8X{re}H^!ikUXX-NPU-AvcpGkt3#sPw7 zMI}*P%XV1UoqcJIi>X4n1E2Aqo@|e2BL0XOk13l=gai4M@cl1=!gQ(Na3!DEFZRHn zJ^X2Dm=fqDt%tMv^9A+4U&x|f?>d$$=P#*^& zYD^u;@Y2GN%ud03*a^}({{eOla;G1U215^}YWS5NDEz?JWXAfBczwN>$aRH?C)~IQ zxwhc-yEiT>Hl*WCbBNiP{~)7Sj<+9XU&B{g?ljrx1nI&xp|yvE9y4r$M;Tr4k%>gy zLcPR#nD?MJ{Vl2H?5-MsP1Gsz9%mkM5KRvH(<6P-h-OeSMD2PCS5;^vI$kg$&z7mZ)?@10iJi{5xqjKPs2bAAPgzf=y-utg9Sj-JgQ0`7r zdiUYKu}-RNw?7bJe+jY_>clP7-_6SW8Fs^U$!h>ocm!-+<-FJPa40_YWbbZ*FX`C+ zjP-D`9O(BHn6vm17{3n?g3R8KA<7}>JaHjirypiIaiAx^h2@5H8wGS$H^aCQAvAaQ z2WiApW&Rht;a&>1$8N2uFeqLSmPI}xIlUq<^P4xFliwG@Ob2ok`?ZQ5;{gt1G2(8U zAmI|plGb4KX1@3G&WWt2og6U~&V`qV z8ZSTF63?tsq8g*v4f-zg4IYv6-UY_)xMGtJU4Gyc7h=&0e~RSTTjclzal` zY`=IIKG<5!=oR_}qC(UZS|8*~#{S{p?Hf;_@<27Qj6Q<4iv#I5`v~d4k2<{nZq`-4 z+Xb~;%fVB~77nxS<+Ao`crV$VZZePLJ}qhBBDLbhyPH+zTukZOl`3i{lhEO8--qSX z6CXrDr;j;|Y-LSQE1nZa`(wD^0Mm;)%(;n*-SOP0Heu)B3^H}wGfXUFdG=xx@cbJB zIt~^h@2zU`MvpzSXC2AoUV?V)dDbOz99DiBg0f#8v|EcOr;}HP9lu$paZfEQvR6h` z-F%@fESLPO2}Ykk3uy7scJ6AC6dZrZak#HX4=72}6?-kLdyd9PsUiL8|ByV|#`3n~ zr1Y+(0NVMNV7AdY!91;&gr`Q}*j6hVZ9A1@ynTPMvnR9L)Z0i!dQ;I2Rk(JgXd2n z^;8$R#+Z`@C{dR}YvMrx7LvDPX>f zL~t5bN;Vjch1un&#GR%yi|;{bh+IQBeIy2Vu5qVou^n^NyAHt(F-3Bn_Ju0nZIXnR z##uvI`)QC!<@mWyX)kup@Ta>bcXA&G7(jiEv2f9-g{-M5LG@M%b>H9tJ&JFG-(4qR z;0(5Jl@^32JQvaoIL&ZM54e;I_@Eazpb>r09rmf!^TeUV91;Md_?u$mbt`WCo1L8$+5A^o{M%(Nlp zBCoxL<=Z~BoQ2B!HDvMT4Y<}c znhxkWkJB_!;@7clJB5;F^k}REmsOucoz}N7A5{)X>6mwZP{pza-EYe=Q#U>wA9ve9 z2X87NWd#cSlM?19@0$xUNec{Zkz?kIN^7W4@Da6wY(*EeHuM&K3zP0WfrDk&#oXMV zL&;djwouP0O1MKIT2L*Nh+4s)A=|N}Ly11iP9b=}87BJ3F>_z6E4DPU-a=zLPUqY= zh-{N<1uOR7L$hrzv|rX>c6i-Z-qUAzjemK{(Ud!1wnO?_%1K`|-lF z0J^s>Tsr9bFuohh_SQMF3{Y|@=)TJqnD$1RX9c0&$>VgQxfi#m&j&8$K)mP&F5`H7 zw6ZIeElnnVS*rZg{w!Z}Aqu8yZh*b2(IRF>oH&BVUj@_K-z~Unixe@2y*sQ^&mfko zZr~{kPkMckCL~z|!=bAdqOUCBw>L&On$pS(F=R=yDqpO~p8wT_FtD}(nv^EcRsD-e z=3yniRnRMYArqX?4vI^y=3OBP`{Z>HJKA7g+w~v*mj5pPUKSOLvRhwXmZr(5a)v8`%lg zANPcP-~A6iBumr7L4Ex>;ki#Oc|AW27hSienK!1A;rT&GlonINP;cn)>y5*w+!j3v z)%NdDdo9!7>MB7Run>NIX1P@MKC8R%JgT&MQ)AgxGGxsiICnfiyoDXBPr^Lbw_iEb z)pUc69Y2|MFSqnh#F6Rxc&A0qQPZ^Fp^b@w%#-y8gYlMO9(2)X+n3)FCI^_8I_N6wz;;p{y(}gxDX>bG2pAN!>L3Jd#`v(m8 z%e0X>QfN`%~656~oq(fA5$bhNgti#`5%p-fIUcpC^?ld~= z1nH&x9!qaX=+?)LkaXiO#N3wi(ieH}@DI!5^wfI8P01MrbCvDHZ1UboyYP!<0OexS z$lgzPU|x!xmwHEBLA&$rv}bz99Q%8N@a@22VeR1@qQ^E(ROYgG`GeM=f8sc_T}c;u zO)MZk8g?LA+B%$%+JfOW?0%spM z3IEF`Z(Xj!4`R=G=KJ5!Wn>7fT3#o1toe2C!LJx*AX9K@fWu=NSu@Bom-YpRXjYUt$WyetL>*q^P>#Kpsay4#KVvDG| z8V=UQdF$j@x}xg)#!SE};MD%@Cp4*BY+j`N9JyOYCopYcXb5(GDTtUuydtymcD1EEp!ksty z3|n*Zgk@{;h{Nnee7nGfrX3#)n}1&i&0=dYgM8853wya6(gqDrvd(q}Oy#`9Y=y#> zz1Urgd1!SarS0Rj`CW`B#O!fFr`N?W@n^O$ko9DS9SFc||Kl`go)5)t{Hn8WRFUxc+jeL*J*)CcZ)9C)yu+4;8@G8G0ToXSZbSn%7C39xTAJL7^;DUqY(bX9ls)95!|dIwpj|8kQS1 zs4FLNvS8fU4`EdSYicyK}n0Ou^f)4gQ(RO>juy0E)x&HDmma}*Egg)y5Snt4! zW4nb%^&iQn?v-eJ(m;kC7vS9HE`Srp2uavZBK8bJ=SD-Sw)r7hb)gWS24vHHyYfIq zB@Ax(%DL!E%Mf!Fs(8@%wxIO6gw)-5gZ0}CWGkOlvYYZe7&GpS=rp!kKf1vpI`Zj!9Ujw3p#Sux@cH@+NSzoY`U(zQugCB&K6KqL zb#Cu0DcAX0{_fw~u?OC5GNc>ZSg-H6P)IS8W9(*ji*jzcNS}tCCPiko`2If$)jZw^ zH}pE7@wr6oQVVXZ!s_mxbeYj>?t!WfC>6l&`82Mb$RQFnWxnTh#wAp&!J9h*12g3q3wf6K`nNx=*8j_m z&>juTmQNFX1(&xORf9ZW3VUa~_Q6T?+)mSP!LA8$)bED{ zsrc24UpkoW+DLxGvMzy;=~gEkeUe3%`Y}(n4*R>^+5qn5JE22%R(R8|p1dsa$7gz8 zbZ&<)IdwW8r!ns8YLNn0rc$Qq1q#xgZ%Adi4A0DFTJF*U(|t`OAj~og9{~nxNec(#Xeyx$C3D^ z;D<2sKq5(8+ku0Auswp6VURwol=a@87w=q`*%nOqzoGPG+Dz^Wu$^v}L*KBY8DD>^ zfCFnj34aqGlF^pMC|j3Dhi?ys8@KFWbKkY%)^kPHW$ZbW;cek-Qqt6ccPtX9)r4GF zaN-NtZ;<0{%Oi8B7~&(o?~k)`LPfR}*w$~Tw5~k|w8q>JvuqVrcW^Sxq$p31=MsYl zL5~Sfv(i-*vbq>;!Fy|a(OdUZ$j6)ZuqXAZ@L5_xe6L-^_}`&aX{ig>C8P;%41Od8 z9LpoGqVM3aZLU<^dkFN^i32UEwRq>cEDgd}?lbAGb3sJi(Fi=2dI|3yRFh`g9XKf^ zke-i>kZ!#@m^Zq|I$l<|;H2LLaI;5_Q26B$@p^Ox)%RVb51wA)On$uMOv2=NyZ+}K zh~V zLA)Qt;l)edwEynGkY*MDzl^tv9s{kAt2n%FD@}PRB{|K#_7>;j40&z|y)5_QZ{n^`m95XI~mYdbW_U`Xs?K}DVzU}C2RIzcR zH(wLZgvs*r0Th<)7TQ`r5|tPQ=-eS!YB|a65bY$d@Ss?U2 zD;2Js$S1$-S>K0MAl+o63>OQRL-A8N#?q(i=%DpShI!163Cd!nw}24|%% z;5A8(v5!(TG3<>39WmOD1ZLIZQugk=;&UeS?ePM7s|T@ur&pwO!aK}7>_r_ns&O;E zJ>XV8mEX3yDRskLord)8hio!YI~dIO_>0|@vkwkNjc(njYQPt1_sqAriFIMMENO(f zH-15cLV}nn);U&*f#+FIqvSPLTC5E2xEk9(+#n+=WN#&P5DA$*-|s=m9%b(lvR9N<+Se$RstQ7yw>@4s7d%t9af>cT&6|MRizMm0m|5cX1^hW@dW=>g*uqCDv# zTK!I-1Mgh{+Zl22srzMt-zp9Hfdh8j6#CHGC-fBCda~_8*LE-{^Mu(kGVE2*kQdjp zfAby2pJBmxi03lwee)>?Q%HWj9j&0_?C#$0o)qVz3=dQWj zSRyAjiDMh(nqRSJMFsrH_{L9ql}WVab;Sc2_fwL{p;n|NOgAv)Z7shM{qNVX|K#Hg zuU-(jbL}{v@#kSX@?i4WZ}2t5pZ{iGL-yWZ51JYtf~V`+n~Rv--IJP*87cYrKnfuT zVujv@^Ou<~daVQ9k#UQ&dNT;*hL-0%ywydr#hdVrZ7+H)Ih|aec?MS2%Cv%vI49J> zAo}RAJvUOT9>Q}9_@{OGWc;uM%vN-u<64G72e|>(rh5dfpx-BV9P?-zb^78#Rv(-S z3mLz4aePBGs-4HoZa`Pl+PdpxiA5avwE<1;@Ml9cl6IEi&?+2>#5 zMlO8AJ@C9O_zJe)oQJ(L6zKPfcgb|PtdI;W>4^iKU&fJ1jQKKI@2>9Dt?{-7qk&m{(vuEpr`sRAb&$-=y(SV#sop6ZQ*u zYro?+X#HD6-+T*WevdY;rH2-8dAEg_uNsQ;zB24p%Oq#kP7Y|{C0gZUX605qI-^p9k-5) zQ+REut7j5gTpy4AQ=SOeJ3QoZ~X2O0KC|2#p-PY0^@K#j~B_XOXt{Ds%Z63huogj+X0 z^V?!1WQ@f?@o3hu_N4o7cxPh^v#(qdJY79q)iFg|p4u(2B0cB5!A9n{@Bc6x#Ot3z z%`rcr>uhM{3!EP5NBR6C96xg?;6f{*zkPk!7F3w( zNAG^lAjXZc@Kh&8xN}YN48=ZMTxjL4uKDB5H;T`zu-=c&5$LjA9XB$c#(%u`4(TDT zf5f^t^mc>NhrK}LGx?z^llYDnT+%Cn+I0njt4%359JLd)*?nHkAR22#L!SOLtgZixeoQ+W zwd5=Q@h^jV`R{_4VA=VJV!342Um78YwA(4@mSrmJ8NFb>&0Y(S)3#$T$d%|8jAs9~ z_Pz69gjoY<7WoVJEFW*C)3QH*o8C0obapL#>FvSCcfBU#qR*qerWcKzJ4zBfmxtKX zvAkjB6OukD0ex;c()C<=s#w1r%^4Ve107ajVVaoyd`(Dru`tvkOPx~xus z*Xu|=FRqI0$#B5=fkE_Km_7Hxxem?^FXX@VDIj-;CgBeqXPSF>Boy|GVqF`1ge)+h z;f^0IrqhE8Uc|$465LtBdgiU(kdq}_n77}LK2r*jDCen*d-Dt*wCr))D%MFcJC8qE zP)Ob^xQ_g@E3|WL80S6qCAU-ecFyOTE>h&cda)7}=*@SjBsH>!_#e~C`b@bF_q!It zM3C{`Zd-QYWaS`A{C9A*j&1O$f#pir-S9|O6#7X#Xy4Vt;NpBwD9PU@+_?_>_Ye;W zVx1VTO5l%474WNc>75^?By*DoM!a;RVHqp4_AP!1e#@8_op}kyu`Yj0~a=X*p?{-if!^9pP80335qZkU2P-pPW}oMlJTj>Rb=1IMS1w zGf*tvrLQCX)ycA-*)*BHYRVvbypGVJ>hCiVU$9P<>|7h(Y%j~s^h?0@C?~pY zq#4l|@*B4>j@QS$37%H;M9U3H{1mxza=5h-JdPOAEv<4e@cL}%UwmHh(0-e4g?(98 zuH(oJViBbycDu@U6C~>}Q6~nr4)PUzTvb<+aCV#vo#W$VC>nWG+*-l%3l>RO*QtS@ z7Chm}cV^jDcZ0LPWj?MQ)CTPf{iy0$WmqpZf~c)Vf=)XzO%;Erb@KW5GRWM7Bs}+= z`KztX!T9h42>vJ26GqC(iJSCqP?t%1|wRm-s1fYe}x2aS2J+{ zKD1PzFO0uR`kTK%?*yjhlFzU<+}ZsQn%_kQjchVpDfp;xrLq1um^7+ae_{}qnM0mc2X*Pq9{WJw+= zU8N-cNSL4DG3$~F+yU*qGX-6D^t%yYqdb%Eb*72rte%V?Rdi|U_7t-5bTpXHzAW^y z?=?xp(T$dLRH+6@VP5@-k*r(Qq65023(ODwAmkTbShe9Sedga#_zc0zHp5cui@eL^ zIud`w75mS3qjia%B&oF+ZKmF(Z#}Z%Rb3`re=pN=`vhg-+^Y^$;{DJtRo+g#_oB9x zJC%bgPt8Hm;t<;N%6G}&gKaomM3z6)N0@2%QmQ--~@_Hr0he+-(RmgpGShBx75 zw)Lq+q_BSeXE@g>!(O?dm9S-+2VXtp4f$1Uhf970Q5We1NmO3~uL@%MT}l;X_|`;B zn(IQd&5}5!Y3dNtD$^D`Q`X^1wce~#BAx7z90u|8Nd6?-0#;AA!}_Wq+AGVRQ#5&?LBkC5RFNpr{5;+aB6SxXQsvROdXg*Z z=ep9m@5{3usXfBy+G%vF`ZrL|e-1k4GOpX8ZV3IYehC?|0hZrEHOPp%);JUC<~9sr zw}#XV6VzJk0hJS?d57dm66eJ3hX3uOZS>&uy*TlVxy;M=+8-P2<#FfRV&1Ze^=ALc z#FG;pXzOTAh*VC4=g;>GIfZHZi0eOw(=t_g&?#)W=GH5X6Am;VIgO+7JSTauvP zPPtWrH%^G84;)@Wm**_7u9o5LvADB%*2s&hy}3ckpJ|H+d9yC5sCAgV{3Zl_@!{W| zVI2$ZAy`y%ibkm%H|#U|hD??$=?&i0h?ThRtr(5jPh+Qsb`@bqS1I&FAw zkc2OSgJ)&@_Rnxt99;94zhsv|49r8&DD)IPaC8}{Dn5X4H9NkI{ax1GdyG-O4s^4+ z8X2~VbrDPuNw0JjqkiHo_IZ)<+wKSZi;F+8j^F%W5WDFj7#_RCSH{$mnF0Or;w5<+ z5oSf|*M;CDhf~y*b+U#hmP70nKfe7z4LM!?3>%NT(%lbKxq`$5F72=EUgl!b4i~!X zQUmW?vhceHjAWVR|2ziQB&ygaRE{o9ua~3+2IC07Q}o!@XzmW5ni#%!&{NXN@&#unyU;5h|K^KK z`=QRTGTv%(9w{2oT|B%dp6-a*1=-=7;mSA}u10{>Rc^uP>DuYGR z?orlgbLj?*SD<|Tiy~4H=ZdO}JgDYuRoK3zC+DU3OW?YmawBlNMH{o(C6o6jGI7cb zwy9@u5L5~u!rK&?wqV$2F1t@%r)VnX!uB`g&o36YGKq5bkAvqL#uSZ4ch|<7>8Ad={t2 z`Ou5fF_QhwSrDxnCv0>YkYMaqafdiJL(uwDp1F)8+xXi6T8bW_W8|8ICf4eKY+xMB^}+wo%dO<_>(Y*(whhE8^igHiq#~w zem%P051_f5wsH6RHNn(?7T%yo7O@Dpj$eyB*ly!6=$!8cg{!v_FFagGZ@Wj*HjZa!vc*uz3x z_D)+mS|thHHjTyRkrhIx&9q!c7}ksMsz-`Rk1lJ}ZStoIoBKeQ7DAxBv5?8#Dei+e z++_TAeRvRlT+F&yLzjW2S~?6nZ6|D7SS%^Q%6kq}^^+>e_$kHo1tO_w6Uz zUj%+TW~Pc*pLH^9Px=KtHlBqKJ#7SjJLFUl^WmMQoplZ%GAM=o4w;6qdVeJvP*-{~ zO_kHzAIFXUF@RUGZ6lT}%kfi9mnvS$B_XA5&@;lD|M}|`(T-NZXWQiI*P73g!JDe^ zdmhUu?f49l_ZmUhH-W$IQ%-gitH5rCtN(S2-85T+k=6dR&&@0n)(`<2XJokQ+!%

    8|Xm~#pX=ell`N3E;k#r( z{C9l9G~2p8);PR60)l5!-tB7Yf?^dV zM=0mfuaX;+EyL2`ZaO&6`8Qv?BbJ0-Qxr!?SS~U=3@+U;0KaYFeDb#{vasJX6nz^i zJ@NBB_w?&`I5NDIFJF*F7TR9J+#l|=O>QXc3b_Kx$F~c&uu`uW^ou(|O)r;{4<(A? zu1@Cdw=V&+=mMCvL6_c)EhRnwe8(S*15|d5!rJA|SlQ-A8@8;>>anj3$17yh(08o2 zWLPCA=E|^ip>qm~-E3&os&wv5)f`Zm`&;lHd{{LVZ?^^0+J6z6YJA>%sMYFh?A{fq8?I{PESkPUd1N;Z1Av$iZr6mKfCfJl07-z%71qYGh7n_XO1M*=1t z#cn3vv@|uE+%g^~&S0CuIt$hzPGgvG)mP}(-Tg2cj}$x7iEHc)mmS_Gj;z;~n!QOx zRo30(bE|^yJS8QH=4`ijwMe??;Zf8aY7bwuWVpIzyCEEzB*W6hH9seHH=dj(_1-R7!~F zJ!Nr3Z;`a0^)GlOe;P(Fv=KaAb;c^#gT2e|Ewv_jrcZGR^T=%r$%0S?<`wVf&#%a< zA>9><(UbKcRk!xyMr?@YQv0h5+U&q{w;>R#C%96NS8|4PW>;cgg+xlWj>qF;RdB0r8LwQBOKRt@ zhVWf7T-AOz5UN!S_&}3pVm*RwEm`W)tLsz9^Y&64zJhs`6$3$MUN}@qFALs-_HH3) zsJfe;9yo|B$h`!0ed>fJ^|P)Ay}PU6)TfJr-=KH210LGyMr%%blEg2i zr~?wZ*rxy-D$@Y=_zC%fk2?2orlunm#XU5%ns`x68I~R?B&=&k51p@u(LKh^l4~WO zaj3FL`dVy_o&&DKktH&Y`tZV7anv>TK70BW+_db*MFlhq9bcM1hv1&@cK+4E6yiYd z~oRuLJHx1YGHzZfS|`N&Rzf+ zTRiwd&96!L8EY*26-1K{PLM=14`H|6GQKL=aTBK%IMH1V@to2tRTy;tiQqS|8M_)k z-RVsOmG2SBoE@-qU=+WE^=TW;IEhUTesn;Z4fkHY29iz`@~5xo6Y?_}LsS~ncl zzP$!E1$za5SEarOPQE^mzNh}=-}sRr$&~pGUiMyzhW-Im)Gbt^%{Ez9v95rV<we z$by3SJif)FkQ9s$#Hq|z<&!U99MQsGlw^{=@2}#q{T}q_mZ7j(!3ET> zZx=KHm=b~$m+z+Mr}IR`~| zHn`D?BUWZXMJa}f*ba+!8?@y=fewXuAzyGOEFBk09B9$0Z0`B8*^pNBJLkP^Cvm?! z376lxO1+*vB_EqV<8Ag1yL_JsQadNuWhcYfr-@E@!j}0%wt8?&MYF^oP1!Tx8t@;7aGrO^F ziey16&|4$H_s2xiM%`CnsjCb3w_XtTi{}&^!F}c4bcWGQf~I4|-Ppd>jh|*%c{v;= z`}+!+ucM=*@lTE;?K$7xaPeVt@ltjR3%r?#Lz711ipLc~cW&B735GI%T0!eklmEJZWE_}d4k*3 zRLFOh=>{j|n76srh_249lx$U&;3++k^n7+PCY+1_%jaKsRZT*ciC)g$xny>lGYqbl;jP+)ay(nbcH~>@;nUOx(3qPj+`m3&`r*ty#^Xkk-k5c;Az4VwVv5z@{mwS2#67Sao?-@qiNd}>fj@1Xc7Db?RzHDhMD7W zLP8&OJuJi6DKUO{WU(oqRI0!oFPCBOC-cE*H>ZRDXPZJwt<$jMm?PanxX+sj zw=k{pp}1<+KVIq2UNZGSJ=U>q3YYOx=-%`eZWPF{xAqwaCoX&N;y!OkssBOjIO9Vl z)5l1*d`N>5Um3rZER05pkF(H!8ycRUSie_{kK({erlY>M;Q}XB!{iVdzdd14jtU>xUQD?WD9#Omiq5@)_aLD3E^ga>g1(=| z{CFdW!n3<>{5Ib=BxlM}EchNk!%RXY**Dp(zk%I?OYAWE-~;d|m1zaDodZyBy&HYm z?>bkURL0exj2HT3#!c43^D|ob$H!tx);Bq^Zgo7p#h#ahXkBo)7|y?ZUqzNzt;7kt zuTrOtyE*3_pI}p^40~_A55i~89(3iVpVkI`q{>Dio>St}+pEo&3YNr~D(e4q@%X2%P+uswq_ z(CdW@jqNMtuG}_&mf0;i*TXx>p58j>wmyW$##fT$$#rNqpJ|4>Oz_$m2iWBj%{zHl zl2f{lIEw8*F01w6Vs6Y3?_->{!`vUMj<$lkRSCZ-F^`zar{bLud#V{b4$g!mLdpOO zL7RQ^Y%+eek7V8|1#n*RiW_)Wi|;CKA?=%cW92|y>T@`QbsUWpzkkB^6b4Vk9u6*$ zv(r|%g@rmrVv~gvT^O;JC@=nm=Hc=5uFVhV<)eUo7bFY)w@a6%RL4W?{ABE=l1?DeKt+5=i&&H`mGV}4h_ z57Ki{Ppsc1M;CiA56QJsoUt{Y>a6ty-wnwSnQtd}Yt1+0BiEhfdE-<`{gyj()}G-_klMblKYDE9O;Ki zz1--EL+43D-6QN+6;Ho(V;wth>*1DTqTsE)VqJ*mE1c-*+6pf7ST~SsvJ$!zFJ~;m z?*jtphmb7d`}isxDT?7st)7yDEEnU$Jj}rl6b-Ywm*J2hiFDo2@yO{bJzx;~3?yXB3fZAx>z)_H^E#833=B%5$a{e+j->?e2pxbl4wW^Jfa#BTdE4 ztP|C)(*inNq>yQCFZc>RZ<&H2R?+m)b`x$%-?x~l!rmDZ8_=&j3)F@+3Yo9qoDt%Y zA9SSk8gl4AXBX6eFcZ3JafKiLnR}LAGJQ)vy}OG8Je_FcnP3=}^BOjM3E&fU*AVm6 zxp4N32mkr`Yl1V6z!qIE~z)2TY-0m4qVP8}s?|LksM8=fjkmh)* zm|z61mccNzyEz}!<1@(}mx`w|PtdkmIb_0=foyj{hNW43jdB0LKze#psKj!Ll6W`6 zQtvc7Yzj|@)W$r%{9+-QryPJkU$Wmr>{*ThJsqu#fPC6+_G zus3^t77Pl5%pM}xcRZYTzE?$V|6YcFyh7-=<~`g`#Sh>=rj<`9%OtK&LFh5li)Jbg zhm#F#3w**3K`Zd-6Nyo^CunEuBQmd77xsC`^nB}LnEvcO^g5(V%TJaPizW7`ywj8Z z-nl00yUk+^o0?1WT)JQl+h(d~!Il4f1^GiBVCcOobXxCRZqtmJu&k~{*nODae>`54 zhR_oes>rRqZ}BmEFZSDFg4-WnhMKTwUf-#b^nT-nm&Cpl-}-O`TKeMYyL6-jm-*v} zqrX7MyM$NwV*Z?4$!KD3PupgU1K)4)Fkp>^ptTm=*1>~6Bk7y<3UK`9Gww=>3`;9s z^}wBDbZNg08SL*hT-;uyBkkWH!k76@(8EinyQ+PTz#kFL)MAAh>6ZEdU$R@qt2IBs z?W{a%-D=dkXb8AdZ4 z$bRa}&xm@VT$gj);zZiePPrF+q4>z#SwNq&? zF6UJcH+q%~V-5Dbg~uaw>DocLq#(i`77p+cbOY1wtQY;C8`b=Bf%L5@#vY7si;vX9 zyVV~-BTB|;7k1>KaexzzHmu;z70H2>#7fxc8JQr)X?+5z(fw=^cqRz=1{ucMMERgJ z+>PeGk~iGi^ARq2#Ck1mYU2Luz0fbUjIZ#`B_r+rq8;<*_lhRP9sxp`D0esGWyxU z7n0{40#K>rEw<*6jn`h_hdnH_aJ(LtK3N3CQ!eqBt3MFcP+OdnBb=X* zOW$X)O~1q>NNMmBG7HTqDL5m`k#>9b(D2X-OR;s5wp22a;GUHearUsA)a=kd$@YUU zu+ETm6OFdUq@)1oyNmKE&PAj+$^nl~@ueR<2Y^f3Kf}C*zXT1T&0ZZv#mw(#c!zXd zNX4E*o$1z5hau2|hxwi|4dI5h2!Ae(rV=$1E?MgZUhTzh3ib`S()|InZ*Jt{RM~eK zH%$Ed9m})yltYyj+o3{hoxo#lUizTRpR@E=-dp0b;{)~-CD6Mpw_VS)(|6MX1rIHk zXaFL658m|AYtmo$AX+8|(*DWgC9U04V0UgDKSQm8koE|?x!i>|u1w@|O_V`vPKBV; zuKcwc2R~G0S>SB4$Z8EJt%%~snpKf)N_()!0AFgf{UW#XY&ooXU&!m)Ge4Z4k5U zzbMWQ$G=Jiy&?Gm_TK#NgO&Ae)cN3bj!P=xa%>ZXylrvKI2_d4!r$(pEl{Y26L={#YaRr22b?LHH(n zn7Uhry?d62qrs4q)c(^W;?eys1hMb>IZU%Px%>j-85gR*H43jDzl^JHdD0z`YqGSG zSntZj0%{j1k5+e!VNyao|EqfiS=pI_8-F{}hqe+fKxI1I3vUrTUEABoV6^%*`ujo^ zIehK~Zdxjm-ZU`5=94y1k{ZpwIbTUWSUaNG2tR5T;>+p8P8A=qV4BiYfBd)kC+rC- z;S+Y{k(y_TxYO634xc{`lFV+yfDU-Z|d3k@^Ka;;(F(QLm! z>4gZFsXM`oD>Cj1*~8I{`RWstN+s|7YjL|5dk5+L1O9%K!_J^&p&tgCldwHlB#l&m z1?JWoAYuK1|81Xr)ZByjwS4KD<1wUtz%cQT6dmboi5XtlbrsI2_zBuJfJo%fc;T&1S++TTo1HJMYD* zEN`MO>J55FXTaYl#{8kUALQ{rMLa#Rlizjc0eP~q1kGkA(A_nj(Abgy>h*R)U%{Zj zzo^GF_L6b4$+L5TP~WeCPx>n%u9fUIq$ZNKv^0bAiUTaKB)fA}4=O$_of#_oM%C^<>~>xII;dtK%;EpuVFA z?K#VaBx^myA%O|B89sye?^<|Kmnd{0mfGgxzP{`xl3Kx46?Jf{l&xi3lWz?%)-sTO z87Coe3ITBYTa2*P{&pPOVVUkuzZfeRZkXN^m&%p%rz3O82Rj}|v5m-qt99W@zj<)` zawgxPP(m6nDTC_{1L4kfwS74LyQ)iX_>DaCH@ZpLW{4-^mfSTzA)Mngu{RuC!;b#e| z?kS)bcb9>^R|3mn`3oJhx4)*~iObIPp7A3?^V=uI!FRQ#?#&W>d}S1F>mNp+DmF>x z2327%6OlBow>7@+#=P9Vls5}5A}=r7W5GH;-Z}OT zd6%1l4ZEGGG22Hycb9-sh73!mnP}pkk|^eFHs-#ssKVEb$J$#oplDM%7^gMz&NH$| zG94_QQOkPxUw6UxDO=#%taXA%Yi;mQEUQzbT^|pVjs@?qkbTb%HjqNIPYr~a1`7Ux z+!y+gcwgp;y^nkGabf_qu-24xPf7&;<~Y9BunO|y?R8wX#D(@7mB?M!>kZPrPX$fj zEw>79>8jD{<=LcH@p4dK9>wpTQAM0qY{%PqKJ;h81+K@fQYckp`?Cy7>z9uI)AHRggId&s0O41O)Ub9J)Z$inVM^s4*{$)=_9VuKbP>1HoGJgk@kW3==6 z5c5Lzp5lXtk1(HVS2#C+%tOx8J3;7p**$eEK3><#dxpo7x2f&e!15RJne4r@ehj=n z9M12sts)PvwL@@!BWfAgkGtBJZGoR^<=t~LN!Mu~G`Z+Or`8SuzZaK5H+zTR8Bp*D z!>*+#X`kvxEZ5)8X7A$Zn!&{|bzl-94QOqrldCyvP=W2Oue zLnG4`ibWXIWd{dt*z)CbYsv8SL(uBGB2{sFBspyU21y3XYnL~|hN4a|X_aBAC^rU8 zqD9hf?Jq&|;z%g^Bl8UOe6t1B$NJK?IWZ)&#~^XqN467m&kXZJnU>efkH6yiibQ`5 z!=ZOwXuOr9;b`kk;-N}9(ybi{c(-i`W}mF&KUGUfyxw83w3hMJ&e(03Vd+OV?CA{- zrc>d@b7Nu8SAV5ECT;)6A27)v1FsZf*2e@Ir0oTN?%aaA8uomcVJ$Hl(S~``66lHM zS!Awi4E8uElGb<@V|zxLqf)OvBhV`aE%9a#m^MY?oW z-&}I%j1AmlJ!AiA0*AkPqoRrz?XZ!UgGhrr_AIan&RTYy}#m!LJ#Ih>7w>iTfJ>k$L z8Q$`4L(!Ypr5nB{lMt0jVmr1kHfy31wpIo}-5fjKAi0*P%t^!nMo#osu^uVxYQge4 z)^%Xe2Gh@Ohjf!Ve$Jj8qSDa}MMI3}h&Cl~{%QyjRhNYPSBU93rq6iNbN=2$`P)SC zE|zaioUO+)tG>rP3S;8mkP)!ok<6$f{Yg z(Z3nG6)d7F#(0C~UT@g_RHh+Bu?~SrWBh0jBX#Ii+-A5X)_%^<9`Y-~hc;_&4$gue3jl zEHWJ^e%Z|WWb(S;h2BOeJRrl~zrBXwJELy&4tyw*>6%@iPn!7hj>3(~`J4v!1XtO~zwGd#}Jn zbJXajG1+93o(V`cNAabiD$>_wGm=59LqPQ+*YTtnvSt?XTh8W_0k^{NGV2h?95f1) zc|Yj>kM*6-{7keq^@5wZqgsm%Oc)K&z6Om~JOJ;;~wy6c& zF^LRsHCR7OSz0S^l^jdX{cT~pMe+2tODODIJ_7W%hx01ys>rw_zo6F{Bl@qTA6Ibm zIecUP{eN0P>?=>~?9O&kxgk(I-WDF+-yvkaET4s8LYyT{Jy}M66t|!g&o*#xJ%n-N zZ-IfYE`79_;jO_h__4%@?sS?3J)JJ&J9j^N$#P@X;OvRw-mD9E^_(qO+pPfXwG#OM zcGY(eO-92EXZqADhx?+Z2de$sa@NoJM-q1af`&szw0W8Z=)0eRAupr(nfohATh}E# zo8V28ezDJS;zaS_^USCB#}7j`H-K8M3~!z1#ACyKmaSW)0YARRz_-B%`Kwj+#KYtv zH(IL2uUOYYX6}>22$oZOJv@WFa$_hIgkBK*1Df%h@G-k}THK8#iU9+}^6c5W9%_c` z{rp&d$&cR=@`|`ST*F_-TxiZfN5jD{*NfLE>PWBVu`HnJU@Ww)6!v)~HzRRCh)BBd z%26CQU_Y>$D*nRWV)E3g0}n9|Ky+jnL&k~g=o7_moe9Y#$U#Re$L>UHdMlynaDVu8Ql<%5huy~QFCFP-6+L49z6qb# z-=-!PTi~wRMp(T|hNUaSbK%)rneOVTb{2KrJ?TM3A9A6WjyP_Uj#MpaDmLwngYzuo z{~vy8%OznX%WMueD>Xd7=ZLr^Lt83uE5UP52czkUa60+;Z^-~p57<;fc}2Ee73+T< z3q(FNPQO27ZTW5J`9y}9L-woTg0O$QNop!-YkYyWj8AUp696W?vY>E~gODj0+;sUN5VH>j{B^?&_X05n}Io@RFR@+$*VLa zT5sau{?uDSroh-X0@ZeTu>0d(u1BO2JP)kM*|e*R9L`vZeWt0=z~@=yQs6?UJrKpu z8B;}u`EJ3p%&T9dc9~oBpU3QE5ijqYPwswP5qKZ(Ulnpp@voE=$i5CvZfm9h);X!Nb6L$U|eu6q_2_T zr|-acY+?7BiSs2~_{=Ggt<)xT6#V>Nf& zMN*6P&Y9nUW;ZepAI8lFrkLvxA1a@pdPeb-TzB!g$ zOzSUhWf_o(JIwITD_=;}^b>LfpOP3y{pd=^9d|bT)4ERl`zz}&y`F#?-v%*%a3$|| zS4!S&jX)zuku=@>C|*5c4$W5xUq6O*!%l9;MNC_J>JMTuY>F)B{17mmzLH`$uRe`V8S-77W%y+ z^Io~2*>pEbgU^wgnZ?-Ul}6_oHiM1rOL(|PhO3vCX5uNvE#t}_bIEf*a(y0I3%%U# z2Ku;{4bzTnImbyO(QrJ*Uw z1paD?KQjMkbbWU`KF=3K?lP^QPsb13YsI$bx>{h{-Zh}ASI2+S${~P-*vfSBc|({! z5M=<^aY@J&6mK|%nNL0GjHy1v>VuZ}KI5pW4O7v2MhrOa^%pz?!+!+hwOZzlx4UOJ zrskm7f_02f*(|}+I|gFx{YX0SNt@)(utL;eT^XVIRyaP<6}(d^FI`te#yOqE{3Sm0 zmO+2m8T`ZWYvM1V+wlGvRcxVM{BhH}q%Y4pmV-{wno*{ZJ2(UM^c;A5+xO(y>w#E@ zQFIMw#HGG0z)cfb_lRBtPPC1OYo~tjW~@J|#{o6*1=b(3`Yh`>(Oe7nAIR`FCs++P zPLrn+v;8EkI2hC7PEpHr7YNpP3Z9jL!VZGd?Fn#&dhj}TUlWzR8*qAg0KK?EQ_^%K z23(D937fekw;5;4b*Db!R8HNoJHyqdf?uodvCi>9G-SLLA749K4ceph#4-! z+n7x=amoVbD_$5O5%>IsOVvfvi{^G{ZyyW)cIWe>bPLIbELZd!?jdkj$uKF`XH8(Y&MKaV$D*AAUk&{F1EojfsV&=#y1ATfhF#aCora|ZhZkZf`(0n&H3|dL&!A$N zH@!c`EbBV2B{m9Ro9y+QQGW!5>qimL?vCx3dg(U1F^rX@bccyC~yAMQU~2PuC`_y=vdjd>dILgg4hr6Y_SPKEs8PmIrxvt;%|cz;TFbOYq9VS)zL%2^i?DP41*q+P zS>UTHJXEoIk35~#RVZn`7lcjhIp1_F4nnkA!1!zmZ{k}OV?m%j2|_>5lb#dtBAicJ^Y=i8CGrZf~i|%7;BImg!1=Y=FsxI3eg zFWxRCv-)iX^?Ncby=brpRW3wOb#4&!YMua!%NGmp{&rv5;J2b2U80yt4&8Z(l}+ii zVn!fLZM^{-58LxU{;*DuiJAC!h!d^IR3)adLAd9VNIGkOF=n(l!NQSWd9MwGJURLU zN3Ik}XL~k-X7+lpr!rpJ_lpi5{-jH5zT6}=jt|keA)UIl=RwbjnZU0P;8#S|5V;oC z@9pP6)r)&@gQz_>&|n~c=4Lxtno|I$R_M~ELMa*X^c18=$TZb||D3Sc!j1ano+G(z zFLnQ`bebdi1yvo-VUlB#kk9%sBN^8YxkS@0`Ij!aoL6?LkE>7aW# zRa5I*1RL4|joHpK_{>hU!?D{)L%rUP>XvB3?nXZ5etV`$HzFgwB={}A-?m$1# zNw9qP1VD`}UVC#12}zWPx-+x*j+f1(Z(~2KdBnau{FBM*tt_v1(~f_XT}w=M#o&%Y zM_T4JmCQ2vj_<7F>Djavc+`CvtXoyb-D{m*!!)A?jAeWw%;XR$ zeBYO4>*T1hQW^=nS%p8CFKA4rKkS)%A3Qh7@bfRz0d72vqQ_ntal7TDc!YhQmZ&wL z`S>`g2H}(1c?+8?l3=DOUX!3B%{iC`)pAxa{PO=f>Wc4} zaxtE62`hqA%R+#%`xG5eN){MO@z8dW^!>6?=ybsnZNq)3+V%BWjRuM4jgaA|6H3u&7voM37h^Y%0}wUhChxwsl62QR zj*Aa@(c8N`xdF2@#ZvY&TVnmtf9iYq{H%nxj?N`(^V$9a!;LljG~vbkD3DuoNZ_cW zmZ{>0Q#WYnY(+5Ik;OTwPY`+r6dwJAh^4ypOz8vCe@!3pF!r4rwMB%DAy&|?CBxD` zl|eY?rYlvxzkwXAdy1#Z;;H4k@31JM85YK*@H4NJkr3vSEPKa%-3>1xeTpiStiCAp z!QO~jfvF??>1WkAVmh&p*qLEz&LlIuIK>0ZnQwf%=_?Xn7JxZ*E>vH`(a`ite{`#? z5L63=;lcrStFq&6SL)hsV*^;m|hj~;Euld)_EcI6WJz!hf zGF(;2Psb&;4s@_b5ALLk4VN`zAYbg-PF_EwuxE=deMY2Y|Eyz7!|~x2j=du1W;&wu zz8jr0>^zxfU5Zvd*)+qt6N+|J!-l{lzA2=f+?OUo)qa87r^*KNLA4}KaNag#!6J?~N9YwpS(B9|0?^8-U z?VZLa8nh>s?9A+uy~@aL2PSFe*%u{T+el1BUwi9%4eal z=?deh0U_AT_rdtKGG1^hhYXqa09S_E(25(=L0xYGeALgB>=&rd@8LYXq_}Fuso?K0 z9lF~fi5OpS1ILHfd`S3va`99YzNxpPZ?Ef-r;l5iJ%w!&Id{T}MtvCbSn9b7@DSn5 zTiW8jADiJ%kRF&Wvy^J5#ipp)ahn>A@g(!#j2EUb@AP(mJ=C5M0iW}vxazAPh3Q## z^yJN_0=dwm!l-JtHUB*elRT91mQDoC-r6mCc1?ut7gvNCii}1&MmSOMLio5Hh;OyJ)yq7)GPA?A-RBgY38Nlq^rFG6N}hB)MyHGb4y|27(agZg4e`UtO>#{sRtk}-4NYZ`Oy_A zlSPi@;n44KEMGUVg7k6l!{18Iv>-EyyA;|N{{53;><8x6kIehY584|_6rRq9`R)|y?s4XKudF9e0~cWGhDaKDEmrim{Syk=MwRnWYm9CW2gPV9#vV?y z$62dg>7I$9+^&&XoKoQZ?31#6vdP@h`14se?|vYLv@A=<_8@yYy5j<5FINIr%TWFa z(|AAC&cjksIGq+|#zo~8Lrr)$|MOucu}>W@9O0xTUN-IlOuc&nHai}a?1Sq@x1!KC zp6Z%Bg;Q63U~Ga8?ViFium?nVZx8Eao2P+l<4@xwmUnXv+m`t;c)ak^1ugN7{du|jysMQ{yD(BQbt}_W?BzL6H0iU%p4MWEfza^9O>e& zY4G4u80iS?j3|37)5hm%0jZk6Yf{*6n@dvPLezDJN#M4^wr#SqPcB=u$$#I z%%^Lk`T5J>3RaSyfu0s$thmayJPz$7V;U;3Ei0aWN%{&;{MupXon-#gf6vLG?;g0r zLtFg#dJS|d4}!5vuJg)&o5<6|4VW>6?T?I&CBya)5H_(JR=DCe{OaohFE4oUbB$`r zuE~CAoa97Js_g~a4L1sh_R|t?ntC6NzNq5TxJtfFR!m$?wu474;mx(!CitxuEM(eC zuVFAGoSOuu=29Npu%i>EOqQX_mstPgtWqpnETYSlf?x~V=|gr4{@*sD56cG*#GPi{URK5*BUfKS|wSnq|+^E&+^N4!VVaAatlnVm-5(aiBs@Pjt>14 z98EeVlro)7L{N540DT@n=WokbBh+(ahMMZg0?m3C&~R&c;m1E^R?cI(`de9T(F*L2FPq zmy{&M-rSeU$g}Sn%dJVID%u5vb<(@lLazw4P_n1D?exfEnNPUfh4nfv>IBd691K0u z#IG8iO~&S=;~+0>@#5Fbpx-eAK7ggf?>fKgII2ByrG25FE<>De+(RoEU)Bg)(%8u?*z2Po}Dc?Ff|;=`ZoShHp|GXC<>F=u9>Pz zFSyQH1O2w{kaz}CFDT$k)gJy;;bBr{T!x34_iw}>9=<&*fo;e9BpU2k-$<~(rO!yO z9%RI-L)3RE*L8JWgU9FjP`jNIMS7baS%z3@;0~g5)NuS|s z=G)I3*U4)g4JD^NBSFJfpXS*ggui2EgPKbOPu^CNviBRYS}TCAdt$>?DT+Y*P@$yn zWdhrrs&I6rTIVM~V45>DZZeVZUZbD>s3(7fE`F9mim;WVGh8H{S|5(g!Ff+2>BN_@ zqLCI&Xv{j1!k4msedSOX6rRVY{L3eSZMHZ(%9Xx03FR_kGdQQT1c@)pv~DCGB)|D} zFJg%G_=o89){dGPo(GMBevs`Z#pF@(y10I07@czLBo}q-DV!enn|JHTBwaR|LNW8X znQwmp>8H-ZWHzL-*rtUXV;POAG4XU)asdQHxI=BB4mFzhj66w8$FJ-SrLkHADLskV ztseBE!S>7*Ycz!r!MqSB_Mq;!C-9?Rf`s?Jpk7!Ibb(&!7thVrp9YDGx+U6dopmIb zozr@ zqH`-ociaMPCojHUua+du^~Qh|&a_0=LEzMPt&j|3_pj!7)HtVt2lcA>iKE3ty*n5l z=Pal9rr!dO9@a0=Bjv*vH5>4rv9@@iFc@y1(}b=7DIZ>F{2gvO$WS+$NnV!1&)f_&4|_ zPyFALQ27bCiZD%kcQnx(U4o~F^K{ms=kOov{dQnJ^Z(^%J(C_`#M)bQ;?MzH?Yh&P zD-P$!p6MoU`lN$}nGU@bDJI*tnLtvR2XFJZmeg*t!WaLXspMLmbGzrgNyF*D7Kl|r?|x6Xv1pyM|s-<(Uil&-oohbFC5<7wFKzdP!sv+oUjL{-ytH`r+b- zPN4e1nm=d%o(Ly}W2dV%K<`gj6~7Rknl$lI%zLT*Ee#F*w8gqP z&G5xQ3w|uOe)E3V)zk-{xE#auTnAcqSl-S!C zW9E7f>Q|}?+RNSvUa}2^vBG1-O;r(>8OzXuf(OLp;WIQTkEaWkdc!;G6zIydNT_I3(rHxO?%Or0@`wRa}VcQTtdLT)56&yC) zA>qakMk=DRsSKS{YfP-%*me@@4Q}(~p~AHYUfuBHPYGX>K&=oM`B3h zm*Vqyl@OTiE5+weRx=^mFM`*uswC-G*JALD0Q%{k4W~FR1CE|Aj&J2JCC{F1__d!!q)90@Q2YK{@2i0ax^0i#~-z)AG+Co=4Kgi zkCy7UX1UskvSIW)?> z8Z!uF-5~$#`fgYgh)FG8tX}gd$r@RLJDG>)@6xXzKj<^$>!t92&7PA$J2{x0AjRRw zCM(cxtS_A|A4lv9<%BIv>-dzr6@Bj8!?3enykcDqDfsG*Wa_o6n_Ju<^nD8 z-I{n5R1QREtdevdW+l5pm*E1s)z}i2`>%oy}(b-LcmD9kB;cdQ)nCSdF3{Ai0>(!JIaManL8#83+|F`)z}{m7vYHpt?E z;m_g2+$0GHwzo~it3w>9T51_*^^J1X?NZIbQDZzNj|`-&B7?~Pu!17Ld;EjX6(mS# zjYS)7)7hMyVD(QuA)eC`%TEZw@U>lFbgYbTGGuzrf>bbywmH8r8)E4Bf|dOO^b0wG?>hZl^iA#OpTc(<3I>q>$c`_GH@rKzsNl^1g%7LBhd*MM!Bn=K-#T_bPy~HdN^goRKJTVX= zYTJ0d?o47lT~2tP>Al89J&+-@0&K2HF*Y^c1~-npP8E*4Cq_eyaX8cH4qNds*i>h6j$@r#gH`X5C8po7Fk$ti?uU7>5ErmVD_w&P&ECJM00pus*YRR zWa+D|`$)|GM(jKKKAm>pDJ1APfYv5mdj9@1QYfELT1c{Gp((MS0yy-|s-r+f&ev<*TeoK5@{RXm~kB(4kd$fjR zDJEg26T@nM1H`=T;ILE5b;+i~cwnmsEv&oEsc%*jst1A^rK#+*l&$y`?3TAe`sNgV;?3t| zlBp~-MPHYA5{^$5V($STx=JgS-L355SAZA4e_$M-(= zfuu_|TKO}i@-p;zQzqG@6$JIeZTY|vY_p7};Aggd6Lm_36r4B*eig0!pbQaN{PPX2 z*~>bmKi5| zSF$W&f95^@X=erNxVVn>dag8R9?Kns=?H6V*v_L$2>z1&0pYr3{KZyEI-{8nf4T#; zUa1RDCJlsrx|tFmSF?E>R{Lm+A9Q%Yhl)=e*JqLBUiOk<==Uxi+Bz|blniu${X=Z{ zRVUw*p#0Hz{e>*$O5#K#1n+QPbUgiK`xC}~pAK^bO}te;A=jPaaCbC&>qRs}I%^=3 zGm_rRz7Ic$aW_3Ftn((-6GjPRY8aNz*29Of0Z=;8N7A+R&Nmc`;%?DJN+p8q6MKbA ze@qj9*ULgpuTI!?Fp_S1{#$fi zyU82Dp6(wcQS&%?k*bWhy%ng810i3V3)x2PeX7yy4QC1y;Ph`>emFFct;0K@N;#Yk z+p~f*;o>l6x3;+d(-s_6?+3ac+IaYoNzT^G2u&Aii)$YBz*r%|jl3Nae^=Z{YkY2X zosRQ(Pu{*RL}%vHPQOLr%;tO;UEs&-&v;Efv(1Jw##c>T>xjl~0qeT)p@S?ZidN6| zhs*(Sl06#DI1ij^+?N{Qd##KQ47Woj31VG~LeH%$W9^AUXe#Y)nV z#O$jAe~OQ+xucICKty99f8bdj3Cr-r1QRz}-8%vD-r9plmlRiDTnoW_mgi}mDj^Er zSyphh6jzr=Yv9iEAgXsULewy$8n-ZS&q7se93Sip)(ltw#pjc+lU=d$K`>Pql){}@ zn8qo$CrI|cLM(@}yUbsHusD`bWwvoL(~g=hWS*%}ZCrG^R6{tudlEKZkD#$@PH`pW z1WJ$p;Z>Zn$lxR!d^*{SJ{OM#w^9?B(0h=-H@k(D6^=$hwJcR=-%Gr2yhHbw@pNfT z0f;|a!|O&}`eSV=QCNEv*S7l5h`2qOTVzHFmp#%F$Mo5Qs~S?lEI5Imw6}spJ`KZ` zWJkIof#!7}Fq_>V7S8g*`@Iz~yQoBRM?0<)g^2+!^tS1AIGGm!N&2Sz$^4Jx zM)Vihem$So+Tv9owJ_(hF^mqhl4KKx z7`fr)8_u*;X%}&v`4q>0y-)AyeuI>y&9Eg{sv+do{^o+cuS z7|Qw_G})aud@J_xvW9(uUi`ki8geT6HrhA3P@Vs72?C>*3pWZG_r4vEUX@DtD6opR zD5s=k_A;CoX9Z-_jj%QvrrM)#@@FB7Otf4xPg$hQwUEt zOSJ;kCu*2BK$rgGqDg7;4B<6@_MUZ~k2~EHz-gf`AL;y>?C?uO3-*0IccvnDw2aShr(~5y z5}G$T(CvNoz@v`>I2mV3vb2BX#^dl8k<{zUKzNkd$PLt9#4EIS5FI&LJg%rqb4Ml- zxAk_w8Ay3-@{f_|{acnED323a`_*AdOgyE_f5Oa^$uQipiJ#lW=qiau&19BM_G^at z2O98?<>vm!W0#NLhhnxl#hZAO?=i!Lr%x z63nXFCCp=)>&3m9SZ3S;PJ6?t$=xo|m7r+6=&CIqx%djEtDS+LGo;w-ru#}DZ`Uc& za`|2*-2G93!gE68xdKdSy)W@6=>LodMJ+pi`uYY^rS}mkDne;NsgNr?8jTk0dwf+) z3obVDhEvs2Ew_pGU?0VF0|G8n>M z-0ka~T-Jyxi9X=wtBKURi>E=M1c@fxwUgrQFxGK=VDd^jc7ZmRnU@0HpQW0>9I%7d zImaZLz*j*CE?2%pr&ni_%_EDsh5MvB?b}uAxcEmfop(D@6mR$gCbCS&6CFQr$n}CQ zK94W($|p^;obW(z5Y^U5=HgBybNbm*O(1^$5RClukKeL6j`bPd$83QeEmb`W<1{{U zwRuvEjUJ(igIVF>a)nHMV9F36)xb#pDC}^T@>r#zqp)q5 z9GyIFAL*K2k2+)SQumA#qz z-ou4|SSP^2FT1h$STdN35_tE`6{M|y1TOY-p~OCyTX$hRG++HK=`onm^$BbTh102d zwXCNx8ogbZpY4!YzdZ~Ov#j`-)$d8Vt_vpq=S)8(?<60Y!g)U=nXc~l1774e!u3~D z9=oEqgZtDb<*{Ld7h!*PleHZjPquCOgFkfG&*HHaue#oZt52o+z}sF|9JhgW|Hj`E z%+^NX{w-Q!%?t5Zy;c!l6jt%Ob10ctya1MN&6fCSW3~)~mqS)dxa%{;1~}O)L)+Nh z^T-KpVKn<*lRY>9SF8Gg`C(g$@9XW+`^?wEFm|a58TgTP{wKHcS^tTMX4Eq@WZ4AU z+;*_{6TtFKH+hRwtjF7UEN&YzkDjiMBUcw|3+3->i9ei~k7w=Tq0cE_iPy{LOFSBx z+0z1d1x{eMk!$jhVr&%K3kYTUfXW8OIg56{`M)0gm&3K>?D9((oa#!+nd@X_oR%=l zkG(!qcu~L3H+U-{p01Po33r!i!dIsz z-s=+~cbdX*Jku8Pt~A3>4Rx?}l49oA+q-dMy%!BI_aS5E3>8K)Z+6cwU5qjEfhC)K z_)l$bh{?wwmg{q*ac<893k-J%QIU0$yvf8hW({C8CxRY-^Gnpshv9X5wsA203Oae7 zfD;SE{KxhJ@~^QQFV5E%r_73h^Sdeqs=`i*4shnM0y=J0pfjpO49AMl?o=wBuq6Nl zTFh^Mz>eQ(+(2x9eS~2xcj>lmYq?P&VOVsC-CjdmaIc;R>|EW>-{{RGVddTUlj#6z z>w6$@#uCPLP_jAb=Vym!Q0)eB-;NLqr#5>s;^|rDgH_X-!VlJAA+c_8)|g8QcvbF`I}?| zRj$V*`Pm+o98P|d3$M4Op4haiqpDFPO;?K*4Yy?5AMDm#+i8VMn%yCt=J7Yq=aYtS z<~a7KJ1wdU=dyn%aN*5T{CxXnFgkVj@G)g^uEehp7XjYM~ z^J+M^GMsMEFyjOp(xLz9zx=_$BH~3X@OP~{l^LxLTD6D3C`XE)Hy^!WHwCuY-J1`` zzJ%eP2Tapb*FdGydr@JE552T}cjl`}LxnS07ACG@H&*sZgoj_Gy!7(=Fm(RuLU&c? zaz@`Y;lbEH5?=Z;`yK3i7)}LDdl~U648Mj*akAo%0W>*B^W1<+a{qHTrn3F(Rr98S z+OVO**J3TPnw%F-=bl0Mv}Y1tYWg|?=gz%N?HB2Q|3P1{N;KtFV?GiOm3QDfKb+2( zCIgpygElpD5tzgetz%pOOg{^WoA# zDK9M)m!P&a^9=tBg2CdU@NLa%iC0#}_bp@v$ZFxYF$FMroSE=9$m9qT_d znK6h!?g4nx+{$aXh{)`y5`2D4TRiqrJM3>=26lUIO7gI=`^Vt=Yjf$|<#EL5o|drM zTZ;{U%*QPX@gQR?<)UwMW3h+jovD^QcL!E+OB06k6Zviu=@AOK7CQ9iYB5>nzXevw zd9njlE%`j+0-DsjQOD_)WXa;GLgzRwvCP?n=r=JB`lU$n zl`XO~=V+X0=P!TsNIg%d9=i{M`cV*jU&<{DMg?IB`IRPgnkKeoG_ry7?P zaL9ssuuiy37X|f-%zFcILx8r}XT%j8Jc4nR)neYerGU6A|HNKon+xM(pw+fap!M&k zWcRQowm)7CSD-bc2>I(?j2A9Er1NqEp+OJ>aLrC~lTrz&hx%W4>9ZYcxv9m0=)iDt zibD$?QFDXIt?j(|ku0*W&rh^v-jcyfdca9-AuOJ}Q*x7R-?vyMc|&d0?T0d&>bsiMpRcTk%a$A{RJlZ8{A zaV_g`PTiKm*;{?*9Id51^ZWHNsQ2g>U-U1Oyt_C8ax5eG0m4cmw|OD1KNCnZIXiB@ z?tSpuQY7&PO#i_4yV>2LV9*4R{b>cc0mme{t=Evr^*ted%MaQy8Z$zp>5YByBA@62 z^jfbi-q&n}t+U)<>YqIRp>sY_UTKb*mY(#CS`>G&H=f&Lmni8Ou=Gqnr<)(HAuWX1)ue#H&^Up`SsM6RvAjGu`+HGHE6 zOoaf8{)Z*ECyzC%xXDL`w%hC^J39O^IPN@smgoX=S6D;Z0)4t>{zt;A1!3DG=7}B1 z^wOU@(Im@G$XTRym;3WhgF(K>lK2-f%Ic4SB~Q`e{vc3CrxbU`{9A#TGx zEMKo0p@pu;_QLyW)=NL`J#p=Dz%84d>C(A7$t{*G>Z*Q73sQbV>y>)Y>yyemE__br z9BbmTbFcGbQk%%ngjtwm!ur6q?h^}_HY{Y^zeBrwf%9%ifReBeBW;-{5mJSH|cH9Wxs!IaaBtYta&g9YPU#v zW~0d~cxxa-8yzx;c)J()MN7Hml6PC+zX6|l7dsId`Y#7nZfJ|M?zF?RV+&xAl@uqR zj~a@_qjc$o&ru`_CJQe!ZREM`e6-$j5BiFIC0&9!*Zojabe`s8r@%5pz)ka)dajgG z@4zWnDNg!&Z3HsiQ^F_rnViMG`M0U#J4=%HWRkEoK})<;{~!j%iJ@nc_LF6fI>tb+<##S8TzX@&F&Tm{Cq_~~t$`51dge!MT_m~bPyXEr zi`8^#M|mQd9BTqUO(5~D2+8+rwatr1*UBj!WO z3P}63@Azp2>t0igfn6h>3B0FwN-%S1lN?TJRG@Fy5b|MvA*QgM8XxAzTe|fwsNRvj z&CQ!Dp)B_yFSrRMDJ;Msz~!A>A(Xy?DI$RY(=-|?otw)p0x9$2e451yIs zlxU%2Q>SA~jULtY4I+0|6=G!FL)t@&;CO}z{LK6%Z}ZuHz1-22Qp~Ir%*J-bJ9I$j zRFURcH#o90j$ai}PHLw(qA`0zJ=~PSy*T)V^9rbvXrWer)zE%-H-C0<7%6X31w-a> z{U2sl&yR&KhDDNo?D0*Lgifr_Vcwx^xOe0xto(6I;-OkFD~&7K>cZPBswc<2hM}rw zH2u6RUer-4#@pioW*d}p7ZX!iMeXlQ_U9&%8XEq#x_TKFCHHnA-2 z&}oo5V~{YuLQCxZ$`i}23*em7GhX?A4q0OJ9966`sqY5%o}T9g7tWbUx>@|>{=%di zMbxEvJZwtw;N(6_JyauIbKzwa^R=!>Ck_8T;}8RF@t{yGe8caA_1~qKxpbU8I(a$M zV<&c!YZsp3fsL8;`>#IO!a4-s?M#*UT8DYmai3UU-2c3+-_&&Q@|XbXUw5A*$9~3r z?0fv&qOEAe_KO#2cuVf}AA}D0rp|@#`QRY9;=4$A_Xz72=ogRC*>X7lbTz-|Atmjp zQvrOXJoDPQY)rq+`iRPcz_e)qn4Xhj=A5`n_`FVrzC4jZZhoI2?3>TtgQ^2CcfAKJ z3}s`v=?z4r6^+@S?5J(aKq9NT9-7)(`I!eqWX{}d%w!%a2d{Q;$({p-uF|)8+c{P2 znWabTs-wy7stLk5C9L~v;(Sz-iH1q(jB_4;O%5hUp-B+iO;|6_6;7Vd`J9v9m|o}j zz)Cl^7ra1BvevEzw+WuS@0?mPtHcadrm${sjhkfoiV4E-C#<(;(m|A)!^7FZ$r8=e z%Onn)0-Wfl^hyrq_;dD0rJS>`*D>G*#_&s%D#(?-mv9B!OZxCjK@iMM5avD566?AI zeyruX##nKZU^Vpu| zwq|J79}KteOF5@t(0U9s@uG_}y~*tt3;|f5zfr6%7Jg>i+)h$GGiZz-UNdo`hweNR z?0K+Jcy&7ayC2R($8m+Q=w%e$9RF9Oc_|c@JY7Uz*xJJag*`BFkC8j>un?&W~I1JT|{?;R6v4HCUp5p@pD~j7Z-a(dZSk^pNGlX;WWTcSEMuE1!mrk zgr)uw{G|nz#4B_jdh~?R z(GYTdjA&Wic`n!Wktoaj70qD)I!5zRIJzRTIAB}(o`7uF6$ z|LZbzgj@oNnEC?USchu8+8rn#ox_=a2<26WSCI^rf!KF*1l{gz#--0pgnl0X_((Sq zG0QWzO-NqiJtxfU$D+hhqQdSddU+lGg(f# zeJq|ozY!--W;eLkyE1)q1_+OTWE+uYyD`}2E|e`yl-%W$-2L!rg%h<}PdOu7HHb-- z;^$RY=DBJKryfalMDeO8ULxA!xE%)Aw_`D6WJUA7oi9ku>8;q7?N1j+`f>(rXJpw+ zE%7w!iKa=pOj~>=$pyU64#LS^x0z2*2R1o*z{Uqs{2UaP5B5b7blir%us7PB`xiEi zKl-SP% z-~QFIzSzjsz?MU)l6QKpMGa@O>W1Vl@3L$rhFAyCqw5mL&x#hdTcIVM_<9SPY`XxL z8GgMDZexYPGn~DIctl^ z936sH?42Hw9R${!2f(B_={vp6`vsKGm!Z1LGl;9o1fiw1mUu;l66TkEPoeSG?1jeSPOnVQf>3q9D?=CtCnQb4jbj?z!ncFehw*7L8nq3I>{=Eh-4-R z2VT$;r)JK>yysC6+vO|iS}8mmh4YvW@X$n_Gndoh?C(ptXmhPQq_Y0fIXYr;TXz*G zE|TJ>eg6{}cha3+)W1oboHT`k8>~Ab$_Q6hh(KmbvP9dQn0*&d?{uWj9u?e0RS(W- zrMYAeOGz#Y7Fp|4#EZl*_XzwN5yKA)tRPxxENg$vmwGEI3G!Stg@HGj2D>;I@pJ=p z950vL=!fK&;c1!s^unTju+8!fCoY!eSnbrKU|WbjHGUDpS*$PQj!sx4*>H(^^%)+k z=+YS;iKM*d3K*r^@X7n%leIGj;x=7bTJ|$WRP9uTKFpg@Ht7faJk<||I5+WwQ<>(e z9R-Jz^{LgXeqc`sfZ=M)tvAH* zrVnm=<3vvlEfw5RS}(jgT1&isOeU63W4&#!irMDQ81nT}033Y3knSzB13}p~=o2r! z6M5Qxz%}d*ez*M|9Bs=N$eiku+>C;+%HUjAMQZ+m5RIl{lszh7F|WqkAK$mYp-F?+^)(0;L>vQj@08lyNrmVcBqKtOfL2bzJh6=Nf`=(>yD>Z+an# zIU30+nMnC+K|>^**rQJsTGxtJ&3S_TkFuY!zzU6X>|of!eBSJ2J`tCl!>C$TglTz? zJNqVz`#vX0!dC+=2jHhL8G1x9fpMfVRA`B(mCAP@_RACQL_sM3sjiX)w?snG5qdmP4~(R~Wk=3F^qh(NUlkq)*NAjX_&) zJ`8;l&HGosApPcSLi+}Ps*~W$MHnaw7qR~HxMWZ4pGcvy;u-%bD2JS=D8}2{MAUxB zf3UOTHn{I7V>nwMYM!6zf!FD~CPU?&5Z>r&!c`9!>_BpYc_MAJ% z`0D?5vUcsBf`?V^(1_dw(zm$*s~E??e_N1@HiLt6z4_FH8uB;U23;Lo>3~hQ1cTh? z3ZI^4o-t7zUZFC$^-DFsCX13e{l>zlifl>$>Yu8Ic;GI(Bak4lPwx*NMr(MlpWn#| zxn~f%K!%Q1%pltG8p5w{wZyicm5|1|!ogosjkIESIBuA3Pgge#B#TQqaQ@lK?-Phf zuH!?T$+Wn7<91N9o&m8BqVbs=XxNYU(qYlesJP_8V)sz`5r-^wAzMDQOqNr}>`zc9mN4ce643u5_n!uiPZn zYsU&tF-?1SnGyDKnGo}zl&=mP<%!X07pQ+i23I%SiF?5K>ZlaP|D8i1DoUT;-gc2_ z&oF{h1~L4mClzGOk`t)Dz>BKO%L}TPj};a(4!mq*Fdn*859__l`N@rxL|uM{Z_cni zk(GNPSfz~9ZOi0CFBFp}Cqls5LZ5z$j^Vm4=5jR-i}>1<4wBW>425HLsk~hx8Blit z4&S%osoHyT|Em{<>~yAI@6978mOn#deYPv1(E*nS_He-gQoNmI69Ufz^l3*{KbQ)N zu=}T_WHW2SkX6{dg>5rk_a(Mp`U}S~yiL5MizazaaQ(GZ2k7wi#)-e2=_dQ<0w0Gp z!Y@@^unAVgNww2qcbR{NVMRpkJ=kxQ zFF42jAv+t)NM%ef#C9rD)lJzX=3psypA^#{`gg%RAq+Mv+DmTqbDbL@+2t8MQgDTf z4!H@T-W~idN9Hs4eTTzYzHDalwlG@rtV3pZ*12_Hzs*2k=yOp2@R zmz%l2``!2`lR9!|mJXhXi=gcTXNlzJJHY5@sYV)QZi^~|Z&O>3+_8oBVVH0#Od!w=BRjOAj86=r;}W_vpM{FHV1 zBv0QApN#jRhi>2HvQ;BEiykRo^>Q1)xQ#4bel&?pYkr2)SWm*_!T@j`n8GQxhVsU} zm4r9ykK&8b)THw)_vFw$$k^D!TQrJ@@u}mO%{&!@7tcT!jw0xR3~>7~E(;d0L!T)xJiDo@>?sov0E zDC%Z?nDchCzNK);IFu;qwQj2P#hzhq^!d3wuHn&ecst^E_Tu(GWMO##D1COKue1o+ zSrr04eO6M@6cZ3#oCSXvcWt9D$nmvnalef}&0g%w(Te`U7>*P^O7M)Un9gLxa-Gp$065D`t}!nx5gd4 ztcNquQ4k?FTNrwhZM=HK;nCTB@T|&933qKY83|wSWb*?$3yEWEGXC~v`IMj_nCKu2 zd%mug`15zKD1x5XGSuWn2C2BCE|lqF-lum;c$@8cSu-sCA9rR$QBtIn?``ytN-&ofUmw!!z(w96biZ?5{YN_GrYCvSaGPRV*uHS}+ff zriH+u`F{MSo3F{>f=~>Mv6u9(PTxD0Q+zJH%ge1~e&f$l@6+!V0o>l}$y-gWB?b!) zqumR4w!z1+^rf2c1l!X*lxBow@#&C$DVdMkUB)&6-Enxv1$y^p2Djs@HTQO|IiGd0 ziA>^t!_>e~nxR%eVutR4s8KQeodXp_ZTLytV(Uwb+7tzvS!zPL6fLpalwe%?Ukz|~ z%lUVClx)0FjIFH4TO`^GMW^#P;b&=f_2js}FrX}qPVH2J?FQLgSg;gJbNauB3rlqA zP{%})xZo`KK9_0&K{q||^j~Kxzj;0xYEX=`OIe1F^?(iA+QzkKOErNd7X3iIMydnM z5iiH8(Y|zzt{*Y6mJ@c5V!a>7b@7qiEl4e6{(SE@#BH)Smb%UUW1&ZVCM*j*xf4QMY_&U~7*ZAKmkg`2M{OhZI=H>ANYM z`zi|vztzDP9nT^cNe#YY99Z=5ALxFc29~dP@`L{SLhRKv(act^geFtCewWf=16%kK&FYfRe7d~-DJ=v!A z7bcd3QQ5(FMW8(1kaF^-@S~^ijcwv37(9P5&OwIsF&Po&Jz0=?Pq> zri?E?_M;2WrjiGHi!qwzfIO1}pua*4=kqy~_xQoMv_&7R{SryTB2IIW-&hY)P!IpK zFCob#Cg^qCo37Q<0Ojb7p!N7L?|-<3-1+#nLbFGhj+`G#}#6vV?zEVxf;e&6)4Zjom9Jyu~v0yKZ=5(a%h{yr@*7ml`hc z!KtuSLUDB-SG@Fwq{FJqe>|G@38cnP63Jli8q^fB-2Iy^XqjLFZri0?bi_GF zY<=NNM`?HnoM4tPhvnAi+Qea)TQ3;sy_9IDyLvp}Mw=5=vlqkti6g+}vDBZxEH4Sw zqFF!N-5?lL*B27|t&!a8?G6<}e4`AV|2l(g=%X%7X4+kRof2+e?hNAw+ws16>~{ZF z9ph_csmBsWk?`#T@ag}VFIgZWbCZ*>$es1BENX`=rDNLPG>qm17m#MN?eG_3c=5Rkvh&O#W8;L*Y8`@W0r| zHRU$($=QU&zm|c_21~x`Nh8q>;V_ExrJkH0F&f@ixNMTPICux+q9^QO)^{nE>Ywn$ zecxGk=%5OL^+kQ*w)t9O>*x$DFDL}F_9D7|zB;KMeG5ML%%=@~Y#~BVAI3eFYN|D# ztML-!T7hZzVA8@Y!5a%Hmj03LhI@HRl$*$tKyeV9m}SpbjA|fH1BxIZx0n`NU*g^b zT!7}>4qnkFi#%?uMkN#G{}1>Fzkf`IS1P+C_j>ui$8gS3E4t=XGg)z^1XCC1(}_Q8 z;PB`)(B3A+&k?hoz^KQG{@H&8%Fk7E?U$syl=jg??Xn;m=dLZP+-D8dWpVtkv*l#l zzB+F2oodPLY2%Zjcue;n|LJ8o(O=^PDI=Wey`v#uEZ@nkej(LSJ)$S!tdkMcy~>IE zRDTD$>ZMp3GTa7lFZ86NhD-soMQ5R-<~YB2>-c0Mzh_%A2|198RV!q^#KjOzh+?L}>H>XB&nfHUax|*bH zg`a)0+m5oXxkeSL5}i%{^DV?fcka`#x_97OO9-c1$wZW=mBj5-Cq#~pqz=1Iap9-K zKL^

    `FRlvr6Wke=@>yIo3trwF^B=g5b6Ddkm z!!yBw)MiZ*i3~poBOSeYhbJ|}R?i-vp7f(Lu6qdN2hJ4sSZaxlcf{eJ>%U=m=u62h zzU`4R{COe8!<%OJusUCghnL^{;Tjf5@$kf7F?h=MrGC%YEk1aJ(6f`h?_!kj)f)%M zoMOid+#5*uwNdEtQGCqQTIJO;p zQc1A=?Qr2{c4wU1KNwqYR)L8^g@jwi#YUj|DE2Psm<#i_C3DMUvLwAIg&v>4-!F`s zBq%|c!b8sf&?LD;jAX-MG z(|c}318qb`%SecXG=ArI-+!R_-p~7ap3ivr>=J2v0c#i@g264a_QPR#%<^9@%bSUO z2J3q_^`>p7^vExGj97Rz z)8AcVNC&%5y7ntSkE`zd1@2P~>A}H8XpF-Hfy>vwWd2NBao!|x z_<#R%vl5>EDFTdlx^bVTH<2|=&;BO=gxZy#Mgs{)VEetFV*irSkzcTAz9F4wr2?GN zRIuM~DxSv^XCA<+-A?ojd?XhS%@%q@YlxQrT!PQ_WPyb1HO^&i19^VP8Kx+CQFS{9 z_569Uf^WaOAhp_nzG2-J7H==Zlc(3Y)Ya9*c*!fIb@RDc zS9-K-IQ}`kpVM5MKpJYlpv0F6T+?i(%iB!EURCk5ROpEwe+&bohH}neV+q;vz!A3% z1ki<9)4^ZzDA-T27Vkf;DwMISMjvHPhR7VATQ1LxKx+?Wigl%?#NoJfg%bVMQ%Lr_4MDz7V!4nU=AT^f70fCU zsr9O3=s3;%zI`uDV{ z@GXkRH(k$P5Mpdd_em~Cb&>-(nDHOM?m#?u)?JA3;<;k*Ob@u1VSxhA%f9;$|IXGYO;RheWN?gZ(< zhBQph9ws=l&eH3_;ylr(nXXur97a{b0|e9jG==rUFZDQ$>6~=(d?ImR%JNvY|W=%rS|;3GCL@|2v|yRArFho+@Xz^)LD2J0Bdb@mSX> zvjeZz3ZmPLoQcX|6`?%ylPq0gfu&5c;iPP~SVNaHj>Fo`-qh&*b0kN1A)j6R9PMuM z9u#$19-*z2MEzX@bw_!uEAlhP>kUF_rk$*yeT#~)nrevtK99mFEzh;#K&@$0gtgXjS z^}@BEJn84-IwYHA5`Uk}rnWUb;3O(Tm36J$`#eJCuKR_)_w(Fu!R8(;#rR&zIBk4$ zx-&c-8_JEi_==pr&OF}7eCWX+Rf02zK!^-j=iAl?SQ#&dUrju(OG&sRxVhqwSjQPu z+X)9Z%G00hzHqOkrttLxwjZVp$9ls-`83b#3R@1qyQZJqSi6Vh2lGEi9W)jD(u)(nc1NsRAd}}d-W3hp!pUo%D*P=Xu9O|2Ml7i=)xg?h-nBJ&C=@cIe4 z^w!&_K%;fR@(qt^N6VMs1xq97X$On^AqG7-do;teQd4Z;9tLUT7I(3tnpAoC;)wOW z6b&mu53ebLdpeJ4r>rKhPMl?fJ=2ZKh3&&gYSIji-1P z>&3k_Lj!Lz#ZYvJpLw^oIpC__zEtGAlgO8A2qjq$zxHb@eDYoetQeiky=i+!R&C5e zb5~#Dz6H0EK`&JB9@hWk_T?t|*7pPtV!Ov^cN3hwZ6~->eoxrp>Vng=!sx)Y06|%f zhOo?*aWLiUxWl>|${zEWc5ldFIR1yv?9AE{k9XW>xA0t}VD{TC6nuD<_@2lY*4^5- zLyF#?o=*zSstBP&Lp1xc9Bz!b0^9aq5qpG+f2rcAFVeK<-PMAzQ>Ve)jXb7JS{#o* zMKOPMPbVxG$voT*j+}x|Z-J3=Hn(kK6$gI8Ygp~}H8kmSGh==pu#Z|U{>1t>p`r>)*)Wb?3< zplqJTnd2IAz1S3M{0*U6YO;cRUzCJbnRmCTA`17ERYE{WjW`SWp2T4jT|YY9NFSc5 zMk1wlJ`0)m@df7d-H@ zF<$iVRUHyEwj5WFxJ~_*_e0v-hsdt7m4h3E*rlZhRA;fz4P)+bL7ZnubIM!Wz2JUO9|f@83s6<$2#kN3y^Bzwdt!?rPzV- z7MbmRkkU5}{#@sI+M2uU@1EgIPiuZ6lk8>+2blNOHfssqdp`q=nt9y&YDbVpJkQN6 zwy5E(U-2~UgLZ+F(HS^0k;lEMSI*(%djsh$$Ghl*Y8}%3&hPy?+7$8Y)erchvOD!Oc9`H#=b21}nz;udat)7r znH5Snca$W3yU>Ufe>#K|eEGd!ynX}d-%FrQwW$RYc0}QAY(KNX-wDU(SwpkbWno~%wIRs434RHI|%>{?VU-%@;0U1^2z!T-=a6e+dxTE9aZzo)G z&xKZXyds86%UGXPF715(6tp}w;XmtjwB79oNr=$H{$bas#L?aPXE*%93zeCk6=8}k z2ZG^Z=`F74Ry8?s&kH}i=0mT3EJ7L|hr-|g`U?Ml<9;d8p3h}ivn@HLl#W$<8kl6`I$mnraw-cT@K^ZuYmN#V`AKknQ4X;6g9-& zo>O7b;C@J(`djCbW7A8poGrWcEUkfSwk&}+LC)M68P=;7dIFnm^P`rPJIRK!>B5oe z8ltoJt#Fj^G3&L<<>m)JBYUlq(5rl2AK|_$;E|IfX}Rky^88ydK6X-5Wa)2$tEO&& zxK})v+j99NHj(tF-{d_7E5oJ>xlj#J)xUHstr?%Wu7$L=*S z+_OFu1(|<8qx0cB?)8V|v6)wj&fA<%`d2CnRmW(GtnB6R#O2O#(ftY+9Nk1>FNfjS z?N@2i8b$JE@+eS(FPzu-0uqoKj_(#S{kp#s&OK6tp_)$OJdR4!0Qef}Q2X*U;-sP| z#1gEBL{}HTd>#Z6*TcBpc@4zj;x*j4#FMUkDu?uK+XMr_s^Yt!vvn_k%~nG?X>lW& zW~2$b@&Y;Qv5iEvWD|}a9ZXktI1@F`VZvsHd-G&1u!JxJ=0UbtAIT4l#J4Vb)1cS& zXkQ*X9sSg|6J}q0MB|d3U_nnrR|sI^@dMGCcI<9l9M!;4x}hXh=KH<)mBM(ACk7;yvE) zDf4j5jc__;*ERAy`a4c!IfBE#weZP;3vk|m$Gz@m=83KIqL&vv6L6+Wgs;}J*-+{M zHnh=(=d+5$xtr_3Mfg4IoC&Z`1$sSGkn!^`Idsp4bj<$@VbSt*4dW_3W2OrSH?q#9 z7$v-aatN%u?k3hg1T%L)T-Q(T)wYM^q*B*Q-@X- zNPLe27^zDS`g=g9iWQu`_J|9Se?$(g3PQ7<@pGv1lc9KSvof_!pu~J{8RnYrP@DRA zShM#GS}BMV_a56wRYA~Q*42Oc2wHhL5E42DxW03QY!-dTCz%KP{rwy;eTU#@36F2< zw>e^GWmg)%;WcsIQ-=RF-J$l0RWMs=A_Tjvqmv_kklPm)Vbw3ObnB^u`PCP`W8;bJ z{pDebtu6$@gN9pNWMnlNa@_;Vru)#K>LPS+xB{%y=o8PXd*`TvK{Y?C=KWcOpKfJy zhjlbcJ@p+sF@A{W1!9w@H^I@Sk~^YUOmhBC6P7W2n;=mRV~4rI?6b!>!M%^{rsO7+ zuu6lI?*C2p4Za5M0ov5uHIMj*aQMCh<4*t7@gtdqkowqJ+zEm)oB5j65>k2`bE!d`A<*UyEpzY{T#9WKB5S$M9|A857p; zvH@O|26GEMUz6(o3)p8yI6cAz2#%wv!auPZqHpih@e=$M3KqWPm@GnAzXl3i&vDx~ zmy@oGig+vAi)si)f{|M*8WGR$=teKR19>7Tdc-=P9IR6iYO-0?)qwRJTy+G=T%OlG zD+tADb{v&$;mSA_I4|qO^SXh5@O-c?opK`l#hy$i)Q;!jDX+PH5eY8(ybF@lKxC9k>#PC&hcx zGtX;~g^doz0uZoB-_4q;dLlYRIM9jd<41P%1Kz75ruW{N-OY zL^Y{Vc+)@`Z2DLu_AZV(7=`DJ@uOxHdN4WM4TX<=D89il()}+q_LkF?ueG4eDh_Fm zSSMPiMt`}WxszZ|PpJGGlht%SP3=Swx zL`%zCxo4q-jO=}joX4}9gDgjLJ9rL$p?8g$ysnXbJ?*%J_47o()xx`D9YB8r8$#E= zBCQkMvBPK|`u20BpjUE{@U^*y=-{XO_~u+qrn47`b>1BLLVSvGZ~qgiaOU0(L7vuM zvEMuGMjNcFk*D+DafEtJ5gOdm5QXnh!Y!+VV7$nU^Xq(1?4!0oZdVX3c)tKmxM>2% z;dA#q;0H<2Gf-KTpjh0;J zu~9Lm9DbinrUKvV1&8iMg5OOYx>v^oPF%Bqi5`!*rOhQ|X6QEj!8wBFmEAy@Qv=W& z%`9<0+u3aj*zWRhs<&1|zSca$vdasoAxeXF8xNo-YvROri?km6h7m4hbg@GqTC>#; zx))2(qB2728{4rK+g)6=%YieUOJS~}rPv29XK)GUE_J2<4!14671)aISKVzV*gqPKgfus0ohS#cWOJ1>eCPzNC)D3(l=n; z)k^O5kYe&RaEh?-j)v$#RT((!XLDHq&jX+JY=w0ngXs>Xuc+kRI^;Zo=Y(G%3N#J)~U7j1jEmg_3-&! zFxMFWn$#V($4ktEX~bw>LEEt@LT%R1F!XUceq+(Wx^Q1|tpSu|n}0!ei#aZKaXHy> zd>F1-#P+M(N5Y8lEyy92$Is#CZo{xoQnW2RpZGCc8eq6YmdIi4p386|f!8<&mxtnz zZVy^ir9{?wD#1h(o*%9m$$CN`F#YQ_>(sFx4z(kk#P{IBZvB9>%>TT)D3RprDhT6x zG(-Xa>Ecl90C@d^*ErHq7&hPINjFr;p(R_21@cWie(rCd49iM*%-qsyjGw*>qALTO ziAkcY@Dl5G?k(Mor_N1<_>kr5OWPPbr`3uxbrlXcp-hXH}?IGMc5l>@! zN=e6;Mey-v8h2$&4SA}x1LG&L)UH5TFe6M>c#84NMqid&9rYO2t*_-WCWy$$UlrJy z`9&>+c2FkmfEG{XG1Fj12MBMKQx9(~$W(|#ora6Woov-gg>cSTo38A-NzQ3+he~ID z*B9sOg14sd{IHbGP^%3J=;Q^1aItkL@*318)_G+EUZA@|NAcYv19c4yd#=%>_G{$K z=Qccy?L%f&Yhl%8r(nscP;Rr?E22E$igo7r(6uis1%{S-!eDC+(Z@&k*<^wFUfsP7?~`_=-h6|D$ z$nr<)(GskxnF7TI5n}z~#N~xBb}EmPm1k2>^b6jLMfkE_m$UT&mS&oKGdLh1{sX9g;*Xc;oOG}f;%Nqs|IxU2bPfdp+IfC}8 zCW^HTJ@z#pUooInk?QC<<9zRSR*2{2E&jIn$UW9!QZxW@Q1rJ}M2G7H>uw^W(TB za`mJUwZny>Wi)V9AgYP=g4%5o^yh0r=DlviSD4>;-H{ydc3%YAvn<7W$5)vPIDE+! zI`=K>7_X|paj1a$roV(yGya3a)$8b-<{#wo_j!1$WjsA(b~wLZ)P`?rvb^>dQ@knA z2d<9I6!XdHOWbhKd0%=mwiv1F{RgV@eTB0>_L7Vz^02-snM+$*ONLd<$0z3`&;aFF zw5PC5oMACm3dGCVycDOlFzhV)={}GiDt#T)59Ua}^((NQTNmyk(F-J!7$p%sDYZxZowr zaadX5ziow}QJE{&KIXOhBArU!50eza_&mG!F{pkQS+Hv*-220GNP`}091|KybryLG zCDx<2y$PYg6NU%lM3r7)R}2kFW{ zPObel(K~H~Ppx3H?L8N=PIri~dzhx^Pv&l%n4SbZ{@I+lZWUQNDHL1o@S(fCpQDA5 zBawbK&nF4n{az@Jrx#7iNX0)L=4DOe6i3&PGX`t0L321=XDKge8#_cO^-V(*bR-Jz zQ!j=j=UQ%Hx`=#OUWP|qDWGNx?SOReLkkx_6yF}&n))6R)q2GZZAaa$j}X{pF=j_@4#4(O|4Y77NSR4aEZLi3Z_Ykse55 zLL0Z~DIv3`S0OzuM@}QUh3FLC3f6yKj&~lmr{MXL6uOTWetp6;#05+6$?inx-5VkH3hsWV4zsnqC|Ef_ z*V!1<^oj37+awhWZfOSej$GZtz{vgJu;>QYIJla`ojQ)ko(-eR);>f@TT9W3K`+I+ z$std9oM9(TyS}Fomv^_(lZiYYKI@NxdCYqcDe7p}T{mz($K&Dn>4&gKG|P;zcg3Yo zJHWl$no}zM$UOP7m@a2|ggiqsooXW00$w-qofZM_20W>OzF)zWl>zW3SBGXy@PPhp zTcD_gpQ&fwUX8u&!>Q7`bd&|&XkHq>Ka8sX4^O(JLR(iCkrOeMSi`x9x}CWR@mqzc zb^||O2fc2C=O&eOZ)_+sKg@cD3ni%G-a>Neh#t&3X({$#&pdYyKXG@XGoHUC7QTPc z!I|r+t>7oIIjfB~9!{iH>bCh4+TY{h^I562z!bMAd4cMzOzzZGc3skGFl@2v6Z=@s zOdA5%J9(^|G(rnUj!B@jJqC5Zevc2%WViPI24JhABshDqQtV^N@E$K*#yk)Dk!6ry za|wR^J;vSk_(*mw(M8c?HN-makU5?(`IENz_C!W|HZBfj8RrIdteG|&Hg)hiZ^BAT zEb+ykP7OCFcR!C62C^O0B26ong<`iw+H<*!dC$nnD0kEv&Cknwjr(A-SuC9-l}n!D z74T<5h?wt<$hW}(PeQ21d_Td*{ISB*Yz8+DO2efFwcqWW_gO8gIYk9-L*M@63IBhAYlO8&6*YI;PHlDuxwg5molS) z{Mr?a(HhnnWik{MD1kg*9RO=$>nRq%UhU1pWVrfOI37p|l*2n9n$H zunW=2mk~Z^_cdy-?8ZA6B*66op5s~m2*h-|H*Kn|LzXVGXiz%8_dBf-2y@?i(ump& z7AKnvY9x(YtzSdBFB;;)`Y>9&OHL4&DI@&BIR71sDE2?6a5S`*lUEXv{@^EA?QjuQ zIdKLulh>i+BOi)8d0N=r-jtv0eiQc%a>C*2vi6C|Z7&9FE z{|?Z%#u1O5=R@t!=#f_z=g;&JR@<77PaSp>D$ zjU;EZ8?ipi#N{Pxu|8WH82KQSyL9{&$#-zZmzXy`S*u1Mzh|D%=rqe?p1+UJUK|aZ zPVqayOkozj63gBx3sYJ5Sdt(*y`Nl+Iz}pkUx96^0-YAcH0!Bjg?B!)o8a@5@Q(3i|$VbO`GMf434T6}y6mNP>=JIURZPMy$fJEp{_`qy;I_d5^az3&N4KrI$m!J4aCg`)<&|f|24K`!B*v-H_da=~K z-ztBcY9nr6%x-^Zn&Pi4qdi13lbf-xnsn#OfNVUEV{h4Wb%{M!CU+9xyqgsB6{U#1 zc`{8iaVFap+}$0Ga%39uN-frF_c;K^)W(B)M5Wm0Y&UwWaM4>0(d)})aLMvK^i8qj z+|PX^QEu~4e1SSQ;$JuU+ISWEPR^x&7TqU3+F97yhxOH$spF{4vq0(#uXjXr?ZYyI z*!}1%b7CexR#?t3O@53O_TKyuRyXBx2GP$*)b1-N>-Z%u*sPUoJoOL$w8zrlF}Xx` zWEOU`XFIoPCiu)dA(#&h;mj|+CN4j0v5R#W`@Q@HV?T}&YO}udW5?5RfqV;Weamw> zzk}t7Y~#7ysNg>6Hj1Zl`&2%8MK-cEgJtfD?Cyz>MfT=Ix+9wm<-e%p&)NVSRe+;eX|K~dg|e*U`@jE9TR z!WBH${bId)mrx{~5gbWS=nK4Vo2E!NR10U5gV4+Ri2gs%hKzT^xke$hX7Ou5WuKPN z_$=$m-+CYKuJDAfzddQu;c^JH7y&IwMciBYQWB7N11n{*`vQ8YkZT?zxRB8!);{F_ zK8M&E1^V?KB`z(agjVctQa@h_%Ut(@9ZTKC{4L&QAt>8)iSx)=@i*|vYnr0;qF%_V zlVjgwhqxz4AygiR%jwa3mtx64#wa0WIh`-A9XgR2{_(n|jtqLn9)Dx$nOX_dF+^_+6hv@NHer>Y8Mx4VN@jt+e@$OFvIuL8|6 zkGWKpN2F!55Es^k(FE%>bVb1(?YH4E&}Zu)d~NLrs;5*;))qX$dBR83J1i4Y4^Kpa zfpMIteLcCIQx3C#mebtbLCEcf6BJC5q^n8`iBaAQJp4H8z%k8%5n6L$CFS{>rPLWb z;tSi8A896)+!H*}@DZ)p-3)IoR-maX*3-m|Kgr@UPk8)`$3tt!NjN_$nns51&%fsI z0{1abj+}}q?p@{vvaA>S|9iiW%cQ|uufK5GzCPlq(2IHprHH*Q69&z|l}d?}+>1r# z_Al@WcIQa5IRL+wjfMTUE5-S^X@#SNoh*Y)EXv@&DGp%2(vCB=`ABZ-OhIS7)y4N~ zHpRKXk{LR*Xix!}W|M~dm|tjhvN~?tKOKfjxrj4yk9*BA)d{4FmRpd`Q$`BYTUqw1 z!xD$@$%BEVx5d1!(D4*Xe8v0sx-Nc!|CsLc^hz%A&`rbJS&vQ8I1_yH*AhsY%VS`3 z{XXpB9YW)Zd_G`>t-E;^ZIV$Oq}0dKRk7pH{F#n zoMgqnN2P9GI2+ch`Rl6$1Z?GXkk#}JTs|6Hk6y|wL z*i;XnJ*K0PY;OJkE%MR`4(iRHP^Wrr@N95HqyAgMS-Wpho!a8-fKbUuyi?hLT>c+_UJFkOWZGC_SZR2&2WKZAZ;%j@NUyB(LQh6t z1UiL!@D>hULwNqLNS^_uOPS*k4dV9omD?qD>d!vauvh>0lY{;oXq? z&wyF?Dv{Tp*|72xk9+@lp2Qx=gYGPACPtC7g*j2|y|xqMs`7hi&QcTl_vdf&S=j|X zjP#-tR2*SW-Z(sYdkjtXu*@Ght{Yadyhg&7^RVK93w*Z8i6G?@z+h4kyqA=~yJQH44-xS8<`Aib&N?Cw$&AkWRAG zh6_{eVb>cw@$SyBdld34QRh6GyGcWQBKBb!TfIYEv3*Oh)Ue^K{pW^6)pxb1qZKBvacTtV` z`b7G0(16D}(@+cic6BISu-8xU5P`Gvbb-h4a^a`i8C7V zyL>R%c~hyl;pAydEz)`NMck!uIjIM|vf=sO3gbp7u+XI;Gtx=nxL#b!_NWJ3bgjUB(PWudiAPUK~*4YG?Hj{k5y$%Z&Z>u2MfKI5-sAWrH}0 zx37u5=sV~d7}C@ETI8VOKTIcRio&&a;{i98KYEtUjeAi^R62cdgNF}w9{wB!8y5=9 z`gt#(#W>a_dMAxbZ(}{Be|oUIBHP1Hj>5My^T7Ok9j9@W>2aVb)Ow^Ls-0U8+yNzI zE#NUtF~kYI9lV6wb*zh=jZA^bXS8Vwxk)S^euu+gNGEuWhNsyEu&kTscn8j%#Xov| z>C_zyiOFzHVQv`9{q3{CK33XDsm-@kqKJuCDZl9k>CO=XU_OW;LiM++Q zWMw2szvMBk>fc3l=+<1B_SgT;T&qf#?aD$WWt0G^onBoTZ*)emz zgLX#eqooZm3a1DL$a3F_Sbh9NdN`nr%yjlg8e#$!U`uF@jPo0?}=Rnp0syu9kE^hLLhyc*CS?bxC^=Y zPif_&+JZ^z5X>;-`CC^C#>Qu3Xi8`%nzF(fmACL(t;-8ZthZ8?whk*HG)BW#NrkEJD(s9Kn9e%L}MSa>#*3pA}J zgXlS&bI*^uc$J`UE&V7(t6!`&TzB|{cFjxS`V4Ey!C~XD#qI?9=tB(hD|(7A7_uHq z8i4!MuYqHGrTC`6UV0JlKOR8i=V-yTeaB(N9iFGT)~cdMe|fDTrritP*BDc;idy3N zAs**?u$vUV>UiM7B*@cr5ogN0Qg&cljUYPGbq~4xP(}E;K|`b%Z;4~tZiC1E+hXs^ zt;)T~sDj_WO?%%2I%ndk@!UJ)PMKGJ_@e%ai~O<$F5>_ zyE(;4hJM2ZWb>?lID_%DzL&CijHNZ}Ds>Zk^S(xT;oXb8=+!OCs%_o4c^ z3Ml^DazWK$9=nFLE(LqbeRSF!=AYam3z-^0V!z5h*>*6}H>8ilw8&JwZfwu`>h(wM z#zz#x!KNphJNmwoAWLujYP>JqSoj=i4@(q0ZsNPPQnE84{Z1|2tt3z12g43_3lcQ= zxwWq4EV9yF!kxX=MS}9;A<0LZ=7??*nQ9D*U9Md4Kof~fvd0f~{HWx`g=A;sOkrv= z>--nm;13C^sE&0Mj5|n3i(Lj6Mn?y}5rjL>6oz?gh+;ePu=_7*Sk+O))lDlUk~kVyG9CPqTq+cW z1PPYM^pI#{8{(h%1WG0jqv}(N$eshr!ZU-JX7NH1C&;_OsZ4iv=c|ddmQID8w!EgW zT|XM{XS1zWP%miKO2X5g9o+o49i%fs25;M@Pwh6xk$oGLh4hPts6BEq?vcI*pPD1M z&ViTY*W{z9^&9U){`2NFoPL@}Be%~h*ch`0{`lSCeBM?OBZ>P+|I$mb@2<6GJibjP zQVpGQvTe6Jnmdcq308w*WQ=tb*XTHe$Wt>=+MR``DAN z_)$k@7vB?Dzu>cAPBDw1UdVGT39DsT=Y9-*P?CvMvM-}k%~|3u>kSeTcyNX)wK`Hl zq|;^!Pv@|`qJ$a_kE|B--i+gPz3Pcv5OH$`OtiG( zj&y$}{|t}ftX5BItKLTR0@*Xe_|?@x7*C*Ak)M+Z9klchvFJPq$|Ar}3rpe)OSA2};QMhyIHC3$0f4 z5sUY4(Z-=EoU|E%Abphey71VgJ$5h(tmnCwdAuW}y*H!~T18gNMd1Eq_WANr$Hw|&;MhbLv4_Nc z#}>R|Uoh>NzK_%uC<-%K-Zsb463_R~f=QQdbAKG3kuia*(3kH#?+S=b2B}e(X_UV& z=`6j5)f3q}@y90o=9o65UkKs;3w=%Q-r9;~975=Z!@h#)u8P7xOnYq~l8&th)xn;& zm)!RPjI_YzNw ztA{F|g;cle2FYCi13#FfDe76Hg9l|h!g-GIF6Jd(mEeKr4Dq3x?G%vJ=_vwBZ@wSE zZ1_CrW_z|Z$NCAHItW74dEQl>ISKCw5~yK)ZHxY;-OJOl5MoQ^l2J ze!T~lWFE`Frg}8G-A(YfjmNG#jfvn_Sxeo<$P`+i9|gggX`DfBH5tAH;iHK8QFT-W zk_$RbEu1g^sT@M8DeW;Fn~DV6?(RZvXfSV()ScEj3xf zx!vj_D_OSDE0)Kug?a+;pUk>RS?6kp?gBFUtGJ2)g)?*d(D+BZb}+td zE>_v%K;H{r5xY0Tgx$Xwo;xqbU9F+;T{V&$tJXjc28WPv3RN8B)T@boOC2#M4QbL#a*dC ztZP6fJ(0c>cpWi_mQ~9yW=t|mQ~5E zCxIiv1&9=X5gXGY_;UbtqfMmvojk>y6y zg&9mQ&goOdaj`cACe?AA``votQEUZCok6tDb2~b9`4AX=k)$VCj`%t2et&R<-2)n$ z1ES4Sp~uuptaXaE+2VrP-qca;BiTD?y6}F6hN!*+u-=^gD8|l&N>2Mj{z#gFgQ6EL z|8p7Eu29A2$0k#gz9aed8pZhe?*HFJ-i}wBodp%oOfFNSn#_Oj2l<8!6pnk-N9Nhq zqp6Z9+~ChOWXRPKSZ#F@^-GCE%f=MrT?`NXk^=CfH9;_BW|jEv^I^eRtn)I68Whik z$??{pIQh7ESLS)^kKn{G4YA+jiE1n?in&Z@It?l8RSv=O?74z4b-a9=8myhi1V2wN+)e)0c(vwO5OGWz!l%U{$XSy_jA=Mu&9Z zGKS~P*=&AHvVg+NZes7pXc;$5?7V1-o-$E4zkzNH>)@ic7m!z|1({!P;@&AVlMinz zAh}wHn(j&?$Ba90)pF+RHq^m?N-jd`Gk#aL|EN0-WjOY7qXMdR>R%RdOO106=^;YD zsW9X8e!A7DpR|-ozz=;M$5gM*!Oy<2yue8}vUAZFe3tD)4BwdJjwgYzWn>QbG`o_x z|6_f^a=z4F_#7EFY!;}>pXa_7wh|+?t&rssOeMndNMNW6Ty03>9ILB|<>0xjUpJB( ze^L+#M}EN{nHD_xeI#BKl?hJ<>bSG^BBGx(MX1BFY>l}L$L_=k#!h_5$!b@SHBYyK z-k=bAaEAn}vam!&!0*bkuZIDb&12f5xr-re<`uCvs{h6oD~$7_S4J)*r$OMNLtRu@)XN)dW-~hj9b5 zUlG~V6SzDokY03rE^x4&A{>Zdd@MZ=?=|j3?SG5Jcbvx^9)_p4CeT${lVP%jmq0`Q zuef7>*!U8tD;P%U!y?jdrXXx&JUJ#^k=;LWhS)k@BglHA3T;`u|82Ha5MKS5&8JSi zp!A^|h02(TcV+t9=HQYt2P(Moiqx-So^z%zs~=d5Z+HcRtwyAnkC~NQBN6NIc3gM{ z_NlBxreAn`Q*!wO`R~f;{<%8}NV*VQZr zWjPV9v_|tc@qXYGS_TKMBvIY(UI_2C0*hT0oZ_}(5^eJZA2MZokF^D0SHBz{tg;pF z%3{a4vGiIKK*F`<(4) z;+Va#YK#>9Uc(V1)k*O47SGul<8ATCKfZL$!~T6$Z(M(4_gdz@?@FP18%^Zj7%bi)0J2BK!N?3=P2hnSXewauru$T0}H& z9LMtq1=8K8wIHqg04!g4oaK2`QRQ^c=p~RDkcn>T@c5?Q7z{?=`Tdw>S3541 z(iF8Flf|~-yFr2FzT3>2NJromywJ^yDjO)1jrUlumlBU}Z`+#CSU+A1C`_+{=e>)l znf6VxYoHxx$+6Fcj1C^!egU@C@%Z+x%MBO*_NKZ^70{Wj50)*eQsds0_mHZoBjK5p zCH?oJpNu;F7acX{wSb)-8o1l|8V${MBl)Ty@N_mG*Yis1r!w! zsriObIFof$TCD=1Q7Cdc;>cZaY#|W~lVR#T1Dcv@K)&u~-Apblcez*#hsLdgng4}x zm)PBEjT=YttEYi9H}1J$@4Jb@7$25vIGKlEIJP0Fg~i-N!%`A6F&V5`XX$7mMTg?u z1euN9#mpN zs>K{6734{~HO|24+GS`J(*^EoydgLAzQEhjWwd{_X~EvyWe}Zkg9}ZpBGm^s;*%=Z z*uBC6v~z1F+Q#P4|L@R(b4Oy$mPz#P^%^fw8LZ47Ahr=j`dS3JN@EJt4wxgCcMKL)Z1ncQA! z)@>zahu_CB-~0M<*hewc>$eJF=ni4Ec%TKtZqs6L6`p}m!Dg}#;L^zUuf<=>i&8k1Lx zbN!~7zR+(vh(=2i@~*uZ`&nv=MnuYD9Tig;mCf_FaCs-(>+MPB3{xWB-Tp`&cW{lz z8Goy;LpyKs`~Q~sV(3rRr^{YlCvx7+_!#4X)uVNAgONSNjJzhELoemJ;Pb9Nv?M?Q zr8pj4HYI?cL$mYb;7Gb9z2GrG&b5C>e#?Wn+LG5qMtTO`KQe+AY;`B}OcQ>)NK=#( zXO4AqSQqfZ9L~|ZlGJEEUiLVH$25({r*y(RTQ;r%CMfW>cz~+~eGqkY3(<+#*AI2fpWpU)qVf>BFo6tT?oixBm}os&;^Ph#@rV9K7qTuD_S*&7=RVL1kLm%?yJbNh_uk1-Sb*7{iY z=BVXo>9UMhcq^gUt$S%^-$h*Z=3xhO8!Bx?fYYeNq9G3|j^*$85!3 z4%s`-_`eU{bneL)B=qq6WoPg39muL_A3#ooL=id$r1#wvFm`w>&T73rF&meRjiZx) zW}yvVZO}2bY;gvmv5IwqpBqI(d`roM=<&jp%)9a_R23^1NC<-8@;H`PU;<0lOHs3a zjtq&qgX_aJMX8P1a4u{#^tbX_faTg1c)Eu@)zT{?ddv&GhEbHA22c7qmrAqIxjINM3 z0nHF+a?bd99==WSqlRS)Le&`wu=0&L9j9*w$MIQi#TIT3y|l*y{bo5oF^Al6WSunM zoaxW~l5S|dVI~Aa^Tjxplr#$T4)r4c^5razqS@2%nM84iCaxX=?TFxHypvpG|sc3CfUUL z@5(9oy$D(n&KYySc%ARcpb?$RKt?c$$w9`A3 zX8j(GpQN4xCet~d*081$uF2)*&?YzlDy&@TkN)5ILE$?vYzsGsYLA$NMzGsJ zl{7rk7uEw+4D!q#;(y zCebZ5IB)D!M7Ce1#udEe45x%`tga3=oQ+=DCLG5SW zrjyz2)xX&@ZjA*%cT7m`=kNHSQXn*tpF`)c+?Y{4v*0+E-}29k8@i79Z*E4=fIo|{ zl^XLUGEC#|{|{Y?y=*%6=WEiFFTk!H{-BX{JpH>V_!cz?m%Am=RFfp^cl{Pp^sDHK*>wb~8n~ShE;=4@&Womagc_HbwMh_i=brIY7L-JP|h(#*XhNSrJ0~ zZ3pX@H{!6%qFai8aip%OMP(5(`49?Y4#bnZwnqG1=8w7>|JaB;7t zT+s#ixGsoZHdhn8RxpBH6&%+(Yi)^)#$BW`9fiQPHXAJPZ4&2X2IwlIfpHUQ$mj~( zDl!6kZ_-F~`7^A#+75oYTS0QS731{gR&;YW(@PZv(BPFZ%q-(($z2Q2qMt0QS;L|c zzkgtEn%ThlE{?CMfmtnV)Lm+h~cdw}YfP97a98 z{uwG~kD*%GrTExn4gMOYGaNakioD9VnBM!DOj?S}FzBIw7oFZh6>27eXvN^RN*QGBQ}Z&$7@1>1k(p*P3EB7e+9o-8(9{VQ}-{Afa%3sD1&7w-#HwCDD;Oq>o~kJ@0H?*s4+dw zo#jTPY=jSz_LD;s-eH|}_ju`}XNWs2ItRm`ilsl5Kd2~_c_Rna)}15!Z*}0W-b+wb zZ!|6GamCNyOYyVVOti4o6`9P;fcxLwA)Dv2S#pOw@KE&<=fZh*Ux0p6!SpYQ$7;_t zVU|xc@zra==JhL4=IcZnBOk--cq+xe$2=Q{L$9DizaK;TxrrR=BiLZ;TA&~x;%*?J zY!a|juqIwrUvQXN5DdtWrafyg?k{ge8H`VE@sdMh?bkx(ryQs1TX`0xXN1xd-gn>nCwH<^2~IU_A5kEeCD2C$P=I|yucrFSBk&Mz4ZeOadQMk^l} zv+X6g<`zjlvM!`stH&d|x$!i8Rsi1K_8gh9dH+v$@{yn7;&k{+F92-_D(c7D^@2tCL3Y?CPJRE~b%Q z%#TL_x6-g(qefk(LD&c*r~xkUrjoOxFC4r;PK3 z_8aF?DZQJxV#-YDvWMMVuzlsvdt1=naTlnxn+bMJ8^bqaw{^?x{zH8Vw+om5AFm## zp8?CFIlOxM_bXhMn?!}jldxjvH53)WH00s4(19)lSKG!Cm2XY>mGxFM>-Yugd%K>e z6)}eYnf)$Q7v4jfD+-HJ4|G#e`#e0}r5FS*FDA$5mEz3}-{GVW$@Cq&k?MPUlDG9N z$H(-)=fiz>6zRzLV*D;tlArR=596qa?(8`Xqtye*kEnLM@xOi$v7(>6y(+}B-P^!E z4{m;}J}t@bWzYYIKgMWB1Iv!iizhN8ns89TNRZqYMvkv)!*73-!@$;ZS}Erwm^XSh z1O?Z~fdkdJ@wPRJDNmwP%pQSd*E4}uNR!wYcHJyQk&90J(QyO+~M*&HCACVB18NZnT4&8H>Jt zfL)qn>GSbr7-f&)moZ<#6jxRB;?JqVoQWw!a%=-$US$pkswC;hOB9cl$U*!ZU6D&k zF7!21hK`QgiGun^taxb)S}t>eUT*w?E7>z}k39owM*RxQgW#>I_c=rsda=<}v1#^@u>f*zanLTQ&J%_z+JC zljMJ4-+S|>Qn=Q4J%kevi1mMc$2i^-mLKvj3w`C>b5MOk0L!WxB@B8!6wYBCtp7Y? zZSJN>@lP~ud*q78eUspKFz@K!5?6GsKN)sS&KKiYsm43r7G*DS7Mwn19@gAwVz7i| z0<1+ypXov+ei1xcAi?*L(iMdqzk<4MQ%EN^i?#jv8)t#6L{9r!XCDnbL##<5>R~?W zbMXBSX?lod##V26h9uejso#D%G+wX*ev$Ae@4P$kk5`_klRX20KpAfvwH8eN&gFsZ zkraZ6muJaJ+gEsS=L5KRqAA^7coRDfd4@`u=3w^H5NT-dgs(vyS<~N$cgy>sE2gnD z?1?HEvwU(<{Qr5>_&bk*ORFoL9{vZP)O-&5_i-5Y(|H{7ydF>IhXi1){#rD!R#&9$ z=8W8C`@uC)+&p+k#S5)#4X5uWHUbU1fTECYZZFCA?E_WP*<@~Z4W2Vs6W#Pnq?er@{22r6#kDzO1X2ul`$sbo^kbLZx~i*L|sDju;=b+ z&>@iHPM-%iqNn>V(EYbfu-a@j{@m6Xq9+Fbp&f1gMI+{RlC(Dh>{opdtWDss=%w~Y z=y)cX&RCp`T~)KtAvQ;7{Lx1nT1_F#8Wd~wYKCs;?&4Vb@nkEncf1<^2g_kI(Y}ZL zPDtX*&fV0gW*$y;B96!9>b=u(wl@ey7Da zKtqDReHPm>Em1^sLiWQR-2n2^za1+ob%9mA{iH^R;N`~8LG2+Yv7f*AST8)SU_s@= za&VBc1iw^=d1F2qqmIBpcqEtOS9bA(JafHp@;j~#AFB~U6}<|&bd8fh^|UT@mCqrg zX*J&A)eGyCEok4EgTQ2e8d!UEO)F^mTLG~puuxT3%8 z2J_!d`iLo`;qhY5Q_=co0xI5~N{{hwgPV;TLG6-UaYuvO=QnVs%UC+ku?!cn&-pg{ zoXr=iBAv{eMK!W1#OG%{UX#d!hTW2M;eCoXd{=~&;ms?EB4STE`by3Oh!xgB9oi(cAbA-w5#Ijo!oEUEbSz9GbKT&^!et zq2de)m>kN@cMpGlg*y!`sPSkuod5n8vesm~=?kvNbu+u6UYJi7X;)#p+;U$3d~VNJ zc1{U8KH&7IEc_Mz1{Sn()?(hVs9&g?@$j_mSCA#a@YSwn;>+gc_gQ1Woj^k73@gVq zYT>}3Wx2RFp)~spJatxv`mGUS*STNeHyI0-x2X+(5G$C~$FgWvc3^CC0%^YwqgPZ_ z@WoTcVBk4-Ul|l$0E9K1#=hjW5I%KTN>A!P!26ne;49`U_Izgp?XS7QM8q(sp%G_q zJ&X7UqUi0O(O~HDsG`bS-0U`N%ynQ|<4V7K{=q))s=%nwNb#MxdAu5$isF3Yk=(UJ81k;3lzWQswwKEM>ujgCY@iO#EjJOoU&CeO zE=ZjU%r0LM|(Et=TKMWh=|KR7}B@R;j2lRaf-vhd%m!(iql;a2izLo6Tt0%2+yYUn>vC zDf1)A4AH|c1?WYR2M!GHrepf&;Q_-NAZS6c_@2mfIrHWPr%}gK6X6Ws-8^TrezC9q zP{IwUv}Y96a(#sN+6|%rUJCOimv2uPkx2Dx{e#NMsU2zg|Gbt0X&ssf)FG04*$ zOe4DW&+q_m34EpUgiJkEj5pa=Ar+?4ZEh@rfxWZgE8E@TjNF^cjw8EIVe~;$6P|oU zUJz8t-A+0u$-~jTCE`rTk*74#!+=z})8;l9E#(NBPH?lEc2x&_6FZiDR%Q5yNSXih z%M4N0VpU|&K0)wkP72AH)qqdTT>$x=9OvO}OGW1i^GD_9!uj{)Vdyaqb99ERM<-G) zPy_!SoO_G?9p;%C91fA3PmN&4Vh(ezYQBQRB83LL-BGx8VJb>H&vqF$4ya((I#}O- zlX%rucD)`bxSCc(k^G#%U7dpT6W&9|@iZWQubw-s!%Ejl)uDi~MB}r=N

    %}|nHG?!??!&F; z4@0j4q0k6y_|QdusR{5n#k=5E1$WswPMmBq5L*($y1(rK=oCiyvMd|@jbpH@#klXpZC|syUjBX9!^Tm#!s<~+!1u@L^#zqc@A9E=Lt+6 zaF{d8={0!9=C7A$YH$R9EYcm3PJ@oA@RC6pdT6gJiaHjLeq6o;&ku4Mc$>uu6y6&_ z*S}o=*};!sq7~> z?M~?Rix?`M)51HfrzGz7vS}?q0{d$?lwnTBz&!k5ej1o#RV?-={3mFJUeT#k&uapl zX1boR}PH!;vu) zpywBE=Gy~|8O{CnazWmw%nXG zVQ(2qIL$PWf+84yS`St(+b#B1)eIa)vk!#R{u9l3PycekoMLXylKCS8SO4aG?9!>~ zD0_J-9r&3Cr1jQ<^|{<^6&%EkrI(_>fRhb@W7E=*TsyublnG+YC{0t#`Qk3HWd5iMc3v}8>LvSe)zO=qjguRp9q^HeW$1hZT$wNm(Fp$$A7&f&?! z`)0i9kGR}L{aem(0qd69uca)6*L%QS%H0*3HN1t(HdxSMa%%Xt^*6*ed!j?fTv68O zIQWy7Pm=2^aintuufWht+!eK`Qx@u_L=(TxX1w>S5po%FiK+}n@N&z)BD2xDqBf%| zs0QAHlUFyB_)7#Il4|C4-siMvi(x)s(@AS_C+R1N!|-hAFlu^*;O?i7&`zd>9^uQO zAEq-;y!J#fn#OhnA=91Fq1IEdCq9qx<~+q$3yvUzZ5Qb0 z-7TQU)QHT*uSYr+(Q~`uLRNzxp}I8<}J7)D}Y`K zmlgh}r3t+XIBt`_$QGSyiKH%5OmY1~1%5Qs-((8hQSt2Og3rr4NhjM^?mTJ*mI}H3 z+VJ;jaNk5P>JWFD^*vogHoi6&pKLx;C2jE^p!)+*aV1GEYcn zVF7X;XvYE9yJ?{Ee7t$)MbN=;=HIQfsarK<$DLF%QXBR-ZsPT-{KRW(cVLsgOc?TY z6#dL{|5io!pgrta)lg7G&9AmW=dB#Kk+!B_f!P4rY)0^n+G1e%fWw&|Qd3bl^J9F^ z9l*MWd(dO15B$7nj9j03!#S<-WL|tDPJbK6J2siqs3k-iaJpoUSlh9VT!i8!lPS=6 z1a=*|1Wsu+i?tnKDT_?>C(%ji6(5iG+!p-pu8-h(EvHc%ZW{s@tCWhlO@H=i zYkYNzZfjK6ddfslRnANBR7P2*>{3e7@h>pkwep*c+kn%Up!k)2K&&&z31uu zHL5tstd6(o6L-t}=AIMWIWwBd=G(&1*c4Fkmcyv%r{7`I;UIcXQ&RXNfuI_u6Rrt2 zL|ujJpmH!bXWi{Mik>oGqVig0VDxgfAi09`GU-e+17FPCXi@hcy#BovJk2uh-aGif zD}DLkdIq;IYx5Y6t`#LxI4KAhWC>Bl{(tWRXSCq;F*uuW{KtR)UbH#(Jbiqj5o{Mk z2-c=?TJ#x9FYq)knqGc=A8)mAfRP%}w7V-025qPYOUGo3c~M)gB1$MpqixzMyp%8@ zy0n4i4%x?}d>jR}_BN1FmqhqrZ;N2op&~LiyaIcCk^z^Ob6T{!Pa-rZ^P;1V{KYZz z#=wJDe97X{4s5q=6>^yqMbUm!d}g&ge=+l8ypMKA{>jp~VH&6ZD1Kf9E);RR=y_QJ zOf>MK$=Rpzq34mv{|5UvROllVqX#eD;&{=RJFC&UM%FFmOH+Kz2$>?}oz4jg-oHwn7X zFgAOhmrz6lU$?^k{{qN9%XS>k^x3rM1LPXZ{13Q^!H=gLURfQOh8(9v(z78$gg27A zkm~~0a~H_;pL=KE#&HS6zoZctnjYeP9~myru9>vk0qQP@W*W;xfz%H*xLqTMSbA3D ztIhM!xz|bbLkr8WQH%wTL`~v+!koD>DA0Qn?fh7QGcO18)*Gdh4Apwv<8Ke$-$c^y zDxTn)g(0kpd?NNQtrZE8eIV1NFBCzkhAGf3n&V6FeD)&EwDZ*LXAAaUmM&O%kJEp; zPxb+&(WPQ9df*uabdufn7WL+VqS?zp>Prs0>>TQ$)9i6{#w&(h+vNG@hOs=WK^3Gs zwn)%BDTOrXFfCec60}YqO4o#n@LZ^Xg0)#z?Kxd&sXi1w{myC8tt)L%W)Pg#&){DcgIUV~zZhIzK9#)5MK8{2y10OlO`tRr{9=bP!9DCD;%e7X(?hT=I-3?WtAoMNR_>j|_ zuTGwYjFjT2`@0=DKB5Z+>*BRN}oO*Yi%W-PynW{vq9U@SJ@V zJ^eQWFAEBdvQBENn{se>-U(oJ%9;dre8JCSc0td~VYK-+!NUuLXuTK9-k&aqPHixS zDf9iwBGiFjf&HlPMg)C-K@DrsQr>BqPvUIqd-EKi)F_tk7h(%%u?~YB?VQit_rO(H zcxee$*m)P5WDAkbK@PiQv+UuG9dYDJVk2&sI)p}SjHLN~NAD*UlCll zccVQ+{^B7XmhgpAG!1za3WM^lgC_-?Uer+i05!3@lAV7xqOX|;Vc_jN@^$!Ae67p_ z;q&aS|78;x(R5wVz_O|T`7mV@&8=9$^#dr%EF z^_E9deKV*`iYo6>;RE!5?GvMx#-mf`Bj7!o2I99_gcsHCMp^SO(5j~kpyg6%LzMJCX7b5FBx^c1J^CJMl(l7({&y^{QRXH ze>J<4>N)0)&KPOq3mToI?u7sg_vo<(O%A(4=3uBrQz(TgI7%%XeW4uJI=O5*3@?l& zADWx6?Y-6L_lP+9_`est4;6BJ;S1)6_bosk8r~pwb+I^Sb*c7eI3vG|wij5yK+n~@ zRpuPOI#ZSevhb z9?8DT}?Tjb2}N@ce(GSNB>$AJW~c0~Rd@!m4+=;@g@d~5h< zn53LTDmGPP&jBOk4AZDyXDJ{vqrfShX0b-CkEBqzoDN;J=Lz0uzKZ9jnoev#KEq9C z^x>8yj#FLx{s0}0(iNHev)tU2NpRLjj#FjpdLZrD5i~ia6-z&OD3A#aAzoc=_}SVn z@M<>4sS=1LRP4DFRaYJ-PJJJCf z-*Ev)JzYy%iu-Y*$|pFjwvyk0@cp~v8JZ5aB>vb+jLMxY$+?QpcH znlyHca8<`!WM#|tcNHb@1ovnF^Cs_R&ORD`#Koi&Kd=7IvthaS%X1%K z#pLxn(-BHy>?h-|4F*@o4JtFxbp6$IMKG z@%dqVA=74u*ww-ErZHIeR1slB5AO_m%}Xoew4*_E3Hm$mj=kL7~g&mBhb+tS^uyYvyS^o^tm(}jf)3Oj3t8w`AWk3t8tKw$80F8VY zUCC)m*DP3mtiYVkH?o2@T{^HSKbGj;Yr@kaSD@o4j^@R@;3aGs#3L5PQRRfn_vk;ZY<}u2srIJx+5OiP9IH&^GmS3>?`EIp6xE%6_DIQ zCs-2|K%5q}Cfp2Yh=8rf8Omvs~(?C&QJ@17C8$5lkKhf%<1oqt=;P z38ij~qZTX5@zJBh_|o!Bn<`a7r#mI_3G)>4*RcWT*DAx-=~8saLYDQXoebxOnNzoo zmEenNKgb`sL%bK0{ks$`s*Yy97iXE%gR_rAvX|*&|J@R6)KYR!z?bVB|M{fyjc01bxc%xIFy77@NW94; zedp?M&9v9>bbmR$S?~xLuwJVCOVwm$o(RwX+ktK{%*njYW;ZWB^qqW=q|Sba{W_Sx z?%E8}UD=2KZX645$oSI6R(auMTnkz%ILztRnT)2!UZUGRy5m<*UZ9gUtd~>L6?HU) zLFK}H67r-HE3PJ^##9JGqOLSF*hE#9$!N&+(i(n1_@YKh*IwM7tg@gN8NS zTy`;P8@kdQLFW`Jf{4gK!NON+#CXUcuG~457x>PN@{<2zs+tH~$~l|~GR{RoA?&{9 z-9{vJz#Tp<%_C`@RoIPbF)v3%)9>U3IN9+=aMOjumX|N4Kt1(ndZI25F1&jiY-Tgp zd6sK&;)^6|v1YfHwyM0>>bYp0hpwnmFP_!b2E(>+j>Cjbl;+=@rz`ql!v6Iy^s&%} z(~IVuuHr=qx&7DBV3t|>GLW_>%L%)_$-|5eUs6-wf!7L_poACEbPoV{Tb~rajNM2+ zo8yj3MQd=_iB7U}A;$Up6v57Nj>9MvN5XoUV5;dGgx6$g!%rm~Zm6GLjpk)0(G?Hg z@t$@_@sBc3=I-SM=$grTaPCMk@zyNGyUHVBt$Z+5TOBl zkET64N^scJHnf9zM}Jf(po_Na;JAzcVy@qgZJ2AqN^_8yR1&Q5J`z5h&hkHxt%Rv& zIY2{UgLvnDxO@^iReFi~50@2&Dz~9$Y+mE9G)4<#4?}s&1fqSu5s&b;G5sJLF7^Ud zJIKNjGjm9vT{X^?)J5}|W))ZV82s%E1-a%NhA5ntKo6EqrqAzI;$`N0OySaWQmI>y zFZE1>`*WU<-3i6m#y%G*vl%2|ZxK9eqzP|C>>(2@-ec?UZm5fO+IEGt;r5}DxFRfs z*!Q>L`HORSOYOR8@3$WU)f>-%>4Z|U`P(CWKYS5*>YppzI#xnxytNFr8EDXemU3*O zAk80SJLQ!E6%;6~iX#w*C&3=_uue~k_RM{VZ3@4FomM-<-X7&>bEN1KL(6{kVmd^c zFE^6Ce|G~Ec0hz@RdE<18x{$F)dtbF4ND8*dSjT!<|cz2mI>fc3MBKneb$8Ajy&hB z(RAVN8&D_G80`PZ;l_74Cpag*n#9Gkd4EP5N@Dw(r|~5)PzS&Zn+}p{-a8yw@MCdT zAvZS>Pi5G4(1*&K$qR#WBH`^XLG)*8091h0U~W6NLpMrbnS>GXl;^YyKhbDI(;5EU zA8CxOjZLc-a{BYH{74wXymPZ{uECs?PayYgG}+M8jFm%XAlA}A z)BP{ZAgCF1*%%4hF4f#HAVl&kn%Y};HIRvIInnF z|0TG6j0LTZEx?=S=A!#dJM!3Kh(gM&V3;6|*xqTxGeg}_iXegtQWe>)+a-bCUo|mr z!Fx4}tk!L#N(vG}>+~q#p2vvR{T95>^*c2Fkwk4@2IH&lIcRvat|+i^BPwxlgVD8l zRBfz92_qPhccYWc)&b|SrDZw#!$g#fS)se zmyt5dY}9c_j()qaRCFiFw#B%sM*=KhT;*SnkIr%pXi8&=dvp_CT(S)9_?t*)8NK0o zGLPR|wxb+oQGj&imw3e?7b#ZK%aNp!q0aC$m|L2cvAZ@&=)dDEGJOh@+lZ94G*SF^qWrZ<|8qoswe0nc3M$LiyAY79`dXG0^tH)-A=O%J{F8j7%m_EQV%=O!$ zck)npWh=*3K+jZkZ2|k7BT9j%PB3da=d@_IrN5xc>d7=Bu@VQK-CVfi|2R{rrwK>j z<+w_ScMdvto#kC@E`qnS#=zIEdq`j3I~;UrD;gPlfkv--fwfwcuzF+&(U*CFcPFM4 z>Fn*MYZQA08`8=^^@dVXq4O9Y+4lo(&q$^U4{w1jHS<7nQ?78exrDIN^AVhyqCuCe zuE0|+O7d;lElfg&3i=x`4J%(xAwQcNaNS~Qc+^dbUOD~{&z|@b+W(hI`=fNB_ueiL z7`cP|wfu;i`w%i#i=}sp`*3cIB!7<<>tfghkl(pxETe2kKTa9Iin&$Lacd=A`0PUA zCpRNF;UI@U^|%-;ui)?}Uc$O)AG?wKcUP<5G!^*%YUX=cS-g4jV1*jbv zBi5O>Po0W#Ze>u3!~|Ys;WH$`xU1chEcCN11CG>h5$iS?B&BF0<@R45i_O9601k6j z9A5@~XUb8hAQ4{s`U>j2sVmZyltYCpXF{h$j<>8hwh28;y+HRWs$(tZ>Y~+Gx`@-W zBHST+5=f2WFo(+dz_5$VUpF@knNGpSk z{Hp@1^;{NH@ymmP|17rAJ}C*|fo&n6o^hCe-saWmAK`xeWLhB|g4?6BP!IEb9(%YE zDel`0r%2x>eV?naH}n148?)U|!3!|aM-dy_aeU_ZKDKDu|BXiXs0kO?Nx>sp+^m#Z zoD8Z=vdKM<8vOId7q}=Xjc&cC%+v79LM`m>e$Uu=G~CV?p7CrT8`MSEf1w1w+Jrsx z1GP}q&;iS=TfZsWCH8fy1&m@`&ef-gUg^#x10BjGr2 zY!cH+POQgxrbH*NvxD>Y)c;X~usoJL3v9x5mVK~*bwu9v3gfjaO7Ndcv+r?s0eWIQ z3(QRAyn@5k7x3O6;;_X;?L16=I+_~2D#1zWeNb_Z1%2K#1va^@g3EFONd3o`SU%7h zY}@yX+$^K`zD6?m?!wJGMWy3VL2^7@ktHj1I#P#>+?n=eY>X6^dBBlA+`Kbt)5W5z z#+*NJoWpOhYbnQ7E_|7YHngQufkG*;-xL6(om<3rVUsWS!7rO9)16_J_~QK=MXx|Q zSu~*@_ia~$3c@F(Jfs*a+{r@6S*}HtT@id}qY5wkau{N4vk48FM$+KPFY)ec6UAKR zABJS+{}D{}?WV`3_6j82FsR+mVTiQ+7pOibje4HG4NlfFpC_Ax{$YsO8VZlLXi(`h z6&66 zaU5ogWFM5$wxAD|Cu7Sg5_~j?-LEYHsLk>lc9F89Hkt!ib#yU&zqyL;_l_)74VVpW zleoS4N!dR5UdMvAyZZv~93ePU^;cMIJcy?}xh#k=kESiwH{eSx6`(GiMJ`{g!=Ij0 z_)G2y4Zi#s6rETF-M&|oeUxc0gS`-swVvhX3a_3w|_% zOTB({TeE_2Ccg;0D?Uf~yE^ddkTJ+`MFJJh^1vU}zCo`~=Jd^ybI^B~Kg?<8@ML-X z^P)|V^XC{1X#fV3Vn~Zh3s!QPfRtj=Y22B3UP}k&d4!Jk!jy z7r#dQaO)PN|1E}E98v+Is6xRqH|}o2C+?--oxd9mTlg0TEBXLOhA02-Qisfc4Zp5S zp%?##;6$8?Ok>!bmAw&JTC?0UhA00xOoNXT+Rplz?rXOK&sZ(2vXSF3kJENz<&JN3 z=K^(MjQU$pF^=Ofn;c_-+(u6C1x+8|L8VOU-loc1ek&ENX8FmQO7SRrg*Q~c&>-$# zxOHL>4Kkfys;U+~U*~~uS#o&tHanb`(aqi9kC}ZGwul0$#U43fY81;u`^(|UpM)N$ z;lOy^kU@d%>Or(}4C_a0-idC@gkz6_P7-nw<7wTGdAOC+TY_>&!{S=z4?Nw3A7Af* z9c~u%^N}zffA%1POjo=%q5%1RQU|)shy3nq3I63em$%C0mpH@C@>mE=+Nw-tqe^i= zKo4AHX+aNvo&vYlEr<5sIV~k`B?1}RgX9unnTl$cz{HFVL|yVTHkhc6>h~qk?v--F zqMbc(p1uWjS-K9sE8hW8SOOXD+lZ;+NWsPFoR+(M;2YqFoF|-?E4S(!OusgnDpgeC$sH2~l6%uh{-%1oCt(ycW!Uo1`}eRt6;Cd3fs`yMy1$h9>%!l_15#^W?2EB9&Hg7IZZnAXs_Tku z$1shzT3T4L$BtH{ux!=T`>^WvQ>wcss__0=T`1ari`cMz+^#}1q;oxq?s?q^h8Prq zB6$gN&S4O5lvKvai=*jUvl~#?aR}&@<*>yrPpDn_V~|^91@F(S5$~I}#Z@8c zU5u+ZmcYBp^B~eZB<@5AlgTK$bCuIr{3cg}pU+tb%>xDDv^)2~t!j>|tUlZW16W4l z@V)0?siq$Uuk*?GbCsAr87R6vjl0hpyR{DZsK$`Fznk&008J!PPNnghaXjJnDzul+ z-s9J^(A4)SaH3BOd2*BB^N&phi@p-#>Bjo1W-S0~8#p|P(?(Ezs~p{5EW(D*nfI0P zlTF>SXvD6musFe=1W)b2^P8N|nTkj{PkRh@E88xZ)!s#{hYIk49qvGm@soc!MY@ft zsOc8#4z@K!_pdC54_^EqL%f|)*+r&@j8_K!6%~SM;he8{#O8@ub@((zHtt9%vVIOE44f$g~e?Tm6=!hn+}=QobYdjaJ=(&_H?D!eL<%g8c- z`Ew-Wk-oDRTo&3O?yPU>WF9%j@qXi4XkF-qS1|9Ng1gN4R%_1+}|0AdtG#i?Sy&ZX?=>bR6QbS9>SflaBGcwbytm&$&5h z@Tvkd`N;8;Px3sZe*Q9DdF2hSBD@#fl+_hY?z@YwK9dA_(~C(~K?y!KX$J2z!#k^tV$onw!14JpH_Iyit{$2n%&H6!xbWa73LI+8vGQ|;!Q6Tit z24Y?K2`gJEqiL-P^iHCjaN6%OG@RXL?v^)Z9Ye0L_y(t?bQ>)btkUM@ojtogfQI!s zM8~=s2k4ANraEbKl5r`h9O4bCel?5z!|xiqq3!l5lowrv`^W7N+}_P$h=s2&`s-5ui&xA z6|m|6w;M8&Z-I9AQs~%{TyVN?Dmd^XSGaz*gz(bn2XKUv7M=Iv30AG?MR%BPrnXN7 zy?VF-SFK1PYkV5;?>}u|a)cC>x%?127PY{&i&JUJVqLgQy%98B=lIE3|M^G)U8L%k z{n#S67ZtNvX{Z!HHnvK_w>frn|MvlW>iQJ;H1ZZX5?+mm+3`@)lgo5@>~oNscn>Ta zB0+{}4C1?F4R&IC|8U+7==r;i_h)F9cu(!LbO~I$rAF-Q8!@6B-DY=EXI7QK!nV24 zam^udC)89ocmo|k#>F{)mzE4mPyh2DNhfCpc;h;PZ?BxMOM52M8B zbUFU$s{@8-a`TJXN+WnRNsg|QW?b$T%af$+RWVK$=Ccz`-l##w!{|w*Li`O z$*JSssHXza56%M|(`^IH4ZX$Poo78RA;AM((Hv7l^k={bvMx&U*NxpB>~=);8(BZg zbro=8cdKA3%a5JKW_zK@T0H)s8+Drc7q1-R4xYPnWg{GOT6aVR|=1-38!622eMFN%8%X;jie1&e zq8K}N(|x-Z?w%8b|BT_h!L`1tc#$%TNm}D~99ZB48<-AuD|ooj@7#B=R)=L*GC#~q zI|Ed*{US~Kg7EiuJ?JCjDpdtLQOM6M+!D%V$qud#<5@Ow_z=2nIQ%@o;lm&`LZePy zqS9F}dCCua&`&n|xPQ8fG@~1NZ92uo{$>f*kk{d*T^ba3&&_+uX2t6=01XRs@%S2SjkIJxrduy&J9yRVV6_sc<&P6*LE5dj%^X+ z!(iAm7k z_Q`@ZXq06nHGT8~$Dg*rlae{#Z_v$Fyf&wsK3dx==pUQN=C4w6Zs=otKd%ZF2%s(bLz9VsOJW&?g0{}iOO zO3@KA#rR_TP~_)bPF-fLg>U_9Ky*I0JFY7+K-py%sgBG5&S~vIzw~rP^S|?u{bntp zL!})(K6w!LvApPU+isC2vufsjU4$I+lBi5xBNzzJ2Okbdkdw88ct-L)-nH3Tq=(jF z$u&F};#@+rpKwBamh4$ciTfN{~{#`OIrV?*c3Kq;T;`G&mBO&0^_!xSx zJ`3B%6oEQJj!Rsv9*vA=Wl+(Jc-|#fifSAg2MfqT_v7Q>*RB@w;x55UK)t|Ti;}L` za=hAJ9eC}r7T+t)($a%|5pvYCLxc-2N26?p72T|_FZi(r9CE{-%wyfzx`j5VbZHd* zuzm~{SW00_>rX^~lK_7>fWVvS+-!3Bb1qbM2&3Wl(!zrqqS4MmmPb0%ka>n#|I5ob zlD)7IYmD5A%Gu4=*=jA|{^GM>y&0!CSqgW<+eK^_#u907U^H~x81u6Yl_X=}>q8k70Faf_o6kL`x8bY4OO zyo1mpvw?U&qxfWN7jm>@xrko1FmOdQ&StnV;8KAjqI7sw#*0bSm>;-bb_IMeErhPT zKSJo0-UR}T{lt5mU466ArxS7Xn4uY-&b(@MbC`A=yb~!p<>L{%IDK_U!4}^177jP| z4LZQpTcW7@)kxggAq`6V$2Yti&cHJ+Ds*T*yVKDpC_P+PG{Q##h3Y|=HZ@SJ zwUQUjyqrJ3h!d;AxxHvT)HIEzW}`Mje9Ry0Ve`wsU2xP7IkY1?fy&s+3F8z9>SbP| z2OSI9p1}z=<|dHTm5q4Rj|@S}0GFSC)w3S(U319Eh3p=1mm*4epGrTMlz^U{$H2w~ z9JXk$dkdpiPNk^_pW?(WEGRvjP7a)|$D-;#K>H7eEe@xm(6{HhqPH`PVC;`!P)}_y zi5>PHZ(|u^AduY@4}XPA6}I4%2#$MrEsOwL)|QGhz8fdKzqCARFa4YkU zI(OR_&RVSji@a_Tj}_H;_?Y?V>!T!Ud9xAl-15NJUI}s|`xovTAHjPxF^gDTXIX_? z9N-kzr*p3>97IiB2)z$-IAc1EpnUd@Gn!Qbzc=VY!xWBt80ah!e45NgHya6sr+PcJ^g@B6klyHk=@veJmq-rwf|@{1ntT zx=T7vRN@P{k%C+kP7hJA_67@;W9X35EIjF}Bb>%|rXM^D;J5h?fX_OPw`7znA(_h= zG~PUcxBZugPL#v1oIa5iy9D^$c^=R( z@FwyzUg2%hxv=M57(LW1E$m+(g?!n3q@rPn8cxrKo4&^pyH$;NTGeW#RToWXD=7n# z`B!jYF^5GPGcMz{mTmO!CJCWMoh8sxh!S@d$?=5HrXq!!Ee^%$k>TjJKv(q5dm~yn z$r7qN-6q+kRd_=CTeOGm$KU0igh{1#xW$Z{aRjvpus~Tc{(Px)1*KQBiAPBd9-Gk( zV|vQysps=}%7??zr8r$tN5>_!SbjImzt})N-=sMC?OQaDX{{kPweWUN5?g-+rg$hYPHf%cfI}uHe@AA@H;khd&Nodgx0+JVhfr zcn5ReB0UwBZ-4bJN@+O7YjG@QH~1wuYPA&%(2b_$J)_~NA!@wqihuB6ln0(0e*)S? zsL*2_Ww>QcA-civ$Krqjx@*1|HX8<#vC8eZ{bLHx&+ZqgW_4XX_Eyk;Ry3XabpsSQ zo(2BJ8^pQyVe2ztda5}!R=)^2iWZZP~G1mzBSnVqysvfoJ!xZ>^0i?TJZcdhd)CCzk%Mxm12+X z${XQmP8<7OYZpP2OHxqJh{Km$$50Wt9#&= z#}zcC;w8}59s>e0^28Z~Q+%((u}b6V>()wqpzAHdJeJiwR|Qor55)R`oF40QJ{K%A zkfsw46k|=9Zm8*AMioD`9 z+0*m42l3UtYH)V;Ei&D`8e1hBq59ZVDz~i_c)Yv;PK+Buc9s6ZBb^<2L2I*!Syvt2 zs$&3EH`j=@){XXssO19V1KK4}*>D;xK5|IBN7kEiMsVaWmtFtTO$u}@Jx4RX4Hs@T zi)DB0KIBnU2Tn;#g~iNswIxLb-Fpl$q0^TgO9L8x?5R&+U%u zKQ2Yb|Hsmmht>FX(FP$>Xi$nGLo%ey(mm%zk$L84N+D$)Qf84#nuJOdjWiI7GSuDg zIaj4YQBt9dl|+eTD!${M?|($N$(lM(osVbx48^;e!byrw6)a|6!t9CBv|Zf*-J8%A zw8ruGglOJ@{Tm&rjgf*FGjalQ)#UGq;g1ab`D!dZryBr&Lt=1|vo*b_7ipwRmM} zA$_xVyyU*Wuh4Rs|M5d1qk;qU4EJ#n^pD>N}}z~fbA*l9xw`2NX~-#)W`e!;5R zV2V6bD{HnnZnQm3ujQ+Y3WutZ%4|LdeX$!Vq=ZFKwXM^^MeD8L#`>bf4bFnm;zuxz zajpM&lGNqTt=wz)d-B$O0nWOXME5>Pgw=V!&@Zzv`R>?klPS#486xR=i0f&KB6>)COZZIWASg~ypyDJez z){m@$lS}KRE*(6JMpave+IL?iiK8Ba8pPmxOjmaB)h?7?xfRVedm-1bSx432DNRFY z-;PIcOjQNcq7q0>(o^vGQjb1ODwf~N=vfqlW0S2J2A`q3%8EGX)ed>K!{KbUYwme~ zn*EmrZOh!j%#-&mdRyF(?W%lvrr-FOcevQ5kRIyu5`}N>jixbef5WrCa9@&)3#a#| zOS_hUy4hP{Gt=ap8mlF&w>=A@Gv``;isMk&d=+{qGzWf7sl)GY7SVjX6g!4VQOGkV z`F)?ZH$#N|gCl5l)o-|=_*QUaUY_%b5}{-4RPpPOW%T~F-w@;73;!tK{OZVYW8VZx`3q-{M|S?_ogt_ zkNMW8tryO;@5Cn7nPl~pVt7toOTTpIx_u|+rCn+pD%Y7f{fxp}@Bja;s7)6}Y%rC* zT$(7XOAW$NrPbtv357;90*09K-a``dK{C3YzZImn4)aNMqhlxKfb>Qb)@J{Y>%9KB zuS-uHq39#$RF|!?7Fsrk(Dhb&;PQA0%-YaIcFqRqwnZDY5Al#^?&Zu4#kT$ZsDhP} zIBt3r9)Hf7b~Bidca1Z~4GIzRx56uCmM|lNWgWZgpz_L|V7ra;tB>rt?9+cwjj)`}_^%7t{oePxAc=7%|8)39 zdD|tY*>3kAPx4+WLFIWoa}VvP!n^kKdB?by1C~`+kU*edxU)v+?#ADQ|GwOUE3N!Z zFwfAoQjzc(r>^r; z0MTon)yJniAI3rD3!2_9jA%POgVL;Ff{|7%yMx>y*{)k7RIr-$BP3JM{v2tg%yL2h z%`%!xI!ksr{g&&{PW0T016OF%*M)@;ot`E*#Id@+PF>L0HWoKdKPBJi4hni;b>6I< zO!cJDx9?W8zhyOv|NIGBjsD=Vtj8YuuDhrZl_un|`EKA{)-!aPhkv~0*pIla3{@?B zW+~Wk2Spv`*k7%+329yCeZr@*DjdP^o>%h-41D^4W*Eo&jae_y$HB$&9d2UcZVonz0T&8=X%crR9Ru|13VCb&7s>4@Kv+)zPLr z-W$xbx`aDr_owab4#KE~HNsLmQ(3=(TEd1?kzjfzmKgP}gr#NY&B4vLS+z*wg-+1=_uWLdX#r^T z0M2#HoYH}P#zoTuzji{c!4AAxl1av!7K5+H2k8c5&Wk3;N+r2z%~boXiugntgI28O z{lJo)X@cQ;HV@8Y`myV$@xc4lz0=J>&zzF+_X;6MvsU7)H9^FFeiz+?%6}J)$o0^E?J%CYxy-}ZuyzX}#4aT{3 zzO75jDK_|;lBOHgB3zR9gRXt%l^G>_#w*7@0uFg}Ru+mAlgMv+><^7~mD z>Hc{47hig5jSDPdnRNj-Cs1Rp?b!Lv1YCXKCRrU{0xiB(LeySU*{A43_*GYTz;pSn z=a(ZtX0`sm){i+g99drBwcaw#AIGrlyG4<|tnxmu!pmzaNK_I9vw$kWj$v75Rfav-dPd@p<8Gl0RPG;7fa@FT)|O#mIOM$8~a^p|G|zk{*3v4QHIHggW+} zsh#93EVB9lHLq&Pm*)V}ZHn$qe97y3h}0iH>F}k79sao3tpS}f1uAvD)q6`oyU zbLe7q;avD={C?djxku*DbDOMt&)dmERT(TwvqJ_=yuP~*Xv35C$581WHSu}wRbk@4 zKJ(H<-4@u9-#d5v+fyb?AfbC9s z_PF~(LAbI%l>Tje3&U(qgGUIzBXefsER{nBhnB#x-BrRhrkg5J*AiY_N`QqyvE-XUCH$G{g{B3o(Dh$(p!wAeRJy@g zuJ3v`%TTCa9!b9hc0iyV)6}ti!sGrDAuM{O7#OgOCQfe$vn+q?%HE2p7q8=)DP8b= zr8Lrw?U%2tA0nvDkE2oPFVN5)2`FMQp9}hI?vz!(Hj#w3Jpo;Y@v`%LE--j~Rp>}$ zGigg6_I_`G?cedaVBey<(m{K8Mv9)+80p9g4~h?V6T7P)M;%t4^7{zqkFuG!Bbu73 z?1qG^$-;;TQ<;kKdSO|;BOV-{Dc_H*Ufu(O9~>or=hVUmhpW;WpJqC)NJZR&&Z3>O zLdo?imghXN71!>Mr#m~sC6E3~77){O*3C~8v=;l~tBTbK?95P!R19)JjUEd?!R01$VxD<38lwB>w)VsPx$znzX?xQ ze3leR_?ytCb`l4j_oKHjDv3si`r>g~5kyI$ig`PbAagxWhhi-hnlS)IY~?Q^%PrCtUHFXUjysA9UcZKCAdux0r8gi12_ z9fhA)o(O~4JCJEuhV70Nf*IR~zIe#)PgP9Lwp=@fe3<$T@~U#t3Rlimmh1Kxw4*N4 zxf5(*-LUU?mA(zF@bSj2HErM$TT6PT13YMO&vyKNj2y3c2S>lXLT)IGB=30!*E$ar zg3ra#rzwpRmDNv#X^aDzx-nDu`b?I6)`e?9dl-GTny1e3?y_|i9&|vP{&`vmNj;K; zM^_lXI#XR}xiA7xU44oqKYj(@mi)>-v96sANTD$8z+!Z@?;5#|V%E}6c+b@sx;0o$ zwEdGP%x1GdZS+JzL%|wftBWGPzE#4hFUIihC%>^$9rH>0;tb2W+~Y2-`IUgQeXg=Q zeXQQC`-BZ{#ZdRG9JIdkN>tqMh1j6?7viQr#$WCYrFC(S!Bsj1PKgObXm|>e_WLOJ z>qD|-Mh>jiZ$f$-INk$$eaF+gvd^mi9ON3Dhql8!Lup0R7&Lkt@8{PgQ~b)SkiH!M z6787K33(Xb6bGd%h|bTWaBn+9>T3Q7!iRpx%}m$St;Yzw!YdU%FXP(IEx3wd=3LUS^^ z-PV6SyJu^U%{+L0Umv0mov$AyPLf(U@a7b%+06GBrQQj`E2azjjuVBk1}AX~R1<|< z0-dLC0~UcJ$FJx9OOlDnbIGUZ7Pyq6hA2fQ4_HBpxXR8V$pGLe2Rh5J|T;U3!`(OZ6#C2l|F<3mF#<$d__ zuofK5^opaGd_$)sPhpm0Hu?Rt2+juI$ey`|V|KL$pvx<~$(u88prX8wkWd^&$vu5^ngmFq8~;~M?C`<`+kD%nK*hnpixp4 zSR!1T&h~e!GKC=P$`QSDLiSlLC3!F-GOHQJ3P2|EWPwvO*}j%UMOa@V?x+OLGZwM z-p45N_+=$D4;~BN%y<9K$LdsT5491^RM_t>-8d!^MeV;zR&-%`u=2z=|&Q zXkWli`CX)!w_0#J({W8y4u)Zd(U9QpPpY@R1UvhF$j?5X=(7B!@i#gozcSM0`HG(d z!f>B3L+a`H2zKVS;Im6@Xun}2uw_mrB<|(?`I3VR(TvWW>DRzq=p@FYTbns%Kc4I( zq#uc*f#d$dtf?({M1wW`I${mp^>df_vtcP+74sV|?f#A040&BnR=a@SU*fa&=7Rpx zUfUB1>Rt}zhqW+aI)r~Xy*@c!ux0%A%ZGW`uuU81b#;~JO9ve&lj^fsdzk5Wux)6Q zj{16>hWn|CC+_Y*Vt-G$zWU9m_jtj9csjXBU$>cBk-btN?H|E3RU&=UrxR1O) zk6b!gsCagsdhF5%2e)9xvosTX7M)l=?x7@Q7U%gFbUK93vmV%`T~Vy+t&J<2!%6D( zO8D|}vaoPY814UE3uP3VL#iI{&%^u;#2VsAOC1%&v(EXFrv4nuQ+}D?+ABASYD5VP z%R@qbT{OL|-Gtm)&w<9VgCxAB78csig}&oMXvV8_e4W%uGAsE^z1iXh4jcNI>X}+f z&X1jijmB28ygtS=^n3;4ux!#TrwDRW6{N>3`5c|mn2Bz0_9pwH-$0**TEh9@3v>#Z z0bWl(;+C5>w6xe8Z`SWB#+THR4W9uH2bxQl{GXrqoA(Hr*>O((xtp%gtP)3cu6~eA z{#hV6GwsCU*_pzZ?%vX{Q#?b%JFLt~NA^>mMc*=iHqO1l@tcrzQJBo$_Foq2LaX^; zJSmL#*bPsvNUKZQ$zf#~DA`(~?;305-20?%)p!EL(zIfcC9&mV3|5A8HCg zT`$nlzyE@!PN5LR=FrEBB*H?EBcfu>GTKto4u`W^(D?QnEq0W)xFnLZ+U0PllLl@JDQCNP5<*DA!!&QmB@o-&N`E3hX zM2qyb0_V+KVpc%*)#LQCwW^r&dO0dI@|0_vZ|;s1_A=d_Vy%NvdTu$Me=n2Rjwyz$ zWfMU4@KG{lKrQP5^I;RyWi?l+hz{j0NOFwN)Rym`;l}m^+SMjf(#(8}(lEAnGh@B< zuVdJS_0s>e%_z+mrhXt~<>^9bE!{1N!n~JuD1V3Ibk*s^@A>eZ{6fzde*b9(2K=qZ z{l?nRYxeolvB_6hAH}$`n*a$9!z4MZm;R?eOmJtt!3jS~_A{=`y9Zv$dTHgXN>G_G zR!AKiPFrtjqv|7;;Aq%~v~_3w%=}?uzON%Kn5!Ue9h)fmIVqTI(XR%L4r6?$gmdPP zj#vtTrZF^rWfKY*5eXy7K~l)>0>=(G2{PufI(H`>mpv6F!^To9En|7O*4boe3(M8CF_o&{=D8EjJFlb8o_xR7cTZ0tcKSuC=`$1X zlw9HcMz+T(auT{RZAW8fEjiZ!FgAXRwDUV&e_QhM(Cyt}a$m#brCNg2FOGg()+lN1 zpDWy%V=9Xon<<>?pDtD3$2st~_PJIi_xK+FO^<1K_G4{oWmp6=Uxy1>_Zeqv#xh`R z2jC5HoCiC(u~r&h+fKIW$UyP)D5TAL=6^S%f6gn%kx%33ho$P`ukvug<~GZfI>C1L zcP8KlR)3umD`A)CVyIT)^>?OI6?|g)oTZ-b(xKaZ(1tWVBRkG`f=yYEcibWm`Hr87 zd_+DYPcpfWLn2LRXXjGrx_b}wfCS?F=P5)>;!xhAV)B#i&<#9PgzLHw>DnU>c*4kM z=sT;wMM>{LVWfqSH#Ce|f3Jl@Ro7rcmOt??dkN82ZzVs&xGrc@_6JGa9Nsg}|9Tq# zd2C2mdp&|KcDX{4hpDXSg{H98J|8wNh$XJ=6=1Tj57M>oOvh{FLFk`Q)akIZ+=Kbw zI}KsVnPGeu z)ao`wo97YHWM9SwRr2=H?ZP2%R*Olr&i-IM5Kla$>|)+Tw?5XAz8mJs^U|M;C`aMb)T#UM0=PQlD+0lX z`2Kkf)nTIrh!3Zey7z-9>$|X}XETXu2S{w&C&|DZ%UZE_sVo6&-zo#Mb%;Sl+~yAHAf!zCX(GuJYkg-whk zxYdr=-@O4u_|Ev=-VaN0j`cSvXLn1lJuQOlaZ9A@+3lEr88UmGBqBdAt^q!ISWQrQ zdy#IPVhhK15aBw@={hPp3E5`aVnVMvGHj{{`){0)MiG9$uZJ?Awk2WY!-8iZ+tyRq zvo@aUZTl!G`Hu)^7-ze|JX5evekomAkwZ3Z$_KLUwv~G>$Fk#_$yn^9Lrazw!AtcJ z!7G>XnFG}YFYA7|;oK>?1~@}s1LB5vkje99a5#1#x;JKxoYU?$IU0vuaHmH%zXVm~ z5J8RAi;~?Fh59XH@D9BTxHJzYFt-h%{kRXG=Qw0B@s-4=gL7ZOhy3v8*BsaOK14XoG~T3GQ`jC<3Jcb7?(25#7m31pj_Y54 zR^#cjLTK+52H43z2z5_&Cf6o3LVII(!QP7HmsTr?y4#2lw3FpRn@NP~nZDxwqGfbt zO*@RusYZ`g(&RdvZL`iI*L+^1_wQti6O&+S+*Sy&N2OAwV~NDdv>a^BmGPkHQnK`j z39;adt=IgJThHi}J{dPy+ zVtjQs`^-1(1OG3DobN2a`x`UK4(npj8$Ao6A90NTcdd(fPxUjc(CsWr zpR7gqe0aT%aPGjfwieP`yFpU(E?AE7VLFMz^@M}?V|F!}u#3Qld12u7gJV4C!X!z~ z|1m!3#be~1sZIwM7eKEmEogu>$M|JiGvSL%I87@zfSnt&VRK9~k?j_tzuPuRv^~#$ z37fqLFHsJp4);5WADp}5g^172M`yD;!Yd+Z{2d*1-)lBpappM;+78o1-zrDybV5Ol zR+=pd8OL>f#znL6Ih$ZQ*6cXk{H%u$D&LZ8`OG_62p?*rY1!>hC`+0QYwZq^s%LfZ zu-r+qXg~^?Fp}-ZzR$+314C%;%+8V>UnXGlIh7>oEQK*?Swbg6J}NnXd*j%Eq@YgrbeUZ&8turqYsl*{}b`7lBu z#VRkG@37Q1Sm1qa+H~KzBKRW&3DpnTZd6}gaNnVam!}Yx&)}DU-IM z`LB5f)U8eT@nro3Y8Rf5R_RP(6lt|w(|dErJ$%x67#%aF49?p6!9B)t{loazZhpwe zw3t}U&w*<%zG72_hqPdt18%P&?bkTQua2t}TU`Fq z>|M&RTGvP7@!WuF6x%*$;eGeg(iq8_N+?ih8R3f;X3KIAAU(WJXI-oqi4CSe&$u+%sqZ6@ljx`;!z!TlA2}Iph zmE`wO3@h`+&BKG~71bj6&+MI4@Z$A7=-4mxH@K8UZ(=#0eG_pB+v%%zu1EFDyJ7`5 z-k-NF)rJIC-}82Uhm{p9&*9>6s&1t!I!+yql+Ag6K4I5AJTfqr!nZvTpcWvgvH7b$ z+dPwmIJuWI!fYu*TUpwQ&|=_^B%5x0Z$J}@zL-EIv_tnGAPGiSi*e7 z<{Iqwg7PlB@kupNSxunNqASqM@cwWA)pokns{aZ;UtibDKzFLuX>nTtq*lL0LpS)y z_5T{HO@(cWQ8dBU5U$T;dGU*zN$GSEEMF)~rnq>J4fbzgp2|eLL@9_K3+^nAi&emy z4iRKoLnX`$F%t%;#?pALe(2(wCGh>K4hi-84aVXEanRCD^mvJa_!oDT%w_YnPU8#6 zdai}1tKA~XnI$mTZU(fP$VQ8egH<{!42DaJ9Vy`3C z)YsvM)JT>o?AgyW-YnNDT^K0Z;W{$cON4__MbgtZkCDN9-a$+IRYZ<)9=q*SEbe~8 znx^#*kgQ5(IaCg&GSnqgsNQ4%F0*pUv*xzZQR`@mg=kY5Z%ti;^B9# z=}@<&xMGGWzVkhbeArkC!;6kV`cuwh)36n&RLXbLcb?W_*9QgkqVIQPHGVuA7F8`) zFn)5CX(qngIE-GoR|eM;g8@|~kXow>$aHf@o_fXP!Gs*BmcGY||2?EbLLIQm@LYsc zcFB1#^{OGlp$FlNY<&+KL-OErB=5u5->el={r}KGipn4zF;TMMG_T`beilkl8^`jj zo+q&0MI&mqMSp;FE5tS_C6i3k4|{;End5KKIjkK26FuBtb7eCAF}y+r>gj8vjMux_E!J02=W6i;Nuc& zYSMBX&+k1A4>r6l*P;xITT8?gJ(NEA*n?g**xbI5 z9=8EWa@A(6^}U+ttS4YFG!vAXIc8P1Y_p0rnJdrVcComGs+!d424091TFjxdehg62i|X@Q%w}b|Cak&9iG7Ja#EQFmJZ^zxFyb1@Cb>e zCV!gIs9|@&DCrQ%m|71DA6&Frs?TTVsZWRF!Y!3#g&zf*A?bp88q34KQi}JsbrY2? zGVVI?A!sNhNvo51zm2udprZ4f``T$9g%|y@rn&V$q;G$x3CZmJPdnu#cqN&LFu0B! zIx2$u%?4=!>$l4S-@yy#1T@8$<21`63V&tyP_A1BNOo7J2}xVojl%W}VM?$Ce4U$1 z{66MGYvyUIh3ZT*)oDA#4H<~PdgxHI7ex>?mi^v8Op_Bi2wPq5g;N+#|9S2#d(9=T z4c%pHk0zln85`JJ+CgG}%0ONHwpQ z%&zN^E-YnwE$hpg!u#Y;aAYX2zsr+V72*a3gq;NP7``5bMYauN-js3gzK|J(9R+`>E#xAzo* zUuRu#eUwOEM3lqWUvE(IbzWyT#3>5uHgR;eK5x5>Z(#o(g17o6`Mm1n@#EFOW}pNEpPO)p?jS_ppq+Lt0f4@ppm6K?#&F+1|z z9SCbBavt01F|tZ>=CkvWj97HcL4&?xyXLr(5Il|PBEEar;rGMY9i8CaDV0yb27F}y5#^EB2+_=|@Zs0xk!lDp7l4aE7Ejxp|&1plidJ*K>)=F5VKTL2j zilM~70I8X8gn7Zd=9+BSEUxUniCWxL5L=%k%WXsX99`Ze5L;^aQOBOQ81LH+8yeh_ z>r66N4G|W6h^0N&en!RfMR2)!h^${%4}}Jo#l}1Fbo$jID4n?4(r9c7Su2#mES5|B zIe^#V>(f((bxADuz^4?SU)fX4zQ#PZ=?}r9GnZ!sk<~`ZpoFNz&&4i8>yx)FP;%@csDX+`sWqQ~=Mu-0V zUIZH}df>P9ycSo)FD6fWbeFC1NJNc~++oz=Kcr~`^Q13-Bbh&yV|?DP0Nk$VC&&20 z$pf(7yC||;w-RQCI}^);dNS=EszMj_Gce#sAUS)v20U8KQQ{Yl>&NV84=ef6hvmu0 z>&Y;5=svH@s^?R&!f#WW^ZW_;j8BC4k_57UW(BMyi_lw@VscD32f9`T;7#oNHf2U% zoYit0{c_($UJPk~UuK3v(7Oow;Y0((J5~T?deMLU*wW>{#7XztXq?_3sgQKcvWRhI zyMO0Gh{0`%m+eit&U|6BD}Fa=0L@`{0L_F{;Y$L$l@_fjl()4(*wk3E+o}@!=U=tl z+qVmSruP7vi?<`?D!!{4y0Q(sS4PvLzZAu+p{YV=R@0SRt%Q%;41CH=(+0&)b)-cvDnrQqraGf&5K0hdA%I; zZ7R^xho$7cs|+Gnw4-Q4H+hc7sQGq8*;+$ZxOM|xuV4X5c08|aX=iou)4Sue{gA%yj%r0{PcGzBSU-(b7uxBe|~i+G_)M>J?-9`mYL_~4uU z{HSe=9bT7Tgl4<*+4<+r5s$x_hVg$p=+Vc%;ZB<`QA6#8V81#^n0ek*7UImZT8E7j zFZtDyK1L#_-0uY=l6k+~`(Tk&FS40dPig}D$>&fc!}vd4sCLK~e11nfHPHVkNwrB5 zwjF2w!4Db2_lmU;G@19_hnG28jVNq~@@HG%c}Xu!H2YB3lMkUwu`2Fea*9kj{R*=7 zFC-+RlkC4Y(MWnE5XR2>OS-7$KtNHxoX_QKum^VCobUqGnc|=dn{)0T%7^ANH`Rx2zH5u#A7*0?!6A#~SbWL5m z^vl>Q*=Gv!NzL#)*lLn0`EU14d1ms@aogFQive`!q*8d~kR-@1uq<>RP2rJ&f~dAM zmgG8B!l3lJ>^RddRL|l8lo#8h32mGQ^V4X;v)0DYY( zJ}#qi&K=;qwMhE$R5P_eDOu+_UqMAvIDQv|YYUei6;NxhuDB!Z7;1=DB4PS}pkaU! ziK{Q5tG;v-+ZwFkPIDqTR#FZfZiT4k5#LAe8So8V`@rYoqu!QqawE?}4!Uh1_Gi3z z-&j@AJ@utzgFV-R&UW_1OWY>WG3@5d_i&btzx1|zZ{=F;OtSoX%6{Cvi#-MfKy`0- z64$K`ymUJxjZLA%d(R8-+PDHw+fpOH8DSu;07lc2rYD6^b1pL5-DfT-+0+7Wb+)7C zw;C*~lhrll95nNw4|)0aHC#TZFKBj;roFWW!h^Fa;(T|GSr6sn?6Ir4|NYL_AL!75 zP-^C-Cgz#ep!j7GBsHKCS`+#SbB@Q-cS1kZY2#i{(dSwbtFOn!#63=Qqo1PK*;Yw< zY6!2zE#3+^eb_CM5mW*$?fr%7s(5Ox{1q8_6~nwlj#G)*9r4C$mW#r2-g3`qORfJu z3me4f;aZq!e3>)fb~)W|QOHi(%2LdTH-4-eb?W>5A4~C+FL-cl{sdt6?ffNfld(+}3=5Ov@# zJY>GnfBPnjhl7|OxtO$><-qMeDad3f$KZOQ9zMBno=RbMH{x=L<8H)%qot$YQ=VzF{lAU)W6S`0j_sq31LK8}F)XY9pr+91(Mf#OFP2=esDxROTcu}r zbfNviSgvyR66C71SuN}~Vicp;wcWWT+(5-c>Xi5jNMs6j+KRL@=r zlfs*6!>p97p(e2?Y;Bs{pEbd=r_e9Gkj84N;<$?kQOh1B`OR_T-a|;cX(4SJ(Oo?D zU;&tX;JE9S4Cr1N@0s6NHlb7%H~GHU6t5t*GdjtPzb?W*(j<^7@a!6;83V-M2aeN# zp)9|8Ou1yiO5P`LNM-pIQ*M)X^5tE^2gq($x!WHAGu!Z&Z)kFsU(_inKlrHnspKHes3n7+C=!fy*B&(Vy^KxG3*;s zSP@3OSz6k?$QLMjKi?4_mKg{QzOl4$Mn81V;t0ES&1c)a)jr}n184g1i=sI5&2*`x zAFrFZr48jy;22!>_M%|LIM{Ki2l2Pfy~N9tw_7F?D-9-L$s|ipM%g-4>;g zYtCix?V={`lu}8$Fn@vPi;KeN98+1src&&3!$^GHSxRhdi(#?QA=Q3sDbJCp_1%Qj zGB^gMnHPo2?A;!NorIJ_Q^my{wInb`gfaJLk}vm$$#zbx#Rb_z5zEtZ+}5V3kW=w&ufYpOIGScJ1=)h#P83*nGDx z9k!qZIwmRMGyOOQN#Y8U+gCwm;}n6yZLh%d*uO+`74x}FJ}+@};C$4Z={s=l6hHcQ z>{rn4p@j#STp-6sRRSZzSSI^va;&Zf3geoYGd`7UNqr33l0InWFW%pJl|*Cj{Nc19 zq#U{y$zbzI&L`)+?twIxasAcxGx6y2sa^7H%z-C01^w_S+LGG{MrzG)b~)E`qQZ*1;E}JCeKaI42zZcQ#%T zTO-f0eB#vvhIc4A$@IOIy-cO0dpYhV8ID3$W<9B9MiJQd%Ro5|KJxpI52IOLgmpB{ z9WfAAOw$yPylp1u+C{iCW3@ENmg^*48*U=m*iiZzsfh{AMd+;;t9?vcHNTs-KuzLk z4(W&T%se2lzYeKonK=a;PK&u(&UEE>Me)%c59vYXb5wZw0>{2(4U`UMR9evqu`QV*-wg-S0j;8=6>?}1g)D@n#-3g3H12+og~ziDkLzVUak z7~9I`O@_63MO`6&vn9bct>AU$I@mqQqq!HY#e9bqXl@qA-2rkL_jYopRig&LpyqI4 zDC5lMPI3}1HP007nrn$&q6k&V3yI;RVX{e~@9^GXR-kl_V=%;MFUpp23|gHo!_z-A z4sG6hiQA)aVHM-4W@csxviql@-!fhYw`%pWa`?n&&l2me=tGz;y>O@myi(gy?Qo94 z0hxAWl7fQl*Rlw-cG^AYIzxeO)y)N$-bW>;T)DOxPH5nteJ+quN|lgD97%MSPO>_q zk9hTgG1p0)JD)=%`$5|6NpLw z3aCy0BzbAiHB|4?qtLvqyW~EF`A^!QaFRdie)T2eA=0Fd6AQ?*$ULyoKP^cvxGDC{ zR}j@FFUE6H2hgN>rC{9=E@ZIX)5YDI!k^PU#A$zHAG<&*zFGSMd%Q_|=xyH>DFcLmKqiKOgDIh<*_ zj4q{?lFJq{@Y()~p-Xj8fzu8iUHzNE9qz5Nmihqf{(w719b~`BJQk%fMKDM#+p#lWx)%$;bn~@chr!#a|!Ht@&mR^ zqU6NVB2dg(E_I*EHBs>odZ5gnJ!u5XAB%c>6&alJA?Eq7AyC#s*i?Iw`rI1;vwrJ| zWzU+)AZ2z`dabYYu$c!*`}_tno6n$E%Axc?Pc`wa?R_*koYy;#7@@Zu;j7idjkF2hxHMK$y z)oMse%%ij1ti>g3Y*D~7?hBsYr39~I*_gv0&WB9n5JCGUyMsB(NpN(SFQzl!kQuwz z)*G)R<;P59+1K7;=h)fc6~M9Po!&{DnAJ>!9hzX(*Y#*c0mt3*)kWBUZyZh8`ayEF zYlyIn^{%gPWC-tCBEVsLF4;Aq09Ivxm~x)&^Z(6*zck;nJB)ht+Vn?IQP_$?hWW~U z!5OFX;e?d})$g4Pi9T~Bp3c19P0{R*6AUlNd(J!8?t-!LY0}B!CB$}*m7EDoCDolv zq5AV`oU9Q{oo+I2<779a$M!7$?z~q8hGLyXBj{ju+iU)sr%-r|&w#TJFem@?ViJaO z;Gjt;iYeYD&q318`~!uN%Yck_ze)%H`~;A70wU@XiRrs?*f}o}-FaV1G}xV{gbfNp_4R?B!pTw>rlvqrE0pX5o zaS6*I8THvuQgnS9UUH;{v@Rjg<>hZMaHB*wya;T9*GqHH%q7nbw1DRa6*OyVPdbm) z${teovo;~L;PMWrpy<9jY%W_5|a3tRv-r-Foo zOuKuvx04W+xKuRyT}ygbif~xZf%LpQRMzGE8?3nGKPYxT#^iACAp6u}R0EuYEnA+8 zKV&A*^zcuTi*7+e1LJub;xmM2^DjZ=*j(bFQUD*b)2B@A{9B%Lc*VI4J-w_)?>>73 zT5g}vA&IZt*W+|xBblT0ogVocjAXb1&~ydbeQ+*hIrW!JW_y-@IfoOUb;iAhTp*o3 zR=}}PJ2K9}7qYiO$c*346txwu{_n0}ACh1Tn;pbwjB z7EwQ10;B)N;$7+1wAaocl-KkbOj0;zo$Nb7W>^Z@S6l}13%(<# z;!2{mgTlu4Slr{fHJxJd6%9-oC+?Fmf9|4UXjC+T9ceu4c+~abXvY(-OSCVn#k+Us zQ=^na@G&3;-*25ppP72%w(3=4w`AVOD!ktWg{L^b`bjbsXcp+Ia)cTJql2f6Bfojo*0hx_BQ&ho9-u7kwW8^ZcQ$(|8Sy2;4$$ zskhOE2ZNE{kUF>*s6egba-nU;Gpm`5&-urxmK;*ThSt1yU2@-%NYz^C$>Itu*cZT8 z=Ii-aTYuadF42+9hpwcshRf;;t8DF$!PaMMoql7T9n0NZKn6Aaz6_~-!9@NLq1C$GBPAAvzJmHJ{tFY898jO)H2J-` z8{gk!|H(ykltdM`>|BBLrzw;9xBkFet04qmx=JJ0G{K`ep`gidI%wci*lOU3A}(;8 zo-!#yOQQcjGuG^Z#*sWfaIoGUvG<|l^sB9^sOEFWO3l-g^ndsU&J3M}U*AZgXUvYk z^A0UMt?ag3PdMb;QBwU~Nv3`-39s3G2OJ&UNsLlG#7r)-`uL33P;2Ee_@+w@*=|4} zEL2TwoX6|t&WqQiR?9gakA1V0tPJc)YsNiSayLjHy9#6V}B_7t);dGw#{@_vK zu?e4v&3<+#`r~UUWqiS<|*8slMV860-hYr^JfQ6X?%Q3oG2;B{v|ko5F}{G*Yd-+{Eej;-b-cgDnWOQ=rh(Kolj*yH zqVUeQ*0k$oQ(Wa?D2^zPA^jFt!d`>fWQ1aOSw~s{3Ub~B83q6dz*y@gBEdLqu#8e(}SaJ}z2?Z_1vE-f#Y+{}m~S_K)VG0dZ;aT#K+HHTb3R zL+VtjisPdeAn`BnZG8dW*>@LlPp&&vbnha5jSaL)+Q56-tofQaL-7tN z+0FQH=6Ov`SCo~0yNu85y$4@sxs&Rrb#UuKoYncSygnKYF~?U9a172Jt1f!QQ?l_# z5!^d>OIi}bcad)b^d(?fX`j zh*sX^^JCVBP?-HlTh7%q??@BuyBK=@m;y&H@cI>M)dOYU=X$)f z_ks9wqc0u4*$mc>_s3SxCs35RACJ*@78O{wcB=w`mEBeoU4>pUr(yT8?up~DC79>N zwEi?iGxGR8;$eFr9`o0iO3poyMC{IkS1O$U?9-Mxc~Uptb80$ABVCKWboa5xVE-!+ zSF-&k(RaenewL%3vwg{?oXztNQb!Km=IqIkAYfxgztgSiU^PPz4e94V-t z#v0xI=)7AYc((ah)O8{6Mg2UULC~K-5-xekc1%a7;Pt7buJAEnr+1QTnl*9_kI7^& ztSlQvlZq=LN%uDxx^Wyy=Y>wmIly~Pea-!-e)w*3bbJGZh;4XAY&120&WgKaIEa^rHzTS;%3IEwbpYEZ+kPGlr72ZSk}u_6^hMlUFF(3s;~hLJz8jv}$oKoNg1yMc;YzZa z8;Q8jn>^65=RIekjcGbw3}Pq-ckBDQ#(?l1PMPE3%?eL?xlP&pGFoWG7i!k=3$7L%zRH_x%3q-|N+V z-{(2+^^AMojmL@;2wX44J~=VZ{RY{|K*jz51&WO&#P3M_!~3Ev?aKZR7I+? zK3!rcYSB5I*4YLpVl{DAWdW(o9RiD96Y#y2jN_Z%!PLbM_{+I_4X@QV^Nb40nYRM^ zHuTO~j!viK;>B(y;NrOw-Xu_MV$+5pUPlw%E&1Htle4vp$;@~cRzB%C8rj~87jiqm z>Ni(mWH{}3k!~5q{A!_`%!ytvT;(Pr$f{ii%YDlsT#R~ev{RnEC~&9U4$F^RXWpD0 zPqx>-g|In3?0fFEpoOjj+v`%o9Q5%McDZ!#JB34?J`>mI0A}%$5h!Y;C^>iKH9WGK zkh|Er!kn-N9FbtH2^AICtb8szKx@A7(mjoP_r;R9e2Xr;o>znQh$={Z<*Z zRr%uuag7kzt%*xa3c0SQxBTOWcR@KWz^1%>Xu77&n|zvT5FxuY*$Hh^Nkmfx_(bcV zOhos_o6_=Ieo{Kh3R0c?08~r-T-xL(?L8T3D0`<9@ukBnbB9v@vk-l;(nP-i;}a@ zGc#c1f%%vFNx|u5Y^uBu-09W9;=_aRZcHH3k@O_@dPblY-IQG8jnvCp<0Z+ykj)l$ zFpkpk#V#Yo1k+-Y*m)wQ5Vyu1FIH-YaR)Py{nbQrh?fPw-xcKMl}F(1OX{Fx?<6)e zqXA#!_>jw%TyOS0f-Cfjfo%Q3Ke>>4&JVm>$zPMBNCc;gq21V>d0IjJZ`Nx%S(Vkd zNq*T>Xt`sC8c))h)mftf4>TyIWKIP#hyKm1$ZF_u?O{JyB@wI5Q<$eJagcRE6*m?B zhE#imYNd{lIj!O-{ry7lUO+ole2?5^oV=76|>GD=2I)aHwS~~wj+3e`~MwS_L9|}90Xo>X zB9S=kVJ#?k`r!Vj{}K6trO;np54ZFwpLt{6>YQ)3R8JQVKF{ok8&7u2m%{@`cQ%o` ztvO}216zJ7kC}YfPv}{_lIV)-6+ROarvOI#nj*5AB1-N*c@1A2ALrgTpV$amOS1>A zd>MltcKHkQUs^~DAKY9>e#w^e2d15c(82<2zcwG%*^lOVyHHG(T^_@_veQV0#d{b~ zn}x34iN`(Lt3heXdVKVgh~UMv9Hu4q9(eeTAP4IU;h7omM(NYHSjO%z$gR|l1Zaq% zE6U2u(^|@t%oQ_Y*6$L>LE*y?=Qs-=7>p;qSq;$beF4jRstby27MZ%<%YhR<)RU(B zUXR&eUyi3>0%@*~m>vCeW>wAgzyrE{BrwX1m3O)dlcII-I-fzv1M zZe26g7qWsTvUY`(8+j8y5fyWme6y*=u=DFL{)W-C(~PY+!2fzhk+3t0;dIb>W@`!E z11po-Sx^3LB55`a+>b3oEx)?)s?`Mkrfb3_IZy0W(F`x{1u)N(qp*!YVqxGO zdHr`Xvt(i-RIFANW;5kAU!$kvj*#9z;;5i<1srw^!^=YJ;ild#X7uF@{Ni*e1kZ0^ zk6yV=e4c-2R^^RA?e|@=TWlMI_RhdXkLjG!KDiGrJ*HTDo)!k%GP{U^0XL_1KW8fA zs_~!#fq7QeNc|$6Q^}RvV6e_e*iB>{2)zCVs^z67_Or|ID8bbaPe5P(0>X3Ku<=z4 zb`nll|D1xr!HTd_$u~fs>m^%k!QGS@S;N!rqg|ureI1~nmxl#R0k@w<=lF3MU-=`4 z!OYN>am^o3?0My!kL3irZKFSt_i?}yh#H$m7|H#~V)J9*jU&kSp;p{(Pg zWWnNm__{`xFMWZ&x#H?8n2z7!$q1hWW1&`OYMUV-}OW)4rqJ} zucLq$`;_vNo%@cmixOrLc3~Cp&&eUxy_DCI=de&{h zZIa#E0~NL7QDg(fm-7uheDO>niQp0Ic$>J5N`&@d;HrQJ(K4%*AG$L&EtA^HpZ(9 zmIN#^{W~=ezF(uW?2Ww&v%!PziuE_{Go5PALhWF??iIY!uA7K>uxvm>AXM(v!NxX& zP<}58>1Vr>dlAy;+7=6b&>s5El4%)WvZm8nHgUikZ(iO<-ql32wX5sl6UTM%9ope? zn2i48DEmmQrU(-EMvsD{?^Q7~uu7c~~ys-xVOz#1)8O{8Jazzq-qZsyG+rv!h zrJ1SSE%hv@-y^XhI?(&g3Jtq=<9j0rbXgm~XmN_K!>SjVD>YOrw;9{W_U%X_E|yc6 zjYan$>9-0uD}RIHtYS3p^<3brucR7xYH>cXm`&*1eJ=m_vILOZ zesBw<`dw7(?S@pr&zpt?C!~(c*usrALIlBA(PBma+0<34s61*Oy=`NI#aHqxBp&%A1%i2kk>C7YG?qp>g3L@2{wn48cD z4}yankMZx#HP@=zWNR$-R7c2vFzig46_~m2~!S@+2n5rLn zP=^7(mlhj{BbKL6hyXfr#3Id<4t*u7~I<&9@W zeI@#lCaf$9gR5pb!X8co?>lI^7kyjpIC`0%v6Xi1{+0U5G%cXmk(hK9JNJJlGp0nb zTE{-Y$jOu^oVV=;Uyk#A{kwr!pE{D2s;1bP9XAU}ITL(fK{2dw*MPQ>RQuNU9Stt4 zl}OWy5?HfhJ!9HIcfYWK+ib0)JNe`-%I#BIkWO(SKixSMXnx^glG`bc)<`rI$H?X=qGVfFoD|pwYP-DPaunq;wjLHigSlNqZrNtuSLQZTT12rU zH`@-452V=X4L$)cgN=k8`>V=5cvc@MA6Oi?lMUYMNpZA4)C*5mXeV(S=W;h9|AQoHy8FF3DV1v? zN_mXTNLB7GusUfIc?VlF*0CPk4duTo4(!Trsmzyyet5cP6WEG-VH1@$B4X&zSbms} zY6C<`w?{sVn{<@Fb_>liJRjzE>5y>p+FlGLcJ1PNuEI%nP(1rX>NO)5OL@W{sebrJ zbPw?tuVM4&i=smz*M&ZlS;{Z?HZc@m>z?1`-Oi^o%lFw%_Ri{g@QY9#&&n` z#ONwm5L3@jt}ns56|dmnx`mAAN++TA-CYyMPMqgX8k7KjL`^|oZ&Q4Ya*hV?D2lJB z@`ol{Jn5V|$_z4!bF|2py_Mh>V2IRh;)R|rZMQ0T9WP5>1Qo-c9lLpw93QCB_8IOi z970nj+Y;%uqG-*>t$0whhvX_Yvd(%byf1~cN9&c^PIlkOFrp-z&-f2bV@fa3*>qu2 z4Xlkw!fxN+LtkNN9Z1?7?y+@T0O|6F0Rw#Zva2qnfkbV?sPC)4rL4P06ydU;YHa!_o=++#?8|s)`pp{tdnMwMaYZFzIX-N39>u z!eJANwdR}WndD@OHC4ZtEV`LMG&Q=JlM*V(P0tmVUuuKVrvgCMpYreq+2Kq#hp!tG z2{ez|g^ai6V$b*zIDF+CqI%o!`rffR#4MCz^m$^97W_CE4I`zj0hUu^Io<|pzIlWc*ns4=)N#1 zH(%kmunQ|)(8=?Bs!k$LzXM%l#(HraSLd$-Y+K|##>|uMexDM2a6@++>3QqVym>VX z{k$eh0=aoxAs@i6*+B87{m7b)9TQGmHpjCDhxtsJdklV6Pz4!ElIUsJb)imeE#Jgn zlWcs%1p5|k6etQP` zPgWG!8MZOUL$%0{`bwD7$wNk)=-X=6hMidcS2r=4`iNPzstqP3$&$|r#W1owLR{!>FR&;b2 z^J^x>nw(JpzW?wm@v1Rl4YXpRcb5+S5IYF3#y>{wKJG-D>owVPm(K_8&E@pC86;j; zG5RLi!c4A7R1lsb)=LbQN3)aX_kwi;r-5;Nd-~N{zBQ&fpsg1~S+)8GJd@*}<4!I? z!$Ac9aV~~G|5@X1#j%17Uwzr7%jd(C3v?%3FuWcN_bQRA$2tF@(E_H0+X??=a$OH0 zw)W2*vSF<@=#8~Uvn+e?n+^hg5$o_9{jq{QS?^iZWAxxQkHwh+f}2OoF<_QTwdR@SgK9Kjc_#rIyM$nce)7qjYydr@Ya*!?(j)pCNZQMD}KUYebF8n?WA*UPnXsY~xSoI{hV&=Hc+10@zq?lH1ox_2s~AiM)yibu#PW zJ6K^kpAF&s#)}Od*w3Z0%mIIjyFXToaP9GMB7c1`W8%92xy%+NQgZol>(yPpuNB2z zySXM~st`eTl!&2EBUzSky?i1kDbQ9}s)$EC>BT#8L zkHRatn_rJU*z)g2h{HZ^hqRei4t2W&c%si6P%n3n^6^be);4J#$(>UV4^k(fgX1Xg z;rYx0i^(eqLY53NlUNN{Y*UJtugimXgX0;MLr%iHp2yM|DA|qTF*qR@Z@xNCFspqc zyxf}(cDoAj`;qw|Z_G29?C@0BCpmg)1@ldUyFqiH3L?ChqJ}N;__$j&jI}w8M;#s@ znsc8rkFO6v!)Q5jV@(O{5+5}2W$8Y-v{ed!kJ&*|#z~-UtM_AG`!}Z**9m51N;<$F`FKlBL;CnAZNt|>s+^GBlT!RyyY+4DgG zK)`@G1(MTferMWa17?ZdEnz?N%xg`opGpy#;JJ)>-Jb>B<5h+Iu5RBt(D4sP$n0bZ zl$quaDl5aVzE3@*>TG1JYN#)(C#;^$IbBHl3{}~>3F=5u%@uD>Z3EN9cv#F~?Vm0d z`QbeC;zc#yC`#Zl{}3`X;qvbKbHxx?KZ0xL6cT7(HM?I7GcV0)cb=&bIPAj?o z{t{j;B_U|iN@qo#b7A3n4?O7524`l!FgY#}iT{hQg>Rb_k#Yd%v-(~Dzkb-{nl({O zjdC^NeQj4K7Fq9LUi4IUg^53Ln$Nwt{zNdpIZXY_#9bIzf<3v;rN=Uhm=C**(fnXh zay%m+0(Jvmc?NxRT`$b!O)`ogH~PfTxE=bem327j^@(TiXQVKLp>(b#%^HceU#I%l z-_p_eJjdzX?Xl&*^%x7^$E0CFW;yh$dhh~78ig}XpKr#FEt^LsZLEhwzEjYyRd=xC z>niYgY=J8e$q6Q>e`CZQ=fl%&rFe`@9;6=~$!v3?I11V_8zuSq<0ao3LEIu7E51_` z+%=jA>7{%~Ia7cq&d!Gg)gO#gK2a@fnlfRmwoWHmMOE-*`YJTU?Tz1Ks$nmeIq-_^ zC(BdQnKW~8G;ysQ3E=L&U9|}?X*Z=fie5GXk6E{!T(=iTA-~*l$aHamvr-?s`FM@V z_)f|t4hD^44t0nLZz33$FTy^%L&*9Sg&^+M55H@ZaNem(h?NuJrDc}mhkpqS@AhUo zqA89}bp>Oy_OImm3?5s>y94KB=(}t|a~4Y38IGc=0rWiI74;OaUA@0T;EiPN?M zE)~Q0u3cCvbG+d2rT|tsz!bW6(*ESz_#EV%RU&(XOW^W{NzB0}ilbDU8|;P_KjPId z557l^qSm85*kS_Lfsn8VH#e&bMmyE9Q|!*d2qW4L<1Dd=aS^{I?3&oJ=?1%n%i6zv zD8(!u%mKSL72ytSrw@aY8^`WqGOc*8{Hxru3Fue~cm$?0LAZx4aPqrT| zW{A^7^z^BVu-na^O$H?o${%L>?PI>*ug1H-U^tS*X^SKL$+2ubwtMI}N*K@Ga!oG* z^X;zq@yS7QOMeslR`nWaRvTg~yC2~EHPzUwi)vn5Cls(-q8Nc(ZH-a5`6Z zFXcT}k1{t|!P6kaGb>>BuhA@7=}&H&IIvx8Ame$5>dsTSTalsGp=9%ng^YyqGSpBZ zN^ECw{qtJY{96mQ3vVp0@R-QPFXQgZoQ-F1zD-~jhsWSYPzA%Il#u97%6p9S8i#AG z3Q7EsEkEJ$3^?&96<3&+!{Nz?dH=Q3H=6Ez19ouLd=gPt4|&7W(W#MC3rj6tkGF)& z2}G5?Gj{ha;Msvvob8YYtxx~s#U7-)CI50DtJCgB46MsQZrMCEaF$}wXiEWLhMYZ@kwywolV^8&r!HE^JB0SQ>& z0z=FsNUWsX<7Pi4e&&@f@|)kpdsbb~T;eqfJ&@}fSD}^@1h0rHhRJT5;E^8nDqHg+ zxt@9@qRri5ER~XC=F9jB`xxiG@nvU>@+VuAN5Y&xF6hYJ9vtN)fLhfPI9p6zz;6D) zuI%!G`CQLx@P!um@^lQNrEyExbDm+$`FvXaNY5Q9rh7hynkE&Yrq&zr2YG%xL1sou zBVB`NXjG+~q?V%|<5fs`NQX~8tj#2UVtb~TSuk}9GW+O)XXduS^Se6u@6_AmAu52Y z&!0lU&SaeN^&MEQvSi|7t1;AJ=x+33UvWG}-zzbX&al(+OkPuZSiMxfo^1<5ac*bm%y#ydWj zUDgqXeoMFGJ-r0XWW4dKx1xeCN7uyA-U*0eqa|$>N%cc zkCG*7SSm&yf9Cpc^Sk+?6X`sy&l$;fSaRIUxp+2LHHygq>LGb$po+xLUdQ^Y8)3PH zCLY*UNP;KW@h!IUK(QzlPvbgN`$N|A?pijYea<3i!&!Yc@YZ}1w73C+U+N*5sdR?U z{$__A_R0&^dv-D3-|dDMyD66aoj&m*87JW#A}_5)DBq511bIK5uwO(c303ap*LiW7 z8E2{yWOuI38Qn@}XxaW~M!j=7DLYpU4EV5CoX=`qnj?EqXB{$|N$2Ui7bmgOhR?(^ zIGOp?q>S(iIg1OO1?)3rJDG7@966X=#p8O!1ryK@cKHzzJpWoB z*?b{2=VY*Dt`5g@{?iKtirmdU&cob%=`W1XU~ucw5TdlD5HzPtpk2?Bu+yPRV1GE~ z7Tu#e>ZM#KCf3DSn5PTb8jG98^^)UpW^8}gV@Ob???l~gMd(+T8(DB&3e~+H4-0ry z`;Htb3kNQ9d6T8-Ft{p}S!JD#|MkGAt&~QVMi=q;b_lY zLX%?oOLHV%; zZ9b%hY>v=*+R!}{D^>rt;UPEp68u~uE;XX0`Grik;Yw zRi|*bq}N}@F`Zkp9T!!sWg_6g<3mM-<8_?&eVq{9;8(98U0`@MZ zZ$sk`znDv0FX+6}@vI3G%&aJ*8J~~3*z6;*qB+|@5b#i_@iZr)@<>|qkcC6|GqOGm(f8sF6-fMD{O+9`>40% z&2x#|ng5@s^@YC7>1xo z>OYArkHt@hy2+eZrmTTAcPOSrTc|te_LLweiHpQEMheZBo&+V!sP6DIP9Oeoxj*AQ z>7e}h0aI>A=jrN2GU#@Xn{bAXy)+GbWEGH2aV>B(auM8Bx`BP3*TLBUeHhDmHjWlG z@g7MOGd^4f)-0OqT8XeiI?E{rAEqC`e8DKeduLB}huS{w_k9f(ecc0+%hO=ifD&om z!euj0w(|B#_zF3k9su zsD5{1r8y4q2_+%?h0MKJXxwS7r50#PC-n1OTJWZ|3|nCa!jCM@(P zzTEvua}!$>FHbSZxLw4gt%F>A^nkH)nTq}!Cr{)?mBC6)S^g`|m%^9&0^tMIjPYyk z?sGyftdiiox8Lo^=tePQr#}k2JnJK&k5Y5$Wj64W+bITZbz69sH;QA8hQAQoyb_yT z3L*L(g|O%ONaT~BgpVX~{H?1qKk*KogKaWfm=g(9H#e4e0blF2g}#)Gw5U?AvYufP zOet3;deLRDRrxV*hZ3E4`ggq1r_f$J(d8v*rn=yB;!1-34#n)d`LXaN%@dD0`U%Fk z=J8fdyd~@p?;2SGWg}IE{i4bbrSQABgGu> zPUov}%_9t5IUZZbOeM-AjkZ*zyN{&|P$PMJ!rk)Q)RU3P4%%3T{9B zoz!XHW)shTgc>!<;p|mA%kLgRInsGqR#?Z3<0|jA^9vMaA~jBYm$xVci>}AH+MKT~ zP4f`Qy!^vo+owU4wckUKO)@k3u^*|QeSnRT+{=3*B<$dVMLhmK*VJ&7!!IDam4{-w!8(W4&-uW*pwSe>;hLD~?VVsNm(z zePqOk)SQH?*ZH;slq3Chb4j@Oat^RY_gsU~3a6 zN2W05?R4k7x^oB0m`3p7lwt_1allhJ&Z?l`1e?C$5**`h+WzZ4S})QFb-PrEQC&Io zZV2Wn&h!=Du~nAwLyOK(3LIJu>ftZOXeL_bsBhvvi&eCZ{Hlj_UU?Ji(vQ zc<4tmrX65;8XK6~X;gDptzF0MU!i1`-XbRbhXWctQ;b|!EPzlAU8wrD4cBnpnf__v zj5eo7{L=&rv>cg5ZFKg%^zu?A1iY2KIJA8 z#~t+DH|_EWcIBUiWbU6Pm{e|p+Mgr}b@pImdn~IaB1o*QWfnb*fu7YAcaK({hwR)MqYNa|FM@WN=`iKb zwaEq78t~89z$&Zy3*UXpqI=Plx;Wv^S;ch)9XZ%eBFKH_%J+FldyYK0V^Idp%8neK z58-12pJ8}>1Y^eeb}V=Ff^^*;cAI)Qc_(?74IZU|WAwI@#R74(H#L+0StA{n{(1}j zIeENq7b))Uy|%`hy&>Ek_99p!G8T#9Bz)*~B^(}C&G*YL$2>{yrpYrSM%}>~f9-9D zYuvx$(vL{;n~`kDc?{D(YUBNxgP^&>67r6D;i8UaIR3mJzC?Es^=;`;FwLJidYag+1FB{dTiy#$jaI{4uac z;D?s`^x_i#mvDXGB|IFdD7g5wi0#%&0;^n4yguR+6sO(d1<$3sWvl#d_H#!l30|nc z$eUM!QmKkCOWwXx9`C<)l)Q73L_=Tlz-$G@pljnb-s>M!vuN_MW{E@?30zalw9cQ8 zwtR9H?wsE@eu4>GlkqIw3J57n;(2(`c{lgNI@W6-jIfWmn=rlJ$mA`>V~5H$9MJKd zTsgRw-TfySI;;%wytzN%4&3K|?Vz0M3({6{-(U-J?aA_DN)Gd-keTOw;SvKzXk zDEHF75b-~KqPMFIPjAI*)`b%%sSf^J+r`K%J`Y=7E`<3TN^Fh<8^-39AL%kbz z+-I_a43UYbJQ=4_2D7#X^B-)XoXm$GhnNk?-0#w1ZWk3_&+2ivkfa9gu-ZOTaCgpb zViqKY23-R1{N+95m~|5ycB+xDz-b>g=q)G>Wb*7z)3>4j^No1p^ANHitO(ju)sf&{ z5?0BrgrTS6VAf7MSp3CjGsfwZpNUiD_G=$mfzE-QZ2WLO4ESpcHN;n+)?yotu>w-1 zV)~_S9~AAQn5~+2hRM2`E$jePe#LeE?R-Q;kL_oF#H%5mo|~|XtTx#L3@Yf3x?+0> zQ$DUysC`V>a1bfW5jO)6%A%8M({L*u=eD zZ-CVpi1;3a79Q`#3in<@;N1*3TIY#tzI=jn^+vpfYdAd0)xaq6rL4loP|`3}f!Y13 z7T!pzVvC+X@L{qdwy{1&mJLgyO?sv9U`7~zR8|j9&sp&94%7X!WV0z-I)l4c!j<&O zbSy%HaxOwYXAjqPyTdLSZ!)QXP34ZfnWrcZGkd2gYdtrd?C4p{PE7YjFKctKu6ZeZ zwhqKPG2hASWoy}hHIKo28`U_5zr5y?SKj#9*=8;;@&HZR(t&gFOK==nh52vh3RceO zWnbSNfIV@SaCl8CWP~^Ke}1HR4E|<}B0}?UjDI0?i&@~llS+b7`~bGS=R@w>`*c2z z`sn~m7EdILJ1gOdyE+r~(vMtQaezgV3z$FURO6V^aUZ8_Z70t@USnSKoKeXcF=CTi z01K;3p`de{u-hT};8c|Rqn;F)u;{{AZDxUfIJvkwp56A+k{Kr#E9~0s@0*DV{{#rL z2|Xij!eeee{?q8^PjWV?lxP%oI~=S3%-lP?h+I7N5v+JCQAcJXzEM{NbDA^2)STjO zZH*M~lmp#G^^(>g6>)zYG^q*VLgsOrY6wYkyvc8jkwKbc~n6j6+J$%2$UAFG47B2s~n>-e9e8{;VZ0pxeJa8kc>^u^e zXBCn_{oow&9C4`lM)y+ldG~p{I3M-D_u%h^Huz;z2+90X1p1zn&^3-1-QQLT-NYO> zE>{xdXO3j!kE+9Yjd#LZ6+W7in7|y0!THxx@XbH%L~o`M>-?YuY?tfc!rMO~v~ena z@GFTZznO<-K0OJFo4xRl+Gd!vW;auOmc9+!Iex2ihMYjQJA*wjUIPVmT)?H;ZQ!ub z5B}8A9d%pv6=v3mMttWr0>jS@;ID zI=vY8%m^g~U$S9a)fuu-i-;q|z==)4S_amyNR!)6z%A?~(TF)?~g-+d>CE17Lgi^$***IQM!8rjEF ze6?*kft@#Vz0*(1nY*VkkOrF^(z=A?nX= z^5#AMnQUM?a%{%hcSRyg4Jdn^Uzl@VRLk>%jPv-a1G29XO)?T#B^` z{Q=nia~rX`f1lapZ-MUV$P>}yWq`u+_}<*RZ`9Z?5czNpTe&Kn9M$4>&QrQrYtWL}T3mKA z2|w?y1oQD0IJZVlaL8GP^=_NT^|q8_J9Do4NJW`Zx=eS`;q4FczDw=Ixx$b=VO0hu zCKO+`?pk=twXZ0nl{Zm|^&b(mlZ1@nH>50SeC)hn)YSOci?wnu3 zTHueeDju>M0+&7GaGI_Y>0cv*!eYFzjlYE8?$BS>O|c2)aeRyVNG_kaT+<}!|M+_N z%miioI16(?DAo|mtq&m=Ij_x+C=vAADj8o`R{>+~O-wYFSL1bOF#P56i5$6yS8{ox zFT%WD)wr05W=n*P(ZpUL*zJ!)9H}IKbJ)}4? zk-c_S481vg35TY(!Xvj9H1=`?S-U0zW~Yya%4X^dwVk#KMO@9p?GFpVW%(BTYo~(X zS%E)mA2^WvpWZLn_|5@7CENfn8BNXv#obVQt-{QxqqsYhmxlFMw2`|G*O;-BE~BrC z;$(Y4A*h_Rg=>WFmIbz(&;g4Eq7lTR@&4kx7u*|Ab$vV=I8T?^J2Dn89a#+(BNw70 zUjy)~EsZeuND9a^l=F=JXlC5wL-XS|JPA`)vxt;@`v`iD)@X+>#a)r$47PpqgDg4o zmbs@^48N9^;&Sf3aGOPi@l(!wHaOS;gO@j<<^Mi2hdUA01ZVCGBPxzj{9H*j^!;K1 z-UIm%={JkNtBmS>4^l!*ro`)zbuqQz%XynxIN!q07Dv`<_i5DhJPs?3sR7;f!T5z( zJLxUI&kS+fV7s&u3F15n9l1^XXs$T@AMTVRXX4Kj_K>Ngq*0TtI^NP)J z{qR%QNHB@qEIU1^1ENQ8p3}$ebY6w(D@Vc+I?V|qZihi)B^u~UCacA zP<##AOhw)wFJRq0ZSdCU76`bR^-o7=aI#~rr!?TA!w8nVa^bXZjQ{H{hEYRj@TTrA z(vY~F?Hq^(yL%LC$_{GCHg`19)hUN0efOO7F4{pfLhypk=KLg^P} zS74b|2qT`-nRQ~!!<@5=D8BOVwnJ#AijYf5w3~nr_BfHgw=$@i=>Rp(8}pA#se7-L zJKRNkPTEvW(Xa`9yScsOVQEeqo$xmcG%ib`;e*Mz*|P$2WS8d#&aB4UcVU=19E`mG z7u7)tkGEPV19ow*l zj{u~&jNrvh-6Xv?fvphdG*rt=xGks^c1mf1+JD>)an28;u+Nr%?M4?_Vy?&33hv`; zX0_x?iw=b5uR)Ao9&XGl1b>B{c=Q|v!J~WrtkIwt|KugQPnJJ^0Dk70#Nb#pjF}_J z~~|F#^sVy-?N&p_k-9oinSS6j-r6O_2iZeiv+DQ{2O!V z4!O^3EVE@stgyFMY@q>~^)moZ@NI-OyPfdP+D2A43!xgQ19fu7pYoH=4949>KAU!(COoHxibm6KZX;G~LyVl?Q-;*fr z9*WPwyI1caL98@tojV!J_mvRMJE1vqFay!uPlVp=o>#8CJF9Oc z1-$uU8{E8b76TIwPm zJFbTemhE7VRV2V`Zub4l=#_7ngk%qlCWYBt&%nv3+@A_m%d^#wLu*C*F!p~1V!U_I zknf4r$FxFN{j*%9|6}lI_*bx7ql(kV{Dl>glX1(UlVl=yt1+;m8(ijw;Z<4fV!#2d-5Bk0|kV<*KpTQVhBr zgM2|O7oQd@gA=-OxaxBcaSB_2pYNU^Tvak#3Zg7 zY8AimZnn^Q_kDstDhm}S<#|PrntuofIVlPLG*z;)ypu5d%{HM|?L>|zvWagXKigTP zaHoK;GCQ2CHIHYl?n^S&s&w96{A-NlUIYleE+ZbE#eU%(gOOump*mp6>co=PQv?Tv7i4kC)6Xz{HP`vPTr0la(@f!-2{io3S7eRkVSU4_-EEkMZp^>9{B~E z_~~~k9@m`M$3JhWOLQ-MfaZ&CNHr=B2QI3CeJ3OFIg3t``#70VdU6mAzEUKE9^B_S zC=2ym&+WhbQB%NtJUea=5%-fu!4led=z9s-krtX0S-Sz8#VOBe%G=H(_r--Bw#RRV z;HehR$;!i`$m+y=)aj9g_eoX(YqJsi`il!LUKC-wU%7zHD2l?3#(a zgWE}mnGu`h(g43DbnvF`A(s7|N)~T5K!(jO*tB@OAn&o7X(TTM!tQdN9RV#M zUZ>8Sy_7BNcyD$t!BZ{81jCsRShimq9eGUW<7fMO5ZXiW=+tM(GvWE}ef#4oXJmy;usC=J-wzP~U^+(G=cH#5f%m2}i_x8o{ zXuD@0UO)5-{>!XJJRmpVcd|EVpyQifmXkR{=#F zPR8?7Dqy<36MyTJYAkQVNlqtjAkv+K$8-Ex+JgiYcFWP9?!WRVAx; z=OQ>3ZWG@7R@!_Wt+B2rfdvdIeAmu9Kbi6>6^5p$?|lGH4{roXuM2oXb2}*+bmh;l zcmp@B=^OCqZbSA*XxH+)gLlMJT3X6AnF z0^P->c;&r3c&04FcfC*bcUxA;;r zy6B*70ro1*hn?;R`Rz+-CcGg~QSKZfGZw5ldlm z-yBCS-U{SQ4tJk7U@Vx5QteM<_hM|fYA^XDErTkxX5oRArQ91fG^eiR060pf<2~Z# z@FIudW#6K^=!Qk%xOwJtqI66YiK{F@hj-9-U#a;PytZCM;8FF5smt?$Q2lp!M3?|J z?#ke4ins{1zxoq7IPgOo+1zHx_H+Ki&$2qWPvjT4%=g0oNoxp-{u^idG9wmxvb^xz zycQ@5>*IaQ$`nv@@N~#G)N(+^tPZVJ0G=dJa0hYcw(7dZ>&=&H34XDegQI?jijreR%%XJP2;Q zjEB^}6V284S(}=VU>fI%yMBFw-^VggNp(0mZZ3~Xln(HJ8Bq)d9{K?yZzu-Wxai^= zn@oNwiiC zWZX{SMf{>z^O+cmZpccIt&fVqdi)iz=QO^5U6;2cZ=q0rJ=r~%MP4gj@?54-d{wVm zjuw^$;D)qD7_z#At**6^$U824KhFOaJCp95{QT71#Vr(H4p;UtR>_OW_7Bb6ov*zp z;6x%WH>!rYwU=;~XFD-*$z$%G`U4h|OY!O0JV8S}PS#z2| zpk$BiPxuMB&5mFztj~m#-)Xn_#{{#{P0ru)qMhpr7GSKot~`Cd4^s|8kldBdB^y#W=}O5kK|HTK;rCO9x7 znSJaz7a5vUtZkb+2an$nNj$YuVgAIcIL1I-u>Kum+Pj+%jcpP5s%SmPayKu`t~7A7 z8v$?78$Bt;xPi-MK;%`-pl;z_I>cr`V4Wq_9o-9dnFi=n^=LBQs~l?VJo%=a$E=aN zH}q%t0Wvz@hexl@gS*>(v08o)G5MR!#=CYx=L=7~lWm3kT`$nq%248QN*3Kc9?qX= zNby)1^b?#PQarvGnu#N=Pm{~%WYPW$oFC+BFRA&`!RFUUpwfX*At!V0SSJ6sEcKgd z?YBZHy92tYyZr$9{4ih!#VDDmS&}I0p7(j*5ZRI~d!($EO8ULKpWlCQ z?|t3pea?B#bDoFPhx0Yj-T5;1v2LU@1J8)&?xtITV6?rQNMh%@3XbpD8i0#dEkY&1{)~PS~q{d^`XzNMQqyO*aXPDj-#Gn_Q zpim79zwamB>v_ytORd2XtC)v*g|BG*ni*vGbiO7|y>d688_{b~d{D}Z`Kh1sz_67$@J)?KT7X>S}IFe7FdHm)*n+8>Fyw`MO zjw#*}?xC}D`>`8j7nnRU78g!00F8$-rhzMY4ffty-dJDvf|@fA^^=!`WX;?#9Ps-+ zq=)ZCYsz$Yg}((4ZUn&k9fjzbFNSy4_NIrsc^#VJGr(Pz4fI2yA-6i<6SSxEm|Y@2 z9bJQc=$mo+q~B6Uv?x&#TPqC^?rI5Vniw9lCOeW$Tiy5`wJH2RvSlkjGhV$h6_1_2 zPp8g(0!5k#|H<6L59~HG-?rK`dtnvk_hA`xSuJQ&tR%iVX|Yf*$%QO!L>zZE2Quck zBFA_Pl~dce?(gxS$TD^}AMb*w6~^SWojP^=n-7R-maPKYLcLBhaaXlLBrlP zXzb-d4}3|0l$>G2$SD$=+vp_%GjgE*v z%H3d|2J^QD;7+GfXwiC%t?wIYwRwaf@9!n@yjSPgL?K>G+fAqV z_alWW=P;@`ntoUv%yntrfl~~>C36elNkFcNt+Wgdc-IRL7M?@JKhdq*4x-6?(?zX3&!cPk8t=`or!Qw1a^oj{g+_ax z=h;3j9V`WVpEc$Y>~}@$f!AF+Ylb7>1T35xy2h5^($fO$m^!12dhwH zIDx$eoml=|NqpLOv9QO*oyfmItoF!(D=gEdRH=hb-m{IfU4oFgnr;2^yMSw4N>s0? z)9y(H;A4s++p)ZE%{cER`E&3$I!kAR=jGc-W^~aPr=z$7sXt)%ejc07C2vVvkSA^1 zs7Oo)RER7!`1?d%=4ZFVQv;u*^?<7N3>=wzih8uOJN4ln7#sJ6hA#cc-PoZ_S_a<5 z7dxvUz)A+{`p4s+f?TllUPom6+etFQ?DID;Ue1GB&rF2QP+fAvF%ng@iy;2z0MyCL zp-(Runr4h022(V7Y%V_^M0^<^OOo>7{puQc@QBCb@cxHk*q^INwd!D?aRzaH(2SSo zq``Z^dwkrbDy}U~=h}B_lOwS_25|=KKY!nsV9;jFeH_v+hW2_WfQH6VvQ>_sCHp(= z!Hex3^wG@2T$SM@(a+mF?i3r9$e~Lk=@|1eaJV_l^hO(BD`olxkTLEubaNKFo%G*> zYX)@E2&?DZ`)BtczH$p5oz(_PcGFEC?Dm)B(LY|klIVEez>`dmZIv(+J1(<6(^yZW zsnrP!cRa-tx0rTxgRW@K>rla6P--FdZh?{@9HUjXug<3v?xJrabO+zlEXe z)J7WjIb1N~?Nw4ZNrm>f6@i1<4vd?vE6$l7&Yk+b4CX2F`kCo93$ZP64;^f-K)UsP zVeQyh{A*bNW+9#?FZ%MhoBG2Wt-_+|e_y`BhDm|F=S@@JS1*;0jFDg>@g`-YF&mBcNt77Mqpy+t^N)A8{+ zAph0_r`+tIT0PsiEUz>$&Nj!z=3UUZe-$|ssZO7qD1fo&K8P}yKaSIt8i=V*B=KRt z@SSrOOb+(Mr(vCR!-Oa!cAle ztD%k8n?M*ihKT(l(Pe!ROv%>3i3K^-;Fh836YZH`SW=8d`UuaLJtoiOQZS|?59~iR zLjO`DyfXefOi*!vn#!x#+gS@`+S#OMbPJjkvDtH0DO&5Oicc4&ai7bFlf-L|ctyGa zZddNWYYTP6@dd+$3o38Gm%a}$qPGmzN1r54zf&dirreDgBDb%_lTxxf*|4 zktlR9)p%*hI77xQyPP7O@;o-rq})L9pGKN{Bu#LmRfFv6$-&n6G`PR^t?11E@0+Tv zvrXgXdQ<;|YS@-^lAIsR*Tevug(QD8kH@(Om!kboc57TQlDw6&BLZUT&G3gfk zem8->EUALI1u3R)!Hv!-J<6@Ka3}SC0r+G}8635Ef^9dN=(GNj0>Odnq@M77?B?DL zu#ok!+s3rQYMn(SUi%Y`>@^`^9_7y7+krvAACm@b@#+^#_EL)++q%4Nlu+27oiv#7F zsK4|*PO!j)46JpK>_K#evoPbd2YnUu7<>!L;I!I3tUk@|wTm@P`)F68buqwwgWF_R z2jYX49C#JsiE4K{=v;;E+}t}X*Kosf4EWInDzJteE>)*H6AIw)-X@V}9lw_hU71Ac z7XQK^lPoaNl_IJvU+ka0bl#sLax31GTG%O)Ayv}w_6P4@?G(s7M9eg>PgD=QYd6Jx zi_g-hA*iF;F`Y3y9D|zwYG{(wF~Ylo@6eOt4CC1S?}o8;kPW$H?BZrzBS?ec4F$Mjj-q&t zQwm2NbjiC5j#x3U0WQiO!2ZSBVymOWg;V{#;l$_%=sBkxDh52jt%4|8HBb(Y_?{(x zQ`wtqoCPt8Hn=mtou0L{=623D7R4Xn>*nj-!%30sC^}1{9746FO{Pj+mt=~4c71>v znNd{r!CFB{b11o$Aw!FH=R!>2CA{}tT0C2Za%r+5V3^3)(2r9!OpcxM$3YGypkuj_ z*fDG>WPE@NIVKpP578aN)zWbPf;hh0H*z1Ez17P-yzC2N16C58?l{T1Iv#- zOV;-fM!kI{FnQk{Jnzo#n3$K_ic~F9#(LN7Icc!@Zlh?L)&i`gTSa|0=?c{1tXkq z5}nflSTec{ObVm%j9nuYZH^G=uee2Sd8*JKtKY+;%C%@CuOgONa+iBGU>{`E@Hkbk z+D?>@wbF%WOvuImmSckTUfTOffv6ZCz{+3R;!z713Wu{hqtC-)(PLu){CDBh+}i(R z)_nGT++-0+Lj~<1Sh|Kp)r3msP#JM9OrOoqp5LvS=FVe$Y`$qTBz9!t0H zb8a6peLauU$b>AgW%KzzY<8WSnEdxX&kMO<$-}M-jWoN`n;UjuKIxm`AgPtE{Y_AP zq6h81^cc?Rv_KHc+}ysV5~7z$;}F_Q1Fy83(uy0&N0q8@Sq8weeqN-C&6^7Be&Lpq z4>peKq^*?U^g#hEo66&K^%*OYa$S=)#k_}2j|aelN*R+b}yUF{&ttD1QzA9I%0{8T1snM29^Tu%vqyK=-Z{B$LgS}co!NMj*b zz324?mfTLF`Q|jH_%y*PZ$DI(&Z6CAQpD@nG}84f5;go-#_Q#g_@pt1-agvJRwm z3&}#R8Lf7v!N`F3ctS~0yk~C;_iC;I336vX_h})N6~EyABt=Sr!2OCbHXM z%W`-bOi~#@;>5<(w0WK3n~S#%Bkh^X(Y&Zr3QP z?_Un1I@*(Mn5NEv`6veH-N&YrVYGVx3V~%X9xH*RN4Anbhi+h2+Xpb(!94dgz3HUkqeZ5x z<;gmB+h|%;0E7D+7D>zV_4ku>K+2lSMzmv1Bb2(HC$g`CBs@~_5iiUSZ>BPX-w0IB zjwA)8eEoHakOIxI{I0Vp+<|2Oa7EZr4GXj)@Jn79ov7X*+Vpk>iIC64K?5_uKw~T3 zvL7Jsda1)LIhrKWUc}=%SMMc!S~rpExPJiMZ@0;n8vz)8tPIYch(+h(M!F3m1nTad zL_S4@=CFH1g`jO1?4Tmn%)QGQO*sKs^?bhkx|9{T%5N_XFi<36iN!b(6~$eBq=kAj zPN3TAR$37dp1fypB5eBoTr!_pUfz}bLx%5@qrnF=R!361)9uiqypa@^hT?8^wLVlcGJarA5(rP@_27N`Ulr0D2Rv2FBIB|?~#Fw z6ZX~51@|L<_(QIfT4!$O-mEEs<3o7t$7&oQXSWTa4ugu|%-G@J*m+ID2|I`Mg$h@8 z7glf#=899vZq_pwwPnG9{eE~Lv4iGiMsgdcD3Z>1PM9^1?Y-NlL-Ryl``YrgA6&O< zr;qwGRr|bt#POm!b|n3V52F@g<_x}PZuvEgw5NLF!?jhgzCagOU&^Fe>tjIIZ!IX- z@VfMtf<0tt+-W?R&;;X-dZOTX621B56Ff1VMJjxGysPXrK>2Suw6x05G(vn1?y8jF zQ!D0mZ~K%8E0R&0%ZGw1FHv6HM0d6?<;Ab~7z;{SO^sMpGCR>GBx=HN_8WOd@IUd0Dtq?nG?= zree(eELdJ~0sDOEpz%S6Ik%3bqPX$DC7#~b3#XE$TSw8@;BtscdzG?3-VL)Ys+l)} z4~Dgc(hZ+21@bA;?GpD{FbB?mSgO>w{sH7m}tu>G9M2nq7 zVg3yaEcyUi)r&D=mNz}KakQvqbbs>Pg5@Y-0eIFriEcA~SY@6RG3a|*WSVM3b3+<| zcwQvygMu*3pafoOKS1Y6%zq=~jbOlH0}_{;gUO;aP%|0;X;XO}(Wxnp#6|2X(Gl6N ze1gSQWwd^2gUG>g9hobYiH0LHm{)wNXbkg4nfOqOq}XOc)6R)>{i6?{XXHuzP6gn3 zd#2^Hy+^7&RH)76_fWUY5jvPoPk5~rRvlV{9bJ2A^(jRXM9R=^grZpYVjrPt#%VmT zp@ptn9F|YKuQaED+vX^BR)J#bWJ+0$6i&a>|Q(ey0<5$q!H8i=2g1 zHKyHC7I$tKE4-Mpm8?V_%X9VF?RlRcl#J^VsNZY?e@hHGKMYPW zYUg>UR8bCI&iO!HX3XMLmdTJ&1II|T4g1zv;0!Hasxj4ooW1uR3{N_v{JT2%>Gdt8 z_WwQhr6EhmwP**4FV;u#JnY`Uyt&>#hJ!X=L56X~JA5i(N`MlsD(aHOC|Oy5RDI zqvTefK{V#>J6KRL3UYFh+jtCOuBMaF?%$}Oz+0O?M`|?pFi_Opf zG!J_=j76V-Oj_g^16~>jAoF(|uB^xfvud`3Sa2E#o^OJhi{3b1Ihn?O_za)l7?H)- zc>G@ZGy#{l=g`6yL(|}`u8=UW1pgjk_?3$xHEGF+E7|UNQX-lSYNDghF6DO2`weeQ zjc`lrH!yMZ1^1~gIQv;0OwKMP7v?qNgxEAFPA|YaxlB_OAIqf~Pa+Zf`FcG~!x4?f zX^Cgl=?FcIVqmrr>y^)!gK4NUY0^u>`B$=7{?%2iKi^Firk&z$p0E_zKL07XeYR;d zBtKI}QA@4@dK(6dE;jPMAD1pa#BD!AX{_D~!Q)TQ$?X6cs&OtCrp>s7OPTM)2hnpb zWYbHqh~aDWi0)((Z4*qD=>VdkGD-CE|NNDq@m|tA?*{Jt{Q(kQo8f=Uy=cvGJyF`1 zf#j4O%fFB-gd^@ZL^~hw8u(lL--?{p8`IRyO%SMjnM5=Np??VTl-m%9SEjYomiBDH zxP}QVB02}(HKf7HuUas&+eWgV9X;KN&|c;PL*5wGnM8%MsiG}^HIViFAQYHM~0DMc(fXz_GW>;CPi6u9%lZ z&pdY(v~Kq$1wMR@4zs%g843rn)2lSAID?7=eTp*QmC8@y(qCeAC$4&%s}I%lQxEUu+JM#Z&p7+_cX<)?X!1f%ivvbA;)8R!3s$sUnysvlUx{q{Q_` zR;GXVdx3)#U!&!!V#)LO$>@ADANGGu!94FK8aU95d)E0Ea;Tw1?{r8t80<#4p#P&f zu*#_*x%o{P=D;w1=RHq&(0gha?L(9;CV!Z|G!o$T0pfQ!l z_^+idWM5G#u3eJ_zQ0{DG_{**-#x`W^Ib18`SVLsqqU~YC%ZdFQFoULu-?2*q+ZFm zBj!Cm2P zh8A1XdQVEW6mT{jXP9yGkqt~Qq9DS9T~8W z?Xrs9rNnC2mARWYOGSDYdA{0hep>>fIk^G_;gtSsbc$}i>@qN zEq6N(TOchSWZ=TBQ*sAi#!LUJ=^1-A;qIk-sbGmB`SZgOn@Sq#)4<2c#Rr|S-h$0d zF$;v;N9HZ77mNKo3Sh*l%oOkc?}@5wAK@$MNc!zwJG6b>M}`N4;*Qb9P_WJktIb>J znT~patWPhjG%3Uza<5^U?MV{n!uRCcVogPYa=s@InNW^lId$|;xgnP^M3ML%=W*@l zb&cgzchT*mJGdD?S|DsSU%QR5`Ge%r7OHO#_`7)?w9?ovPHDFZy0UD#*>9s${ zU{_E+S<<%$AK2x9roJtb_-OjW$et7Z(IC&CIAQIIdN7jO4_(f_xW=OtR@ksRbC%=w zd-^`X$CLr2Oq*)r|o;T4$w^o)eN2J`VmI=~Y%4p%`V^W_^M7msG$xp3m^5u&4X z8a*PKpk?1ZTz@;BhAe1;&mId%?~O=wFDnA)VS8|l8>jM;44P$%WT_T$tZB z5v}L3+^620R36f$oy?p1;1*Yr%3C)aXj=_ww;rK`Y8W+putIRgK9O{L$k2J=x!`Bb z@ZsA@#k*p;sf}W|oW2D;p0$A=Ng}mHp7j2rKIHeqhoUfnKYAOMz_5-l_-$Gb^$BU@ z#;G1ACB5!AtCnT7-B^uxth{Ik>WT6|i+PYeMFp)wSiLG#oSNkz#TzS-DV(wEIdE9luHR(ApYs9_vGt4g}z%t}>__6HM04SD|v7-h;iL2gEX5 z-?`rk#%H$T{_Z_gVWuK63A%)PUpG*d_K;-1#A_Hdhv7PGfzaVw4eVjH+t;@MURX(s z79g+lcS$%zMtg;#f?+YZvVPgUqnV~ZuNQonCrjomF2s4mUPI0D%fzQLn*M!g&OO>} zE3$3o`*36b3X~sQPu28|xT11JBE7)?hfL~*=&h?UpLvr`nKzQ?&2qy~mTC2)v4gv2 z_6hD7@EYTe?3W_xINpO@J!ciEy6S-ca==|LSz_W)T&Cx!mvAEwe`W*GR7k55F&P#LjuJ3|JFPuq9G>>I11yh_I zqAAu(>fkIwEFrNEf72bZ#`K{!o2J7pK~DC-)8_ zSv#F@Xh9uh-ZI5>=J#$qaJW$Hb_g=B`(n6XDfkE+toYMB+-OUoANK6pD(9F=-`2==cOO*gY9H+{*`rJrrZB>S^1r#hizZ zEV*uHD7hVI+Y<}nqg`X_EBh^*3wr$#z+Bc;HKJ_V3vwZzA857b;!G z{c{+`JJf{53*Lh4{0I2=WjXxU6^t@0|7*&&zHnOW2B~H9wG&}?H(A%QUuHY?{$kBl z`0o`tGH;@PnOWPb*OD@pasP5$B`kguE{f>n^&1m3L-4Uy7}Y6UA$Tq&A_?1MsMt0a z?$5Y^$y2(hMpGVf4ndMiI2He>@TfbFi2Q9#EqoA4#Md65@>dFz*U{mG!eZ8-g`{Q)3O{CvFz7*JC~zDrMCE_ zUKF<^WiZs~|9b%a8QyEdTVc=f zooIP`FTKQgUD;8eKy`X7w$cLFH*lm#roFEuH(Y1MF=Bs+uhHtsF6dg-OkauW1-mCJ zk#Srh7LI-miND>+Pqu@OJYdd^@AMLFf5+G8$;Opb>u9t|K{Gz{>@pl%M@{%$;=QYtq0QtoM*vjlU*pi)Re!=H^BngaPc1;JQIAI9r#J zzn6M&%hX)hJF$p~yVS(jP4c-{vN~keYA0OSRtI?);BXS zm+9oKw7el@jSHSSI#8T2TV0s(mSvWVd4TT%%3-?vZ8CgF8q!}`pndrk4qnnhpWi&p zy~INz=hUB)8y^qD?IhGrmwvOUgeM7aMDmOitKVD=MiHSnVp4N<$=aZbzIaq9*&NOc;A!a1639&4_MrJSJ>u+=2Jv9CCj6PFN z6p_Ej$+EtgxG^vT&ISAs?J?%>TlK9p$yb@l)U3S*QZxL?8nXb*99s@O^-<(bk_z3n zs2DEa4}i+_1CrS}>CYbg5x19asAs!T=IvVjSxW5usEa$TGZW|E@}ep+8hFe$`pwjCOugXuP*rkx zP9g4@_!?Y#yh(3qG+h{F&h-m+0R<+>y#g43&pvdxAhhhuJ3@q<~G5HOPkT2`9&;}34=3# zRmrRK{0{4N!#Y${9wJ_0s3KUrXDZ|$;p?x??QqhOgQ%*^JPfn4agU>-`1!z#+*IA4 z@Y`XT#6Poh+--7mza}jnPz=MRx8ml3I^sdzKe^S@&%&*Ku4p8zg*3fN((T%V=G$`N z)ua-9yg^lbVn!Z!!)*jPJkCktZM$^ZR$RvX_~&gYj7icUC#BW# zkwFh|Pj}*uqmEQ}rW(<|K8v``<#D>-Ar!iL;;>6G4+bARLk3>8MeYsL{jt2qXGYP~ z#;yv^H?AVV^CIy~UJ=ZROM`bU#gcpTf!r_kHjOWm(FqbhiCIY5_k6|ywH&blMO#$idrvyI3b$zFcOfDYL1c{ zz2332v4!PpJbQQ-JQyFQpdlkpeIh61o>V~jvIn@jk==Xl`bbLIPQiEEEJ4M=o7jx* z^xLQ^QU6L0;;h2Fa9Otd!Fir&meE0TrX1mn15Sv7z4-cTRm%%LX!bkb&fT{&+`J0u#^NMCCkp%Jp;NG#l*5i4b=Q?`?Q(9P!-w6s6V{!o%z= z(Yk9qmS@QX!pg?MNH%{C{$4qysKlCw|(|eOxGz4MDkx~%mN8v$-ChFdrE-33> zLZ-jW!P`0vBN5xtXt$17xgd(${%{+#)Y(Yx_^wZ~AYR+Lskzr2vOC(1oM*m~|L$t- zm)^%$c2DWxJ1<4t2RpKANG9|6&H%?YDUdhk=jhgLBZ){jnK~@31qaPXWY(+zJZV}E zqx-}VVX_L1*i#H;7NM~E`vLqfu@z?j-H%1)`)K|)B~qAEgDn@O#7E`2xK>pua);eA z{Hwp)vp0!qGI)&Z_155fUnz01&rsol`ZJ_%ODM{1D27jAH*f;GNv|oa6C7{WB$o0# z4_2QLNH8&)YTYsCuAa#e4NK&;Uagxxpmu5n-4ir}`TVOA-)? zW9p%7>SWUbQd`uC_8o7Dw&eM%4On}1u-FU+2&A6QhQkXgv3wGMG|Q^G-Re$_hh%ZP z_eYS8-w++SJjks01)A~8BzFywa<|Eg2|PbG!0bG1WFAU)Y-?d{VC`-MNpv9AQ*0&k^33B8@Jw?QJs(pJy*JmB zhiZ{%`n(9D-krb$F<+>Q?Pk-ux&r9`w-`M=*vi-d$zX$I%zK^>R~+Bq1iNZF|Ly{A zX;Ocp@p+CU|EPOfCOnhj`)Zk=pV^M43FFqK!+#aEc=XpFdc`D~i^X{){^JF7XSyld zbVGb`)Ps)Q;|Y&iFXMp{8FA-jd11Oi1GE}2&55`ic0TDQ_`H{99GWF~v)~&}T&5tF z>TfQrf9yqOeow{zI@yrA`X08Yby6wwquk|mJCSQpw`6BMWzKQ3uTz)G8dU)a?91FQ z`T07>`6fE&xY7BeCJSDKW{}WxGSq~5&zfr2pijtu;x!*-gnw8*pK=mkyJx+vAP=v4 zQj_t0h}IHK2)OQ#4zVThqwhJEt>7-uC|*U#}7uN?Oh98b-o z^G!P-eBB*V@Gb~*FO`CqMKu1|%-8GHA`5ajfXDU7hx>7&y^i?7uPE-~4Qn7vj^oHh zEpQVKk~@Y!X@H3#sr=?n+F2bxnqCdbBkyDQkw`l6(hHG7(RorZHxt*YWkON*Njw_y zm7edG<91fdg3oZirq5CwPbQ3=Oc$^_{S32UQmhbw{?p50i~W5Z@h+0)MP3lZsK=3= zFH~r$Z87M*eFB<=2P8dqg#BTBu-1xp4DV0MhBjgQmOkPMgcrDVzxH839cE8fL2A^M35<5Hh6ZvW{6vOzxn%+nG z0~}(v_AcQFz3;{3tYR|SzRrhVYqKzFU=2M#Zy~3=LWOL~=5c-N*-}ir=u0nA9kQb? zAFLEy@Ma^^1~^3!jWHo?ezyec3!TKKrV0Cbro+fJi%5=$$9NPm!9%7Vj0f<9k2#;A z58F+T%PogM<`p`U;bMZMIo7_loK)S&C_!^SQZpc6PPluY6!}wiOOFVB+1gBki28@5P zd}w)Aca(3DlPg^Dp?nRTJL-dTW<=7~1207Pb~=&k8#1xLEECRZ+GC*HSGxC!9M?Em z32q+ZHKH?2XOLpg$y6_g)tB>+$)5^;N#B0B=|1kd98R^5I0ypXydvv&tI#jn#h|?X z60Y0ymnNnTIJ&hJs)j`{{X;N4Rv<%M>yF{;Wma^vVSi#9-Gs-c{-tJ5 zJGi9md6+ZKo9_6yDS5y&MRHL$7PGqwpy$1-sEhJ-|7PD<^sJ4fCWE>l^J)vOXFb4! zlA*%PhZl*=Xub#dZ0dzLv4y_8)*#5v&?Ut({5xRe6GxgGqiJ!uIY&N9!(0bD6xB7s ze?L=ksa-PFzoW&~)ek1sG5V5S*i~sIvZ|5CepJ>7To{{4$J^Y4zxpd+Ks=ub)xUcm z@gnw;Z0obD0@3VhHl@E>!2k7dvh^;{t2MKUq(hu0?G8)Fgd=TDmn3JnTrDc)Y$g z58{e1l6SqQu&tp9%8DMM-0VnNR9y;93Oh-yG(V4PT>l6*^1PR+zik>3O0m6mQ$8F% zk%JGud|+PC3%HhCRpKg|gO!uM!S`Y2n62YO&mGq$JyNAm`T44ZPn$C>mh4vwpaoA%^Z^UV@IEpsD#C_UrR~ ze&8BKJe1!{O}%CbHVlu$0e2$l;Wu({>}W5Zl2R0V9$YT8nd?jLd`U&WZP{>tVF2#% z`a-vEvf-XZI*Hah{*ZW5X`FB(udMZGu>1$8*V2W*tOxj~TZ>DILG7(!v_N&0z;0YV z(YYu?e{IZzWeWZn9M?(5^?SiRt!jp#YkUuof7B3+D*bWyq*6%O?L^FN-0_EeHCQD@ zp;}oPZJu#dw5NVH*)WFh^Ot3Ih|Z)}lFW#|FwCS5UN_FCt2Men>8}^bVsFBS>{9R@ zu!-z)%E1{E)4|PpFFM7kh#S89ang2|;Kn4r?ic0XCat4fvEy?!RDFMl?>9x#=(rc6 zkFw6>)Wl4THp+y*ZyoXVmoKy?Mvk*SrvmLXR^q`pDBpx!dpDT|GtV@?v@p_G?T=mC zSU*3;2ZvgO(UiQif+=3f#Kn?-2cC_&f|Wyi>79wr+_1t#XzG6uQ#VF($-4ih-H zZkDm$pHx)y@4yJ>^>8kWuls6cR>bb2y`;|{py+|O%oAzqsCO``&q&gCm9P7MEF8g( z)%s5}0DeDwPV^{W>tzTNB*0% zn8c0r#IMd(@Zp{#Mm^9L=j1OH78K=z9n+cr>kU$_Tq3bAPN8OT6O`Nwz)5E!>6%?- zpmTFC(NBnwXj6|1?D52lCVH%Eg{htIcj)u0SmNiOIy{3omnWe|M?MS@72?=Iwe+;@ zA}-%VgXkQYgU{Q(!Z6pB7+vH;d*JU~%d zIUKTA#b)+Cd<$gnL+DHV>KaKu)XG87B7bsqEW3S9%!aIIukqkwHStN=+nkpFRgtnj z&jYy2T_rzu>e1<}54svP4YXL#@Ne%XyYU4cXIj?U9jgSHPBoC%PeS`ts zowRt(3$9>XJDj@7_Y5!lFN2E5{@B1ggnu5oObT|pqwc6`P@d|Ic0-b>PttNxW5!$( zpvAmFwiQCT?;6YrloE%W9>y6~{}Cmx<9mjQ>c3!Zzyey^=L;-ba-Zae^Y25v&>L+g zC({RC9|^|SZ)aJ1Jg4`q<}ik~s)$X5{+!oXS5WA+kz}WuDtVH=Y%Vyxvj$}E2H=oW zk@WNT7ox!CtHjrUc_XjN1al`12zbuF4{swE6Sbz6aMAm$1IIi$=kDuHP1fs2>L;@59Qyr?E`Kih68dUa-sB z@bHmdnz_D%tDU4l?9F5G&yqrT8Sz-;rqmZh_5VQAh!;3m5Jr#h`V5}?+Hvf|zqDh- zP~pX`SBUTUPz;YKhM84?I8WR`+ZTQolpUE&ItLbF*2dS6RPcsut7hKgpUkm!uN%t-!CIP~x_dGt(^?qvQ;ZypB0uW7F6omLC-(H*2G z;}7P~V*NH2V}rSj_~#fAH}(EBvb^FVPN}W~wO(Ufm=jLDehw$^8WJEn*cVr7m%+UD z;iQb^68*~&_~$?OQ*?t`kJckKo0gFUYP{}cvw|}^glUVPd|xW;Z&3zf!+5;to(BmQ z&gAF4Q~3I86GS#Y!V!WNalA^jbX z_prEBBI?J_2;#UN(v-n`m7CwdmrHFZo$!k~xIN)qX09YF!!F>*6|01x#yI?cJ;0p$c-(j)Rl?W(#x%@OXc6B@s^+L{iWBew^yMD`e~} zz8_F#w`)E#l4-_Ihzi#GftuT2^I18Oy;jX`ZnCKJdR{dQ-W%oTgnb!@iyJVBFmq+G_$uj*J|e-(-{6Y%Th9Kie}9KJb{CT`lpZE>_A^L6=m z!0_%p^cw$)I%*ZbNb3nK2aWF&e7@{J=>YaQ^SVqu(*wbFIsYaEEKMY_w-LiL@<87Y zut&X#D$U-&O=r27#r8Z`FuOW}bcSov9BFp@pka@KwJPF=u?^gYWs%@G(iMdXwU89` zmFOw;;=KF$uvxzX#r`s4T`Jb4i#kPRvDUp zCl3amwZ)u_XgY8FCGKbRFDMM%EV(Uh>^cI=#QtcZTM9=blX2VONUEgl$1N7P5cPii zzOPY^X{%l0sa*SF(H**o{A9C3Ku{rQP1uD-8dBm#%{tuWMM`jgDF1GRK2s+P&M%}2 zW4^-9z+^Pu6G^XEXK<_K{m3T|{@r*q;T}4?h^MEI`3b()9%6cr96T484)r-!ShBFM z_`hwpxh3zs!DaYy+`G30#&&y?1PxczwXXq>s1R&A7fI(Vj}xgSx|0FpGV!EGCR|wW zj2)3Jbjgf9Tm~5qFS29F=vXOIGJ6XVdrhIQ*VTjN-e{7w)gPBEEr+0Ik5G@jAu@OE z1-B<<5IuVpiRbO3;jXwxiRszY&vQQxVr z;T7aD(>4s$StJz(D}+b$`vvpDWb|frYRrp0T%+%CQZ>pR*PL#G9lyMB!Z}ebgl0o)`AGqTgV)OT99R_-Cyq{bW3G zC#`~^&)Z=4SpMDUDRLoOEKlL$QO&S;_(`JnAVQ+M+v9fy|BP*<3o0y4;}0m4T&B0(g9?20h9fsQ(f(Zom;8a?@)L{ulKPCfck=xamdx1cS*LvmekH zb5*kUFS0Kozh{KdTRSabXhk0u?$?Z8EHYq=;|8L5<^q0dYJh3WR^#1p=AWi_7hLbS zqbtkM)b{(qDOmR>#_Wcqa6$!$2V3F>#o^)`uXYLS_X0-TjHIqh<)Ob?82Pb^Y3w(! zy|Bn0U$#ZlsN~69YQb%h_R61<+jEP}cgemMJ-V39{&sqcPu}F90+;&iLCoew^$!S0bb8j){}1VXp8#9xi@Cdkq(fmiaFu zj;j2-k@iv*%B`v-+41J7!^yxa3+X)LuaLSFu+TP=o*tXYH5>^bnzw>5YIYe6OR^!G zLUM3qOgiMo`$3V(aa`uv0tprOSvJZwTz;em5|V>)|CdmDAudLg{^AxnB+SIFx0#US z6oeYnn4J%~x---K_+_L0=`DYTB%!^zMXVr0tC6k`lSaKZ5~y1T+&a6LAg zXdvSp%u1jl?H%Y{I)H^`t#Gc6lEI0d^pAQ6nASU@m8umz%Cz3iPTlxr^B-#8*3P9p zU4t5rJn8=0^~nnMdgR=JSfpWv@L*e^NXnk~B#eCU0w>i4QeD*s@a^{t=e6|G{r@BB zI{a#U-*7{cP#KXuvWtY|E1mb)Dti2 z*qgRZ7*FJDui>P^XY}@-XWWuiV~EDC8yK;=7NTnJgD>l3v0I-5as3f}j)`bx)gkWc z(o4kC@(LcB)c~^s{IEqMo^lVe;LX#yWN%;o=6HBZBFHH5cZWX!WP%Z5Zdo31cB$z8 zwT?E}Z{-$T975JBuVuK=4(jXUNwtGI4eD0{@9iAWa*3+s%H9TUU`Qe?{o^dif&wdUUYOODVPoV+$cvTr( zO_@x>ya(gJb-mym=Yk?5SL#5=6S?AT%wy|`^CCZj4$I$Y+?9Z*s`Fru>n-v@jmL*g z;!DKh2tP{<74;EiS?wTmwCggNL8Z2a$q8cR=|!2>+#2&;gX`x?E=rf6ifU>)cKquEN+h^gN@#x z%jFy}QS=r^vW(dO=lwoy_ahD!lj!>aRd70RJr>L!E;%^3hkG*XGz?@Ny9P{$Z}32j zBknN{VYi9EY{qAz@ud$oJ#g_Z+C2DCDj>L&fJ{%sNyGk}Q@H zdqhNWOAyz*$CYGux#9+PyLV~7hl5VU(xBia;z2i!$sM_;cs{xi%1#W2U;dRuKKCEY z%brf^toY~Mr-V`IXV@;VIfI)8A*AtKC~`~6;ML!IsC^}t>QD3+SjAjqo~azvFL?_y z&mBO$e&6ZO+c&wm*f2=5I*XPyO`uzTpJW$1<8Q}m@G^13n{95i-q=Tcsb4$B?jInz zV!l(jE!mT39nCuiZ^)Jx!F1bg1d!&!D&PIVnFB zj3-Gs1SLGdiqqlri<*@n^GiM%m7_wh*_OcJ%jIz9K0h1C{g+8bykMO{W7cM_a= zT0{*eALiT*tw_1^73mCc{jxuv`W{2o7$-Awv_9$g-AAf1_6|Izv2=kd(oMmVtcHm1e7QIo|lp!JEAm7~;4+dotdd)H-ABgXaiYf``j z-zMCABm;h$-o~+SnWpH+GA{SGDQR7L9oq)iL$<|klx_8-kMDcK-NnO*8p{v=|19x) z!FC)U&SrqP9fI!ER9qM=qJQoy!r{}m(X`l&PSGpk40@x90_H91OAcJ$h2w); zK%vM3Oy39N%N?aq6_JYGjv{&?D2RJ=!JRl(x#H&)>^7n6j~OY?Xip0#&J5o|YQ9I~ zs+a6uIbtl_X19q%WtK6bqenKIte}F8KSAJ@ih)c^;NzIVnQDa*(=DM`#4@k^z?!If z^H?#d@+!uCla<^UbcgfLj)E_&AL{>DVbBvuZe}>+Rp#Y`g*+GLhz!a#7xekU7gfB}Hp==qk(4F!_7} zkxUH6R+c#srRvW7_^$N+iA{pc3m=HvHx;_&LkSEF@xn~GcKZADHEzy<8aRFTC=MI_ z6^)A!SvYS8d!hkHZEtn#D`Il+|?ux@^R4f;Osi` zUuyw21^(afyAOl@8zYH1|B_pAg7vaJ;d@TyKc(Wg7b3bLb|B}sU@A%5$nQ-)q^mchH_8!VA zKBY_gy#+_>g`}UnuhgqM%>5*)kN8O|9yb_nWBs^2Yb(+2JivQf3E8q4@!+_8C{=og z&3|g?!qP3=SQ~XxEVBmFHh+iGIj_m_G<9m`R05BStntiuIZ4mB0&d&mRM^qN&ksT` z8JxfNFTOZb0ETB;u)9i8Qr;xtR%;8%?ngYH41TDGubz5QT^nUGaWU(k_TuMp6F8c5d!TN;yGVWdR*HM?ygiMw{9n3tYJQE z8Rt%XW6t9bmQ~_((3aTjj>L@L?_t_h=CvK^MTNf=3=5dPeTbwOE#4zc7*IymKTpEZ za)l60t1(Beg62x zgy!GUU8AZhlx$w1Nw?)z!GyG<_#%0Xye-vx04 zU)~{i72R<9t139K*dNa|MA5Oo7K_b7c9IT;82n-ek3{|14G<0!Lr5! z>t8j|2ez_IBR3b^#qrXtNLN{VG9^=o{+(41nJ-=uU)f+xjVuQ{_uJ@E??R`fY!nn< zEhlrYsnT-R1$kx5J$!tqoi6HOT*TBS*zoEoZr$@0DsNSgyj(B3;B*_Pq&r~NAam-M zHjsGFevA&eWeiV(lb40-l8@@~sOVY>Phmu#XP`^(w?GsZCebu~4(MTRE z{A8cuU6z}X^u1OPzI+oYV&3mJ?x|3qau%L4o?(?*BTVR@j_LPBbalxi_?hhkQ>qttezK1a4PIID!S)DfP6aUv0EMqKg{(FvL!yl z`59vo%USBbTtr7rN`*yn9GTVNBfVv~Zmxn70q^Iny84c+Sb_NaU_QKDl7m~!>gW^4 ztz3%LX!74Ae#R&}Oo+CPI&Irg0-KnpVOxZpq~H5|PIglPeCc+U@(lVfJ=(3W0I>d7h7vC7*85>V}&9Of*{?-B;Ecv;jwrD2FmFGE!y8U-? z{1X>ib#^=%tk8rF*JLEAR^6QV_#txa4!>XY-?|t-uJokQUACZej?F9g5>Ui^eEONU z$%y^uag0tQSc5e(8>sS1e`ub(G!r4APiLO6h1+8;VV({#dlH*fk zgg%4sz`i#wNIq7<>XUD9O(5eOlr{^BN4Jxkb_z6Ob|IKw`iRD_R3y{2in+L!0VG|> z&ksHAS}67ir`M(rA>(o%fqNZ~2?34i7{|00Gkb!#@h?3{V+%7&rdGk$h4*pU91*oy zWFT&IG$kh0(dhHB5bWcwVD!!o+TA;htBITeZq=2feYOlypJPNc2d|_QSVdSG9sM1T#pk+y$c{}9vN5? zmI-@4c;n&GO_W=(C&mAHB2BMAZNhmH#u43pLXwQBx-4DAO)j zB)WmYjdy5_=4fIsr$wxkZeaeRT9D0R9gsz@(Jea%M!98TE}IV(ejet|udpZjRhOkZ zh)z=gwzE6ngr%vFUa^cMwfmsUhf4SoeGT`P{-E2%^@b6dUtn8%g;e|0sGLd8kK(c7 z{iAI37FN*_nVY!s3FAn?_ccwiyz7gpx&k#8*l!jhws1Q!pE&8)@JgJT3%t?&ue;L;GM&2dg?wrSN-$sZT`~t(-?%$(U0agEQlF_3gF`?x>tXQ}NJK8FW0oISo8k~`mFLVP&gwQIAWv8Iy@ z9om=978Jp^)>8D`++UJykjuGOs}P^LyQE%Y2j@9>Cm@_|STcl^t+hmbrd|BAc8YM$ z;b>6k2*x!}N+I-67Dlsuxmz=s%MbJ-7m8hRYkn29TnfbD{YA8Co`Lv_#vx*a{9JJw zbRc^m&s)xv-%b`TTS-5McEW`nS-8$cL<^T^a(mRHNYt=UGjW#E+-mZ+H;h+eze==9AB+|yzM(BHvxn+w*YkdFEw^zLMu z`HEO+Ewv+Ky=|J112f93E>{1X}v9>oNMuWIFgJ(>bytD^n{TMKwVGyrQxs|?`mx*hV_f)>sn(VE609!3 z+JaP;8Fd&3XsSvE?g-}s3mqT{F5!z?jj%W@3!5_7Y&m-nw@_~u8LGkKL+||?_^#g_ z8frL-%zsyo+ijF3md?t;%5~Z#Nsh;gZ67Y;`=_HMF;CYE)eon`VwM?lB{c`$IAx)H zyojz59^pd2*^}D?8P>-(!075g8I{36{D_m> zO(d5(rweQEl!N_Oe#XEK1-$aP7t?|ZAmMcr##HpuSEpWbMc>zwZ)a_#`F;k0LL6@8 zNw4_#C*M|d!Cs#LG`1~+xe7XDdcB%-@7U_=`pe_j`#xcSO|xzY2(Ubt1p#MdH%=A7G9B3N-0q zcZXqp4WHhfLk68I#;brJyQzkp_GPzG<_kEG^cMX?6X~*vlesDLw1}(*&uwmBFqn*8 z;E3lOYhi)ObTmDiO*iY>LXP=B>^|O%F5fd*-jM~-Xt;((7wf_Eq&M0wNu<9&CPVi8 zDdh5Vo{O*;2>5YV5OrSBBObKmHAx=$2IUl4pYq8>#@98{s8?p3k!F~m){1H9;8x>9$92i3Gp0Z(juu+nUhSP*sk0h|W zS1_JSVLYdDF5U?g(W-61+_^v>@+HNUWh<~O!SN3NW;$1fH;{xv7}pYb!sW*0p$ zx8nJVJfnleZ}&=iFuxNH%jBXa!K3uj z&q2c*@8CSsQ8r&@`R!G1oFco4YA!g-GDEWM6sENs-f$WFeQf}fk`N4;6GfLtra`o+5&8Vy z2lZMi;mpTt=xNbF8+6MJ@2rs{BU&q@-scS=dE`?IK{MZc*s-VtV=mUw9~#@Zsn;~g zqNDhvjAv9}k1f4g|QXPe4h!R$B@5P&}Q>G!O z4c!fxU%2}vck}ut!fmvbW&@6zx*9`Hc+#b@{mImmeaOs1{JhaHSC_1-R716ZURb`% z2cO-(MQtCBBVmE3iRM~QT$}I_RO(ivKFdrSAhZMX_)#PyJOP)7<%4P28tl9?U7}oZ ziA&e!H#QQt2|mEb!Zm21=taZk^)oZ`&EjVai%BZzZqkf_ zL$Y9{Ng{4#ywkM6Q(SZJ8DbI3W5@_LQ`qVx(_@`t*mZFR@$vIR!|@exqbwh9rHQD; ziGGkZG?}zBef5*!xnMOi1!vu4yGdU&Zu;a%vC>YSqc{_oKssDB=@H***u3cp*t0yM z<=WLyJvRsK-Z9*0+$>nOREFhw_oZKySyyIy6(;&CNj9F&;iCQxBQ4)|O6Q7<*EcZt z`6$W$8PkO4wg9xX@>pTyk&h>twsX^&U@kA<9{CdLinh&F(5oDe2Rgz2L_S_WE~4O;$;F9c$m84) ztn(>@?D}BbxR$-s%RB^0=iSH~rnmh6T%quv8z$NQrAN%&xW3Fg6vpxf|G$rn?iWuE zJn^PydOrfBJRy^foN-G(=AFEefPLn&|GP%K_|U^JqW>-fxs_QkWl39xx%6hbvR@+Vv-`rT{h{0xFJBz#^_rrYV{&ZN3UabfJcgDO!oRN3fQ+Lk z`_l`%*Aw(G52V^GXUR!{y%(4+rDI+$XMQY*bR<4TH!K0YuSba{<0yQaQo-P?Db7=q zmu%MY<7~fs!D-pc`0jHfbXymq_e&8~aTvrc@|s6BwrJwglrFg7=7g75xzoBB4PtJv zfQ)Fdm+CD|8SgIg9VKa^>xCzbStp8IA{tH01@>OVd7&ceS#*T!jCUg4w=QFOP6KqV zc!Zj4R{U&}3eyLE#ssVWlAX`Bg$hv{Np=qFoKyG+=dJAUflLGKUteZu^s*mWxTX?E zJO?m)SV+F~MRc!Yxtc2Fc(tLHeub@^Birje53NBvaXY9TDkQ^dhts-}GB~%c6*b&U zBu{6}5UM_F166dE-c5ceDr4WXy_k?)05XT#ab`~s9eX{2)4H^k>^@_Q=3z`fb;JlK zT6j`r#uIdB^dl3t@VN2qz&z4esD{V#d%@D*7Zr1ysaDfivaj_#>Dl0k59>dI%#!u^ zp7|fukJ&*_)_5}7m&c7JSzqEl^*qXcZv?+P$=J?rg5OS6Kji|4xEX%MN$FIqPtt>;O=b(u8KXQs2vDcDZS$hpvud9dM z8MDX%cYfX&^nNcYEB4ZXJ@W-lwnexgli`L>KRDVTCibOixR!mtsY3~x4``s*Umf8p z=RXs_vg!uisVAY3n0$3X$IaES0`hPJhSPf* zTLf?3$YHUQBKpLH$w$v6JCBPr=C7 zxJ<}$U^d5#4SmDOw~P$*JCy}@U#*4m-*M8+(mitn$$cAL`XR3o6y~Oq3jslRWJv`~ zz4#hmd56>V25W(N-*(b+Ta8xeR)FnemYuU9hGzX+$mKcpA^$4PrJC)TVaXWAI72Ou zQ10?0U+geTps}-WCf~ZVmc+h~lkO?iMw*a5i^q-GQz`!G2%ulSd;(dfXZvwYL{D4g za_MOgh+*(!tj=T_c!kqsX=MTaQ%{4Wk4Ny$5P8YWC4StY&-dY2+a)P(7~CzwreYC| zcshu4I53~gtm1KF@B=3dy5~mE{2f8uFEn7ve72|DQWi$v)h8_sLu74h!S-PzY)gKP z&p+kB8RsGl$Yx&{1u>Khvg>+qw4r(@5T}HPRbvss4Ln zcx(jKWx2TbS#RA^<~5ePNx4aG?cno*pD|8PP)1?vA6#~v-RYQK@u>G78sC|~omJXK z9&NV8DOc-Y=#};Oh21q?{OC`jLY&c}=sPvc_{#;wDiQ6S0r==x8BAWi1=p{cA*ob< zBsid}N6uTTN$;&kPx#>~FK1ejJ(l>tyF{)I;JHxZwh0RuPZH{22l*Y7$tdpx{PvP@ zp@sK|@!<35Fs2FYVxFV3VhD})&I6m)+oWqsBr5xVfHDsgjGOI6x7qhKtkPRXbUzj2 zgdG$jZ|+7*+i4Q7x*X0wxS1sFOv3GLh45@4;LIz`Gct7qcVIH}7*;PpxYh|pzpkME z+h?@*wG*f5Jccan!|yUtPX=T3f@ah`kp;Q)0b`j4=~B`uZifD4vg_bA?Dni@-XcG& z^nO8iJH7%}ldEW{7(=W6J?Bb?%q78Bc$_(w~|aD$=z!#b7YD5{=^IBvW^%a`Ib7ldHWurCBbV zvM!eR-lP2;703aDe2A|OMyGeB(19N?n%zD`DZ$)Ln*buSjo)h?v8=w_BPldyFR^=AWUCr_w`FqMD2RovAc_lTT`U?)Ed_YC^H;+`w;yN{7 zkj_&fY!)el!Ji)C$u;40sD`KDp`9mbV_Na4@$X=vj2ouLe5ZlO9k_zVawu&(Bi(U^ zexRhe%8RCURD#of5jkDvB)zkA#EEgItcZr6N)X4miOBb?4E*7n1@m;T;>fmVR3=;^ zc(cwJW;(=?mAhm}#E}q^D$=DV#y5dp{BB(KXqrTBuA1<_%r|7MI0#=ntpLj*$vE#x zIF%J%6MRzXB$21pXpU9|ESh{3`!ujTz^4njq9{d@dYhkNZWsdEFg#fgp*OB2?oqALbaTJ;G!)&M?XJacMt zE;nC4lw|rp#<@RBAn=nVQA{jA3zak&JO3mewvv;acyNyk`5gkwR4(JjAx&^rQi6|O zi|EqgLEMc43(3?>O{|gchBbq5glx?ZRx2Cd^(hsu2*D;1=sMl;!W6x3c=qo#IxNkFMej>cCYo^t2h2FFU9RN89_B?E-UxCFo6#tvpG2`} zrtrb;okS;>@h9t8FOQiM{{Hlt)(?$alu p}p%*5uxQ|K)oN0K{STg&&6*WWR`-Krl2o#! zEDek7b0I$^4gY0)rdx6jbM?;8#SV49r1xC8*=giVrzXv{sez@Z_oIq)8};A)jtgQt z*tkX)e9rWiXJkL%(t>b${P7lnbyr_Zd!UqT z`2>4+GL82tPeHPu4;h@EgN|MApf3G3e)49%txq?(@BTF)etSlG+dVcVlVr1u%Kzg} zze&-g#LEeDysBZu5k!kIB6=bzL44WcDG`3mz%zMS5LdPZB#m)WojJYmgovVbX~%y} zFho6_%zYSyrl}Rs{6vh?V#4Vr_iKXLd%8)-B{jPJU`%08&87a7rJoQ(*^PTx zdnlK<`5rz{h^5+RZIdg!w-D`TacG@Z2yfo$LRF8PR72ho^A@i<2GX4Ws-dBi?GTKo zQc%j{7TpgcUv55T?;*x--@Jzx3}flcxiNx-5muyMLjm40NrU-K`*BqN?=+#W8`npk z={Lq)#;7?>5P7K_cfJ+TMan8%J6S|}Vl?sisBSPfamRHjZuInZ4dU~m3P0(|O0wU` z3e6WSA@3jCOZDVw+w|~*o)5ip;vkG%bOh_0S%2Bm@r=KfBgenAyQ@(dxOvilr4~atFbeC)quB+(*1$T|sAxj5$>e9Wq&s=WL%gSCJo6 z__^qGrw0n}ey7hLQ0{YsJoy~NbGAxpgK*l{3>uoT4&K~S#T$cr@#5%0h)8nBz#=z# z<+l-+d}BYcTWO25vX1pf@5IH_lP=t;ObkY-ll(ma82Ypf-pX#r7jrcv8^oT1Tju|f z*wsA#tUDTrn@&4Z*N(B|&+^-t-|j|lPIuv6xZ03!wH{Kv`tftSFgVGRZu@En!OL~X zHl`=}uQDIB`t8EHF(W16XAW>4>jQ}XlXIxMs0mIzeT7d259yZPTqyqLMUHAmBI)=5 zs|}1<*KIN8ZKQC8^_kQh93@%MAm*;swi3JFi8!;1-TqFeqQ(so9b!F#Qz+3VXC^L? zYSP{x@k6@$8Lc}thg7rP<)L{F(wp)-o#AK~{RPKN&4K=>*t?AJLQ9vQ=A86x$X~T< z_&BB>UKjae`Ii`~rScpcjoCbvGDf0*WTJ3l*dh|Xk)M(L9ZzDSOea09IY)5hW(8_i zv3L4NCD`Qfmh?vRxHPfqEnYuVN5^^{;+{WB5C=8>gfUBw!aetN68KD$jx(%*Bm1pz zaIBoZNdH_ehNFB$j0jdARqyCG?`xZKW$`1Ivaj$0+4Xae)gqd3)_&C3#J)7lD z=BTftc`CmlcyeOq~5yn$5F&SSC_V2Z-PhHGRbHEAav-ifX@FA9TLK6 zRLM0#vd>?Va$b!-cdUTD^9GUB{XAX;XHR7L7~ynWP(MYotU z{umwql|ZwiElDUVz~}>MQ1j6oEw#VXLo?jC=s~eCc?RQYjhjHtvjQ`lMRe!_74E`u z1G3Uy6Ssfug3p(3qj0i2)%>GDF5jrZ&SSEYUU@lT#*L*!FPO)xNfz@lez6xdyRr{- zUYO%bx$pGwj`70UNqvY#$7}RkmkZ|1BbNC=M1$MRxRwfcB7d33t7E~{IHFNT;x}xf z@Oio^8T7;l2M9kx^LRac!!$XyoSWgPKcmT(FBO<}2VkYJlDN%ced37)V7K@-9&dJ| zi#7UkDhhMR!xd{#tn&k2RMrsZ*CXgRn+ka6=!t2=zS9p&DHrv*4_On+-=jr))zI1_ zi?&``4-+n{V$P~R`14u;s55=(uWxSDbIN+oZtVebY>h3JeyM}_Jay7OCjfga%ivF> z0r4|Z!_>ZiA#7q0-dgTN{Uu{anbuuQ7rW76>Mq>s8+K&GGY_dgHu%DQbl8|pw+>;O z>4o_u&NBh$b>&0VuprWP{TzPW-UKP#uh7;km@doDhVIS2q;?C|I2xp%oVxKed`f2WJUpq3q z(Hj4X>!CK*AI;07>GL76u&HkwKD$0vlC^r0u(MM@ZZ7jf^92>KJK6&GXtvSrzghzE zyicgnAfjn2mEdbc2ANWohA|Df5RjaK-les4klrC~Qfi|36Vuu}8+Q!8*5r`WvnErq zaxJ`AYKQw&QvIL-9q}rgb5285S`QVi)7tj_b>ksiVF^IP=&1e@1fd`iM4c=HGtp0r$`~ zgsdIniY23~Ssx{$-0Bp%&S9hYn1Ve?P~zvMTh_ba@P`Uw@Z%rMo#jQIc&(zZ$!{3? z>mvp*F0@fGn-i{0CeN3Ip!1h9FlKpx&cj^kQ%6gIQDOj*>&?MDi*$%c@xeJS+Ni9$ z1GlET6}Ft?F~@931=0DzwC+nk!q0WF#KP4{$|t)&c!SGkh$x-%QjE^eNk)AJE|{JT zGu)oyILCTgds2ooE;fZvFZp?CVp=RYU7<_&MKX`@@`IS2uOVr5XB`%m*@SZq!cx{R zyiFp(lX2m6^3dx7KOb5A6{XQR&(rQW@Cjr3N6|9J zPB5JQ7F8aI=z|M++_$htzR7?0F$lLkUtTTEOh zCt2-xj|=|w65c3W#xkx6rdLPT=cWl(Kvj44%_v@-bbkO>-mVET=&n*xPfh9spA&qe>}4aQj`oT&b*G33ad8|3+29+xui1Yw<3 zHvPIi0e&v~kLc*}T=aEW))!%+A|chAxPo`Vq*I^As4h_=Dr5vv%SG9+^syh~f+8@g z`2(~}kHTrASx3o$wT1y^yUA7mVjOykLe#`PxM8NMWdEXAF2v?1>t#zs^NmHYH6a%Z**Qsxdo zr*C~}EX#ep#d1y0cd@L|jxC&b`ZS`Hyc1PSTOsO%0qz~@N%wWj5KqOQpbtDo-DbLF zok9^cNPECNwRl9vesaNR`D!TtB|+bN$#m)uWAUK-H;IX6G#;E(1np1ugJTMhQAhgv zlV$H$(cH;h@II)TWtOuYWLY+6`cO;;P7A>}nQ~a&`4l(p52u6UJO#1ugGuXzT%7$P z9hB?+aNUwN*41*8>*vcddl#I++wo2CbjfG3_o6rbIO-Er%f^$c#r#|prk##|$Fslr zx|d>wTQAAqZy6Z6gJm;@#AE-=Mmp}TEO$`<5Iol8d8C;^Oxqu-OCMZmg5yQU@hxab zTyFIdzBb4sO4dQBy|EH%EZ*R}%y4R8bzLywy*xgqY819qg0m{i78=+{J$)@X8J2ll zq+>3%wR}I<-9a^|G%$+l7IwlgOhG6Jy zAB&(BCJ_QT4M%dKu>jK_r$Or;2MjnZFR_&I=i;X`&Asq4f@>34I@V%GnTR^vQ{j5= zE+Gde@ca^|;f=-9-D!W*k!0(0HrpSTksK1r3P*BAr2Zg}SBYl@cyyg7J-E*lY?KF+ zp?_YZGUFMZxzytER5t6nn{%gXJjs@=mr+-?3HI53#oQIL634oU!VBuhN$C!L@B6on z!=Z&tf9v3CD5ly(yQV^VFS|JLGg-)di5q4V!cnG0T^x~2^Iqt3Z$2#`k!7oJoJ>1> z&~GJ{Wg}?E@JdiVtU{ie^SE?q`9zFu%%<9M#_)O3Fg&uR2kVv=fYF^3q)NjUN2z~? z0s5232{tcvy)J{O=v`PeURiR?$UzWj#u1w&Rq1X0mQn}?3~{0%6=O)-TL*F{)I)kB z0|%DRb}^gAo=X6;7y%i3HUXXF3cxbzATF7yA}P7EiThFgkceE)A@{8bX0hAE@6$o_ z#@{Tsq8~uIJ0nnkPB9eSeufzvKhgAkYYlaM50Jr;#mH>J@H^l<&M(lAoSvS-6{-Cu z-~1ENdsPuk*_eeB7`EieYj9ITII>K_Ae;+D=*U>!kA}I~qCgg!*bT+o7eWFLM z?&JEm60zhMzsJGz60-jMWZDo_3-wG#Uq4u0vPE3R>1cceaRkqG54=}}y6xfg>f5b? zJ(~yNHYG*6=VUR2-nGNSgWTx|ZYzg>W|EAwooMFS3Nfi1x@&vV$&+M>>cGFi91&R2 zQ3`X<)gdimx8tq{+^`*w$xh}49sa8d1clFW3G-9m6BvpobU6~O&L~V&DFXW;0hnRZ zLKiCy;llFGpeK~asEYPr;xTLP$S_5L}^L4(Jt&8?S~l z{kErIZ)pfooRW(xE7GC=pFMD#JmtEed1znEs8XYkV=6(AoPeok8tG-N3*779!-=5^k44;s z>3F8=0TuYmk=3&=qW0-gl3yNL!p7ZMC=)EA^|6n*+4}=AW1)z~%(& zt0MT@WDM(>et1yPUs#z|hc@a_^u_dFaMdgetDi94__sW+{?Ai#Re{H%$pQXosuxZ_ zraTcijl4z1*A$?23gfzeI^)>&@{)=sKW@{wH=wS?W6`yzb+}uB^*Cp!aGF_5nD3sS zotCWf!DcUpMO7n7%la?4LsmvIrd~$a`EWgXf1JO;o&L?C>K0Ghc*zuI_YNWdSdRMf zm|U0_REMLwMAWL;oGTCZA|oGM#@B3@x&P%k?tRQM>(;%2HgOB8R>?}@o=p;7J$!<6 zFkJfoez)(d5I3lJ(Z)1a!@u6M$?T#E>1{5c`ZF0a5b^vXmh-^9!CS+V>2f_?uA*F@ z>>amS>UW;%+(y3ijG)S!Dq*@%m7HA1dz7MfPC^ByqpNn`0OqN~@S;nPRR1$}%t`X* zkBxMXs}X9FgH6(N zzDIfBz)7Fr7wZ^$Ka=OQ=R7%vS8WDK0>d|QuOdQ8{{D0LwSO~=aTTMCOb{I%ngv&F zSw>t^1ojRt28Gx-G??{?o;|eI&=1T>Sxhmu#85b{c@izs7nJ8h-ParpVA{ERyUuW-7afVVr8RE*T@PKEpV7cp zMG~YrRCu^^9Wj{5GF1*&K(F-`+%~b1u0B6iU~JTY6+LWTDo}#G%L|Fqqcp7lFApx; z72(=DwN&HMA?~_*nt1Uvey6K`T}hn6C(~={><0SdGt;WNU=YhF3!PnyW?#eUdYNs4 zO*JaG%AaWqTR*^us2licusdCFZYy_X@oe()<4)8qZ3X31@}xY3pNo>`G~g~av(W_) zxf$!iNtY{+KVP@K#N~{CbKYkte&l?Mcq>L@?3yCzUTgu=-c?BbNg^`QGTzo$=gK;f#By9E> zspoNp)=T26>x5B@YTyFP$^1H-X=TMP#TS;Okg&)Me0ww-E>cMuk^%&`lenHZWKPG$Po2#$~J zhrwbs>JwQB>sY>sVRHkud1uL;T04r!3^d38dmhK%nTeZvgXp$_vcxya2J=>pmdxT~6s+g5PRVWI)LAxM(4_80h87m!1Liqc73_=-ga6UU zJKmhh&}{G+#$!%hdn4L0PRX}Ng&VVc1u<2fgyv1ZLGzX${@LnIeM?7@HPhR0`<=fu zYMYEuGkr6ezQrD+18O0!eI+hnm@_=a6n@?wOM2g^05&unFd~W_)#vv+m{TV z#bZu{T|3S{$@55|j_1e$EgokEsI5jt8850_?rPY|{YNsJE6|!rxAgLx$=qs!bryxN zW)I7ua*SfPr%Bu)Z9{T**=nh;p}6c98Tot!)tOxh8LGoc`bvKO(Y&vXt30x4YTgD& zFCBp=+qvRqvMX(*{I)^cO!7yWpM{e0%uq)`NfNR9hCrgU zjKqylmFBJtFAKv}IgWI8^%(NAArU8@ilQ$IBDmi_Z;{2{F{y>>b zp5dC8Ig{TjtueZ912o?aMG^ZyzM2yQv%WN=x4Nq2ap_Q@WY0$CLGwdv)^(Uza2*AI z>gl!TQv|tk%{WXhiq^>V2l+i8NUJ0b$GGRgwizYZQe8{ubRXhkL(;{4cl?s}E^V1v zOERWSp^;6j|GkxE8C86zZL%4hb>}y@_sRu-dRIfg=Fd3$UpN))*d|EJRKr4B76{Sv z0qoc6lK)=v_%q?yYFxX?lMXs2OGN(^$)V@L*jKp>tg@PLDx2*`?|#TFTop+=EchMG z>@(v#ZJ2NOmZ5m~G&f>4EgFseilD*lJm^OASoCIzh{%muO|R1~5Jfd%D*HWKDCKY` z3ewnn?I8}cEC*|*C#__8GSLgY1dsoOlPT+R5msk_fimk@+&EbB>p&=Ha6y3#ljC_L zqkgYRimVfUn8ogIGxAY=g^2!8d?g+=mJk`I3@km94d?P-WBT`6>KXl45INx-h~CFa z@B6+UZ^;7PdGuQG7f3EVhbl8vBw8bWaZWdj$(Lh6cu18#6 zP8{~JNv36i)9*#qxoE)oAKm+P?+>iH}q*RmTw8CdnSbo3TE9Q;a>{S zU-k{8E@0UO^8e^8e{XKpr$R_#{i^d#n_$PqFSzfsh_;Vc3`QVDE0jp?R?C z<`=xexb7;;qujt1ex&2iB{Vi`g2zrt=*@1>wcc-l8}0DIzBnkUpWLnmb6FILEj(i)%<5f~& z54r0$f~JnCgdo3>WY;);E)wq>jmuv4VoygA=*1=B!2=??g1f?9E4o0!{cX@2>)_oG z9dfhlzI0#vuw@_m-jtEVAG##SZeLDnTU4YNbv8K+o5ncM`9nsN5qin!%syxJ_i%2) zUstmEk_S$l{Rv*aT~D5H2{>z50bIOgjsbi6NPgEW;ZDAOOpaTg#m})#&?camtrJK! z<+I?Hb~3_F5&ie3h;z^jB`@9h-7WFqdFJ~oM%^3=2}_RQyzL5-4bvWRnwm0rXb0dQxqYr1Sw=YVde9`sy((Kki1YXYb*RmoFkMYk0gm z(Z>ygynfTJfq`Hh?1W>TM@dv%O@s^AO~eZdUr~{Doxhk=Bz+H_>N&&7^>HB*Eo5(=}5!_iCv8F;u(iZNoq$L zc74x-HLEJ|Z`Eh&Im3+G+MFe>(dO~0=W-(vznDUAWPb+JG-r$|Z>L2q8CE- zcvWzs5p886=vBXMf{k87F!lhCSGQO$(?oU$S?#`+v)eJBydyi&Wndc!4jQp}z>~(F zmnBP!obk)gcIurfFD%y{Ky1DFoleu@EB0sa=w`o%-26dNL}`(WRBJtLU@{69i>Uo^ zL-8^9+eCLpG(I3jpyYf7jPom`I?3~YV#r0S)l|W_8yxq2mEIrS%>T#Ib;ncrzJFv@ z3JnRRtfoq#p^x*Nw)P%MrCl;oq(q_+AzMQt$~a|2S)Kd7?xTq8?3F!35kma#?>WDJ z`{TUME6;g9*Y&>MBaeyI%fkC4!$1vHp@an~Fq7t5_?Y{#Tx(*m!dVXBIF8U<_$>9i0Vr#sNbzLnY+G(;HC@N)XR~JHf2$r z>c>WM{>d1tUDF0#AByMCSLfAo@$`Ic(ucdy^3VIh>~{~jqn6J|pbD&f@C6LcrMmr( z1z^!kG2hUEHEV?w?Wd3>)2eFFBM%IQo7#x^U2CTE*?jyr^CEw~y7Fro%+-2IR(K4f zz!Voa=cK^9khX+vzb_t=yB)}nVP*WWvlv|LVu;Vo2*z9^0vhQ%GRcUxC(%he6Ojn$ydUWZ4M$;^OZ`uw>#FBw6SJ@t1o@lhY$6)us|P ze-Pl?kK`^ep2s0=#xhKT)^_aqLY1#Wh-N*9ms>qa*Q`e=hCLw$6`mG(Ge+>*>z*QGjntt-EphAchrG zx14R44nR@jorJQWUd%g%@7y-~(PJb!h*TgE(p52gs*<*Qa`O*l8fj zyHmb_83>8QCO0iXZnPb3x6OcIsbI2u$~Ppz;er(99*;JCXZ#*T;Hk!fdCWWIHqP-b zgYVS@mAMOp<(5>q-1;4<eXqHb*^Jlv9oWWO7dk!-ps%mYz~-6<2{txj>}6QE z_&>p}_teD;R^<;6rwPx|vTv$z$GH;@CFG;@@1^jOK0j4^EtyXhk8tP|JCI;nk+o(d zILdNp2Xq`daJv2&Vg0qvLH4;P%EA!W`9LxqRpX>*dkJyjqgZ zOH~*ieTI~e1t|aK4_F`7OnlTXGL}#Bx$Id3{Jbpd#4bFrTZ8;O+l+!Qx`W}z9&-Is z7PFvn6d76x_^8W^I%zIr6fylxaqQ(x_<2d3)U7K+6|ruh*X%)zlMXYUH`d_7H-<1a zw-?21+YjknUy|7?jISQ^fRoaFWOw5Pw%RipY;PCB*M8Tj^+0oX46!T-Wjr>Xm>T~NAd~mVWTgdqJ9f_IVhI*RIXB%9>3OVM0MiT{?b~xq(er;nw z)}N!+t%c0xoyquwX9U=vs6fI&;ZSrTlJwk; zWKG);fQ{9PVea)WDA33q=DzMBms1`wmiqPRiKz`=Lsd513wC3)JHShZSu=4rPCBCs z11pEointJ{UFk{UR1~r4(Gk#kGe!myh1ey^r*Y2-Cz!IJ34JX;2&bP?Z>Ga(v~tx_ zJXb?7o1OX73nTT^BOrH$v95lO#X@ahnr}N|wVp!%~jFKBMJfqsPt&A#j zrf3W9QZeB7b($uMfN8%xnIm3{LaD~bsx+1u9q?p=SF7OGK39G}$kN2QV6Hy`E=P*d zBU*v=k-k$NG~H$j?CtRY?VR4avKdv(2?TCj91(lG0H3D*jQfSLq{k?g5$3GHW65-W z3#>#Yv>&ytY=r1}U1!anza1C6m*#ut_gKb&oUseBZk&VTF98%%Ka}_GC}#3;Z~XSI z4>UciL)Hd&fs-3cF5GWn27VmHi-ZN-yUE(CaQ@9G@l;#Kgk6Znm$zF2ncaaVsAj@L zed;Z8`GzWY0I>JRkkc9^%yHpJ9C#oK&TKA2H3y%7eM|y5u|rkA|EvRcvnvDjCW7WR z-vmou)k(Aj{kPyTRyrlz>(rP``Ph3MMVVs6-p0lv=DzU~*UeXK#ajg;$>_X5Wyz2t9W7Gro= z1dC7{{GYcakb1rEPmUtVnnzjrV)9_}Nu1~om7$>2N6=B?LCkY$uHy|oe8x;LzqxKW z4BsEo9D@pBd_{96zV8u2Z!48Zv+frN|DkiQWEitpG!B=Iy7BLWGQVh?64iCfxaxD$ z9{AyQ83ESKR&zq96$RY8$JTUQd&+<;KQ)ZpOMgKP#mo=GdCZ%Gx%in%7?c}TBfphg zSnL}~jNkjw{=sm95nD)QyuUDO1oSo(Zajp$WH?9IAnqtU+K??V9 zSQg%(n+==8a*@&d4EUhkOltNCF;|8h(1Xx;zE;X-b2%pVI^;{!PgJqg801T7-{SNF z=HVimdHgGwKc_AFQv#0kW+B0GVEL|)f$IITq?pv8P18Svb$Bz`GwlYWv}7UP^Wq}k zcQ2)>4Rf>u$-iHJP^W()l$>!OW^u~+i+u$=`$V-Uu@OuN%>&*`J-JmoZPJ5QcEV=K ziM&m=E7;|0X*SVFJUB~!M@mCCP_vL=9-F$gl>T;u$Qk)+lz6`aw$nYGv$%+P^)?m1 zz7YWnu2rBFGvC1D^N|EzM6zbkT`xp|b_zfIf_!_t;HTd&658#-%%s`)QU?W?_NTfJ zwn=cvlP@w%Yvf+M;Iu0E-x@}7cpP@hkCSy$!tChIv)F2#6Re)ygm$?egCOKfJnK%Q ztF>DA()Lu~9iV$eT_3pgQa#npD@H0alem7?2e`AY2zgz(1p7Ow56f4Ji8{)`7pd=i&Y=!eb+;N~J7b7YeI0r!PrE{> zw`=;%62|sTgSK`7s$6MB&HuR4CFdK?gQf z!zTJ%8E7al>gjv&xof(hGHnnUETb9YwjM<2s}b}0^%lHD*ct9`Y()02s7L;uKRK}a zKNR%f5*(HIMQrA%u_J~wz&)x1gst+C_||HwN2Z-eZI;ZVtjD-vmL14IEBe;u37$nB zB<_+on$2#8DQhS268=cAmFZ2hw}N*1##EzCmaFM)G=NmCtkAcu=m(3b9Mbq<5|W%g zmu$W}KvdK9*nbZ-;J3w}A;+u`seSi^S*cX3);yJQFE8O<&+F&+Co1_2;;F(52>W#l zQXi^>yR22bh6!@)Id{Y{hvL}(^y=5&^+MRZDB}M3DC^S&1rX{NC#N2kqc_xdU{>Hk z9u6L6m_mL0>Y5=mvU`!d=yCY@$(PQYA~>^hHb%4u`F}X3oYD^ogE2&%9mbqml7OFg z(0;>3^~flh2U}(7zkk!`4$Tb28<57A!$>W-A0|@# zIkz&OL0S3uqi`4qU#~{v?HJC}d?e{6KUVy@B%E|JAJ$IELE?4afW2xG&mr+CQ&u|- zr{56FX*;K@!plifWX<>}x-kQ=!&~Z+Om9Hr^qI+~&&=$HDcqXm9Q;@#n>NtqBAKO` zpeWKrb~%i*D$hG1_Lg{lo?+YkT70rpha9=pjs7#a12M%SyjKewm=Uudn3og`^Jmne zMyjpt>7ac~-yB$J$EHE*8d=hpSA#6PGNJBz6KNZ#&j9TmaM~i6*?zg}z=B{uQd08^ ziPKC7tvRB+eWKIZX_r61i)9YvYPd44+g1(vm_9#E5zMMOPmuZSLChrgr7LXg1u5r= zJUzA+d+WFpW@aXU*AB{`SbKy2f^PEY&U~g;*baT7n$mB-$IyJ~a@brPNS3~;LK{z4 zgA~=G$l4b%^GrTreXj_Zn^%GUwRu8jo(I`D&y#iU<8$0?Rt!f*z95G+zTixs?Vwl> zMkKKZiQTe+b7t)*cJ?3e)Z>tN5m~0&bst`MN)?p7htW=-Fi@2DBzEf+u|tC=9Le$^ zUiMzh6pi!Pdyx|uPi{il`Kxg4*;J6WDL|aAe&|x;R{jW^`C72`@oM*W_~bT+_iWw* z_Ja-jSOGobYqySCnZiN!0iwLrj1}#*8_x)r=KF|q(K}f2!I`YJo`ZiRegQq|Z{3EX zm=te+Y;NQOdf)0$lFeCcOtabNTrNTh6W?JsDNFcj*@1e;YT+)um(|GsKpqdjKq=K8 zxJ8sOx{Z|QSsn$SY4?`=Q)e9ETLybIc}P9{9_Xfv@K`#bjKX^{xbr&&w(l!JJ3rTg zY#P-S?^a;W|Jsk&%jv>U(EwsKM#H3aZ^)9ji*fFHTR86FLAs`#WU7vC$6XTyT6dl2 zYk*TicQ-9PwDaCV2siBD>$pO`*Fyal>P^*B~hVP>pIYt_7Zr9|@=|)$ev0gopDv#Iko1n*C%R8GAZN z>ND4~CoFBownd*I`DGzeRj&u5{nbSLz)5EEy(;dbql5h3hYj+hIBYyENcN-4q9_u{1Sa5;*LWaGbU4B^^}UKBfX zE?#LOz_j7LgRr08Nvo~Gm@h-`aap<>e-Eu#`UUc3sLp>_pL=ZZG3=`LAh%>YnZ4Fe z@Ts4)Pi}SzO8fE-o;bFW<=3Q{5c7v9Y>oiy&RomH`tuA(`{rRJyloI>(%G;5K|T{b zREQVUgo3{v%@DZ2gY7XCPiFYD#6^;E_tAWqJTnI!TwOr@cN2M>n@^bq(sFpsApzFy znxO$RZQqd1ykRsrKrqMG1rkdd(ESBk?jDH(F%j2)`dr;2p7TWHxv=;2;mdEEl3z1x=K<%o4iC zI(>Hr4D6L9IjXhj+Rkj)^rw;dytZVLA1=e0S^~~Z;@@h}KI}`q^F3(r&qr{qxJz;! zm9cGAEiC>PL&}w2Gb4r^NQt7F`DUARm!cNR)=%7?Elv9n@hYTA1IWo0U~pD#d% zb^k)xFwIzyH(}HchvDa|Z9wa9J2DH;g5Oj_vI%7(D??{ICEB0AlU6}A?A59x#;Z&8 z=WRZP<u;K`I2TEDO@qS86S;*2D@4-QT{a>c+=BQ4lOff)!yEVUtN&q`v*-N$NL@-~1c{lFDSbzt)Zg7%u)7y>bh&l7~rN5q958~99?Ow7DS!FMRLEm;* zOf~Gg?$^WW+!*5c;5zd=&JUkCYX>)MY5wQZ1ei>3h;#47Aw3NfjPiqEQFApqtoR>P zO!6c6SgHQW=qlJGA4sIv^>gEtRLFzz0kYY3J-c{&8#ej*8G8B(k^b=}xWuj|QdTFK z9gk|ctoH+aAGE=BAvo|`gA~`apx1L+z)D@4cmAgwoAYZ5)>-5Z$En{frn(yXIs(Z` z;f*ZwkvXvExi~4hT#jl-Hevr0h7jk{ivn#_@N9z+_%&XElxGiv4BcOBlfszGZAsX~ zPk?U?MOna}LvN02S=^$+XVkO60TZzjRO_7ptK{0qyk=>}*6?ydG`y_=ARuk6W({n|N*=QRl-B33=I{pAYpPazc-rmTZt!%CmrcRMcd@17?%u7}UYzWnU^Q!y#<&*Ux{ zyQYjcKdy&E^d_iw%^bS0zhw;|JTj>+J+aN(fnD^w3276nFE6(^G4?8Y>M;XQe zAatXXOfObuOfw!JVd{PUA9gWUtHAAN04c7c+5SQG@R{o2=L#1yC&vI^-Vp&`Xh-}3 z&N~ph9Z6(^38eiy8R9rx`z}&gwawS`tHYM4q7ZSEkssKZ!q^ znSY}FCP9D5UA7Lxc8JH*J+Fby;|{dpKojM#X}&?o4N`ih~3K%Aopq8~w5J#UeQKG=evW{UR zt}e8#8A7Wr#DQz-8xnta34U8i^||5HGv$7g+4pxJuKoFdk6mmN2A z;ko8`1@+2Cg;b-N7c z;3ryy7RHiw)V4P&7GBi?;ouzPwx$^qUQdUJGVapUg1z*cn}s4=3PWPB1pChbVgm1Y)h z^g^y@s`x#>>Pw4otj#vE_1#}2SuqMQnM3w2EMQ9WO7Z^mP*_(~jbh!hU_m_XI=|%4 zIym+Tul_F|zU;_BUUIo0S0KVuP4S_+2qm00&w}qm{L}dbA2f7!#%vJ3O1)a)-(X;M9g+Gl%#yp}hEDjz@$Us~AAjPy3A)5dz6VV>^AO%l zn!u|qYG7JATJQ&D!R|Tc_ybbto-1|m9xLjfJh)R2_2tZ3+A~`SAHFpajqdBr*&J>B zFzf<9Z%TJJ11D&odx3Z_%0HC`>HqA>a${w@fIe^Y=<_zo^)=J7H6B#GBgt~@Tj?sg zeNY@O%9A^>gspbL9XA&XFfI4dQwWIZBA-9aW3-JPB3bbX@KAOfJ=s_Ti#!8J#q&zk zzM}~ky30S=R?KkkXW*~9BLL5@URN^Zhk zm3FjL?H|c<)uvkDg1B6~_Mr3g?RMDAdqM|Bx*WZC1Up(XMTD|nFprE~-EDAltlKy@Wb2mwY z#r!ceZ%HCp$T<`9Epu?9YaWEt+>8wd(M*5mGrW754;0V)fu_=XTIXtdch-D@<~Lg6 zvcE}i#gpbv6wus@qJEDaWz2y)IO$4k3l?1W14JhLpN5!3zeQ;8U~*3FVz+uC*V+O9meB zyU0~uZGssGe2HES^~gS43g@=BfyKEzRMgf2MRc!JSa^duvLXl{$-M(}P212_#g8Bq z6GPHo#i8gh>TO&s%$vy)XRBmh#~Y%9;J_%o3vf0AL%Rl|-<9fLc|8nXsgY#%M@iHt zq)tvg{X-_U>ai`xe`42|&)_zP&Z{RfL8&d3tW^GwnRlmwdqJ&_?;%ngr(H$98YDla z1^rhs6aQK$*fHnDH$cUcAYy-J6KjXhdFQK#q*e5UUhAIIcxF2U2*3$SZ@ z=s56ZaL9GdSIorOsd%n~8@S%9M@!msK~;?Y?e4RS5+&m7PVM>tU%?}Xyu!-0; zPGLk|`ydN$6<-rOxV0PyRBq$%m0l0WAzPF~!p;>iLVGH(OKK>5kgY+vi*lepJ(4_o z>d&f^0K9o!KGa#}pca`_XqenimVR|)u1}wb*VmZyy+YgFwBYcMaN@sm5Ovc2=%r^} zp!G~6($H>&26}g{ewfPDtt-P{&tyYtdLFWtE`|gC4PM2R znYyH5e-E;AY{$G6!4Pa!i;P%}phCGvS@(M^)$fS?CSR_$=cq@HjYY$BPBE++{ z*I;)@cw&#Hcz{s)`(5LK>ge2+VLFbC)apQiW->^guSA!rez@>A&0cs?%vfn<;$n*k zkaDFx-Q8U17kW>2OC_>COpL-4lZ%0qnTZlMi{a(2H{nlz8=4D3q)wgk71^@P!l4uR z^;%U3iWxx#A{?ltoj8pT6|u@bYdoXQ5iXu=LKg}HA@L{81-0`+pTF(E&a$bX>sEmF zr3w*4I%^q7Uu6=V-(VNRoBTad)xQ8z>D|BVb{5Jle1z{l@Q11SwJ7IuARO9|MnpEe z*Dsg1#JV&Lzs3@yDYHeOV;I2+pYJFrwg9^5oc8jP8nf5nDCR^7@XBJ348$wWCKq

    #l+h)MIk)rW?Y;8?>0 zlDUTFOO4U*c8PLXhoc#`#0xy8-~<2G{6O(tH}R>`B$!2WJ`;3Ypf0+fy#A!kGzcZ( zcZ%0wIK2aThP6XjV+=Vvw;t79|A1>^Bl)|bvvLT$UK~kQURBU9nc$0+-;{w!JP(8Oe|E6n+G)RA}E;CAa3d7%3TmFwl; zRVQ3v<}2!t=xT@Q3LK)4lghpJy%HDg%Lb8}Jd}2;7~Jja$Pd#IR+GLLTBH+)+bhS> zSCt_wHKs$BAMHVPtDIqf`EN4yR1tF%b>i^}!L;9^7A-7qhJ@KsWaHa=tmwT;VE;gd zd`_=HzN^aMiCH80QDezG57WaL`4{+|BhqDDn4)V>hIT3A*WvA;*-X1UhF>#>Pk(@1 zdb7y?bSqt$-47>Zg?Tk13)oZb9^;4U@vt=LJ6ikvG0LVL%Kzi)o2S-;VY5Fuv!)XL z3uy;LwGH<&iWv#FuehG>gQtBekr(YD9HQ^~p!XbB-dqkAODzVcpPA_5G7Gq~Fpm6s zw}+YijrLQ!-Q?$DwW^2^qeUEIGA7G_&nYavSruU7C~}re157z&IQ)*O*S?LXG&%zE zZ$jR&Pa&E5bfl8K(4NMrvgSD66SNHsXy2u7?=*0;pH1W@|3DAkU4g}Bp2U=9X{L z?f~3`U2sTA6B&7Qk>q^8?OukG7xvqaG=~Xc#(b?>f zdoPX5?-~Gp=zg4$f7fq=1m3t1FHh?r7tu$xRZzK zG~D39hdz?^EP(l!DFw}*Dd0kLh68qVL37>z{&tE?p^`Cvd{h^v+YF%^`*@J74kalA z>UhEiS2&yPK|UQg#njjtVTY0j;MLNI^z@d4)?f>?;#~BYe$Eg2Ima8Oae10F^&~glHb9>P)bNZ|W zBoeoG%6O`&Httmm0mIdm$oGi|xkLRg(owG%?a5s1qUQ$hpVp(dXN#e1-T%BW4EH;V zz`WZWNVr&nM6-gByRBf3x;os5P2~*8nY>}N{jmsPQS6eGC}f;uYcZx?))my(Y;mFh z8op3(_#c0kV!;=j){w`aqc$}oC~IjY;s+g>2UQw)Q=$O7b^!IHKXHMtv}ZZ_Y$yCj zXY#lysoW{jwOIddHdOwXk9N-b4!_@5lOOg&tfyK&Xfj7IJH7n=5BKiZC8(9&D=&Jaq~KJZZQiBi(Q1Zs0-=s z-vvK!)4Odc?M0&6bEQ-}(yyb8Ezfk(UdR}dzvc}yy)PNmBWV}a#M|jBo&SKb{Wx*5 zP-iP@`r^^5c*t&|-bNcg^y!ZXi0>Ik=E03{KsbPWi>^c`&o3ac_xs2xEjjkM;y1kZ zPz1cItVCC4rbDh%3^6I=u;yFD;^Q=f)%r*lTD{l`Zq1G(t3T~w$_=EjnXO>&>q8<$ z`Y?yQ(wWAT2cO3OQ4Rm8y`$*U$9Hgr`s3_;6tPxs8dMv{kh}};n7O95_&}i}w7WE+ zi5ml9DCYywNODK>We(uh#i@`^JKTfci;&#S9I`F{D$}14g}sNY`SaDP_1{5{>ZSGm zWucP~(?DL7-kl37n0=jI_z=$@nlIHMPxk=O>rNtp``+nqczzq#NYMDU8TTXSH8ZI0T7f*EdD@o~ufWMd4>B={?uOm} z;bW!(921@D0e4G=NO$BNls|0==+_Ex%y;&8Se_R{{;jcNUbsENixvrR%xFhAXbwh` z2x(Qk-SsH8c6|n+x>e|Kxg#V~>~iiu#WE^1#PW$#`FrBf>J&Jv^MDlQD&hW9rEu{< z4B1f_&8%MeQ* zQfvXja-GPTe$Fh-rzHPkHfq_BhFfk#!T~Pruoe!do{31(_e4Q|m(>$I`(GJItj|D) zG~HpHLl3z$!;eY5Lvsr&D92S>iejaE;C?sNZ}=%PG55}5B?(;^*foR{ec#hgj8L-r zn>uzm42;Y44~mPDr>i)md4?2neKvsa>=9sEL?jn>)93loq-BhCdJk7BUVv#WhorzX zQiIQHadmIQrHk#e3PYr|0u2%RNH_9~Vk)Aw8u zrg%H8+L8I?c@W2!9)r`py=Z318f+~Y0-Kjsq7-3K5~Rr?cROA&SEpjCmve)<_w{HI zw-ho9Vu-2)oBKpQ5(jPOz@&pE=naoR!j4u_(?;`E9G;=cHI;mhtGl6{X6G6ZMtKA| z_e>x)lq(L~S;#!x{{uH36yV#pks`>+izIRC0j&J`uQ<9n559)xpz_BAj!U-^jlO%# zb=G1W_QIU6A3OSmYEb_K5uKQ3B>p2GFY|VRfq*6y5!MNCGm0ELoy?V)RgeAeWWyGk z`w>!53Mm@ZH~^K-ym zwJ1%m6FzB15i==AR)E+%DDRUdp$0Xmaoz@e!R-QnPc+`*0T-0|$i_qow%iT^$4u-9 zS*MJXmi54Qx)*PDc*C^VrNLi%b2Qq1JAF;FKh6?KfZ=r|Xv2)#VDm4Q+(`It?8+24@w@=3bcvFmN*q!!&y*=I;^3#@*3hrkfd<{mA(?Vn^R>SsFDP1u7a(8NBxz6_?s4Z)jp#Ypc% zIXET8kbOROOh>gBc9w8}ATiq0I@<$u>O9GdTax$``!t@ulk)b;Rp^hcE65yeAz|^S zSQ>^#IK6r**uofMmZpKqoCjoAgA!iTS`Ka&F~p%Onh97MjvGG+=Cp-dXm(oF8#486 z02=lD2^DW9@h1P$Wp7M#!eS{&aPkZ7(H?pPEnm7w&eG+~NuyNU<7EM5YMrRtl=f1o z(Yraooq@u1JYjKFH{pRVTu?#ouXdR zb9nhH!OXTx@-P&<^d**wdPr~YN;tQq1;m1KQD^lpP^UghLr*J4Zea)>3$*3)`74b- zfK^>6nZ4=_O6(qnTl@c!@R_3Q5BnW)(0l>bonCkZ954Ej(C{+-ZaXouaxdkePDmk( z(7!lx_h*O=D?;Y9Yt$i-dVaSrW2BRRb8~5~jnq{WG$Vg1lqPDBNB3J%t@vHIM4#;| zExwH60(GpOAi%mS^CyrW8>2|fs3B{Y#6nn@FG`#mN>Sz>pc#NPKU~;}sg68?Lq8mY zV%o(9B7w9MFpf-7P{KQD7vKLh)w&&s*|z6D{A%O{f37Pv6C)qjbI4gOngcTeSe51@ z{0{?{pR0g9l*?Vuu(_w+L}Qb!9MF7Ff*wd@z|xW?5@0)(NeF*|`pPT$UE9a*^x&bn z24tne2(mdQMpUTgz7etY{D;!zg!}CEpLz-Bwu0hX_ZpNIG0t~z{eh8ANW(J?RL5(D+o_Zi3j<~CFtzRXDH>6 z2+TM(hDN@K5cT{>QkPD<6#rXFeE;>6yqmMwS9TWSY|{t`v8qBRtpL*KZyB9@%ev{E zghTp@LD(+~i8^P&tv!=?ohN9w#mebeM^Auzm50Si1LgMjy_v=g7hb^CLn>f-cNA@j zcn?EA9+A>Lig>h~fCJqfbUNQL>1mF*A<+?fE1S@%*e7tyJf7(NaG^OWr?G5y3YbR} zpoz!D>72zOqHd;)YUn%s-pU&0ZRnu6H&yT^pXQcZe?_-mjDnm>Es-yo!d`yYACDXQ z!@7NSNS=CSPTr0qFU+F!-_<|BoeOFpR11)LDuIOvSO7wvw873 zy!-Ap2rTYLPxdRo1Q`Xg?mFd3uGYauBE*YtEM)90x8W;m1$^3y?Yba*CV>2HlSk~u zD?r3>2;@%|qlRNu;6?x63@h!J?jmn|e5wOXq#X@gH+sT9>H)NUCxNHsc7XFL30~qJ z8TOjMb2w|I01uz}yF;*K3o&s##d`7L6s|9u3is&!#X#f}&9T2vP!09jzo~*Ms^h(+ z9m8x^eT{cGdPCdNABdK!LKV$6{1QdKGhR`4A5cU-Rq2vW0F9uq6mdj$Fb?Jl~v9y-oye7Oj~T9jBlE=BEscrf^q>U=bvm~{T^#Yu+-hj0&tGpiP7;5gd1cxIgPd$X#cx0b#u z@3Xmea&PhPg&Yv}DnS8LGGPMkR5Cd+mDxTu3{BFi;&*pW-1`TctS}(o_Kl$5U&YB* zI>!bH7cpD=nlM*96uK>H(41A}&`dM)xau!J3aFI4YS}mh9r8o9WB0{F5~YB)9EgDP$il9+V~W| z`w|Zxn@UiVP6+Do5pZ$m==^_}Vxv**0J3!{#;cb{z~JdB##TTct<+cXk`!@b?;ZYsx`xFS7 zi{24a)*Jmn?A; zX5;m%$F!%5&d-1BkxIoch`1}s3q7gLF6wl}%OjFtyuS#Y3HF62eqChS>gCL@zE89t z(*h*TJJCp41sFaIBpz=wQA#es^=BgC>W*?W;1dJw^uBOjPElXJG7M)=E{Dvh3{-38 z525xwWWydmW`D{wu&4ZN(wQ=}XVV~z3314sHA+lRlnKr((*eW!A#{;yAg4|UA>3G1 zyqJDZar!+!NS|h2y}F9Uy&gcjQWN#^JO$+|xkQXOqV`}Nm=x6vTi)lQgX}@*q}r-3 zb!(BK5_134 zl5ZEFV7euq;qG=Aphh@yj*%2;tVSwNDv$K0T zl#XZ+J9ZnoucL_zzq#=<66O2E$ci&jG!_C!GIW=?eD~h zRvY0nH;zHF+Ank=kM^Jjza=GqXX91Nx8UOig1N3!Pm+A3{LDBfoYCF=1&jWE2zzOk zb!tv6v{Eh2`7Abfo@XpBljT5USP3e%%Yt)z8;J1yDa;xijuIaW=DIDiBY1+A0a<1> zg2E28;&UA@A?9%nn%z`MJH#W2PFeu#c0&;kNyvk5gE?r5TQ(@aY$8kR92lE*+IYom z0bloU(i-?fxw56%H7IFnDL!$;1s19`qp#kB(5TBHYoyb;xq8~wo&R!X62zIjl`)bo@j+I_jW->XToWDzfj~ zAH=$MpTotCb;$8(AEa%GBAU+}S)3kq7&DV58)??-y|Eqm(WVQ~{;rD>j8CY>{u>dO zU4W&%GXaj@;q!RiX9wXQ%^91d70IM8=fRVYRHHJ-Ha$i!7Ttqa)&A_&8Q|>m!`LBfzmX)hy6+iy>Y{vCI@1XPmLv5xn*`p~v%{!9D%A zq`3AzddxDx(-G}cDJnpZ)hCi_E$W|IZN^MfO2AiIt>DAn4zwFUn4~QtF zI)NAJ%p!6b&yg3*Y{x2;VCyt_V%=SfRvFpDQ|d1`=y;JitG*X!E4uQ#!xHTEKs|}} z2^z|wvv*fP!=pjIFJL+P0SZ|$MA^-rDaZcUSHS_=%3ILKsCY)Ued+Rv?nX zyx!i4?A9<-{6qg4yu4k7&hK3hKFj?`h^h?hsl_?0_ID~|2?^n>{TNaX-X}%wO4wp$ zJs2d@@0=CGD9($<4hsaBHYFz>I_RxLD&Q%aV(X3%c_zVuu_7e;7Gdk3=1^A5#SY1d>C@+uJOXjnlY&i$0sfe@JfB_SLml2nERda$h+MY z=SfiClWq;#cr*sqO4gC=<0>qFJdyO7a)|Q8DQLTuFnF7NhRL?Y=-TG5a4$86B=s+2 zu99(X()2-;A!>&1_sGGbrwfSw&UQr0p3ly(p zPq4OxXoA%_QGQ-o9Mu~;P~5Y$abhlKoW_$>1v}}v%1$kj|R zcg569B*%R?Warj@Xi0E6{M&XieV%x3thcB2iH?x z>wkKT=Xs`h!EFI9wbUiU{uX!A3kujIB^ykrRw2$MmN7Z#O0)GGVf(aZdar*52R6~% zCo3mZwax-Bxg*#mWBewO6Lde-d|}3HEq;%$2MTbhd1oUSw#JaD8?sS&-7~y(hCg^Y z)S&}QpTew7QRHt!n0~6W7ru9{2I@WnDmWnp8G#5c4ws-~`y1gS#iE)#b!OeAtJpqc zE8KtEkIHw?h4`Jb$S$E;)O_h4WDIza)BP8j#T5tep?(*>eoWyB3w}QHrQHE?D9l#} zv_B5Q$B<&=f2I-iGpIj3-<}Z(4#aMf4lv_S3)-_J4#b#9(rz#xe~oU32QorD_JoP- z3tz6`DWde&xr^o=m@%+X&X2??%dqx;ynvm4PlcR?LfE<*0Q#J0Ziy21Y-ogGdfT-U z;xHT5a&W7RV1LYVjf3ZNY0usDKs4t@7xXWs`qhEOY^z0{SSTb3wo?C;v_0UI40AA! z?nGw{Yd|GBfH+EKBF(S!i14xB#Gp=|tzVOgXB~?Kow#yjnivO5w$Utzq{8x3pG?}Wa!AX%DQH%e z2xzYV3`S10Q~pa16jB~IMQS!A^7mnGw^5+U1QPTF--cE1NOa z9okqoSg=cWeUv0VSE7jV`4cRe56eONswh8C<56x7y)DzMiDyoX_P4Y64$Zs#A8%%! z@*Kqfiy_*I^4M*p5-RE^^G2r4W+&+G!FzcE?D{ihGI_O!L)I^iV5Ysx#uxe@!V&5Z z(qG*Kx&P?DQvc(zS%Ivt(<<=KlsvFB`i5TR7Q!>VW>RtG9uqRY4$HTi z@psAYT?~v+PtY!!%i6uW65rn70uREQQJLgFa9_tE_8#e6oncjSci|w(5!=GPy{{K< zx|$6)E)}4eCh5>*{+>9_&S5>Re2He^SUzv2S}P3=-&T{2d9>4S+9>YQd=4pQbqGEV z!HMlrr0usOYsSsR@WEf2h?Gz*NBn14wK<*qA4%8YNQKvitt7itb{e9gy_9m#RcUMd z+Iwl!P(n%eN)lzJvPCv!p7WkdRvFoQlhLqRD&P68f1ts=&w1bHeMXJ`R@5+a4@vVG z!!h5S=Wu=6dm6A)lhjNpgsSj6{P`-Vo_%H*mkz-ZNPAlzq$WpDvA{bSF;+oj-h(kr z`y`hFY0o}U`<7|wOKBvoRS|;n+yC%{EfTcaCz{fzzgS+pj+~PVg{~3SE6p_L|Ja*e zs20PCdFrM|FH zHiCv{ztk1O=Y#_oErkIHiV)i03ehSKmLeiT2t!UKIDTYd)GjNncPE{dY&8=}#Fvtmfj z$43w$){F~TALIG!V{=zl^&=t?n+!TEXHvub1ss0%jqbEwiXN@xk-vAZ!s^ssd_b`Y zM0K80y*KZ055RoyCRm+K9(#(ER~N*p9*=<2@`E-bUnF1UWot0Ttric*%nz_`-aer}rh`##3M5eMJ);xZQ&` zA8{jl1evbGu>s4*KZP#gOd6Cofg|@&k`5Y2(}Jr~c-bWpn6oJdxJ707{KX;|jf|o^ zvSFotm%?ybTpMn&-CHRIffEs7sHM?&fk@^{A6Gta@^km(GMD-iR*Mwl8X z!TZprz?F&nkNipu1ZrH1wM-@HOQv%ZzZ8n1hTjue5f>P@rVWdF(1dgBfG^Cb41zv?_Q~)29u% z^G-c^uj>fT{T;Zd46}mqyvcF= zu2}tzlNe94if(ltVDITaqNN-FE$lnUH5-BSeUWrP!|K5+*g%~K9vhp}@@#LADGO#oK*Jw)(a3;b z4_#?UrV`1CFNV(DOp6j5i!_uTkfftF5VWNOk4v#24#!dBthUp3V#M>yH;a%5B2G|2%_lq7gKH z=%udR$P-fI+5o9?6c=xjfg?s3k`7klp4?BM$~cF-%^K*~vKvIxX%hr>4q=(`v*6(! zdFme1hzp|ZAztbs{b_yy#a}%_=46k}Y1i+shFwX_!#uYfuW$VXTbNE&>8Taks^?F% z!maptwYuajtYlanTdYnBiU&ZtSAeIZA&EuS635JHpcOed8C`>Gd*bM&=EJBXL;(gbq{6zJ)%fxPLF&V@ z>AufYWdY;2NTul*c3HCdcjdun)HP%#i7C570=C#g)yZ}|-`NKoy3%P@^HrQ=wH79P zZ)ceTMR@N#L2AL?*=t_6(btWyi0eBGu+i+so-;}zp3P>8_Y$y=RvPr5iKZDi37xZG z^LC3jAG^F1yuoZn8qIn)p7Ua890YF3fil^0d_uJp*0J58$Yv4p@DawTNrU`(Y)QQe ze38(g0`Xn=uB{<>9b;LzuZ@wu$68W<#)Y48-S}6Ex|v1Oy+WrrN9&fs@O2TInp1_H zl}e#IHHxNvwnZyBm&nDggJ659ABV~W!BM8=`0`SLtXSU)gGVKJ-ES1Q6Hgu_N8bkm zim%0vZBo>o@weMvvy4H_V$vw=0?zhrxb$f^-}C5FsF!u`R4QRv@%&wK)73IqQ`$s% zB9dsmaXdcsxR%JUZfl2fad3XOjmB&k#Tj|u2=DR>kY>H=B@P{6J1&wcxOj7RxipdM zthXps@B^O8^2##&+vvUI`^exGm&iOG!>c`yH?vG=PiofGfX`iSB#o0D;l#fVym|k3 zQnRA~G*e6POCr`pA(PoPZ`r` z6o)hs>$nj9d=<8_6m~bTd}-epPQGU@`M$mkVw+gU_>nSzg+jcMQ+`M`Ns}~cn)17? z1J2zdOHR&&Gd6#5{;iMvcV9*z4rxh0Bq0oo{@m}t`xNdIKl4;rBv8scV$zhu?&h@_ zSCLLoD!J--3!LWnVhPj(lG7QVAXR{yt_P88KfR#qJImu@GlR~A2)bM`NVjE{FVV7T zfSx%N?{1IxwE0CPo8dbZNgWLPmp7U zjmxQFY=cGYC>@ z|ESYOG438gD^gbN2gCMtc&7Ib7(U5*-y&r>rN6I`-8Rxtv`c_kCA+6A$&{ z-&Mg7lJkms$SM#siB?d^72{3(H-&rt^-)sl9|(evSkK)a85(jjnjRkrMYC3w5>B5p z%a~}xclG)}Uoe`6h^)`LRGdyGJ4C@|#+~wX%i)Z61KnyPj<8n}Ug=y*=I<3CnkyMk zaAiBynkGQ{RR+o54KHA&QX^Jc@ClZQMbex!Z_by5R-!Ln3`@}m{3Wh|Wo2~H!WS?l;`msKLI4auAcnJYIcr=o} zu(Rb{YF!K#w`J(Q!;RR6ro%Q1<`E;>C}YA=^7g>kj8u8H1hj)K_%qU#CqlGuel(Rl z8i|splt6Ay1U0g`n_=}Ql0<05!#s})JmEwpm}zxTg?bhABRL7HwF>fgy>mLPtq%jl&t zSP0wAq)?p4Epn%A27g96#WaUAi(L4fXzSg|Ae{Me)~t*}daQe~(98z3-gV%c0iAHo zMS>@^b}g6uzEAF-PX(19jO)88L&Kez7Fy#PiZe|kQ)_NPs7Egjm>5hPK9Av2{eLfE zvql6B<^<`+?)4+y)eVqnNpbViiO_#-440xW_Q40$Xu2d_16fSDMU?XNVUNKO-gH9) zRthUnUTPC|Jv9W9Z~oCEAtfk7|0K~!cI0#E9o0IZ6#WCXnw8@Rd-~u9%bTrLxQ{NG zKO=W;Sb_0^F5D@e0O$RJ=*t5t#BRed1O|`NY~=~uFTGYorOpqwda&C>m;t0Yc+s~X zWjWEZS4sa7X;42dK%R%?fmeqO^{!VY2CSpRk9}t?zeXdcABkkwf=8f1n(!3eBshIK zh;~&x#z8zEzRp3tu?(YI7O?PG9Nj4=j4Wv$kzqHWt4I5Au73vvSjctAi(nl7y=(FT9wglhpuH+H$`MLlKCtwA5?!-Yg!3d`iasF` z^p%JNemQ#r^ONO(CoX5&s!BM=IEv;^i;!!&7;ZZLo$uprcAfzlC9`QX%QSQ8F@ig{ zS*F>Nt4MSI2GWjP_}OA7>t*Q*hiLjD{S@cg<5du(E<(lLSK*B}Dk0{56#crv4hiU7 zV;RL`IJWOb7~HIVMSrbVAUV6++21;zx9ZPi?iZy~q}OH)$1Z{_RXE4~%oSm1X-FB7 znCJrOE0}NP*B4kX8ciMa*JsT?kVOvMi2`qhN_^^DCCq(=%;3%WIax=S?znr2+FRnPq{DFUuT|S&f<^PLOObLr|IV z8T(KE2vtih__{AsVG$a$j%i=RSq3tEga=hDORep0M#h6^vU*xPbiS^@!Da-Yt)1HB zs-VrWZ}Bb3vAxggaXZ=I90D!|_4tZgC0uQdqVfM?INWz1$QSK0I5s~Yi#h?^)99pw zkxr;JX(4-u#xPA!Sc0y!4WT8kq>%A8bE5AwhG|dl0EDb}q3v~wWH6=*{#}lu2ad)e zjRp_$Wc?VXb*#20YKu}q>`Ms_h@D7p{TEG#Z(c(a_hphf%oiO|4o8{nhc>3G$&i}JIqGtq%)2HHWiJGXq-_Cg%Ce!C+my-s8~xDF=GYp| z*C=g%3VApG5qSP-!ZDI5aJuv*-GBQrUZ^fWV;%|enigwu=`DZK{WcjCrk3MfZ|{NJ z`&fE0LkRhM7LegyV;FSm!?x#y=(v*+baH1Ce%@YA6xj^cELw{{?#l$uwg`H9wTkY? zYpKK~o9Vc=zQf`89;mZ?+S0JYsJBN2G$*C99-10_^1wJcU5j~Oi&Rl-{9UrAX&FDK zLYI>R+DZXbyLASs`@}TNW(WC%A_Syk8g&!F^k<{OJeDH zkACE`P!INu>wt#E#dzSvIJ#sN%O`(phFX{gVD1-lKE6%Ut6}>t%go%Eh_}}e;9X*K z8Yc-Ine~(y6?uc^NCSRh?E~T)6R7!rLLBXAaoBX3?SsF{ajXKK7EB*#bJh->J!3+I4;+Laclw#%JQ4!kqv$VDMG_Fv0;O%jyiL`z z++&`G^#3{tE-kxi-F(h#oEjiQD;D*eV-p;yUPnr4y1?UrJ=!Z}Dfg`yP@M z;ShRqvNT$xe}`I49X@-npXuu)cba%VSCSlyd~jI2z-)R{RME+o=)s;G-a2!?GZPA{#&DPSyyAyu*p z>%ANV6Siai*3?9w>h6*$2KsRB<`C;7nh)wTqN!Uaa@1y;kiY+=z~Zt189ntLZu;0z`#xpjtUUyC zdfCnN@@phE{w;ae=FZPZTsY}1Y%zIB=Wcq83+)8yk8y&$q`>*yX+NKlPj1POEm@8a z&y9kFkS-c{QVSiq_nx%X8Np=EUL(WMFbpL&w4HYVhA*hpjXXR zbmx0!kgT+7kiYN_XVkri@aN*ZTN7H`UY3SrFE3%_} z8DGz@H6a&zp8Hdd#|*OZ0S|WCF~7No6KZj{C-PEbduY%I!@XZ|RPX6&%vIh1KV&-K zhI28_OBbbiY(D%UWR9kui6`T-%)wz#HY;sW}bwCcKZ;E z490!2J+z?P2li&gQd3U>&XPHj;P77#7|*J}wF!05oXfJj_AExSkrMdTzac)>4PV!Q zpG9L>*R3nPPii}vKY46^b1amj#FfWsAD~( zEL*_K4kc_bB@+e5<~Pqx4*{{y%&Lih@yyXSND~p}jT@EW8p&TGsprSIuaD2=XfDIL zSs7u7I#-cZsbg4YZ#e{SS?1oWn)O-6<~&kh5(SMGm3YOqhmh9pMk{6|aL%-4;BQlF zh^NCSzAG;eJMV0#U(X6KUHNaauKhV&GiSZqXNSO;bybUu`f(;K>mv)ailJ`g16H$t z2#;8AZ>s7Hv_fHlKHpWn*k4ny^bCkBZMNNa3hG2;J+z1HGbjAG_@y-I$eC zyHXI=$QHoM)1}Oh%!9*0%+q?B$2o5hi!*~_$Z16Za_P);c(qTPuJ>SEvF121a`cDj z8_ifOP=uOTMAEcbb{x4?t3Zn@LytfszVMm{CttFjyIZT#gnmQPC}RkB1U};ry%o^Y zXif`F)rfVYDAhc|_J!52kfJ~}1hz3=*UmB{yW%fQ4QZsAbRsvyEuJ(s#eo#CyGCLT zEY)tKiyDduJNIMUg;M z9qeUXN9oTv^xe{noYA#`!xEkN>h^~q&(d|Zvk&8&jO+gED8VZWUdv6Zbs|A4Q^7*L z6i4yoXehglzSw>pNrhq3&~p>kzUalpRaKzX?@b%jl5nh%3atwqqVZ{}-0MpsNx(TT zFf40gd(cDBV0nz?Yn^rP{0S!bO9S996n`|H0`x}~AM2+048djgoxZJ3f%g$-YA`VpvjT}nU06r#8H}Vm)96wW^54FPFqrQ~NACC_lLrn& zF4&Lt|J7l-@)lW8B?TpB0))eIIGy$G(a?X4&;Ruu$_80iY}9LHd?=0B|8(bT_2(~3 zgX0Td(uE5j;|XUTK`i@zc_w6_=^-!3n#atisl#&4y<@2%^&X|gS}<9 zUOOSJBaQ?$+3{z*yedDqE5f{K+>>}q-A0h;Xy?4m$6wP2jem9ZL!@Am zP7a9gV7Xq#jer?HIr?-l%2$!XbjJ{%bNhW}F3j1iK}UtVv9E^(`1rfgBfqX9P~SyX z%^u_2CUva^1$$wt<5`7A4IAO)N7j#-W`~Zdn-kkt2l%>u%NviNuF#DdocoK{o-iis zSB&kXl5$fh++sd);cyg|Swjx7?%r~@cASv?32bG8s9mUb)>@%=WZn5FSP)c++YS(H zc)o_DNeGaE5G8Qa-$BJ$Z}`!Nf5@iv=ivLW5r@tF!MZ`C>GU=JoO?Q7iS5*4n8ET7 z&72;=RhHwIp)mtpIk$(bC^3Q~6ML|(X&1?Bwdd<7oa4sP&B`njtT8Q1@q-X7RViRT z-co$qj@`H- zY3Xh|j=#cch!Bur`)nib-N}A0OpEd(W;Hr0e31lYoQ2w^KKvn!b$s11r)O`fkxMJZ z==$x^bjtZx=(l$*G_*v}Gpr0qnPuiY{?tf?rcC0#{F_LG;^M&kO$8oK$%FWYRvMV4 zj50lV7{4Ez)A|d0$@=-s^Zc?Nw|h21CCkgL50B+EY^)-8_mshwf_$vXy2_s&>!7yQ zPN+a&HTn8@Y&JV~MutXx38C{Mq|vCm6=?~b&i5HfTzCi8I?nXWMn&?zyb1IYS$-hv zwfC_0CVJCZ@7MB9oM9ga%Iw`#&a}h9+(9^{CdQkkr_DXN(2XqLmZ9@TRH*iC9~8I$d~wm|pUp#!YdKCIj*;dnLUID-OBC zixF2!pE>HLZ;2$q{SB}|lZP`}<$)!sC!$?hJz}v_}Khk&?v(+fpzy$`?N5U ze&HU=CGW!STT|g=MIbf0sz`#by0DC2HkP*@*S2modJ`SQelT+Ee_YRA%kbe=B_SxcBjhnqmF_z$RzJP@ML}p zsWK;|eZZMK`eg^L!X4Pp$PZK*KFAzCinr%&f;VCva73+y&Ce64AN#EK)R?2QTFE4b zVUc@TH(ori1#U8bW$?E|yf29Tzg(iIYIhRa6C6NZM2un49TQ*HF#n34)%mSkAuR)n zvvVNSv;xQdXohCSLyj+8jLxP@W4noCSacz0KDh7HpfkALc+mYGqz1Xs)}_}_Y|($@ zi}V;4X@eMDm>WRn9W>yqn9c#?c*Yw}V;+R>&9I04nWY_es7(DXx$kv=&;Kvm+6ksJ z1bAg)Qe5T|CB-^{us@>~=QvKKlbM!M>1a5b^sJ89x;w)qzjiFKz6VZRdP&I)?JO~? zJTmS|6sR{;;-=L+yg_#im(>5M!tL)n=q*b@@*?{m3G{jn5Zs7EN`65#yOpfF<sx%L_Ca~PODjsJfA_*7v#PIKoClqEwZOSU@ ztTKduyr_bw4nwk-biP~zvRrd2=%Pk|eFi4&U^k$buaLo{1{h>`6)Af!LrW!v zEZ!3b*KSr|!LoPQ!AFqq2mhw?g-B|KfM!!Y2GtfA{>d_M>S8&Uw%3xc?7p~uG#`Jz zQVfqvJ88R_GfFa8OLp8Do2ks3WNC#=D1G)v8hstOPps}t=kJV1m*qj}FDIJ0K#_Pj zx5E5P_6C{9qnINsk5tqKlJq)p-u@m45fuwX(?8|El(3I*&C#G z14(LUlM|C~!pE3iJa!y1}lN5B;#qn{JoEy zzJ?Qz1^4(nW6|Pt78D*bNo-`qq)-+V)d!yb_R_xvDGs2;1OzXlsu z!yKCv=H#Kb6rU@z@F|6zKdkB3B4x7r;vWc?VDHY-7*xDIi&%z@%~6SZg>anlFq^yl z@wC)XB4CmXqL<3?Y0(rYYX3yDLKmQb#4+X%JMT~QZIfDO_+X~3M1NK*yV8LE- zTFUYPo@!a3VTm_nyOTM1{OiU(Wo>YU;gZMfB)o!K2rBF@R;7}RCcg+IWrp5hIkyov z_xXaRQv?m2_d{1VT$be!=0JUZ1>O+R2FWcfYhv6I^iNd=*L(N#JC9y0UkD)^H0byX z-T3r%Yv@UJqs=bY(2lwTL|WbjEZSS}^4}Bap4b5D8g zDB7=JkCrvuBkrmPKwqvOr|HMRQ(cDPK2ynrXZ?USits)rP2?I(zD=&k2EzQXTDr+nrN ze9pluQmXm67VcUzVB;zS8k`|W27?8l-RU{3Yiq<(&;Gy&oBzub{W;Tb3=_L~#jwt& z2#-(6fyTrPN?AW$oWddEkuZi=#o^DPW#fCgI!KB5i1v|Ntoy*-wG-PZO3?e(%pI%LJVJzS|mLO&I@W&rT8J7aH9^i&q(q% zS`8y>Dh5Y){NKadf)z8wXzb%idI0P=+a9cgFUm4BTE7W9UoC`{$?RUExCUuFze;8% zorO&9XZ-VK0N@=gtMH%{IT26`Dzy^4S;ned-CcEHDQQm2!qmuSAqg6LHkt~4e}$5g zn;@f;X*EyZ%Sid8PJI?j@C@It#6v6u)c@7v zfc!RSWgOA|iE*3@2OG#^y)yVYr2tzyeS`sEu;1 z$mEVSne8>5f4lrvkO#5#PBea+BI$h91_?|Pbv7{`edzTir+chHOtTXoY)gd6@r+NX zu)~fs1|Z)}gm)%z8TUf_BeMB)Dv+#FT&|!%$G>IyC#(yM_amFQY`n>Kyk0zQO9MER zKc&rPiTHtSED=@rf^$mE*zimo3^M&v*4AL%vfS6KTdomoU-R(4Iz_l#oCTOvVWs>( zAjmL((d;=WEXRhNyuFcs(>zqS6b^r%N?%(w;kyTJ6KS>&e&5!Hcb^G?q5nQIU+@9E zbJj+1xibX0*UPYb`X6|=KAOH>ZjBT!Mv$-D@4>3*F8qB@I($+Nq{e*;WX{zd2qR5& z|Au}PzR8VbvYfU4-St>y_8nrNCj}Y~0!)We1{N=@>Fnpqq+#kP^s?`G^ywH>Vn)c- zAa~e%u^Auw^8t25Fz<|J0KU$RAPGCha4bHrjNDjf42?mb@%bB)RF83n&s#cifPM=( zs~W*FE^2W-o8L~GGVW`hs_tLud~z$S8dL_~;f^oG(B~t>6CDgfZ8z0nrU2W`AJ*cn zZ|z9b-=#3!?I(UBQ3UopU+QvXIuRZD087K8=(RP@NKV6zjDEC(Fs%+O{grV%dQsGC z@CXjPw+%M;v_o)s32r+qNzbs`jjWFa`Y-D(snakAop0SZ)3Ot=U^KNpoP=l9e}G#| zH+5xuGTQw01u?(w4S$VUH)x$dyzdXE#rMDKu3a<<4r=6piby5?e7q9~!yMK1OHljF zN%+R2LH@3{En+b!t<#`)y}I!cXIqG1`?4rpL%-aQ5Zvhut20}0fDXG!y$GNOat%0} zhxA~gsW4r?wHhnz?gZmz_OsQtN6X25V)t}EKQFOoX9^r-Z%0CsBKdOcD-3-X;1w*8 z=AJ3IL!PMzLgc4ftao0Kj`v{RgvM|rZ_-4ZwZ?EP{`@FhVI1|`9~-jNLO+mz6H#!5 z!}P9Ka^YQMI$dzRkE1t~hr^x6a7@lZ9gO`A=%YzOdX^e``;*tvpb7T zyFX`L(oYi0IDDhdA{-u`3+r0asr}D==$zwGV))VsG_UsHfh$2!F#bKg@sQ~%3qF$< z*dE%icj9xdOw;?2W&W7qtlXpHK}DZcjy z)~FGO^OCglH2ZEYjY5NmTA`8o3qq3aW#k>#pba77yek`5a<3doCou+bu)MqiuQV!! zqE{{S$!2BL7F>iy^9A`?uSsHqq@g7k-cM@4b@rW5#QF|I{)^+hC(XpfstkIq3UJ!d zD$tbuL?>T$L6=x|bnxskOzV=FOdVZA>D?L`)N;j^RP3G(v66qW_DC00GJe4SS3D{l z2p}DAt@%5npWs{YWxLPjAv;{Z_$LG%7U6Awx{NEe@(EE{%XDugr8xV%61~oT{)yjj zAQS04GNso9l$Z8ll-3Ld7oJk%V~KcrO9C+iPyTE+=V20La+puwBv|*;@JN;9t#tTxr$yIYxfzaG6*vGBL$7G=u|Yt^%sdBMoB*w5yQk@KYqTOZ zicD&=1jD>8to1VsR=7T+eLLtc71-T!A5 zN9z7vGCx5QX08+Hk);B zQ`LQ{@}A7Kt_Gvu@9=x$GBCO%#9Lh%geKI^hNb0i;T_Xqeyy-4kzPyr8jOPzOW?1i zFGcI8lajk7aQ+d?liA^nMCQ8_?^-)}daVQdb6B5ydOO&cl;DJSQq+-YI5&=1pl8q0 z$ZJ7!K*~K>d2=_!$}{a^coKHn%5qcBGu+slj9LbQNXQCrSj+mLhmHrrqd(zvPWE@* zym&bXpOga=R#xH#irpZ~_>DQXOOTlIWPFtj^0|7$oy*|DSq&N_+=I>-u$;pVHZ zqyHYAAU`{t`Lo%c2az111MPUXf*{?_WtleIjajwFO9)|i$wu!g?ENtn?pa7|MEPIdBeXIHXAWzLT z;kKUvHJB?z45kRfr-RSIRIdpym?%iI*=<*0Rsd&#`v@5kEQWx_BJA3g3g2v)Mks6p z@=H5G`T59{}=YGgP{|*42glz!~)p<*aXrY6L_=C`_auoaR{pM965`2z z#CDGb`CPrk#bFYV77VvE8*ul!ZkWsbZYhuAIDZ=3h~dpLprHlWfc0QDCv?(#>CR|Q zx<0XrVwQ|J-jP`XD=7P;QABXYmg_%qn+_7Cv$vJ>5^sYs><_keOS^KQ&f zK)Hp1{#yi zRug2_l}}8vOrYslAHJ;F2A_xx`UA*&gV>5TC3$xwHC_s2Az^D+~z(kE3IaLR&DTdHy4I3WttqUleMIq2;g z2NHg00|=)K;^ob2VBJ9l+OxD3>q(_U5%Xdj7Q3N}_WR`GOh?#$s12_(^8@Gc8Fb-q zgcU!#)2?M|yoKt;T(yxc;O8?4x9!VtmZA{tm=R60J+0A%w7mAyB;2 zfo|O@M6_JfL5ckv{*y~XPF9{o*`DFslX|Rl^d9+qNs{lEeB@jS7geq4Clh6&w@rwi zXS?m3x)`*!J)0!?xWj_hW_)2)87yY=(#bmk_^;P%@@aE23}u$%Hy5+uI_;#&m$lG| zIaS2TZ4A?VR(2AJ&Tyy_s>28O6hqtH2zuK=RabCzF`06?8cxXO;)4cN5Nj&LGY}3& zZs#>&J;O9%@j5&kPoRbGL+J+-MKssIkt_{a3hUnd#9vpG!QW8Eec3sqfW;mpf%QDu zC3Rpa?GW%|9DC8rqquVGPPo|E4#zf>;<@u>s3n`(5_jD}SFUG}WADwNZ&eR|`Li2d z2fw2I2N<95{UcPcyLR^DWHj9{l)O3N4U-6)*;wvEf;97T%Kgw)KvTd$DhC40D)D06 z3roJTKKH~WNchcUobslhp9j11!3sDuM}t;(b>lwGGo&%Z86<*RuzRZ%(<=o~YPyr- z^=Bgpu^dlV-zscg)(d~xjbQx?d(@m{OZ+G82d`J(aJ@-7P&TJ&j4G0vTSG8pFiJQ4 zkmT;aXhV)j1j1jIPyXwi3bl)2{ui4F)O5Lx7&khB7HP-#ZVS;O#J+2`8?%%bl#$ZF zDEK8@jR&u%gAm)VliaE~!5+mpEVr8P70ODV2fsfVFdc&sc|KnRT&J?VaTU`UnhMc= z<{e&sJb@**&?(7dIqJb%*Q62bf^qucr0@XuR({n=0tG%*gO`U z6bxs7zM^TDq)3W!3)uOJ@v`NWxce5gfY~!M+A(c9$>qpU19lI6k{X5TL%NvGKY|7x zw8{w8XSDRMSpE!F{izE4En8^EC1rGTQ6;X<6NJ(HQS4X#gIx0qh8y|~*hR1pp0L~5 zvC24(``=FDd!Y<`3JdT*^L|*in?A%!*f-A zNhtH#DV+X@w^*pqDjxIMfeG@00^%om6aMo0*o~|Wx(`03T|SApt5t)l8x7JS@oC(K z3(4fGktd(G5Bu{5cxNK0M}Dww?CUo~$+r&+6f*D&mor zHDCFW_#Ur@kOjHexw00b*qkOeF&LRv%>ko4Hc#)W!@27u=oj%YTF|D5ETf#r*RZ8v zD)9^NtE&Jdrn%ApXY_pVF-f3fm?oVO21}SWsbKIZ4td71`d3Tvw*H5>NqW1%U!((; zy)9*)HCg)OR5bmXbqB4Sl|?wNW}wG<==R!Hz@>W((~6SO&$;2`$hfgRR6#Eo=7~p8 zbF5_YP;K!tE10AgXNib z7pu~(DJ=K6FalBI4kG>Di9f%cC}Y`-%r7~wYGc+G%L?+yJPJNYRpaiqO#Tl37*})b zf0wdM)oOlT;t7)lER)TEx*7?QlQ+h}=#1x}5iiBc(F?d94{2({cZV*JT^$N9xXpG zVVx;ar}bgNEE#(3SThc+u7F;qNtpL-4cfBuE>WvH!{^YdSB8Pyl>hg0Ns)om?QmIH zj29ZB$lX8M3Ij%FbeisT66r5X^{z+L^CMB{*}NVYHxxl*!mTn?-pkW()q~Wea5~pI zmy*RlV__=eBF;I~;6p)zz>ONkYoaI7Bla)ou+ulJvF0}c*I-bvXuxkDe1VrtKR-<@ zp7VZL4{3N(1{XC7as9&`WWC@R))k&tpjX-3eJ4v6y^nGrUY=^8G5iOwSzQX(KRVI_ z%?jl4;8*ZvTF{wc2`Jkzh=`oGhEvBov8QA*%Qg(6cYfZ%0UFQ9QkMH%xb7qNd_RpQ zMMu-O8*ZXh+YdzHya}93?!#JHOgD8jg1&Um#|?Mq(vRT-bVr>k*E;MiF_7@&=Y}ax z&H$HPtS{zQur^-${0?S8F3WJZ$J)x!VwTS- zHy0%+I}_=}8~7bbE(RQ6ZAVnxr4`G+!eDcOc_MgjXqk&0acyznb8AXV{J`N-GQD|o z4gNLn5giCr;a$1(o@;u02Ygi?gbRsf*r`l}8ZBbkAVb#Za#tKV`1dYrUWLsF60fH&E1>j%Ey>hY$DzOe6GB3+!im=pN+KH2?50vex=;>8oj z(Zh<&*Kj5l#Y*Orjn~{+Z%_*^GpPncc7F+L55SN1CXi?ElR&_s9Iun+!2{cND)wg{ z`gOXNM3r3O@1bp3QuNrFaK@jv;AwKbTR z%EiVO^I%cKTQK0U-hl#1x@LVC72BhPymOt&{E{@l|EpT|R5bb$Tg~R7CowHOlwft+3 ztS2~mp32mh$uOz?C6)J{NR*b0fML`>>RK(y&E`3f$1P)6XS`aCPKso_mT)8r z+uB9sJe=TjM>}?2Fpi$w98EXK>SxWJP))KgM1ksxYAkb$@b9@-`>Q#ZXgR)@RK?eo z?RH)a7fTJOiKh@bA0x^-@1BDo>t&ubcN~q?V;N=n0i3XNLg4wi2((O!vFsTFb1kB1 zr|1S05Pgx9e7XYp_j+)zkQZD!_nK))go#7?Fd5OYhpD5T*hEi?UM>lvl5^9t(tV^r zN1_0F4a!)qT{XNaV7=9gb2v*k^Kh2*819WPT?r!xS5rgFAK0p+6|6sr@XXhBqiPFj z$iB}$+izO%x1h~Xt}a98hBf1>?$xk^Y4eV*)IsKsRwNb9@OM@Jos3^PE6fWpp3HqM z+X2#sW>nK+I?0q{lN{p2wH_C@mJBh-6wFnWsh#R;&NTYGxlHQrnUCpI0FF z(+6N0dryyiVRPN?5K?}~8af<1v7pEsIFs^{av$BnhXr4dSmr5p_4$aaHcqFRvC*{e z^-W}Xv6y_&Hv#;$51VZkrbB-07NAyu|NcxPTm?^9+th?@1GC`S?g-jCD@500A|YLe z8sUOPHugI)6C#defwgE2mev%d0n6AMx_d5Cv~VGo1MB&iCK-Xi!JKJjU$$VGgA|Ul znE`&eA-C-gL@~qx0;aa%Yzsfoj!mH5d8@G5mPhRSt<1v`h1|ZBonT-%2nFlQv4XZJ zeX}&0R?V_OPZ;kP`};1GOMk*MZ|4F|51=KE3S{jS3WIFV+TNOqwu$?ZUAz6@E6b~w zu=It4XX2^;p@kgxVQXR#A^~dB0z`RcJ-Dadr<@37;%d(R{P~QJN{B^zXA4QleRnwO z+QPW&px0Oz)z;&GLAkP#I$fK>RhpDce%B?zrrdIza3BZn?P#NP`8;I!rH(A! zeFa3lKI65QK9hdyF?`!1R0VTgBIwE~({#_dSCdx;)lh7ji?wy~VNPBbt(@k8Du(8R zZ}wZ5Bv_9#w@TBLi(%A0P6_pmb0t>)mhiF8Y_t|aUPV#YU(QIc;VD@gYX{<@ow$Dd zLpaYgeuCdu;{QVSg2LT)=6$6X?PL^5O?}G0DHOBJTFcoH)S~={u6e{{+L->FhI|}{zwi{{T4Oed zt5xBd9fNR!@t=Dwmm-fJirDv5Kfh<(H)0(WebAteEN@Lz=r0(i{Gpp2s?gbbWAcgV zE5iP@;Kb62tcNFnhTPr7sW#aL0=h!9Ac1+t8wcU7Of;3B>wsi;I1$s>ef$icG{aFi ztvE_kmP>J0t#l@WY*%f4ScjjG=`<`YnzkN}L>oEXB<}3k{I)ejl-^+6xPpm()`t@2 z1!tbkGv3u$gysI_GH>;wT{WDWoN8S1uZpiR^S4{Z{GkR^JyeJ!H;jkUjzGv_cmIz; zqSS+VLX(xBaYO|~U{`+;q{bIx1t}i%yGGH>?Hf>|xDgS~z5P2IiW<0+GltzSkM)_SR^oa~?-0TNeX$uxE+6qBaWoU3^Gd{At4!S#| zXvuvYl(c{WqLc@J0;A!<~W(#Ce;O18_Z~4_;iwGD@Tvo zGp(jaG&*PV6?FbEUSi(;jL`;Vy5#5(t-3pdJ6O+r%DJ)db6F)eRb^Vx0XI5xem2MC zK{GDdJ$6T^Tqi?&yL~C|B>Vri{3Gh~#;|Tsb_ljIe7NNn&-t71jfBLPfoymoHdK5F zy9cO<;Gr;&u|YvU|Q}dB|2qE7(IP{BDx~#M6OOz?QkScln+=l%xTuf3#3YwqBG(;kBD5c^*21|;+E1yNwR%Grr* zw;i5NHx06TlNRg0m|sH5Zka%w_Gf&-UziqHMbMp-3-Ix*bW%9a6Fj7w|3}hwhg03Y zajR@)laUmvx4o5|?@6VtrP3bSX>ScAq>Qu>A{iM`BuSpGM1V$1aEs8)CS+%U|iHy&mAiu%Pyj6kwA6eY?>ah}`m(COvV;ZS!kF(zf;%zWQJr@L~i-gwguZbP&2`5zCs`I?D& zo9B=UK|5^PE+vTjV#1Glwu!A?wV<;mhq$(@U=hP?>lCkYFERvlpWa0X&Tk?)$=z_4 z@rhIOUz7HzGT6cR_oOEY+??=edMN3ka1ZR3W@{O8jR_mr8h{Phg(U8okZ(H@$ULBIpKlZLo#b~AawK4%sCoQ7eixlNBw zQ;q#YoW<{T%J`ww4=YEmZF zc5e6+j42yIc~YKGgKqdu*`HH#zD)<%%$)nKgxuuov)dvH%Oak0LGf%4cW{AUSL(6qF(d%*%ZxXe>yu+o%+=qFrm-fUl zArI?~tf%|G7bto|f(E7b(IBQp{Qt~!yd{s>9l^-Af0Obtc_h>iq(Lv!mTzh=gS&N+ zm_|~07ngh{N_o*jtZ(UL6G)zIjEe7j$lTg02(B2!StXTR>6ej^&GH8y_Es?td=(_8 zDBvHa-TnHb4D1<~{WxX;C)4Oa9ZdHLHE&_EwV*#Q%Wb(sz#<39+xyVBFwM}tc5KeCN+sWptldUq&}JKPgSx2oI2 zy9f1TpV&LN-4TfA%P*65+q=N~?uI)~0cW-@gf=aD3r(pxWd72zc#uZnd#`g`{I49E zl6V?!Xtk0j62oyR`)!_xPbV*?6RKR|1<7KSWZr85w6LA<#KmW(H}2ns@;o>6J2Har z_w*yZdZZi{6?`D;CU|1eISqlK?ooa;-vGYLr9jw*BJ%o}8#B-xw)HN>53Ol5bRz@ntmbXq`bWUhzb|WDUW;b)WgOA~(PS zi!PX$mq%udl*Se8eyL}^<8;<{`S8#cXwhyY*B%r@!^<#C@f=GpJ^lo1&oJC+Q4+W4 zRsj7y-xu0+%82JFU)KE{g}=Hc@D63%plg+6g*igK_bWiax5K#}T2y6)G#+6bT*LfW z?wH6o%JcL9*ICs>>|!OH{L1_(m;Fi0L^0H3xvT~is{Czpl4xvDJS?ioBTb&np_pBb z%e5wQ-j)^gN%&FWExhA$C-dfqf#$OkQo6Df8XvPPVtZZFmqq2Y^}j;c{PGhq_xTD$ zwGO9-d2rK8r@%3XMEG^2l;jSKM13{`Z)j?9#y(7I{bXncvXFF0TIY$2)6}WuvP$S; z9ABBaEBD>gmx>%6nunh>e!;DOl7c!L6aIJGEueP17Ea#IAw@gXFqYjoTTWl)z&4dy zzr6sfKQ)o>ZhbJHVfAv^o?Qp0pD)pxf7YD z>-Xv74lC9rF?=N9rE0_Gun*vM`8zqirw<-7O#8^+8Qc?D9r9>@yO7s#IlBnXJ~G6A z&zs3n+w(Me-7WC!s3MaetDqCZX%#lD<6Syp0oT-r=APxzK86XgTfozaqZ4k^;lqdK z-p{hPP`BU-9u68oKfH6J_gnmhv+nzsvG^&UVVL5qM>V09e%Bpt<4by-X zikhcf^r)ccwIad8t&q&!{TY6<{cs;G;t34P$@XjCh5YP_x_PicVh!%uDMrVilz};U z0Z@Lul89}W#>UlA_~?>9uYZCh)YoUiG^UrnwE8pDv-fWeEau)mI72I!4c)x*u8#08 z`X0`$tt6gaeg_BGG*ymFF-l zom44B3$=3v&88qT(-=p0_K*XT>{gvVhzE{Wat6N?VYrwtsA^V|9T%if>8>A2OI+mr zs#*h1=?YlgR!L%mE1{w-62Jalz+I1Yq_5WPgD1hQWCF|gYrQHWcyUFM?>oL3qVz9f zsKyvN>9`smWgPd4@zLDX=3j7-`D9z1?UE%=jK=Hozwl4U7=BY@2HkWg2F$k>knNjm zV4QO)z6#agw89(6>Jg&CF1+DuMxx(hZ_E#?BcWZQpd}s*a@}Pl`(_{8zu5gH@rpNE ztB1zE$^~)745C>{!9wF5j=Qs)8)LbR8t*&HGG2cWiEX-gUN@B8L5iHf@irA<`{DVQ z|HzW?@9<=o6Kbev&})DHz-lq(3yY28eic5anxgh_@MS%jtB?+>8P6!!e3Lv<3a2+# zvmU7a9OCeG9RB;t^#2Oyxu{=x^lsc~kU7&zwr-HbcDHcE`gFop398%X1qb(368Bvn z;nfkAllJbJ>DMo5G+}i)?5q7iyv;n(dZxPIhsR;Q@l!*H%6<7&Yzr*OQv-v;@Pd8N49+V0#QdR&@R@9 zb5N_I`FoBEcfSQ!70|LR2u)cxMDK@RG+!qSBz#KXU)127CugdEA^!$BSQ%<<%Qz4&sv;IwL1+zK3&Lh7|+fI(*k!? zKB`9Db!$L|b&ZAG9X1z60Nd{JZD3g5}v- zC}_$dWx48TbUO;~S6=0&UH?Rnyt@D!b(#r^_CN#cAl~Qxid2te`b?&CDARhw>4&_e zttLY=(7H7Sq>aPz(c@mzm}$B&;p7LH%evrK%t(Pb(-WoY+vkyXP*jehtrdmV52#dXlAASTq{DUa!g z+2f+HJ;{j+PP#*_>Ng7YDxq)QK_CR+yDcN=&b}XDl2pO;H@)1`d7hN79RSi386IM8 zfZ7F77_usYyZ`1VJv_$+R>jnjQ3W#i^dQsDtujwpG_9JZsYim-=R&gfXF4oqnztpb zMZ6;nw_VTtsNZ!&=(DXRU~z2?4yKCH1vh2kse1sdI9EyHi)GM?-6o$h{dwbxq+qLL z77V-kjmYGt!#4JQx2ampS$CeNIb(+IWldv0c)Xb9aXE<5sLTK8tXo67p9ssI|B%fx z3?(t;m$(YJ=%mBxQ+Xt5M-Ak#XIo<}li+e8t+ zR6fG2({<#ZzBsghe+uz3AiJlVObLM2C9$7jXOip&RmI`q?cr&rH`pOQ$B|%VB!f2l9B85vt1-79m3$*E&+eiiAL_yRt!BJqWvJ6BqChf=l&Zpf}-y)%BG z&S$**!)fF~jt5#EP!oiPrt+=TH^Hsd%wx~Gwo@Bq@ILc*9B+5vbSo06*{Lhwa=npk z@~#1+@lhyZIG+A#X3vp-Bt}OhahG^OGlELvGcjvVrVn^VH^&uar-%8Q$Ho|}yD zF7`iI1CK@Q@LZA>RnwBgjcgYhps}3QtvouL>G9lCtI3)AIyhF%^zBXlB*M=SPwL7F zsc59++WE9?7)EMbqKLhD5OVSxVC8 zdQ!Vp)4^+YAIVqCgHp}|#pTuM^4dDcVmD68M^~@;#!E9iRMw;k31|U_~xDy+ZTObMv&HjoqxP& zG{`xA0HvSb$;g5Mu+n3C^;0uB|9(B9{I*?~kz0Pn97^vRGCh0?IlMQ8>JuOC z*UW1a#th+yKaQv)ZS!NjUF&&Ki#C8xsVH`t6_Ufv1Mp!=6ng%2;u6lf(_7+}LjRYk z^?P_XHUP)9E6`$*pOCw*3JW*?;i7MN(GcYTFke|pLcbVdWqA~y3W(sAS9Z__0~eUr zR!6c|$f4LJ=8q0HPZ@TkmJX&yz?`5$^2qxu+=*mb?%Bn>RM%RfbdF^uOckL^ZF%tO z(Hi{SE=DE7dz_FcVh4B(DtmzVs zdVCc4ToYNF5&)Z*L^A)Q7@f9vkS1()g!U~BWc+naoXU2Uq&1i#>Y)niOaoKSGzR5^ zbzsA^k@xLB^3u(+2!ABYx^fnwYeUQ+_0&8p+uK7fHmE?w249%6p@vi`%VH$k4=p}l zWVg?Hh~A@saix_+vab%-vD}#32TZuBUC#8B)IRXcYbDuI36Sc?{yo_Ww8*vtT7hJ%iNie}tm+B$V>r%@rH&rE!C2 zgnOeJ8G{caLouvNiJSA(jsCc#E6lOnYghsy1vjy?UY$;wErLr2B5}>wc+T-kG}TMC z6XJ@~G$_+XJ;A)>izIqUG@U2Sa>9q@5-S1As{ay&W6IBSeNzhQgiohnsX6nZES1OG z?3uYU`x{9JNTvVWy}-+|lH8d_;o^uVSlRH{RLI`maRj&&IJ7mTG9R#{9>%kH3$Nu04-2%T2%1FgI=5=#7`YD74m%{Sn!FL$Cn zt}<{=ON53h)xm>H*M<0@%ME!1UKA>dzvNCw6;PXV9+3H?n#_-F1PA5;BvS&&)xPmq zy-rq;kh6fV{}X7|@_49G%qMS3^TB;g4QkSf+}vBW)Ie|q>i)KpilR|i^onIL#x@a! zmOgr4JPfL&N=f95T4)LlM>WmSrgk-r^r~GU6x{htOy{(Nug)L_Y!Bp~xXpx?Q;G2W zOd0uoMirk&hhqO|ZO%L7E)6iB4qtBdk%1eHkj-)kXa8{JZcPrP28xa_Z%jQIv`Yk6 zrql4Bvy)6V*$ER?)I!^(T;dI*@Z+N>lzo4V%h~&dPV~3{I|7=C*T27Tl4YbUhgT%v zW+Uqfj6|!aZ@BiquW6C&LrA_`PHMzn!)B)Im}}5yI=@I2x3>A<4QVkFvfBgI8b%A! zCST*TFnMtB_yCWY=b|r<>A=|zdFTC1?)*-DVj|Km{0^0@&2g!N`dx}`}FZ2f7rgMl*FtbkKv6`tamtqYs~GUnmx{t^{0+> zFYe)8;obdt({B0?RYj;AuNdhiHcSY9Q+ z#2weKA1$bfUdguz9R|yypMuEga&oy<1aWN?R(*ZNbKNNd=U?PPdrSsd#5mrn%`6+| zumyuD_tVQQXM{VU$S4nL9K>!CqXClfs}v;sZsPP(bsFn0igvQBug4~y@!&D^guo8W zlp4s)zHFGvw3K?*PGqfmEX^PD7Ni;f?zn0K8nfHsz10P7^weUykeq_A0j)&j*C!g` z?FEOJzj!h8KzSbs$CD-@rgC$0>6Dr>2o*^srB6Ju{JyfFQ*S>%Zu@_%Tlqa4+)+#x zw98_{oxALOqAx`jW zQ!P2UEg0;Wt{`vDbkf`Ai8Xo3f;%$={0N_|5b(DH?)=RoH{K}VOZGSMwYtISD5lUY z)wVDquaPV8))J$LYMr=hQTdN@7zazEU{m|1sb#RdAuI zE;7Qr-;{6l5GHwD=t1NEQo#D9#x@3B3fqXv?0#A(2!+gn64Ldf z9agcIYr%ESYTH+;cl`n=)Hjn}-9eCj8IFS0al}Ti8En6>4wo-)xL)N% z`n&ppaK3fjeFKsf;du0TpXpam9sG7Y5GzoUw1j$KOQNn|RNNK*Zqc!@_3Q_@b)}H_ zOlA7d3Ct7GHIvH@9z!P1Y9SkQ50QlERiOXe5Q|6)31T?*HJ0f_r0#KxByP~UK^OR8 zP)#O^sbOETHy&8FnwOsGfqk{Qf{<%%eBE7};reG$oPvd9@=P)GV>{ue<<8tyo)?{x zU)mL%>-pzWli)l5_ zT!}!v)+H&tsvmS|bp$M5RzyB_=D^4gEaU4-F;8B)iKyN$5NZMgvzCBv;TjxRD^3$M zM!*-X0MMwYBwEaq4Go!aK$B@KYjU8T`R>oWS;8rtwxjVbM?oQ=iL7@E28&@V&oEew zs)ve#yqF{NW;Br3=d|%f1;Ezcr^i0W^u_kcOFtXoz~tW;U^JE={vZM+>5yNOb~h|rrhHdh60TpraPXI)dYCR`5qR4hP9c zPa!0voQz!~hKtrSjiqcHFI-9teq%2C{b!K#%==(t7m3fj*KpI`9-`S+XN0<%hHqn8 z#%d`3KA_Bippp4# zByw3VANxDsbRrikW9foliI6;jX)?Q*K2Rnay;3i5uVRa7Ptee8{FnNfet+o&_iHN2 z4wg^Dd%`r~_93Pp7Ua>gmNF<*O(m0RJ~qbBL^EGBGjS(x946uZ_cDSd zrxx&6>wlt$HRIt1mru^q23lT!801@9$sAK z>mPR-Z5p=vC(UHs@%pmQYvQ+*F5t}Kh-`A+hF&t9;$tp&e5 zdE|Gz4oWi2N8-tKZo6t0?bjcgjd4T-{cYL%VqF}0*W3y!?C#z&Dv^URNi^%_1L2LV zrI`eC*lhd}*=O3?ri<2x0&!iRB#Dak!17f(f_3?q`R1#~fse`uxVNv61o(=h7Q@Da zd9yg5!v1_yuY2qQ9=M_ z-~I6OTm>3%<~=-Ty!N>tDV#mehjwTB!{ZC3NrPoHZyx^U9q!pPJZ&1 z$MV17n08@tN}O2>h3KILlVG@k>X-$UiINDN7C|1d>&-6<(HplS< z&&5IPQ!Y%H_m%v6^B%4Ce;j%9uqnjLucEzK+4biqI6i4?dbM+mbwD7Ht@J0@j ztb(OBH_=){gTA(wz?}Fd?U_uN~%U&?fi%IvkSIkrpGUYkx<8r{X&mlXv?l=At{ zcEW@94)A}%vg;oz;%UYYK2N>DExr%5WzNvv_+eN+>~Qc#r7Ts-U-})CnRf2W@ps(e ztC7^%#s|D-l@Z%DAuxP$IL_Q*$eS;?MNRXhg*Woj;wE_d{u(NGXwkJ9iuhqo6c!Y| zFG)JLR(JxH7Z@?!ZY4ll3oNykh*j2%cx3#FVcM{iR^n)fWJ}kr! z<-L^ASTPW#Sbu@pZ4sDzF%)J@FC|?YTHy0H##`l%HZ67Tq-F;T!B{$tterd$MlMc- z`aR|3+?NNmQ*t`2F#kiQniPRZ#2u8=Ql&bd+QE@wAb(wMb31B7=-2ccV7Q-kCgN*& zIr%A)g!M$}yfv)ws)aN8c_d`kXjF)0d6jZ@TsxOd6;@vW^@A2H#_KJ=$9;=&V$h(A z(DU2AK@IH>JVeXyD|r5O9%!hlEx=*T{7&(0V0=^*uQHC~tk^Jo#W4&v-kICC{{g*l zVrT|NUP^_r)qZ&NumatpOF@c#{)?%E^Y(g7CujIWTW~3vRzC@E|Bb@44Uyd4BY$W_ zmNVeDdZHLFkF6KNP<~)h%J7?Q)N4-!^UoF$lZAy~ksgWpt4eqehP9K)6Nh$1&TS=J zKfeZlt`w)^PAGyX^@o4Ttk?eUNSHDv3r6H;6KBIhSib`tNAzR8MCACE2D|* zHSVC3H=lyv)_LU617$2z3B>sZuTz$+(1yAL>9EkCfUIa~2W6(=U+({jH(a5JOgR}P z^o)4PS-|y_d6@F9ms~08g?oqkFI6ia%#8T>GmsoL9n!q*dKZgo@GJ!ex4-N`oc1itOwD2wIV-f zZ4c}`aRHw#*QbZqjmAY;QK%#l!%Yhm!`%~~cwb4j1%*l8k$6GNf~%@L!8~9?b8n}G7wrTcp_az-+c30azSsXu zUvu|<#nZ?QcA%-(Kn|4_fg9V^#q*rVma+X%FuVd6scG_?%id7Kmx-XgIhROOO~zRE zPW+mDkyBN!pc+R{3VCF`qYCIgDGZPGS)qX51udE+rpRqE4N1c%t% zQ+xJ~TaX-0Z|(GfhnvdC*V-^RzJ%#md<}Vx5w5HkOj@Y5c8zR-U$`aSfIrJJgZkIU!MGEw&nT}3 zE=Sa0*1P|>6vbv*GVZVt8$1=If*Za(!C$V$WM-i#OgR<`kv65or@ajn(wQ%5aJ1<^ zt!^6hq7ar}OCv^)jp2`KB1pKG6UR?lc;R>$p3c|dHmE$J{<+g&%l1FS(y9bxz3$+S z*{W3bL>Hv69KU-nZgV&N!zj;v=yrApc>|+kgYf>c^<@0=1F-r)E%eCd6X%zDcrPIe z#g^J}-hXoFq@U-7^UyX*9QS+(M{BKk!avjnT^*5_8<@!LJfFhy6du6U_;MoP6R=_4 z$x-HiOb=#_LA@)1_~C{Wv1A_YjW0(D4qm*#|C?+CBQ`Ky&8i}D;q-9a$!?#N@3T1f z6XS_yZ>zAkYtP~>5c+-sUTNwePFV$-jmvFqL)IGp}X1)lzQV>YKFf?GfQlcwec5j$$1pv(t0P-6j>(R0zcThhC@r zkkbXRd+D$upn!Z1>w+9zh6z-E;$5$29RrV|gjp^HSJuJ#lgvYRx0hu~_rr=!{Wxq+ z1-Edn7Nm9fz~jVP(o(00&$ImSuc0k(Va^T+F;c*XgH^;ZxC`7E7D^Kra=e9}H0{V< zczvOblvoS^>J4CX{7Ak;MlWo^^O&utPt94+@2GE4czAUT_k(p$oS5|-XMDF$u6tBL zUtEoWmg?_Bu?rzCnDLb}e)1$4mt%ZFMCdDNxUY#->%DQdT_f4O+yk{lM+pqZE#_H{neID%h?^b$Kf?+?E0E!FC4-N4-aQ~j{|rFL(jNp z*r5EG+_;@ZANmc=!~Tu}P+&Km_Lxx9+LAJw`HE>h_ocGVEKj^XpdgSo+r=+-oCZG= z-@{whTWTsY5)+uWLZ;b>dt2vCXZD%_D)g|tu1!$s#q`w+Ye_?AG1wNej2)( zRVJW|Wo_Z0+z(>ePym)$kMQDVRr)oj7?v~bvA9GsceXj2W{&m|YHW`Ebc3<^Zn*M{ z9M50pHeHz}1(PQYl7QMaxPRgrikNBBg>fnvzl(8#rB4T~5y zn>*(TnL1yGWoC4toVfvCyeX6J{~QNj?DNU{-yYyi-5Bmrz>~btLXX-Xg4?u}TrwGh z18*5FYT8WB{uYDR`k~-pRZ5y)bU*>i|G&%EGo3%HkIFa~Ld%^ra=Fn1ZpFFblZF{w zn#lr~HYyPsdYJZLtPWn=9)_oe>vD@n`p~;fZ!_8ZFIje>6ym?%#(-cIdd>Mc)w*~C zJU25=IruGPt_;G2zw3x-j|Y4QH?&Mn?GIWN*iY&ypimGet>WwZk+8UvwJzn-=VX#JxlFuq0O!8!VXqZL|yL z*6U4Qq*#J>dl#9;^zi?B{DkxH;LcQ-b(MKGg9%qTCXkv&`@`mvQXG%d>(Ib!R?>@uksa#5AN*BGeA_5v777^l824M`RJyTY~3pm(K_G=8y z!?r!^L2|qWruT@`wD~F!RpAfVUq!r4RKS?+hy7ML$UsJo^5qou6>I(&?MG*oLNiu&sD}l zU)YU&%a$jR#a^wASM_HY=r zV4vBW;f8O5g19E%Kk)L&5fHRtgrx49!Ug*Hq?vVAz_M1&6-p>GPb^Fe>r~iL1U(7d+E} z62AeG`>q~#G&o}IWDUB~Ukc@!uIAy#*WBcSMEZQL9sIUyAY)fn!28@t44&&uq?f*@ z|M@4vYt~J#-!cu~{)obWpi7+bx@wx?cmhf-TS*Sng2oyKV_@7zGU_nnP`te05qrPL z8<)UL?{I9|6l$8ariQAymBDYfRAMT37xm-h1+Q9n@K+3<31kn`Iz*O`n4?O#ncdV~ zmgBh!%g6MSyBTDR=^qI0+c9wbC!MXm=oDCNSRYoO0yKuY97V;c zxEM?pJ;Js6s??Qz{&%Jsh~p)58#`W7bCDr#rIbCBw?^H;px-jQrdM}ptC6%YD@LxV z9VE@KVfRsO8uXtUCLWE#e!(lwAitXaKI#qzqiV>z&R*!1WO|;1Psj*vG)__eg&}?h zeE*bedaW`JlJeR8ZqP=n3=Rpom8AlGv}ZTh>%?YqewhTw>x9CHz*3SK+fTJ#7lKSn z8d>_v1S*+#qHt0LiFNa(QfH^b8PR@HS=9^c`y&7?l|FyUphehDK(tY^>97WQ6tW4Ptl+N-f4;aoH!T_Hvl163b*J!hH;kMiRvK}i-a2NeWKAKg6T4^M9J8M(t zflpAxcp|wn!l^nvrJ;!oqhtE{aHr|GL?Ie=YooZ+2Sgz0rZen1%lgjL6>ye8FuHy- zO({|CrUr5mpu+kq$MY)T4tp1;X_fN&Bl^f?odWv*p4KPREup4%4H`9zQ$aqP!_(vi z3un#Zhh9^KOKJYF(4?9?n=OS?t^Kg|noxwSF(w_8WH!FVfGf!r5 zC0S7#DZGnio^FB!#i2d$v%LMutAe3#m@hlmmiIz-FPv|cN8X}pvRJb zO3EL2;O9H)0{34Tmd;EYqbAUSYTSiFjW4WEnWkaK8`wndITZ&(O+t zgC#W<9G`cY8W*32Y?djsWXD6g{*w*_@drtVMeWP|qzq2@v##(vp{8kx^;D1b@A&1Vk_xrExY1cou;J=AUFlO-?Yf;T^x%`T$hebigUE0&@MRI{MvWb2!?O>ncv8MaOO7 z=-MW7V?`M9dPj96=65o?jXk1us!^ZVjO4OR7+S`UL;IU&$+yOhk( z?O|TkaNL@tXS$pY(uvF`zpX2ccr*XLqIM!aD?7wh?=yuau|(JvUO}{O=wWAF7)B_J z=KQ}uruGY`gS}cm@!e4g8_o{xbz3t2!vC|yrf#~!wXKb&u;>PCu&XCp8R_sWCKCI* zcacZKkHKu+TF7h3Cy6r*5Hq4szt4^vwxy7|%bkZ)fh{DL%3zZ%(})%%k~yJ&Ay$Iv z>khu<`m|H2`?3eHZhQrq5R(ku$xm>@xHeN!eM3~g8;GOUNfYhSOfx{$1cL3S`Gs32 z!T4bxK%}dPybqGZd(5joHF`Q%o;rz?&uk%=-H(thTDw6vX##2|c9P+7>2Qd7D*00P zId2bl%HQn*|E*>jJ0AN$=AbCXjAR`j;WDVRGYZ{qyKtu)AJYQ{OaoKiMUF6y_m!SV zEYH-Yqn@S1N4H44Hi|NC*m=eeXKUQ$?eSCx#o1Y~vpa_*rB*{Tdk(FY%(+F4Kqg$!Ws-x485#$gsIL z{N-n!Xhbz>eLghzQaZPQbHrR6X5LFK*Xyz_U>|7MUq?cQTLVcNnsrag{(>j_e_z{~ zau?4$pw7GY!sP`&$<0~s;Lw!-JkcgWoxK>h-@lOIpMO|3mjUK5OiW-F%lU4TV*KZG zEb?c(8sE2@VNLws?|=UtrgiCQYvd0eRdYoMu(tiwX#ET^l7_8629o;y|-N~ ziOPUqqxYS*XT`za83kmjEzA2In~cA06u2|j+o{oo1MscAg~d^i0!OKDV4tA>1@cCr3IFM9SWv_lHBAbrlbmSH5BW#}#Dm zWPPmB3&#f6(VX1^f7&s2Iz(Ca6J+nQiz>HK`iu(Y9~gjCDTZ~NzQf(_e?go39fVx4 z%FeH_g=usnjCPZ1$>Z=-vliyBDj?l24N;9@IASyHxw&G+^oid&;XOMzO%9(qGYrk} zEm2rG0K3`u_51!?Zt;vybh-A>+*{z01};n|-+c71Y0N!6tf=(Co_ulQ$oItTJF0>Y zc_;bhqEkRdhW(b-6qDJfrCF!VbKGb@gR9*;m3Yo-6>`C)H9LV88sde@Hu87rSCF|M zi5e5{b7tP2G+~zuINDc}o#lFXYP>I+q^{#>Y3+x{3Zi&7yNJwFm&2xmj9dBO!nHd2 z(^2wF_on=dd`_-|=3eF}9nhw8`CnlkyO$?eP|mj{l**qN+WnlK&%$|n(a3)o&AoRJ zgN9YkpitC67JnXrDQpJT$e5;hpZrS?OGQA0S}}=Ds)Ma;u5L;#<<0&)NCfHm!oF;m zux(&J(E?XmO3-;@HNcDQmQHom#IjEYe=&XXew(|zTbngO**XitjFY$AV^T z8kCeXFUG3@IAp@|>ZQ_nVyxZitVyI$Gb5?F9ZY-XGT&}5`6j6c1zUZ<)3%OSZ&$}N zO@3J1e}xw}`T*SWmB%}~t4YPX0f=B6x@@s2*J$yGZgklT(a}H23Z3`xSTO+A5+$hO zmY;AwxeAGhD8JM51AN_Kg6XUKh*GX09_nP-JHD}8JbPx$*)tN-5LQ2uY;iC zV+E1BE)Po!a-lyWlW1=J3KEPLxH)Gn*XUqJ>kkdh#y7Rz^v^>bD9;=uyG&YOubCsR zG|-@H>X=@g>8qDNPvDL)eTZJ$b$I@>ftVd?fK^OatSxXR4;Q7Y<&I z55AbTlRLM&fu`&}4ri@f$-BQrw04abw4SRbs?%%0o8dgA;$fyHcCEBFvkcNVd?X*o z-o@uLWdx;xR{XE^b0MAGuz?>-3I0|?bJjC*=kf%u^7Rv1plSw^_j^ddh&^EaM-5-R zsU>i|0eacrr^?!s6Ql;wwx2hJyI*+n8&G8WK=F$+$gIe_=oum-5Q}-sKjnECdXKb& zopk}Zvvw4&bz?b@nm4)pS6``(zAZ?_HIXH>0y-rgBF|QZ*57LYH_CEf72b2=!HINF zsy96FEh8eE;^74Ilvyn?;`x|)QeYnVg3luKz@2WGWqB3X1ZvZ}?xV2oI@_b7~t@0tqz?*zgbXj(6W=BCflx?~2|^nNONGrpO` zj6OmR#qNQ!L6)Vk`zO)r%7WlPrfJ-MpEG~uMQx6|fYdkkF3vpw!@h}Na7q!mZZD6k z7`Cvs&xK2D3839!8-@;skSU{4Y1UZ`~1)SkX+L9ZQ5x#_ve{5~mr-eKdEa4H&EEl5+{FsFm-7 z8?$0k=3FrVrQkF;!g71El0-0o@!iwbrtucBoP`aBL-^h@$DMFGbS`fD*vonW-oktK zyV$bPhdVcI3<$>ifP!Bg86TyA;T6n7XLXe)(smFIvF<~?Io0GaJMCe$JHdr#!5l)S1t;Iu!}r%}ta( z@*bLpmKsgq&$JE0+nfoP|B1Rx8JdT7++5tL5sgl7Y`J&qe$Y{ij>Eoa)|>OEgl<&x z0*xcpgnX?7nHaW{%nUOfE7d`DM9LvJ<|DD#a~I>xqy-&!w(xJBHU@ z;K8nN%>6cji_#6EMrEvt>qsuY2}p4yHu!sT8PUOXPwq`nlBgr^ zJXw#AR5%XGO(lnu?qaWtwBVCVB7f(Fqae1h9Yk0@r|MTNH203epv^bA5h+>pq@FFf zOEwdwB!&mZU&pW`|484GCJ14-_Ucvdxow$A^i{Aow1kwAJs%PvbW}JFvohjY&AUt0 za;1dx@b>avSW|HY>0@oWRze%+v7CXv-Z<`sLNjeiADV}Hy9QvsbvW)W@FUK9jIgBo z7w&5}R^rE@s(Q1OFv)(DsF% zo$>%|(<{ie5eV9o0?@*(#q_t=L_C)e$ovs9MCGC<%8gYPY@s&%Z(9E&={o#se!qB& zwlHm7^Yl*u++jkUxRr*eEbKT~} zhde9K=LVU7?*?1G?jq=wR#BJq{ctBi0?*YH)3(+Dc!%Q>M<-q)C!Ir?r1M(w?iaoz z2i~6I^D2aqXtNmBEgcN!ete-fMN_fDFb*AOJtUX+$iU%3ck#Yg&$Z&0-tj)EO-oYz zM@zu>xF{GkxrA;|ZHC=ElcaBcslY}?nr-vV7vH?E)OUjZwiUQGQHJ-N`{4Q{IT5@a zC;SaV;6`vTOg~>uqaG;ZOWr^7?z@lR&?C+-*k^&fTpkrjHG@`D436(wK)xhjV_7R~ z!1H1=b?SKuy?pnxQ(3LDQYz$)z|j326s#zuJ%&=4 z#5qla`|kwdj~Y3a9WCZKx~5n|;kBvg+}uS6*S~~qhhs4LOaK|}Yygvn1VUn4E%oKz z#*RG!xaIN*!IrcGaJru|=5kzXpsp19&5gy6TLfgxp<8TqtF?Fr&iL>WGS~48-idF> zt`QON@Qf}hPxwT4k-cuJ%x@swWHB%kFC)|ZoCn{)3p(=Pa z=0d7P7X1>D1E09BcGHWM#HYrMdH%E$<9>gxO++$_>rpiak>tc%OxH&j2AD~(AF2F# z-symfnQClU+W=HJ&S(3SB*N=fSmGsTaPH+9UlVyZh|?|9*?o-mdy>w22R;Xj@?5IG zJDpOu#o=P&K<-*Kva+~?V!v?Bu`evP)dvFRSJ44Eyqkt|k)8)5EU#&|F=v%BsQZvg zuf6fczCCiH=!F}EuSQtFvm3AB!I@HOJ9IF{EsergGscj!EAO%?A+yC8;ENl(KrV71 z-s7Epd&V|HxIE|6v%N`%P8d6c|MtMXKQAHZ9KV+nC(=tpeX#PmoT$?^NjNp*KWI1l zH}|fu8j9gXT*G$b0+~81oAp_og-;WjY5ws_2q%7c?574>uhk4n{3deqeoX?GzhZ6C zd=E@6rEf1J!2^x~Hr_T8IC@-X#dUJ;cwvOyg0wT2&1j7xKK9 zr6%~Tg?E>$HaT!qfOHIh3|gr?O&2u!%UVj$PZ?IE2oDJe1f%pk@#tM zk7Z+~32O3u;J=F$=sS0BEUi})$(h&+=ii$M83`ij{8>UX%9K&bAqqY2P9j>HCvneG zlNbXm;5*)rwoy2^;yYcjJRgd=UTY`bAX_ipWYv@Y&A^Nz?zOZ~7s-t*7v7m|18kK9 zz6mI%;hR-4g3rV2ytk`v@;#R0x)uaBKdI@HI#~7j0ZuIAJAiyXjBw$ZQJ)z(=o-hm zdV<6}h{dMq7-kZOI|3e(l%YS_P`eXwoc9htP1QxC;#ky4S&~BBC3#Ls6ufaQp~1!9 zz+5&KE$^2Ku5FcJ>xcf^2|M=hfpYH^DBmf=uFms8wU@G@mAPiZL!WhE{KkK?vG>~m z-0H_U2>t7VL+kaxjQc2Y^yyukfs$Wv0d3~oxvk_YJxPE4^3>#td8vg9yc*Ws2WMO^;tjHXSR*$l2$~F_+ zEfI$y-tpvxxiSi$M54-T*W{10e=z3s5c>8PQLl46+njR{lNS6C+VVJcXfVlxL$9)^`+@%fNH@l40Sk0AMYBBFC>29eqUpu_lOL3qB{xVwDM?`odpgb8;7>34rGSq zS2k4PpcpgsIjVt&oI~;L^0zdxshlki`Zp(I%$i}Ki07|9jIi|e>14T;rLedom3Ce8 z;oXL^B2UTnLeJ2dFxu=jXgw^YcW&w6_oYHW00Q zYv{!I?~udqh((eVh^%PC-e*F`;6qS2 z8f-zf4DZk6IN@q9(jD@QW#4jz zm}hl#w>IzKEsViO+pKwX*KzoiQw=Slg*5I_1#_u6D%Jr8m=3`86S;5YN+R8xDueS! z^0_K{Nw$B_W+!d^U}QoC)sxHveg8<5dDvsQe#TfdatY-=cLnP9z#BDDRYa3)gujMQ zhAa;e_~?D6?*FM^SWFZK4Vp~SR!^q=J~WDX;q@x}VP?lj97bEH-j70f_MHFUzTO~j zP6e>q!53k26aSrl^TzvfY9g1XrNY9?|A9r^UntfuruBtt=)-xjbdw*k+|nRu8eK{cwOgQpc^uYuJR}YZ?JSdP z%--aDqAB(oJpUjRO*>|$47e@@0gIv_V*&4(@@<8e%CUI4wN!BINk5hzmM8Xx_(*e& zXWt5ZVAYRRYwJR;c`)d|sHRe@R8gDvo^;q=7u5C+gS11uWA{cLoqxO)GWZNEb6ZF< z=J~RV7B=wbS2H!(nF#(3cX`IhZ>qn$k4bS)@&ETj1OBY3


    Jx3?)RCS$;T)xR0I z`l}4ut>@WCQ{M~FpoQL99?cePkzftgdtiRHIi9fVqN(Z(_HjM!({};nx9LdODjx_@ ziFH)r*+Cc)q$J)6L;33z@Yl(06Ogg_!K{~A1Nr-%mh!IAS=m9@Y$3yZbr{Uy@8RH- zH)Kp^B+TLcD{U9Esd9@cN~^@-gO+&GuvHoF&x}Ba59gBog4&t!^oLNmu85v6DuQnu z3-!JFLoolp0nAp|$Nt|_*%bBxyy9kJiOzL8dz3f65~_-tbY}{ez0w3p`@3)`m)|=J zHDQ}}9u)9wMhk@^i2E3WIZIcOoEaX>?Vz3bE_RwFkH1uwrN=n(V$nzpCk=!Q-E} z>WZ=Oa&{JLtx1Bq@p*JOfBp5j4j5cIjZ_wVV_`nF;$88lwI(i<55?yL-qI5aRZMW& z2j*B+QTg0&a0DaqO;v=Yq+T~Wr&21VjH~FRCmd~HO+L?8N~)!2PqcwMzf)FN_>jT7xt{Ip1<>SO zjca#vAFJ9u)Lvsu6%?T+RU{aO_vroh0naXPcbP zfbdi^ZSAawtpv?C5VG0q<1=cv}-`=QlFa_dFA~CkkNZ>c|2759_ z4&16GnE8V~(7o$`hv)0Eh^zXzJ)ZYd%O(=t!#~*9LtbzotD3$ZERDl?-qf=d!PIMR z4YOGH1SX~z@Vg0l)H@2fEp!1$B;@YV>kvczT;f8 z*Kji2>pn|w94Ee!RSy+_oyA%Fqb$n`C-=wgQ({rW-HXiic+SS2bA`fBb#(fhG*J2x zgc(Z9smA-0a5T0W)M^W9;~Fz;=J?M68&`6`vx>>Z9u;#aJ4W@#Yy+O*EcuFj9GT0) z*7`vm&kAr2EP%ya2Q{s;$5Mgo96oTr;j;xLDIS^LcqURs6u;qs(7kR7On)GP-M2r} zRX=!-Np=)Ibel}%=S`+jE9+^e`#yT5>j31Q8i^OzwNT%{639*F{W3%RNbZqaY?@@Ua+t=AZ+M2J_Ya`b~Iow5$L%-=U6A8HK@t+u1bel64AM%;A zH0y0jM6Lo7y_5BDWP1>1S~v@ay*LaT4=Ldf&Ywyz>yNwFa{uE*LVUK} zVef6M;d{$>`to=>xHtsk%O5iAeIkz=agM?HKi`mBrBSe7V<>KL&ZYy7nPHY%9PSn- zkg}7?SeX)z1M*yw%TIPN=M@j(c486L$}Is2jwc-Y{6pYSqQXq~_p%KZeN^V4A|BLn zL9g^wD&MCCYuDZdP1#E7)u;uim-r+4yi32_JBYtvhT7o3)x~qPsj! zdf|X-Gin5Ft|3fKs0-cx5=>_OPiWlhh8repvxfORo1NpU2lbwlX9{UdZ=W*^$Y`K8 z72lw92FK7mFVI0vIw;%y6E(Aqg$?~bF&mxd;Om-4M}L}$LmlJLuf&nOG;U!!^KIdq z(l^@EqKWUvb6#M>Tb_GS#Rhu&@C@iGdbz#@R5~KD|ENgI=21ONIH(NP?@OZt{N>TI z&;jQ~r4!Q+mXNaGHSAtkMh869#leA5_++yQ!I$B@yK6Q~YyW?)8qcg6HxL`SK5)n9 zD0a{8-<;f1&23$r8-2cW5;fe#c^tofqNWv3g?|NhptJrv*mW1s%uo6l_&XL?t#&7N zkMr5Wt!Kc*rkPHh-wspwbH8?D3OV)_*!N8VaD&gK7upm~@?Mo@jnRUF{(fx4M_DnJ zShs=a^Bi-)SUX+Tub%-XJc`A(m5C%A+u5XpULY}|h9=yW!Fry}XpW& zx1)eASoju}@aOFD>r$l8vYqKiY=dt5I_m5*08$Qx!`205bggIM z{d=()E=F8Lg^?Pp%v%;ObM33uV=pr2_DlBef-7t@04#VWDR= z$c`_fM{CDnM_(*1f8pMTa})1oOVJ;nz47F!0iuYUeZsx2Q(?Bh2o`eR zgTn!Jyj&B7DW#LiO24V};OKvQqyB7Lup=Y!&x#hhY+fl?aF01#?0zWe!OnJv&U*WTG`K3ePKdTQ`1Qk)yOHJ(HypNRbW%BX$19tDt z8u1P}D5MB{-2CzVYDH!-m3y9&xOVF`5G#eJ?7mYFFy2MmXKaZ_7RKR^Cy&VbLmf=V z%3i!f>MrcZ`^TeT>gN*bBi8}%2J-oEu}ttdT8?#_{M#E9)sDfdk!yKBsT?~IKMbr? zf`Kfnp&I%c_?&w;8kKwnbJPuCmrfR}&CR3u`xhMKm~hsRMWm+qCR;zj1{9BerP?V; zVEgP2Mttw!!beHCF8B|UXXR4k8HPCgawyKyc#*Qnbu84bdj}Rfi>TBqSybV>Q0k}m zf@9m;skKG4SWlQ!W)DZ*XQKHo3Fgl`BW_=eL5negI8+HwAR|JQaqHSJ^eAvnz9jpbS&n-M8*+;11?N)u?>o;N8{HYC7a$oQVL)G|6Hh8MQWQavqon-5LokEyHTO+zl5P+=fY>;icYw# z>4qOHc>fyDVp?d+Gl*=TlbNRPS^Pw2(A00F7SWw>eNZgEsJuwi7wTd2pLSefYb?|- z&1cz#9BaFhM^h&Y&~s@VKHK3$rY~z{S7i7;fA%X~`ClC~-RuLRbgmaIuZ3-4cksld zJC>1^60p&z49NR5`tFktigaW|ySA?uzT7E?#+yyL^H=; z$5GZYqQ-?!ghQf_fsy8Skp8cbKAvKTm8rb@$;+L%gcY%&H%~+FvS#XH{SJ0!Ir99s zUg}-d3F|pmSQnK-4&8do?)D1+!LL#}>9h!bacxiQ^3j6Li*K^86|!QC(QOsaI9cj| zO+mV>?XV#RK8?jkA&KOA@-Jqw&iZdG5ME64i|z(Du+Y|0%|8I}!_E>)JMZyUVv{1#;q?%gXK-!%;m9T$PQ_7|$~ zK?5y+L}A9*Ddc4Kbo%RAqZng6asN1I%8fxg=U;R}ZaJLceC6=deq@e$2rJ9+05832 zdbwaE9{KKvH=ZmPNSXU!=>uiaqv&E`X#EkW_3neg7R7YRuz?66vG`!aWinhjlI`67 zZ*NT5T*5uO{&;$nA{&@j4rAVP-ct@q2Q#kgZ>jOz;}z{@T%-%B0aB*O&w*}V6)vO5&#{IN{gcCbH0XhwlzZ3*p+@8a{2XPB3l2`on`uwa!uvF=)_|0x*$ zZ7u$8kz)(4`k-c@w8%ewj8LgnAEx&O!3zHx`Z`7vWrqZ#x0kP=>-GpxSIh!cp0#BY z+y&?O@6>3|BC=v%0Q=o~Ks+<;R%xZisueJgWA!r~)!0=2J$Jam z`{4GxCH=g)?{M-EJoPq{x;jq4T+U}1wXdA9wVQeCKZI#g#necn z0(|~(@5Y%n!OkNZ%w<$B%RAXeZ67J)tidkm?v_S7oxE|yPbJZ+x6_2?ZrU)<_%6t~ zRnoju@~Es4f+O7{1Ug#>L&b_bxKYKk!F%{;+Q@Y{`m4#|1D-5d%TA0p7Mz~JGYcb8 zATyY#7KXBQ{fCOVn0efnz5baihAV5ct~#!Vv5&=um(R&?iH}UX-U*ttz7qe0NRFf-PEkX zsL~jU^R?4x;gkk;OM+vMURBgz;R|#a`D4+yo0h8`q@Y8l433tk(beC4aPlx|QPSj9 zLfSbSx;vBMKu;Nc`eZozJ&(c%vrI|WTD~8y7K(4}qL9Oo<)wvX@inyW;2)6U*^-Ua zhuAkiWc$?q&Cd%3@8EYJpL?Gs(GxSSuIsr zFU_6oa42DKSDzN|km}Pvz^5yYsIjt__6GhDYwe!br;r6zX-wGV555LvG*vzo#?Il` zqtj@?slJ=+!X8=it?hG63SBlhp!Zi@7TP`n*Q9Vxup^N~^6s8qGcRzpt)X3Z3aG+$ zp&Fm>(jS^%*>klgkZM*)uk3#hPW<^>UM58r9qwc@72BYWXEfCemBPljv$!Gp5gqea z73xQZLxWctb&{9Ev({0VrekQS+)o9zb`-(SO&_VtruUG-=V!&c%|t_gDGXNNIHYA2 zHTYtN-MUeDg@Lx1&rkwyN%IRlDR#F^=xv5 zW&7%>TWl3Haa`-Z!%o`fuM) z!?&wmk>w|f*|54BU?E*eKb|Oq6R){%MYhlKxCB8>?gcP@rA6Up7_s;Z-M>Z)$7n`lMc@>YtYSg$axC`$+;pzuNysoV#^%dEY2M{3u*#3Yg^&D5 z%7{>AkmLdPO{%H=TCUH(swDbvdyz1`!48J3?}hD`im0;JAp8>)i}O7%ll$&btV`qH zoSZuH3mi|riE8Z%Y@baPyyf?M+XN&R+@3RH6$F-C15mq8h=g;Inf8y#9)mw@d$S#s zj>(}TOARpKYBc)CEKbq5Bnvko60W6{P~6=Oh1~mQVOTEce^-%R`;;r5lZnM=pwDkD zVu>8Hc;$okaZ)1LW@F)wDFzTw83Z2+YUmK7fmmo6jLj{+g39%yV9wAisM(iK@9pXa zHU63`ei3ai9DpBpztVB0uVB!f5Zsyki*9}<1rGn&z;&L%dz|YI=B{}MccqJI z)tD~2`D>K8-{jhEdl>t9DyDV)p+}Ft=UHof_j3s(?XT6K`jIPGx~0;H_F-6*a0^vx z9Rz7tjze3%qL_=he^MT|8*?v7tbqJg2xIMGJH$AoMRpZPD)219XKKv-IR8HL*{gN$ zEwR}h4UX@%d5%*CU86Y(6DG!C`0aUc88{~>tro+IB6RdAYn zn$G652`;N@@!P6Ld`I`QY6O_Q3a2i(Pqjn6aYTip=*6R{LW_*SpsjWnq=0u=e^$Us zqYz9ijS!qP(Sg}cd7!L{?bTOFAm22??TZ_A&s_6HnL?Z zKG2d}MJ+#+f^Dfkmc;v8&K)HUbWs_Yj7_JrHu&JXHBur4g_Xj&59Yv{>91kou5zle z+W@mvqVZa!DH#gJbKIXcoip8t#BXo50nxuT@){r(K!jndRyRV2G5fejKoysI9wv{LH4AVuvOzv zgVt7_Eg!3Z($TRP?`6tz|LcZ_qj)xjF(pTDrnBoK1EAinj0UEqf`IeCV_%FG3>g=| z-fsH0TW*~pjn5vP#it*2*%#hZR8F~{Xx=ko)$^Mz?e7J#=WFP9{v1}}T$sG_JsO|W z!lo#4|J~j~x>_LvB(L&(gMQLvkK%8(+<6IV>==EaiPYJwu8??FH|EkjemkuK96M-$K5}t3vc+7udAp4y|+2$JBbR z`Pr;V26{!Z>#b%Wnb$*q+qS}kyB_%Hi8@Prt%%3C&h5bZtK`T8#>lvTvoT>~Ega|1 zpii)qo_xyF9&et5g%3{B8BGmLm|_Q-Gr!V{R1t$`^NcT(WODQ9XVw>fL%c)wXjXz$ z3dd~M^jR*66`}!ueHZP4)X2aG&zmZWZb$7Bt{F2EhA$OCZ1@*y(K8S~Y>LJ|Cgvo) z|4cgNZ9UbUeSkVWJH~Nr{+YFYr`?lkp(T&+&!7EBp!_{H!uQ`ijQ`JvYtj`(_XZRS z-xnT*Vy#~If8TLy|H0@P!Lg$cmx*z7G`niGTC80>)>jIpRyT3Udj%F{Pz!Bo9IrTq zBs=mY>og7G*|nuK{M&47<@2!O!($Tsx0?k&u!GQ*Ikdl@79J(HvE==<6k`c_xLqCz zPP4eb-l7lIOy>Os=gS4R%9WV;^jvXY-tIk)U@N^A?}f^-Wp91ZH(XM*sbREGD$o$- z^LZFZYH3vbAiQB0jN`3t2+q|TflFs5^jyuSWpaH`sm`&W>O~|u_cl`wKLEb*Uum}L zYp@z0g7vF@QNKshU_Fa-^Otk!9Nt-Z?r|W#)JsTlnL826hrfd+!(v)~=?@Ki`foNm z*&YY^zNz@hzMDqrWkCNsoCA6qNG|L*fgJk)IM}a&2EEnC8z#5#w}XSAr~L%1T&ai| zk1OfyDh2#9AqLlV3y4HYI8(l~115}brKt|Ja88kHAgk5bV)+ah$$dZ;S#L?%F;&=n z#syydFs0Jbld-}w4!=BkLJl8O!~H|UaOxVDw9;jdXL?gGLr07^PT$)LYALR` zJ5ZbX*AK>_H)HYC(HCUp`D|9cm1`GgH_?OR|3LZTNc7n5PP;D~;_~h7IOL|Wu<<}C zzkie9jYd8_r#2Vo?}|eM2^aFXwv}DIw+BY9ZlGp%*KkgnzDQHBQK<6xD{KDj4MV!B z=pjKjC^vC0zjl=6g9@Hot5gQgE7R#BQ+^klONy>^E*H|CdGPQ-GJO88oF-?Ezy(cF zcv5C8+4wbvxdsu?dD%$|ZXSc|5G}lFSIc)%35??3nQgPKlh}g^?Bnh8VvYACl`N>Z z#l0#MC)2(I*KzW8Ns+^>$HKSLXCQr83*d`Fnw?;Tp`W-{YqkeD_kjOhlTSgIRx@3~ zHCOvDaIIspDf=QXfn)fd4+kjOAM}xZ`r{8i(Pi}TAqLm1@1RG^FoD93K(>3CEKFH0 z$wpVFLDK+B_&cq zcsBMv$pTRT|GiI;CiV-u+3A>V&~Dj46>DXAC+#_uluM)m7d2pCT^Iy6l+le`WBcL= z*QL0RvJ@Os2Xob8SoD?WoIl9oeV#EmZ2cCpe~&865IMmBwGgU!#1O;w-o|@s1IfCi zC}w}tOpHmMKivkSTs`pj2X!VeR>m5>H)dSDO612Qi!gBIKB#(nOt}HZaQ-xIz%J_G zuL}M;&Y)p=jH(!$W7niOzI(fok_-;F}S^SlDjZwzF1w6z5cry9pQ_6Na+<@@T z3aXS@4QoH~+y8Z+<&YP%z`{fX-^#zxNPBI(x;q->T+E5>%$an=i&`-k6aV`-EH4~^ zH=0}MoQ8V1^*ILR2izn(JMXhgCp_TAv}&q$!3U>rQxFYL%@?+xJPwI&J@EKi5j}El z2yWyYnXkeXVrCZ0B!{mS`#l``w?RSoNHqO0s4uZz6$BHouY*L;NP6(F}wY3-thxd+v$rVAc zH@cQT2M1#!pN(!IHv}7kjbZQKO!!-qPYn)9U^3^tzD--qJy5~y?4biN1-{bg&J-|z z8;s|^{iN9eGEo2H00`rAX+g6we)7JH#Q#;wkjhDLNBJF`=6yr6ReNZ9bELQ%iHpa7Hs0$DV8#q}yq;ZPndk zU3dJ(uVCW5lItt((=g8Ky?G=rx_fGh&|~vZI9eDA_qd<^l)p0Xa|^*Hr%1trt9nrC zmIqbUpJ@4z2GEiGzs7hqVV`}NgQOkAl{8V`a)MnvJ7Uy@A*9A9j9m%QfvKJn%)#+5 zOpJ6zOVnmMi*)b+*C*ePdO<{wa#;3BXV?$TSw$V_JjGNv zb5{lHDo+CclRWq7={(%`UmT8H;6jqe|6nb@cfnM(daC?;DAt?_#q&OC)GD)u)h2qw z8cUvkZWYJcZHf54UVY;vRJUv4>4kOl$U#Zms?BfMqu0rS+fUii`15ekx|ZJl z^a);Z?MH{}WIFBgb+kS#A$qdnkTHJJ z0KB!Bcig94CDnu8uoeAXA@_MbZK`R6J)2{2&H0^l@ncoUF?R&3MteFpd@4>D8HW;o z+=!{^SGFzd2<#p9m2Tm$1N?QGUMG{{bLEUqx*_JQJ&)9Za}IwdD*d&bbl3+E>&c5O z^sR-rrwgFu55h(HQrcBD7*+R0X~EEOc+Vmb%^KDUz6SZ=l|}NRT`qaTNu?)X__J;Zn^i=g zDGtTqA9(i8hAYHsUmSaJag{jNOAuKJPec9i&j|%K@n#dunyefZ`>{k2Bs?Q#Q1hpJmYdH`{P7FkiPV*FlSVa(~Mgn>LnI0;Y#G})A zU%;>mftH~vn=v6*?Dbn( zT=_ovrjYNAE63nE-%ylz_cEp1aSC{LrGtEUG5t39FNIN2VqV5$#2I)aoQer@-L!Id z4)kyybC~Ka@=8J-Lfo9e)?7sQOZCT;cn3^0|>E2-lTWlZ6|n^m=h zytoy~76fdE<(c2J6RYXtP6dKp|D_Y61+_5R`L^_xJRN;#LXvrziqmd>x9XOW#uEo-sIsdxzJ} zPa>;rBw%NiCrq@erB#6)EHNYjq#_IHt!|DPbHCC!XK6z2|7B6t+u+&0MjHNF9)G5~ za8F+%eP%HbWIlz#d*^bldsIfJ4^b#(Kf-cZw-#KUR}59RGw93aJb1^kox=PrWP^q} zsQWpBUq>))be)2-PohxXVFX#;9mBEmv0{!ULQ@qj_Qc{&^=ss3`&-sjc@7Sw*3+~7 z^C4&HE&M)pDV45KgQnSz5Mg(eezTa41G%oX){eM_?*vr+cSoBUH-cLg_qp5uwLE#*48xrLae0OeUCez?>zcXd`TBO@;xYoeS`g^g zQu@PL2Ze#rXu5PNDL+t1ua~>9qS;a`lE1E=@w&*Z(Ve;lF!CH-dBiI%tO}Ow-PSw zZl~?0)v#}XA8yc7V5e4ngZ;JqJzOjze*svCK@jX}Ev41ca%ie&i|Z}yiLsLesL$aU zcXM;7MhN$1cf*@V5j=EIn;L0n(D46ai2$UHMJu+D^@lpY;pCFCP zjd>Q+yTwGSAe71f-4CZLzS6JZ2#ZRBaB=^ibfX*h0=OQ4^bvXV$p;gR4GzWrX0KA7 zjGhXfKhoj#uVSkCN`kq3ixkgB)m;wYlVy%NFaA(l)qK7OaWCzhTV(pKaqwZ5T`?!!Cdg1$kc z4(Cq?{uHRm4P|{NyTy9%!~HaH<8)_S@*h;F;S7k+e*Gv+A>D7Zt@u46PRnfwA zs(5cx2YU3cvpOyzfF?$tHK`ko&P8qIZ&=bGv93FC0=Jb#pm zQXuy~KVbEvbb#HLU{3EOQQ?p)*2oNIlJoS?B9M0!ZhT2}?F(4H4kt)#XrdEmNaDJ~ zT(92GgDO25gL{wtLjMOQ!Y?Vc%ql7gN@70>cJ$N zCBo1g=_z-qjKgl=xZ2@ zODe9DWxJoVRfqr0!&lmc;QyNE6*Nz#x1z4&=*}Kox*<+Dwt&xm|8L-KS44NjRk7sH zC&c@qpM?y1@b~c80zLz)bD7@Y0I0lQPFuJ?$kja(r$-nIM5}JIC$D%HxUU2=dXx@J zR4g!5p_z_yHpOXtKdcK(BIC|U!r@d;xOBCaUKsnEy*-ftQ7;Q=*zH0H;&{%8`_jZn zK@v>Ot-x+7$2t~&gmwF7;SAdgbhE=CSRE4vIy~PdM`8fp5k}(c35J%BUk(Dp4aH#f zHG}5*7lLmP?54lx z*sHS;CpC=R&F_K**NBNiIvZMj4q65^(2Zry;MNj}8713kTlZkxIpP=2OBgG>SfCE} zUmT#p^C(@LWr52%ety99JSpIscAc!l;@NodiUua`48@r9k7(IxHI(H!kXx)@lbx@s z*|;)aG2Zz2eKQ=c;Q1jbe=QFTS%`o6ZdtHy5Eb!TxT~qZXyyhhVV}=zi2sgoo0ZaD zC0+cH#QD(YQ;8M718=`~VV8Mlao4Mo)HyB;2S6N?u_S4i2PM=aTGC76zHrx|Z+Vb26V z)IFrYbD~;d#Q!}77e(a#cM%)dd0RXiJxh6x&HjV_e09xuXOU|H}Kbv_dP|l(`A0LP<-Y9oZ{M&^H=0>|9D62&Gb!aUGI(dL8_ul zna71n8PkANrNeg168fi4l3mP>6!S9Hvt8iH^Qox3poflqSP0v=@6!6eTjb7_@vu!Q z01_rQ(wuv87`nv~KS-_;e9v_RmtXRj(@;U(>r~PHG4F|fASAQ1V|ahqxn(OTsqvhOtTm)zvp;M2 zc?5EJN92UI2-d%42wZr?=VXBt@91>J_cI4G)uds#G>ZF76JC--AKWjP$A(u$Kw}VE(C`-hGu1o!t9oUSlkn_AH2PZ0HB$ z`XpHLfp=g!XF47{)JPyE+}Gx(YGAox z-(XnqUon)-%%oF?mcV*GZ#A}UC8PO$J!3q-qc?=mUmN6cVw3}FeEcO)-uRGhobhi? zK3nx0)~<8M$|LIRZlyY^ajf#yd7dZP`;OU{orAJ14Rnz4H(0M4iK!h{bl7AaTrS}L zZp*R42@^EITIdMB_8z0UtK=~#$N?jRh2%(7D?6-z7@ov7(^ofm2hh+^ba!|}-+xg@ zYmTWZCA=nG(siu5$`?k?s-)JdT3{L9C!6|92&P3Z!sJ!FyXV0m8o@JjR+Knk!t-pR zuR53Cm|WNXr!FrUK*cMMCDeFVsf9KXz`8#eB0$!I>~k_AVwz?5&TS z*J0;11vX;!IF!%w!^?VaNy}ejFz1{&4X&ec@p|a~Fc@RL_zCJI$HT+BnHVYLhUown&*!|lfC#+6`^94bu=Khne+#(0Ivj66!f~`CnW;&o-v2RMIjW>2V z@%-df$As3iEco7)4iQ!*^zLa{lvKKdbA+!2a zyHCG+i+nAg0CBzkAa%EquC|iLx~C3kT(nZ4VCoEa9pv%#*$R4hi#pOAo`<6`o6MUO z$7GVM#CLb)ivl<>CIGEJN;1#sCGg)fj&mxfkuhqT5U$_|zLKWYo_~jDM>^nn!FeLH zSQ8t0Zv4@*v&qxn_lKI*as0L~rp4`Tpv`p-KJ2H!?dULet>uq+&%Ad;6FF z)ai^ozG`qlpSlPVy>B=S-0^Q_>W^<8o+FMjQO)-v1h< zwPcH0AS1Vr0rqVhDRMI5a6aPMF>vTZDOHJl?Kp$6qiNz-}uZVSI5zF4} zB)+?+>Ph2ho_(ja+k>jCXk;}v{>{vZ+{?12$_3AS6%hZ%A1vC<3RW~!(dUvKENP!N z+>WZI-9h}{&f;3%9nqFv50t^QxePq}zo)^eJ}A`xjhg0*ghM)(!V~voSjV;Q7t~Gh z!tZE|+&Ydp&WLALJ(f_upp&k9;|#kEc=t>=&$iX*k0>$m$nyi2L2 z=Jsju?0XO%zA}=I9C95c9{t8)PBFrBy5~U0o$rt(Mf8-F89o&-*YIS2XrfU@N?g0=jA|dA(!jpKuFES)OHZZMzkj{gO#^Sl;Ke8T<3k5jIZ zU0NSm2%n9+;~HrD)nA~%p9_M(-E`n7UF<9RiE^c5g##2UQGH7sIt{x({=3r3HnrKp zjMhdvtV;{K3`6l(#v`h>ToVfpa}BLT3Ng}eV5QG|;pM_gdf2!a$ix8rE?;k{SNjyU zY#5B)(>+oQv%T@gU>T9zxy`~!uJfSD3*nOn?+F^NkFR>8ac{shBC7d9NBsA1Z@jkM z1>RX3;)5M6bgBI>_$9;dufhK0-G(@pA#xXEj}dB#pyN0gw{;g-_DWvI8{_+ld=s*S zAICX?1J|WV+$^Ha1;eqFV;$L+p2XcPfyG{10S;+xRQ`nwHgm4< z(VZ_e?4&IBYH_`mccoxhx)$5h_DSp|tckn?Ig0CXQl0`!Udo@{vR(MY%}}_*(gd=2 zzj#fQ!;<|Y#k~U&7U!X3!*u+q`7Vco|@o>k=nHZt;< zq*+13^EEJsYppwu%qCwyK4kk(S;3vM@AO4y5!k2%pmUid^T_-HTlhY(Yg!uV8f1xY z_Qjz~MIxEPhGDf|GIQoitu(1_tnFRVcXaucmt=H1PocyL>lB3r1Uwf^W&ZC(kv9 zD&FE))L*Q1K1RD}zfGK=e z{I>iRIdShZ`<3np<(#{Dv9BK*L`9-oiU*aA_{I*cOM=9|`Sj%BM0or|8xuTh1a=>O zvUX`Jh&HIEW&I`b3g1X;tlC0H8eM`A9fFo!shU3%S2aIFwHB2xoh9k zvwn$SBsCaKl~0jbHY;GAd@@X&$h%+N%+T>eGMsPYmgx$H`4=zrUWHslbp>ggIl<5}H9MuW9pqcyAqn?wEVKOjft0ye!uBG2c z4?wA;`?%HZHr4l&fWvbVz;k{P6*`wgGT&+c>dTNy2^lDmu>!fn&GbvPGOo08!Tj<> zYBpU5Y=vQ%cJZF@KRlnD4znzusmuACV(?j##j}yi;Vz%0`K?!+o)=+Twwvy&(8Fq-pICKqtnkSV0oJXK!<5Yz$hN($Y}i{Hcsr?qUY@Uw zWd?U~%J_I1nyiJHd>0+XqZgQA6Ps}M->#^g(+>Njc^{>ngg`bU5e8OkWBCw|l+Z%% zUHTy{IvTxMn74KTe2hZq2q>c|I2^Z`@|{h4I_bV$PCtSR>(?m79zQz=1^W%f-s&@g zE>PnC&%Yb|iSvd>O#i7ns2{AR7rrEdUaK~4jVQ33Ip8{~8p?=X9?cX^c<2P{lDgow zdm(+e+Ys;6aSr{8C&`@il>G`=A-=Cq>UF^wo;&(;^BdBV^FNZ#!!PHy4dZQXO-*f5 z$QDKS?@sm}*|PWEG_(j!l}bZJ(z>&&hthSO=PfECWVQF6Xo&P)Z~lQEpPpamb&lis z9{F^jFcKV2vuvZXG+52P`R`-(IFIk*pg@j55BpmSX_&xn9n9bKV_CNMDixUEkqFmB z%gEs}X&iNs?G~!5cq@not=;y4Mn$o^=XM`(HC>CV73FAbP8yV!Y9i@f$T?ph2Ucvi zxyZDETwt2s;mtSk?#)o1{;DZ(%i}GS*fD*VKpGd0XPIubi@EXc33TnueK60ajbv05 zFb;M!ZZ+;D;cI2#s9+x?X?`NLb?kQeHx$hlJJ3pTO;S{Pl=U>e{Dl5ijbZ3m8tWHnOFu}XX7<5lFxexwjbb7E0Y?okr z_{UPXG&m8>%Py0|z)sq=I|FvC{7j7Aq{Gb$P2AB^%Tw;@p;t{D!21c~(qu4S$rmR) zY8_2>EBv9m#$JP)mbGM;In&##Bw^K;WSdT=-@DXV4hl*6MD~6<q?zc@uGh9Aohc0^6Ymg#9;2Q z4W&QFT?9w7dNL)Wie-?otku$KSs_g*##9N8)G*&04x?+cM8hIY73;EOU05j>453Y(> z{Ej$`uLjC|aJ|-BxZ__o!qkv-_?2HrN_%Fb=&5A<{c1G# z^y@?FJbBy@w|3>CLD*f&`l5I?cUx(oriTEJSzY7G{0k|_dO$aup{{ut;C9B^4LUuZ zKZEHCJ!e)!ilBsKTJq6;D`V5$y~Nes?xc!;_d#+=Jze>F31S`gY! z5*OavTENfP?*^U8EbpQG3)x*`f{o40FO%=fg$UDV_uAzU%l|<>E|SGo8lAM734Hx}-xhApgTt3M${l`ZAq(2{+y zcJe1Oi|Oi%n1*UrYJT?ghu1JfQ(mb0_9%aQC=Z@B=R(B85|ZsGhrhIAu+}1*cXUvS z#%y3eS5}lx81Mpfy_xv!#2|UPtQyqbv-)op$sLND24j7~pqK4`I_%BRiTTj8!<>1g zyF8&NUuK9+(JG~Zy6nIE?A#pA+xQWkGx}d`bXF^cy$zvQHdT}=^Q$3^ecKKNueg(c zli_}nA|4$hB#8_8cO?Uh_3L>#Br0#hN9j~noMIS`y(S2gr ze%Tqn&QYhMI+?bxkL6_#&*H{Nl~X$BUq88jy)3TsV!nxyK4jC#kF#>1KZz4P9%cA;m0p|S<=DeOzI@Rc3ZB&h{208Yf z`)N)mM>hoFk10PfFej0{r=IXRxD|S4eIpv7O>~g42mjBrz5BKoF0A!Ksym!+w3I~+ z=F{(g3|viWDGgo0dP{b%x$ajEn|l+nug09G^D&mL)R!F6I)=9)V~7Fqpy>XsUxAdDh|T;R+46c0p$Ps26pe>kyp(uLyvuLx`A7`#Xg%s!#^GF z&1P?b{9_8$V~6Tq*dtBs_Ga0vj@LNliy!FC@9vP1-$XK>RKVZoVfbkEA`&WYggK*r z;0xY({)!VYFjGGHDBWL^E;`k*C6wJDhQM&&rGtN+w+5$9zsA!9`_zu`ugY~Jp7!)R!7!q8nNVbK-XTQ>to zpBp4@gSBjjnSvV+M{*NOr$ff(Fwl!=Cgj8b-g@!uOu(R0ZSR&?o~y^!!=Ry z2-6UD&EfQ_9@B6Y2RM1WlUR3^L6#5m)GLY7^x9fDzpq zeUW1-4v1%PIlI(xrI;v6{Dqlp$CWU? zhj%A@G<`9we@GubEkOex4R^x*)vrj{Ip()ID=K_sHJ<-p+i2Lz#X{EAT5|KZCaxEW zL1U*BUc}6?uy^N2ke2&M&Nd9drO%)`Dji?a!9z@aYy7KGN4 zTi4}r9Q)lK&A4adpQ{e*v@5{Hj`6rY2jOw(!i(eQ@^2I=fvTAstlSzwI)kR5u>;Fs z;wEvcw`9;`yZ+V5>klqLxXK7DnASv|Uy;Yah0MP{^*Z-w)C*d#a1lOv)stl+4X~Se zJ+`f%PBImP@wdcx+*y^tUwuOf-n?-I^G65CymEcUUb}&E&L_A>&s(Y4fm1{C_-wa+ z=I`^xJNFc6Y>+&r@&xFifZRLZN;+9HZ0L65(o+o$pAu0~XDn~hiCa{G&D;NHKdQb} z0zGhrQM-)Eo;%ZU?JqWmra$EtJRAn@Uwq)roO*I-j0Du5dk8j$UrCg61Kei}x^+ns z-0iKy7G6$1;V$sH6 zI8hy7e7RN;p=a${{^{1mFmV#XE*{I?x-uHqGrd!mn-%wpW#sUV|Erm2l)Qld-55W3 zbrRQ6B0~(xX)Ua86iK5^_Fl01dJS2*JP2P*6%|U#zUFsq^k8#p-_Tv=b(twvvNx-5 zr5~3(_dmMFVHtFM{Z15>nf{;k%*ERbX^N2uDlrYihY2~{OwkW?LTMzl&aWUlnn$Ah zb9ZzWyUfk;mx8XlhoKfekPkNuF}^w+jkjB6Pi6Y6FS8TjR$>`BU#~+4H@+Xb#hl*F z_U`s;u_s=R7K`g6-0{G__fk3ksmd_i+6^)~vx(Eh8IU^fEnF1&N@UvPar0XC4Yx1h zCXW)(bPiVlgKMTf4G(RV~u=@v(oku`~B7tQ$5HFZ2$Q!himoBI#KO4314(lHlnAvfbd(vos z(H0Q8calu^25@2h=dfkDT*DFp^ZF=Y%W))b=j`yUTPlk0$lyLWs^c&D2z>GGRMy-g ze=PW^FANFU%&&4%09naY@YF6LzKcb$dja$Lp6=n@Oc+Ds*7egj-~W>MmzpRe2yx9g{#D~KaC~Ge?08;F=nidMrW1pA%TsuVn*A|K!9Wn5p=O+^Fok4R~U7RCe$2-!&aR)vzm5RI>EQg&BUOav00d2?(r2LQopi~#=K95D?2|E zk*7L1V%r7$FPZr+Oa9PJU0Y!B*IF{_yfm&ecE{1?am48KHC#}mDs(ej#6Qdvh2NR~ z>ZHB2BHr2~K+zxfY!)?XK#*Sr3~zr;;v0j|y1Ih}$Jy~Wge!qjHCi4v_fs?NqMy$DhLSOuvtVkV) zDPj$KYo4w|uK#T{ZDN^nn|rNQ!u16Y=~ zk+1XHVQ<_DlO%TK2J(qBHwF*6dLkE}mF+XYNHSTfn zXL|9AI}F;fzl-t#7#o;~{_D4sSBhp>-QJ7Vs+0Jeg1n*ZV--Z+FC}K`^RV_l4%SQ3HN;U52`;q7~YvwlM_$>!ZM>I zRG1>l8%gHjhVQrV;VLEKJvIm>e+@DZjy>N)e;Ev8w;Q5SNovf-pu^)7eA{fr9Sf}| zdoo<v`nyEw~LtH6-8ikQ{R*u+}QCMv|yzd;HMh0DmL|BpBWV)iu+l=D(RlXtyxny}yBD@=eI_gF zEb*JfEo|}4&eo6&#CMg_!s8(a`5HcUusxMA#aNzNLB?>L!#rQEdkD`~QI^K5CJgBz zS5EeUtKVjzxQqxjInoR!4J^01IFefxF%z!O3WLVIY-b)h6;({4ahTOb-lZ{@VS$J& zMuyZ7qfi}u!e*95_w6_vy9^qWzXj|+c9N^%RgnBT1VccCe%#8q`s}XsDk7It-RH0F zdqnXy>xD|*^zbI%HK#l5`sw_MgT#)fjj>yuaPFU661~L&69qR=S+jsE^ECrW=~$3d zsv}P&b@AiU7#!Fs;E5>)VDBA0;f_Vu`Ab|ZVBOe{aNzJqqWn-4XIU|?ca=SN&moQ; z4*OR>_Y~{mmuOcssBhy5)bG>6rCPAHS%jV*lK_J`Bhle%CNVv2hT)Q_xLoBqXEeQr zHuO2c6w*vOy?;>!)=wG;J~Jk&A?khb#OE*PaYug+(2tuP80UdymA;V1(<9tbd{P|Q z));`i4i%wI&jNl?F5@z_1wg(?9r>G}h(GTL@b=vMHZ)!nipnaWY2h1ka7PfX324Wo zx^wu)zAM4gBIaMU3nveCrsEdInVCC%GFPVdlpgyvYiI_yZSew|80G={&1$BfBF??U z>hS&RoJ+||`b*{_OsuUZ!o&|yaxMasRZK|h4d!iZY{$=LclmA~l;Cxg3*5CmKqh2a z;yKnY`AzcXzQniFFUcq2`<-TTW&aoX+Bt7f23CKb0jKjT)^$bg%l5A3>8 zPxzHm@Y?!c{dAFQg8XezYBaoo74f=mv7$*8)#OgkhbhI(PGT8a=t% z9F&gyCU!OA*ywl(7tByR5$#Gr~-j@4|xnXPg;U3H3vn7JE zK_yAaF~fcAj!@%Z%~kN(oG{=_lcGdvuEkYYy~~7Ye!9p^X>rW75TM?H8{8$!r_^=6 z7wE{=l6>Z$y6FEGM;7Js(|H$RynioH=dUE@mpQ7+G7tVYKhFM0Cf(VwbV&b`FV21^ zV+3gVA&1*dKU1-Xk>DCqL3Fc5;sQli3|n-GJ5eJIL3xKE{P{=n{?b^qxXKv0DjdsKus)jatg<(i<>lK|?X<)oxvkJ>dBQa5iATKGH|4$WALlbYpdzqJ9L^L58f ze*~Q5PE}A6cLUAcggjqhhK0wXvCr)W?_IVvyqo_PHa_`E@;ip(Txa(FW-R5>L+(?} zXM2Y3I8FzPfG-k(a}~amAdBIk=d~A}vb?jGETc30^)R82=>dMl%z5A+oeNV-OUW4{ zWxRSO24e~cuisUUjvt#abl0AC$rrBNoq>HyjGa50v0GV>5ug;sMR!|4qiGoI%4;Eg z7c4NtKMe2xaN#}fzYKq)Wl(fO4KW_j#dqxArrlx3HFW<+cgJsmc@kY@epU@UWPYWw zxgu1KecQ9yw|(YQE_doy3d|PD;)&ygG_ddI0sDRu>teaEKy|F%8ir%{9?zO<5P;YD zBZZj(8~C^9DZ#p00f>i{5Q7QgSiGJ2Tx@%Ji~k!(ryuL5{FFhW$LjXa>rN;P$s=*+ zEl}M%42}9jy2XQLiZPi{FnG>^xv(nH7e3qv*Y@7@RW$N|kE@Ajc7iC`9_i^}(& zkw1B3v7mza@=iSGLax`*30aQtacVOudObiz6VhP{%SI`%(PeA~CpwlftG0w z5GPwt#`(U6pSxyb=)_}W2jg$_oL3eO_nXi6j1h;!_XFUkbsgErm>%mq+5Iu-zRl+o zI?x?m0S-=Y$Q*@WT)Mjz&#Tz-Zx^b-iVH3G4Fe&Vxif)*vT*u`f2AJ@5(W%)F|$`dL_HxP>ppTS{L1WM?ekkB>3xSh75 z(z1Ad({UBZpw94e`2j*#TVeamRDA8`&7E`XqW1SsK-i&XB3q|~6IkyW(S@9_ubzs! zgbvN%6ZBf(K`Ucsei+Nk^twZ@{}CVRGhd%pfxTOufmj+5BUdX_V_7^a>Yj14llrN_ zc_)}=P)N=`QpFI)_ZTpbAOk#U5Fh^#-o||;7c)8_oYlRF<0U!$eX>xYvGO<-8?|~}PSF!k5ThB&uq$zA%{tedH6*A9Y2OMB^Ci0#G zS2TMktYbar^tuM}`{@MC-4lkRqSd)mcQfdVljcJite2llVD#8a?C!5h!@czo!x$Uw zXdvftp_o?3xx=Nd1DX)HcC#{2~t6ZmTmu-nwaD!8S~{4z{KYkt}T zub3?6e&%=48wa+*=L3~2`$iAlW0~J}5z8~Z-b>}`gCJmjHJLVs<)Ls%xazhj@6P;n znERON2ZFRo!lWSl)ASq7X07Hwn7k4O%n-ua4XY-Q)hMRx5E(X$s}weoH%=F5dx#ia z%J+s*N+uX0>|*){3A{6d<;W-8;PzW)(!W!^V9O+yp&S~7bHo0i{=HZHr@EIQO5_^qvg+OlxNY^k^k!F^IZ}+!;I;pM!e)!8GWNG6CxP{v4V)6(Zxg3PRKj& z$$8(GfgFxyJu^@A%+7Hb7|7d&o2`(&4;bhuIKg`W8mCd?jZ$DPx)o z(|JlQ<36ro`r#XUVBFz0GPCY8Twt?p$ieSq_P}r`l>ApS|LQKlaQ41;7r)6q#aM7H zFQtS5pZ4)Lbk2vdp}FvDY8m+vt%C74W6*3d!jD!4~82IH=N8J1LaD#IU{;^2q-B=iaiGOs2+}t33 zR{tbuobnMGRg1{qD-yV6J?rIetmU@$+@+(o9R;^jtz_{A1C0FTird0Fc(>L)WOJ^@ z5L%>aH?oYZQ!PkDD<_i_cGdtqLlmT%i1MILR}Y!Gd8fc=($* zccn0k=1iP5q@`?Mcoh~NQN!0JjU;`&3Vvtv{s@Z@?&hI4^fRlOb!QsL--1@?w`V%} zT~mnP!C(|sYQb8kJN)-IRpC~aGc@EJAOpqL_+wHkE_?3HT@vY{pS6yGoqZ!|3lqUr zz25kHP=QLUW31QZERVxZ$gR23MCXKrg10Txk`=Z=Mt36qQX0owygi=Ij~9muPL#?# zQiX`K&QKL;L{w#G;bqlS{9u*IowFREZ;G7Q+g(U-qZ*DH#`2Z!hZDOiGN3v508XVd zP9tMY9AURk!)=mWL$n;oE^vU=wjJbjlNxsUT)^b7>15^w6ZjYw2T7e(B!~SRGxl@% z(Iah+n3=)j$KT*)Ya#J<`3~Qi=kBG#RxY|_7X;5_|L>MJlHuK&I3m*n4Nr-31)u+; zCk+49&zBLBc&FkbzEM)8U(^inWGdsgJP+jVJT9fh_uRo!yoFr)A%?B2|6DtH2SIl~ z5H6^Kh0NpZw^9SW*SO>GHw!tXo-V4I<^ZaOY$v(V5bvLhW!&ILM0dCW+9e23a?j4$!& z8vc@15-vaJ&Zj4JK=*zET;5PloL5St&Xiaz`1_I9mu^TW=@ky$%4g(;!j_lzSkxm& zf2T}?Pje$7K(mP`Ol04`w==%@dy;1?#RFNzw-9IcjU0NTf=U+!_-fNKPEzeLeRgIK zs6@4qTQ5F?4DSYBWjQ{RjFh2NaW9N0_)LDkU5MZ$z;&Anvcnh1;NJ{qJo%)UlS*F* z7b0_^=4KgrIZO?2rN%I=Hs!??DNx7MyFXi{j=V zn+;vBL*X*lNfe_UC7{g8bJP!41nFi+S)hy|?0l4O- zwou~6TK=OB6}XrxfR{Zb!1=h|MLnEXUK^Tsdw;_x8Z`(`AD%y7ap7(9p$Vw{y%#G>e-wM+{n%9iTwJfy`i9 zg|=;O7&$<0h3O&C=wblxFv2w*Xjtu#S13RZu32W$+n2uux{R+ClgSB24ARYREI+ZTkZ1;|=AeA@8+_7#Pa-CE!+BOS>sD{&zGUqI z4}Ln#FKr}~r=>ys9W7ja>IP4?_bJ^^&ETZyA7WrEf`Sxh=BJRSmM(^9bCdmjwFYv( zPnXk@)9!GqyP1^kl)&~|iFiAH2XXQBhuf2?;KD!|nbo3+%Mw}5e7cBJKJ|mzTRFgU zl?oCZYKR;D6X13U;N%wkq2~*O!2d%vx!WRvwab!l-7qm;eclGt7{+Fzcx|$e?IEu$ z>%(8eSMt@O)&Qs={Iz0iz`JaRa5NH|cA9gU9W5k%qBF}k5v8kk`hjbJ3AS1OAnw+~ zFozT1Ud?cBrzN4mie6CdT1#Mw32MD!*`SMO^2+ns?zF8BuZQOFpIBc8sO}l6lc_-y zFj_kmbL0Iv7iUT>$Wr)!{&m$idA!^ahj|yY>F0^VaQqZjGgDr2c{|H!_q0fOo?b!P zLiBL%WkbuA&69|>J7-|}H@N6Xc4V>IhU^Otc4UNLsM-5yw**+#4)zOoF^Fx=(eLF9B* z;QsqPFh}7Fxsv+?Jee+WO2zbSN9MIpej*{fWUz<-JA5%nKF-D#RvWuZGd2K6klTHJ2K?_@U zi1M_K_=4XlS@dtKBTHTx;^9^SZrnMKdr`rATj9G!;c0|xWOl%d=*IpTlO=5e_qb@ zW?4Y9TMV=ft0!ZM4e>&73~JV<@>Iu$P>J4+loAEm=z|1TtS^hm5|J%gt-W^rjR z#X)I?1FSjQK=OXDtne?cSZW$aP8;pOrBP-0=CvmOQK1whObme6%tLK2&U_+s*&bN; zfsN5?1IARVfZb~g$X456R9xJEmyCIQ)4y9_m3AgvXSoSya|v}TvmRov&3Nqt#{1PU zrM!`NSgYd;ra@{>3SsYTA)VCd33FM$T7JG48rjX%?vo|iaw8b+G8^zk`E7och!4y8 zYKH!^#bkjt58W1}V#9hLE&)5K_w$4Bt)-T%n=FQJ$9Ut<+X_^6fja84IimBIkUKNH zooa6nh4R2k@@(1p2&6gLQO{s$|Y^(o*di<@5iOXn0Za)WJ?-| zG7jS!(;K||yE18NyxEX8DQCDbX0W=~#szVQEGwxq)9%PICV+p1B)YTQoHFyBM9U=r z`a3G&gH<`%TagA8Ov7>FK?hIsXg3|4$YzkUEDPIC6dTfSJk(zReA#x$8M ztKxwBL^Qa}w83X*a~Cw)$(qT|^n{!kEz$^tC$^^8#d6h;#Y^L5c6(iAAI>H31iDJg z3!F=8iSZs&#A%-R0<3x8O|O83SI-c`T+MhAj%FOB(;fcY(;GlRY3UGCNF$i#lTKng zrH+@Jm45~0OZ=;umkab!-O~{}l`nFOqvav&+98;}y@-6&GR2&EVfcQ<%xux0Bf)Wb z0$jLWPF4@fVxDy@u1ziCdDWQEskQHh?nJ9MM8H(VwYbDpo|f4fV^6y)Hg6MfNBm|$ z`>aS%uTtu7ebRR{_t>dq7+J3z=G+2CluDLp3w6}Tfyh(#W_BOALG3Izd0T`vKDHIj1=1bpI z2X#*YJlbDMmfVwOS~+%q^y=fCIX;DMFX^LF%LmEC83wq}+zE}OUX#|^H1HJB!hqY$ zIo=U3=q%-1vMadH-Svr+=mmO8*x*6+O@ zsfaT_yJFkfIHIo^h;x6*3twj2^7s81#(Z`G(34k3atj!j^}Yb_6g;rGaL@>TU8#Vu zg9XGc>;dd$`{%hmJGs7*+rVZ|Ce-%VlK<}VSbb*i*Yl~|NtWRSkF19>aaN!311wa- z;k8X9pXJaVWPX#*>JYBH>I1cJ_k>&SjikwTS=4}sqbrnZADNtV82)xhsNWOM2xC^?S zRL3L~u6R`v)s}8}Bb$U3ugCF(tqFAAO|c;jl7;j$5aqGE#u50KFv-pzqi>a*XuDk3UR5{8N&vIHd@ZQCpzapp(=v##gY=5zBaK ziyC9IP0|7)CVqp=#qWv9qkbr2?|5p@R?h#x0Z_J2 zhtq>iBs4gSK3Ms$PHwXj!}t4~@yrofNw%+am7yfnFNMbjxQ;DoB_S+hJNc<3tTVvgx`B zJ{1aZ_7mWC>=J>vh#;6bp@wh~!!VtBVE3#QJY!1hCtX#Jl&Q7}n|r-K?O=i$bM zH>?A@5@5RVDk2cmMx$QXEqS(IgYevlZhWyp$S*d%3g?#eK>dktL_T3MYA~); zltlp7DkY>HPnQhU&q5tFlw!K6Tc!H+ptvmdGws>@`L8%tw<`KHB?8tk)>G63LoCjA z#0f4Jxmg|x;A3$JwmTLPn?h3@l^Ti@I%j0hQw&7uV0mHXPZz$JgFZ+sPJph~av~ch zkJeXWv3U0Tdh57Zu+g1?w)YMWf&HH0k9i+}-7ds_OT+pG7l)uNDb!xn^?l z^=On6hA^g5AaC(BJ6PXa0N;#@$x%}c#^qu;M?05u`~&|{f3rOxv!I+(+i~g6IB_y+#)GeCo;3O17V7yDX&{^Eo;nsNJK@L$!2Zx-71BW4dT3bviSz zACklw4{B~ccS|-EbZ$b(eYvmk0hp0LLa4fG6<=Fj1D3M7T0=_7 z^$pW#%FDi?p0lRP5GNEd&630$cKe8-GA^;|D#8t)*+v&j{_8W({FHz>JOA~TPcG=;xPUYGWz#Iq z=A0xv5;}k&sgW2)E8>3&Ec+}gj)YyghEB@z!sX$7z78i1Z>0X!&wzy*IF+#MkM9p` z+9Zr&;jIez9a2DE7Tt&ILTOws*ukZDYy*e%OmK9nBm3ua*v4+MeA#K7L^{x(r`E7k ztB=$i@PjQU)lls~6LDuh)0q8C>FJ@Iw)00i>z60oX8)ej_uX(iG7-50Q;D;BFn)Pk zi?evQ_?a=j;P#{$+Rrl0*k(TZ-(-Hkb|3D2VFxwXw-3&ZttMuZG;m!U)5(Xt;ND*D zq+7K9)y(AQJ+PJ4fseA|d7CaK(Uh-ZU==M&>l2^C{0!y;O?pKnn8rJHRw_O!&f-kG z#2~oH5rR&r8lHu^katmCu=_KzTXkej*6DoD2 zkr#$RxWQOVxG8-yUpLnb>WtzbwzZlBRvKfY3)84bo7sF%m;eW)zrl)Q?}`4gfuS7d z6?WS=zRe*h*pLpleVdu~-T;^0xrpzMNpQ18v+1>IW<$BOFZaq|pVUP(9Q1-AFO1rM+zJ&gw z59c}z-HE==7svMtoY8Tc9}!m{jYfG)Gsd*911_R)_-qjLt*jwVIxJIQZxWt~7vn8% zvBPzPVYoU#hMX3p!)6-|<^go$&fHUi`(NF_U~eeV+G~KN`Vm-IX2vbq|D71J{`3E} z^xE+N7|%1p#dV!z+DSRwvV?i$Uxss1$8zY+-bY^I{a#8iCa9Kh-QctI!CFM$p7f0EnG1GspAWmx>tr{fRG z;c;8WVF-N1ozAae8F>+muUA3NwCbZw^%<1R_TaW0QH02E2f-w^h}@ma$0K@-(U-D1 zJL0nec&|wS`3)7sKEjlaQ-3$4^DGzMgr}Nov9wB_c4io1z+@*J{UeFv*;qrhR3t1CkyJ;U}4#AI32-m7CyEJDz~t}0kTa}0x|8WsIbv)2Y=+16%gZ)3tu|RNj}qO z8tKR4R~O_xo~J?`PR0-2l9m}TruEZ*HB&5w`4032=(X=Ar?J`=690z4XstG4_m+p9 z1<`osu@_HcCi5W75ECA7>*F_k2!OmvvKWzBPaKzw#?NA@DC#($%YK3M(UQ%OnbAey zrW|&%`nmd%I-P%c0A5Q8aH~%~H%xCN-ca|z$vHmUQyl|5`XwACy3b~nv%2ROqAoP~ zvx0BQ?%p-K1d!8FO3It2)AKX`^`aZ{jPTe}w*QoWLk64}M@a4>7I!`7VjoV1a-$gV z{9I4GP8;BV%ty1MIgwXV9e}Y9)rB5jete4^RsgIQow(=|`57RG)vSNRN$a_9i&#!^ z)#0I9`ZwJOn`9mF+8qYYXilR~8`L3NR)mh#SB4FdZlIy9LyX0zVJOpe*xx0b*!K=9 zzvSG|{eAaoEsSCB-IFbTB#A!^j%`hcTE@}6zR&<$Eze;4n^~Nh{4lU`a$tT)#%)Mx zfhge$yjXvUH1h)Sz-w7y;eL+aFkBYi7x+W3Qaz~+(n5)N*5fUDXrmlA3S2BJK=)1o z(a(Jd+b>At9?hK`ft_&tN+#r~*AumNTO7?agnm)exE&~@_5D`x|9so;IsR}mN)`XF z`JC>rg#%1`cKC28S5yC)?VUU!@mC`m9NrJGHxYfqrV{&?!Kn1H8l9YC`JZI`!LhIj zwj3`ZE1KruMaB*IGuxL79@#}#Pu&BPpI4F@?Gku@>s97?SD;s}X<_j>0sd@#!ChMW zlP-E60#_0%$wkZGa8n}*3+IpLP30w1!D+Ff9q9_`r=XyyiNWC=v-$=8f2&S-lyK$uySD~Z?J6~^x zeM>t@(Iv(JNOc^lw?>9z;jvB}teIa!F58U4oHNO2Hs8#~+hh_vdGi&%UtsyF@*+4_ zjIlw&w{b_sj=-B8>F`dgh1@pL#*^z@aOc?po_A$7-6a?^G}kM!Ic#BzC;Bc|rN#cH z`1TvS@2CfJug}*}uNXHt%@_sIt@5aPp4}@o_7l^DAlQSIka4Ag6ohEw3FQlzWw(H{ zjQvfeHaS35OC?e8HpEB0;V38-kh#I8xTTzV8&4s(Ia&<*4+X)wuo_~}B#&=TG2W4d zBu{zUTy*8J8arNw6vhRii&z(mMl9h!A&fEm!4)*ZLP*>4X}FwmHe6oYuq?J8#K+u; zjxrUaW)H4G;$$QA9^XY$3*>PcoBNtXBREmpSJeE|B^Ym4$Fd_wG3^TDo*kafGe}T^ zfxE6?6tsib!!+E(-of)P1Gw#sS)_S-37j(dN!I8pV@t|yJY=m+qjTj^Vkx^_*1X~Z zU)Ry9brC}vr>2pHIHT%v0?b&>{8J}~Lsd#R040gCg^3uZQLt0${$mbRlO?hqfX1BRWgB9Gk z2buKolifr0c1C0cWKRgid3x>S>l<~L9I_kUvRsu78G-E1BO>e<-_GASZxu{Em^TrcMs`5F}bt#~}L>!g6Gl;pFE>32`(M@LF zoImp^T#}4Hm(+7vhe`tQzddR~rR3%OhA&zmb4CCoHd?BZOWi<)(u8KdPWL8Kh+5k1yiMyeXxV3VxG`6R zu5wZW$9fmgJfuaeZcWFvtlq{*Q10XVF8Z+P?9h(XT|x)<-VvbSwjbH@L>fAn$KKBD zD{1Ry-`LwTxb4YoPGBnyuWmaGW%tN$ZG$gPD=>BN5{Wq+h}D@g!aK`({GaUpayF9P zFvirA96cQz6fix^&4)JihfP63zXAe36_DSDg3%VaQzkwL2BhT=wOB{krIu>$_kx z(+URkOQPPmt5_bWK>zCKU?O{GZ!XB;jGy(;hO`hU`&3Cd$-gkj@)^tB#`8AMO`-jh z#h~_@D0P4O9PZ!J#;_-OWZ>gmys;(~H$HjJUDzxEgKCcOA@n_&*Uk822V&7bB9eSd z4?vSE`a+Vqov-&^89E{#fZOn5GR;R6zca?gLO&@kNL(4L9XA79=_DHtXkn_VBc5nT zBag$zfsQ=WMBQeZ=PK4WvW%_wDP}e)`2kGpq%T~q62t%UWHKZk{|dLxz9+w2MNyL7 zfTG&Baq^#;j(Al%tP5!&3358vnCXl)hX#11n<;(jJ!YuaEmMt$lm1z<(8F(GnfB8|8u;1M|6@zyZ2!tOEp2sUj<% znB$o_w~)6tjoj5SL(5MBoGV1mGfo@=4T4~qTMcR2tBCfF%%8qnl2_Pbier|!;!NGf z?2)BGD8H)%-`-oy*XULPFYycT=*xAYq-lxyy^P&$&*MH^?IEIlPD48UG3@8ae4`3Ld(38@HX%ro(5k-51;Wk2KBYzRz!@ z_46Z!v{I*8UhU}d=TK(YMNY6x32Lnl!tA~xB6-yq%#9P^?N^rWl%s?%pTwd>>}TFt z7jruD!rP(#c9H%q_$a*=ZKo;F_SGz-D zl2>835b_@vKu-_zfP3rUq9g&HKDvS%hLxSI?byQXps#^ADrgYHUTo#pYOR5G*59(UJi_Fjt(=1`Ki2~r!oNaht$Oknqp4F<2d zSw1WuEnXCJ)Y8e>z>zGU)(umFyt#BcbCfEMMIUXCEYH6Ic+Ol^_;~3uzW#I_*t}Q( zhg{1@_f{+F#I$$+-?ci<9)(F(PMFd1hO9dsgqO0~v2U|6-$Ggig6dqs!u}ZHy+Z`(n&zUx6%ZO(3)ldcJ$++RL`*+9!#ughW zkQR;XB}(W(wf~|64?zcpUtp8Lb>6;zR_hO7s264 z6ZyXLFW52P`ee6h#C>@%>h)FNrsin=nlS;Oxv2@B-zXuo=g!0T87!OQt1tJ&t&`rG zvJ=*?EGIwrNa2UgSMgGz0xh|#gKoL(eM!#Y(r)$Ar9B}qVSW|M5dRBC8Wg-TRp7CN6# zDrAq0N@Pd)8YS(>UQI1pil`7ul%D6lkF8Q6X;X=$rEK~=zx)H|73ZAm+@JftuJ?73 z)0`*?-Dmd0z2g-m$72|_?@qzlZHa`wV7h8COi0GA<=@z0u zVS0>~tz*|2+&XWVFj_Q;KXPUwn4PEwm4*uP^sN}`$}#VUtp`^ZvjTW`s|d^z0N6N+xTB8mMuGhAJjjb^$+ zF0?@czA#PvUe`>vy-`NfuxxysBq{J-F&a;V1!GIqhvMSyNHovhpNDB2!tI09whYFRJ3Ou4X@n7xvUjW zsQ34|AlTYR%3idBgD?Q?yt+xpEoI!Wl6_8&JmwbDb~<)W0_@jqA_<`*Fd*LtZBHHK z{syUn$&zhw^}s9gG%Ny_FP0JZsQdCd??=K=#Y+%Bw290eriN2*rr^`QDgoCyh9-^w zr?+XbsW4&7vOzz9bCNM$-r|p^W@d4VIRW@wPJq7ipU8ww7HAjA`qTGD3nWbELPJ?8 zsO_yKCnSdACwA9(`D_uFY)0tvnHynWUMFcg-3&daV^B=^nfRX90_z7Gn8&r6gs`kc zA)9}Grj!?N?qwbB*Z!bVxI6D4w;Zm8K8DVvO$0U#LnY>a6aOd_*uB!EL!P7$>a9y6 z%gCN*&G5?NROycxW8t!Vv_=wF_sapy++!e#`4I9B+q2H1Bz&B8L@=BAe&b92;=af} z-h}-|%h}7}D8morzQ`CfXU`WgFq?aO?GasZ-W8H`dPzl(7>;2Y-mvExm-sjf+T%r0 z>c4z)X{sL9D){50q9a`G#xWRrhW%~&2a1}9g`=;Cny^iBK5rba56`W$!5iy|vF>zQ z$^FyY^sUBtMc1Eoy_AxJA(5Eb+kt-rjCetTIxJil0^3#;l19@pxORC8CZ$~$WK9jn zSY0*Y?yBSb{xkth#Y%9SUPVIdl(CN8Qcu{f;-0nMqW+J!gXo;kWXy@tm~xr<8?W{X zf)3oFNsBcHceAY%)nL-cfWi58Ikm>mhB?SpP)_}GFD0dWVXV#v@_w&8IFDxcWyVWf zC&hA7PXf{B%S`UBqa64!p684FcA`|Kj>(b1IORh+QDC2|SCP`f-G8U^?ei4j@Uqk3 z>;InA$`8Yuhm7}Sf5Y~6ks0{6HGqp*8CjGTg7iv$2HEz|g>{kUz znj(RA>MXAm<-ysk*aL^zGmCXh2N`fiYJSdSkP-UiyDa{m8iFf-DO2+iWARNF+xfRg zakeGxRQ5+OG?p+<#Rw&oYi1qpGd2>*k{Fo7=G#?;O~n2N)9?s?bdR3J_*x2m5et)+bB>J%YuWk%k!P}rA%TN@K;kf)2KZr$$-{AhXFC?1z z%?xo(Bg>f%QAICyvyd-J;PQ`^(k5~Ud}ZDf=_oUdI2w#&ms$&|t)sBTtpgWqEavly z)j((v2%oNcki8)`_?R*M4qOc9qCY*QHFa}A?s^~5a&2SzrU0Dj&`p#TRB_u1meVPH z%q?r~pdQ8vkUp-7+{qt_1Jnnt>ko2XYt`V@z*g9q`HJXe%)+(fvhnzK=VG4?5x9Mr zv~aDn4<90G4DTLZ9Ms{iz3Mm{Qc%+MwcyGGbGqbN>7XyG=0ZATIWS&mp(5Sr#dKrQ ze%vwn3TN)g!LvOH;Q06xF)x@0v00^1dZm_3*u|LAh1s~+y?as{{vO!?qZd?@ACp$#P+-5UCKbhveG!;={})EiU(IKDuK<(jk71-& z6PfpZIBrW%LELp;P_k5uhW<#W-wZ@4z&V)2-VdEWVsy5X1fF8q-VBE%F3flqG>nOX z2R)z3XeUQ(8k3CIOpgj|ZbZY5adOz;`GI(>9*axNa&VLA9M1LN6ME~KE9=khC8_Ln zM8;;L;e%(~)3Pimy)J^YPv?=5jxw0{$OTnZw{!E&WYBd;Ab#94zi8Cxa6J7|MYth< zE4f&>ZXnPF<-ED_;jd%XJ-6y<{4GADM$E#shc8 zw1;Yc_z!eTTZq(Eb(RlK!MKkHiOVeo7}}f%ny0FXLHsCO@__jYe%f*)T;&0n_71c8 zMAlE#z-5zzFvl&OjJU`;pd+M&D!tSAxm%RL#p*PaU17P)7wYKGcJH10Gi*ET$HLU8 z25=ftM)qY#p~=r$ypcPVzkX#aXwE7GPi!M!lAln^N&ocr-PI@v+@y{lrP|4jz~MOL zYBoLyiREghH`0}v2VuQLJ5h@hL%;M)+*vk>tdfpK&Z`dhZaU9r)x}3ko{_*+mKY*+7T1|)aC0Q3;dZ0% zpx)|9hhs^!p3uc&HQ)4C6H0=vLsnf4am$fJZ#Ekwnn-h(Q`JE}#1)K&GVerh*z9p&IQv})LeD88oc|Xgt+;41*b#gt zr375gPREsIF9~G948K&O{>395;3_Z%Lhy+wxTkx}QW0 z>TTC$H5?Pg=28VILEO(s)EU{1jzP2e-})NxWmh1WZHytOtz@zJT>xHBSKy8q{w5_l z{ssSPl02R|3$%ektcGRZ1ns%>%E{equL?Wl*$JunM$k zbeI}W-pqQ|#y;Vs9lEHURstw&X(AG9O|YZJ7q`qi#2p^34z)YB!ka|aS-E)*eq6*d z5t7S`_532RR!vHHt$8p1b)gCLrCfx23!2DDNlkqEBL!myUJGjZlx0Se~f_X@;R}_DeiNxUMA1JTm z#*f^$3Kp|n?n%YB#B7-%Zp&i&Q+Z$D>8DN8^8RUTRag=T4%?vJ8gUwWTM`f3u>JP& zBu;kbY}Vr$4gX1Zk|T_-XmcYN-%NBByg3vDTS{ed3FFWfH=1MP=o~C^nZxxhd`5>P zyTbbVUh?LaBAoU{tJHf`hd)nrlgQUK-#%r9zR z7>?fxl!b3Yop^(d!(oF(HrQ=!AVak|>b&h69jY!u&*_fFA71_#6IezjHW}dE5g}L; zc%9oBU=3GqB!NWG2eQaq7H!@Hp!Jgzf<(7)Onjg$tkXQkZxovel9wvMxTK0CHJDjWdOxFCmOZz%C26gq|TXis32n4OqI>gLK7O&oCpH=-+oLyQM zO}MlJhLye}Ppvf2U`PrUNQDuGnBg3?I_`#Y=H-?=KA^-~L!;nC&OaPdSNv9-{^DXJ-$8=PV5`e!Wse%=6L zyUK{_q$oVwP=i*DQ+P?=ZSeS1A#At#Kpy&Q<2auKxPO-%w}X31TQ=H2naU6Hc25*! zyivn#{72#`XMo*JtfTN=EI0jRBXvJ?5Z1BI_p>JAnEN>sN19J25&NRhhp)x=7tZk` z%pyUu`U8j@sw1^88PlVQu~MCC$u4mN+`{fb=dvGiZb5(Pw7W6zy7euQJSvWDo|kc6 zw1r^N!>iQ3Ph{}^wPx0R&^OXUdA$-cclJ26OO8QvwG8g-PiaVq@P%cK6~ul-IDVO} zD}0*k%BM}xf`JLwVdaY&a+md|r<-Nt>1EQK8RN4BuxF)l&so0DY&ia4T6!|JfZQCT z3{z?kfWBe@$rPGn>uJ`vRXxVmWI{OhthVD z^YrwI=B5;UrhE1V!Hd!DgaPWX^mPUnKJ*~3T4Q0QaT7c^@|NuVtdCvFzWDmG1GidR z9MX@uL(#fs^14WY$#E$S+{Tdd(En|Eo$$!N;<;>xkUs>UE=fhH zifVzS+BiDX^4~0)RD1~*y>`a^EYIXsH=1QGSni-Ji__}1gQsc|7;{iNvn?Yi*k z?Rt2_m;mPrT<|x0UKl&2viOd9ByJx09lwjZ@?Gk#pupx*Imfr`UTlO;c_}D2<$>U2 ziVhX*`lp#O#mR8S)CN~96sK#9qz8NMB%dX58#3pB`qOAA-qT6$%``-@PeEue=_;5X z6Nxr2zoYJ~Zhq{AvoQOrEOzYtK(6|+tP{tcHJ;DmZkw_HgLAInAoxNK(33mLTYR&J?w6IYX4z|^Zmxl=b65|~ zS{Lrigu8Uintxi_#O@9S>`v_$)h$SGEuyndX$*D{?<~xN<$H8+-{L~z7-Nfv_#B+7 zgxn6-Zd&?d8&t5asByD~pvp()F`gbqG9M{}hI&4fu6{$B?pb2l4MoKH$4dP=pru~}C%Ny;0RD(je6Ze6%#^k|r$af}3LE)#iL0vt>dI6Nj>fo(MKLvq}ee@`subL0k5<7n*oW$-3TjU-wevv2) zTNeYNzu%Ix4U$+n^D+*vwGdn{zee{_k->TO6aN5w@^rCi;2AmlK9BXn=-{Shqd5l= zSuj}R3skR?I7|#j?XTLxTr(HmzDOHJI9&&BChKU}C4)UoV}rw_Ig!(va7)gWWypJo z6w8y2)$zx?)B-Z|Y99Rlsf~W}&Yb1u380;v20CL}30Y~07gMuvjP+RCh}q$oBCjL7 zb1$B+b({tpO{?L|ol2HLmcf8g%)=13j+13xl9HEs5Pj`4305`0DVqMcI+W?H|3m6w z@K0}7I?Cg^pa7JPQlf2(hvM1a@i=5l7}v3^ize3xf-3X6zhoblbdz*ERlbHS`5g!P zs!ee2*IS}-dnnp%*oU$a4xEjS1ep1_gU+L7BI&J&=d438EH;7|3df$&*ku|nZX>)M1yG#c z!u|#U7C7hN_hUS_WzqmKD&0SL{~9|s4&HhiqWZF4vdLEy-48KsIhn}uk}s*v{X?KH z$~qKeCg5eggSg<3KrnN66yBWOhIp)yw`z@m2{-z|aZ4RJ!EzrB8yHLHSOgaY&uOB| zTsZ9BPi(z3(Rm-sPo*#d7qLE+OA~kV^#*33cK9Nc^*50vvfB93J{6sH-UzCOSkcT=rL>2! zg;g(HhRrOiwaHA0>P1H33!`d0lBmJQ_RNH^;m)uXY2W_ny(8fbqe_f`%+z>ZOuC$buedPJvf9tufS6oEC-3 z;4T64c>GD?RF&p}+0AHBYU(5j_YAScx0g{3e^)pX@`daOltD2z1Fy*{;Zi;C!nlJnDBlkxr(6!9convW zZs$hNFhRGtSj;}UujnDuM!ju{!X4jc@d8yNc=RC)q#v;C@LxN+TjA^Ae!xCf4x4{D z;nd(u#Qsqv`b~e2=61vR`P_6^crXc)%s&z><59TsW(+o(TohPDgrjVzqA+FC5k4&5 z5&kd+)8o+B#FKSeCbK>EpPMdR{QzT4Ox+H~1E0z9sq&cA?u0fIg@V_e_h`n{e|kH< zAs@b4>fn`ig{01qL$Jxgz)i^QP3)#qt+qnJxkeJ?qm9lFQ_yG3A!0K{6|PI?!_xC_ zh_n zS{n}yyC7&NEu-J&+rW1IC#ho3r21)USfJ2O&WMe~E6>$m(A?9ly2w}-jIo1t~2 zrd*V9)dFyFf;jyxIuiA6Ge5(QN1WjrF_3qTfne?(**sAi$6H@UMd8DV9J6WaZ-^g{u0dzlYfh1&Regfq7z zej;K>twmp1 zXQ+QW*%GUSWfB+gSb{sTmP~+c?;AnPm3eya55pXzeR#RlffG@agyf~}@P9t4)gLAN zaxw(HZ6itVVk=z2I46%39&iq`h%D&f5#U1Q>(K1wA_^{zWK0as+qqqLkjb$~b#Zu7KuJXVibo@-H`|&^5n`b;halhk_kIH9wx+ zm^#R}b4$U^wG<+n>&V|-BXME<|GOraaGeE@=t<`da3iFPNH<7fj&~+re=bGick4sm z_Vw^~0rPLKV86WqT6mB@%&p$;4i~>Yf(5VNlJb4Sv4Jv9(b-~wr-44bIV_#F%oC*! zf776Og$<@xiBs(kSv=;LjaoC3xst8(pg1}jj`3aOKUX9CSrCBEx-No^qEYxNu^)Mp zPQLq19MG+@sLFb6HkTQ&oz*!Uv3)Y9TTo7KY<30R$}i->XIV^P`Mb-KrQ9dRS$Sdq z3mQM)ARnJF|Do(kyfDU#yM59Gqf^gf_)edq&KNdhEL0Gtf+N2xVg%UrWP!UyBkB8X zPcJL}n`w7TTHvi80hlUa&y^8IC{zfx zg0kRZ8aq>Cumg0hB99_xa`4@Is8Ls+gv_Cx@_+?Y>=eFBOae;u zLLf?}f+)>5Li=-9@UeZaZIzT21iCkX(z`P9)inxzr&M9HU=rVb_dg)6h0L?`k=)-? zMnw~?VPNMEqBc7ghCEk8-<|E`VK~#$Kg^dH6UR+!X`%C9|I<>3;d1DGI2%X5upvR| zQTQ>X3I#h7_{AO3aN~I!>HwO)>M5>ydL43D zUvFL4HtyJ~EpY2Q1;Y)kF{guFiYtz(f1gGMzi;!@0~-OrG^&huJME) z$E(QCNp{%ZpMqDT=M-niMxs9R*c)Hp$?JX@3)8n;gr;+E$?73`Xc3u;;Wjmb6(*DD z8{<+s`Wy4@c;>*T9m~AKb_QFEzkC{%r|&2nJauWA0oV?LHt4&G3+r#U;hI*{*H%0or}iS zqJG@+sFN?3Q~_fz=BZY7AwPHnlwhy_F?u4`Ca9!Z>{;ypIyvKlHs&zzU&nwJb(trR zLN@Ex*_Uz-M{j^hsR-7*y-ns-%AweQ%W>bAt(^I-aIChG7ru&i;DU2k(btxRbo_gzylrFxCkkCs)F2%W9HvR2vW8%f`&TuG~u(LKBj_V5w3k`8H`B zZjcJZcQJi}i4!S3oUcBplTzJxcyW>5qnxb?=CgzXC2`{`S!OR)Un&M7Vd+U|5XwfmUnwJT~oNA!8Uz&8lJ92PP}R8#S{!=G=er|V z5Xujimfj)H8CT>#&mOEZ9nF`YQ-NaEDR6FX9w}{OnUv6Y3~JQ1t-BD8=BqS?NsrF* zr+|a|w$(7}@eA@NR{=w9Sx?Z__1v4wfe@dO2Y=1F$aB?^xbuKNnmUVcCb_KlEz1}l z{rp41c~#K#4FTsaRdQ=wKkXb72wg|piOCloyr0Kzqv2jeA^jYbE^h+s_s!(hWJ7E= z+=m-(IC6R((%_xWb}5@$iAA6)KFm(b`OnKCaSXtlVtu`t+1j`0$fP z$HYSdn;|Fd*@KSGS8<)#Jx*FxoAs)ALfexnQl2~$E$f&k^X;7C-2*IZU?3`V8o7gC zwAcbx&A$j)Z`r(eQy(vurlRi08o~Y9lj;2668egY&`lZFV1~>Jbls**Lmox3`TPaG ziBjX=NX~}Zh4COd?lbu&tBV_#1+w?RU*KT60wQOY!e;hwu?l4OvTo*mW!bu;_Rr`Q z*$rUO*+o2RS^ov&X>46DN9pllP^-KiV#I1l+Ik1nVm=(#v^&LXcd_qjRW};1T+Rnh zQ-QMv!LTeXoYb_NqPKA>?zDU)FkU!}uJySsRhnTSXkNPQnXI z8Bf@CF1Nb*1=V=s0(X1AkOXm6^uCscxsJ+I_K^bGGymI->{3qVQa;o@6T`8Vh2&+o z9LoM#hFLA1T${{foIj9)C6mL7=09OKECV^=;am=y#!CU~LAp zdx<*G3nJ8_<{l(3)oiDmsI~lMIA*UpDiH z=4e7H+kuV}tszq1EKxtt4==v5=gKYAptaQUwx+`J7k|kH(b# zN}PUu0zZoN+C6)9mvuO`6G4$K$}$$#fj82el-diLd)yi>-TX;hk0*d~h#D3S{X_-= zOmRKCdj^e&=UUP~vL29sJJ?G#ia2Kt)86&d$hZyB_+sV@{3ajI7be95FWv_CGwR8@ zE?t~DDG+DKEat4m{!rV+?hrqvp7e#uV76N*{z;dnn~s{I{}aYoKJ=I?qmq!>84WLT z-;w>Tig;o<>xYt^ATZf?lR6s=(Erc0Bix_C=3JJ&d09%@{fDAWKnThS&Tu}Z3ScI` z53Z$DlKx9(7`rnSXXz%BdiD%*L{UT76|;>0qC5=5vaf+pbuGC%N(VgiSHY*GUa}!^ z6kh3OKETeq}3qiBma_HsVX2N z41}DmD#TQ53ib|T`=Xv0PD}h7O)3c(^bEMJ*2Dd52bKNKi>P*=hnI(%Kq8}s46vPB zfU*x}&vE4XSbu>C`(3vG+De4qC!^Ak9CRD|kXstB2#M|C@V&Q%lbzmQ{YdKjL?dMh%{abZ~(*l!(x?%!|Ku%@Ty;FM^LTW719=hJx-?wBA=MD0@DI+BuaB?qE-w=E9_V%kk}Y zWqPV53N39bQS+-Rzkl=`Xc3Qx(GH)P-%JnhvRUZo{QyBo?@DO0E`@3R^+fx-DIWXG z_%^SXa`$UXXu#F=gPOcJY&eA8Uk5_F8saO)zB_Tjs9<)!`0wdRyg0H8J)E5Rz*8y^ zksJsrs^P>tT@sb618~~ObAlA9;dBR08{`s5r)PkT_EbDqBSt%|lu(<^In4vf+~lQ; zAY45fDlEH6-S1J@8y0{bTU`YsT~%P(tU%~&UP029O~J2h-_le)mm7KE6%9^zf!`DQ z$TcrDd{LB!^(U0+jj>8ByO52YeWjcQV+YAPisF3lJLI>hJbLY4ips(*+}EyfT%;!} z)SNw&*9r(G=*!PCr5XCA;fVwg3rwu@Tm+Rc3Tpk`t zCBduh?L`@+7&bl#s}Fw_(929}7plYDLJ@l0p1>jneOx_*lCy>ucnahGpJ(IL z{JN<~zTkv;y3=#gwiK@(BfJ{^ySB4znvc{ zrrL82uhgL5V+~lbJ&){4T`aEl$Fkq)m{qXQ{$y!<)dIA6%|A;UlSFk z#-qAuitS(1Gbp1!T-f#Y3h$vZ1@5uAS9j@iVw4qyXF4kIc)JyEW$6Q=GYg?d^bu!P;s6?Dm)p>ljV}mF`wkJJ@MS7=8x3;M<}eA z{*ho~6t0<4i79Szyt`!_Y&_HkdDB@}W}6=V*bs!jbe3>S(*DqOq3$3XR8J;r%V6WZ z5S%P8O@mcO<1y(RT-W%Rlm5zB4e$Qxt&^(~N}SF{%S96e2O@7#?Xti0|NdC(*HSnu zW-iuIX*%ZTP+W0881e0C?%-2JIP$;;Bq}ONxbztG*uiq*o0Ev9FdXG;)Pz5#F6H-b z8xD((Ujr@aI#Tgd2OiB@1+hiF#52|y?GE`Pr&vg?%u@raq##&po=3)MjzLrZ6jV51 zWb61Y9IyXS6Kb_Y^Uh1{A>6zgJ~O`4v7^fPish0Ls|kTgFY@4ibT^sl#hCe* zLa?$$oJ*TkN^8d&gUG_aq{2oO;voRa3{^MO>4)AEEd>qS{W1hc-iadpr>5d$rrTvv54p-$ zN^qq$9MTrHl0U8bjBmr9i!-DJw~j<%&AkTvfjocTVFxI@qrlw0#A+qu$>+zSwAvW% z$9Zuo*WokheSN@g!h*ky%W&@t8C{`|=}iCKTF-G0`35@L;}FmvZNxm%1B;B4aqH4; z0{d4{*k{#K6$a@86 zG-r1)ShK2l+mc9}lKB@O3AgbPQsco+=^||Rct=jKJ?ESIshE7OR*?UnH8mYyGPq~B z+jIl&<}SxIiOO{Lw^H+(*F&(tWUZk4tSWSP1On%|l8mjLiW!^OGmF(c zZi(Y-TIb;c=a=;nK};)bDPf+g<&DHQRvB>xd%l=i#trQ)hP(nPoJ@h(Sjgj5qb0bi zax-J~MBofL8R3ZGcKloE(Qw2!3npnak-mg^G%vEBep@3#i*>BfYOz1oePm1|8Ds3t z_QQ@f*SK?acJS`rc?dkvPI{+WU=Zsm(C)e{n4ueiuKF^mcC3%eHrx2qC%>%JlP z`xs~S1$%~ycjMNj-=}@zUJ&KmNe-C_>HW)UgLACj2MQWH*l+v@O3u8uz~w%%n4X@+ z>E`xOnOJ#UZX&@#)E9-2K%Wu(r(| z7QXKy?^yRiY>FSYJxC{3DwYVW`ylvh73Xw91~xqif~_p4-)A!fKOBk0XV;T#o#n#u z)TN<98{uWX=C?KcDXRy~d(X*B`)HguvK*^NTJh4~eL=SGF6f>3M1Jiaj!V~s;Ho`x z+@{!9^m@hA!8!J{@p;&CQVpBsJIKP|G5Dt~8zl-G?q;5-%n5>st$FmniT`wUO0f{e z<*DJ)A@@noZY8jh@`3p1N}|3;4)0fm;M%4j@*iU+PrIcm3~pb{cicCCO@7y4&Fnhj zyipb(ti6B*xuTrcb6p7TSP8lxdr8=96FeL1k7vUQ$zJU!^xn{c9l6H5tAjd>cL{=A z=RC4`Bg+MBPr+TqMz+g3!_lEsRoKuI#p_!-LffKh_*?aoBs8j^EYsN8*EeuG9)!Z> zsyq;y^^l$4S=Y(qAdG7k<2v%o=m=e7a4h&sRKwI@HS_X~j#4413O2aMCaw(n1>;{%0M+>^YT+|*BjRW40%AgYzX>hkib0$H*pi4SoHVf> zxi=iY{>e^uhNbZC*Lx!4V2S7wi{gLHxT1&RRNBsako#I8mID3X4e+5}AIY9E47=El zV*A+h+&ZZyS~~up-ZmaykKS97QDvr=;L^J&mVK|s`4jT_Sx@6&)`@=jpvt<*=3Aof zI@Spi9>UcedqZ{qbAs1hU&&Q87YF@r`*8EwiH%9ZXg~%#$bmiW4m2k#yy)-PUGy?!`$iJWXE?! zTw0Nd2FfyYu8SeKYpsJlmurag6f?YG%z9_y&lfkZ%!9ADRnhI>0j@n$4F={0!iQbq zWMQ>5M!pQdn|kL3TMP}Uy-wO-=Bp(7GF;KNMuQ*XG*?s=BiY_K^k53tk-7v{Mn-`z z>t`%IV}=W|g7KTl8o{2!YOr4=5YC@kNzN{}LC4KG`25T~uC$<(@6D&%Y{|<;fWJX=U81#Wx{)<}Z-Y%OmygN8(z`efTZoDA#pp7W&R(?Ac|fi#${# z&}TqOsQ8oPr+Jydy4_i@iS=A0Pg_6_PWz|BlV420^dJ8CpudvnoiN4)8T)aR+%@jo zT6>TzIS;z(pUBza5qMQWT6prp0p4@zV%QQ>2|8>C?zUnWerMWS+v&z#b$Lil>$ida zMRp%?jKP#K<#^m`F84F%K2^A`1|z<*{rm=fT&(KH@(8+AAYzHPozLQjyer(ut{!^m z(;BcasU}(C;V9(vh4*K#=g%M4fjwS%aGTVS*bOl#;LB0-RywyWSQBzSy2Ci%ZZhhL zK5EDN;YL?k|nRWho@v=Q&`a8OgmxE5S+2&EPj1{-qzSE9G|b%7lveJ z^6PLKtRVG}_4_$tJ&5RKRE`s4toXYh{ouymyRdas2QjWPz{Bi$d_Wo){DnQfxn z(F8q^-?LAw<0I#2^5VMSF_=sh5I-Z~9tShRL+Jl-cG9^AzK>G1u{+8BQN0Dhg|&Mo>< zLt~Ww>F|R~!}0HxY*d_E!o5`xgOQ`+;Z@UHvXt>$SI;iT9GMnQH<@)6g>4?x-l2zA z;@k`Dvvkm<_}cPF4&G`u+j~Q^3`O?4aGs1q!G<|H1qRHP2Gh6WDqc(?wP!SfXXj5~2&a3{7Dl%cQIt1)gjo7+E>ag)98z`dU$xM$;C zQa_imiJE=ccZ1D`f;lM3zMEY)PZy!4ENVyuqOV0Bcd=p&=&Z_u|8km0OwU64tD$dj z1{SlJgoa`Ps1x>ryqFP%TNP`uyjO?Mk9L43N6&+n)hD8EwG`f;uLMQO8Zx?RIR0ew zp6B}2+%v1kRD*7V7w3wm*Ruuip> z+!HyA_tMMplu-s}Vmbs0*RKIvlO8gD)i7)b4ZupjizHCe66dgtlG2PkOuo<tH6XUS zkt~yt#gEMaXzDIWI2q;Te%n4Uw86Syw(F4YDYnRu z!h^asjE5=U<;LxScbh1rUTGtm?Yby+@gPoKuE`w>kfOR~K7$_GEw|I4qTYb{WBQ1S zwITj_$XJ?1=Q(M{FkJmIY*242j5cFZL^9sKzFn|IG#X=%)nJX!EqT8=u3Ds)^2>zGsc_0?FkVm3|kA8`lT=~ppo1hX^FkYIXEK9ne)hdLC?Hh2U-c;Wb+@EAK9Lc zyV@n_=dVWaRP3MLw(8ACyX~$XZEeXg)jev=D`C_2UYJ`a4L3v zblysLn78LOsbU-s+$EGGl!*d2IWIeH$Qz>6&mf-kvuLF`=zaZDVJ zceMQR(_9(u&zu@+ylE`-XrBFVj=i%_ z2~YN?vz*sNGA<|FfuA%rkb{`g;Tfl9q5Qm=g?DvH< zlHi^4c;i?gjvpgMJvGK*63di*b$iO~ohA?FhS6Z`&`b^vXrL;~3c2i=C|ES5fUXYu zO}S1{DwHY)d0Tm;+Y8CUzl@u!y8?f2-OYu4Qh^eey@NBYnTrzsniz^pj)ss0BO>q` zrzHF#wSe~-GYaIlTmv)vdNQ0U;>My2=yOJl1G}MMb#etbP5462YK%d{0zc%&7yXZ< z^Ny?Wf5W(v_TD=!5mHDpI?p3BRFul9WX}+yp+z<=?PwY)6@`XA&wU>wvm+@{AsR|c zDMWssU*A8yUYzo(bD#UUuj_hWr0FUTCdQ<}dYZZJv5CY7Yi0ReGa}icn@iy`&4O)e zd_#QZtKgKKRLA+cnHjV=2I>}cch&z+A|p)k+Q1R~v{Hx}cv{5;1kxUwga3%Vr6f-J z;)lCj)-v~NduSi)F3A2~PYNCNQJ;2^&u!jC>MmtKvF%6rW8F#;olWu4r6cGUw3G>c zCj+ge?r^}rjYym*0&7X?DQPh$e;aJ@+gzIcv8-Ucw3MLSECLSkn~7=QSoHVK#z{G% zJTaJ!pKk=C*I;kCLs>L7guKOUH5)eF_#j9h;$SD!M(WNK!D3krJpDVDx7mR`oOr}yv%6=Se| zR2`nYe48aJF2k|$zoCx*gKmJOo%bk*TurShih2yA_(5-ak69=;T(Ac6>|5?=6Dv0d=g!^NhCt464;+!S17< z$&+wn+&U*6$31G`3BR@Bx^FxkxfP_`D+YeJ3wpW8bF=&6@bP?lE7+vSPE2xuQoVR^ zNbe%&iuG|%cOY8D2l0k2yx@`j3)o0|Z+BcYN4{b%&VIj&$({3tYxePi1E+h46Hf*& zn`B^siU_yvi6Q(A^n|heccdyx5>G2H#aUMa%5}4MfkpUZm^bi+d^$B1S($WPboMFF zA=QWrU6VGVf2rNQ3A$&j@m;qFN1RmfeLxNhmZVXxy9*?lMMGIpFEK8lJac9#%4JXG zRZisLd8%DLXrQ~wga+<9-)%(m8vR}t&lkm^#%EEk(J~MAjO&55+isFoN>cbyuoQ3f zdNG}Jf3Bz91U)Xpr3xz}@ovj#en#qCwm94j&dAAMIjT@M98h%$`V89VNn_xigsk zw$lZQ##cd!<2y3ttpR?ZjE)22Xpel^GtSfHzqz_bgJ!}uKEn-Ci z;zs?{!_sd@(5_aCdrJ8(Un|tHJHm|lr!&AQPj!cYd$r_nlo6iTl8UFkg_AWj^Q*H~ zo&WB(JNvv>2Ra<+?^(iol2a9r&o>G1v%(c-EviG)Eq6HF*GqPc)kpaZe{^ZNLe|UD z>^t>)EnB*ViQOy>_cjNP?5Kg0%yC2d4ZJbB$i^;&YI#T1`CAueu}V8w2>;dqi`8C{ zJV880*b7ireLDM4I~XqADxrD3PO_^@A3L4}py&w+#*S%yWtd*qM^np~6nWlh- z*E`6iYzxeweGT&MiOja#eoj^@WF&)dD~a;%&ShYt`!rH>DIWC)EAdoEJbNha61a#_ zuE(Q~#OaXZjiX(Gl<9H0M+$A%2jIk)W4O|E`t00BZ=3w5%z&*l zls83>%+;%#ia9>>hf6RN=B)b4pqw%eymuCp6CN~^lIV(e!+n?sjSA2qd|>2GtFuKG zS@U4jJQ+l+rqXT*H5q#=q@Bp(4FNIancG#^`#apF9Jx;TXNA3Wn5ezO^O}TTml(F-?hx_z* zJ7jKqPr52-&%%lucyH-$Vwjc*3r2kepqc1rUetF@?9l6`G4nxE4s1WUL#WAD5}|n) z>Wnqec(VmrPhYdgEf*EXMr0^3V;jV{y~zhg^soDyvmpB3SlTJ} zgXqjL!W}ecI$^~nrfy0r*UKCm@zY9c?!=~|NO?l zpS$r8Ilqa7s_4<4j;&Biv#Z-L7ePsz8qHImXB?ZXApK+($h`PWnl|d;w5CLyrCH6B zy2)^3E1q&*T0)$HM=2cebiq3ZM<69RA{BD3fUnuiL zE|{nFaU;YSynr6}kHmVSE^fG$fWoW|qwuPRvsM0YmUa#q!E=94SmF4dOgbQi;cxA5 z`d~mgJkEoTUU3{1;LGUi?SYA=k70{wGjW?go$^-Gv3ce*p0~v~F7#;Hh^OoH&3tI- zwZ^ym#&9vuRWa&h4jzk6W4!d;AXOq7W~hB9{`B>K(bsP&oyxn?oept}#PQAe4(iQj z5b0cPw6$l3o-}gX1Kmb+u9k1IXt6UEzyBD+Wl}c(z_x!dG*C=l1W2KBvmKs0=*5g# z&tghR8s^*%FFUv;62E;G=I5W9!yX!%0(n9=;ODMSB>Vj;&go`9*ZXc1cX@*~W>Egy z8mBkp?7nEs@vXtQ7iw(GnZkc9XTa85LUicxfm${ElJns10&9-tOS0@s?<=F~$YCsrX>-3DU;DfJc_A@lV;U zXGJ1)Az^0`h}FF(^LHdr52^qk9=XD7KdAvGP9Cu2<#$rN&j9VU19AJ`t7Q5UX;42B z2&#*#h}$D`tbTL@m2Hb`oT@J%=dQ-TW0=Y6O_&G5#*HAf`4wsMNWgD-0<1kXos~Ko z3@=+sAo*P!Wm4YPg7=6zb{IY^+MZ2Um|v}w!llhREFxSD2cLnLl9a}DRgNA)!Ls@z7RUB;vM@>nF@8aCXnNNm)S z<{NomVDE`Jz=Q5uu$WOpwi>D94ys2OrEXzfeK`&<-W9@wZ{LaR*vV+wcLd#ggqV(w zH=M*qW0+|@io0}14ckKeQEZ9=H$`(Ec2NfA2laSn&AeXj%3kVIa(hRVk~9!zq~f{7 z?xeIS3(RS*R&z!h`EqO@R=M3o+ECo93}l^+<{UFT$6g@90fys0@zRM8j{Khs>vrAv&3_*YI{=D&IC@OT%V zpgD0RiM>2kvl!gp{RTt33)l{qG#G#Q7rYtYOeE=!Gfn&`dj49?sOf*=_(DtI)7e4N zd07}$Zqwe1vpiG=3}C zjH)9Ul|`_sQI+--pJP@z%EOboU@*@vAg2$F#jf~7ysuWx6N+HDvd>ROytS!|?t{%S z7rgjTp3Ct_#NcC8`&g;OsxMdxKc2*a2+dMejyA#xNrAX?dN42Ts66P74uMdwbEKwd z8tNG3A{MzYV^ZF7DP0@jPel)jYm-Iqfi(PeY&3Ux*ch(P@Pt(<@5x_->F6X8iZ{=v zmp_TmhsP(x(aX-4$$04vA;XVAjQT)gr<>yIL7H8?S{u#&~`?nf`#Hzr0@Euv%L^}${Z};H5@e zEXoAl(mzjV+(2REzN$!PU}EPH{BlN{OE%NR!C2ZU|K=j&r}~>au0{K{{N9p7>Gboz zEddvGg^=W<5xA#Dh2O}nWy{`-1#8nHIICVywis)HfN}}`(D!?vx*@Ks^~2+OSBd6* z%CR^9j!W7nvni}Be2fklxdR+ptB>U;6R|cj!=^nu0&V(K`2BJjtjdS^FnFZ_run@h z`!$nr+ByMlP_$$N#Y5p-ehFB{b&+tIx7zVN0F`G;GM9WCxy8q8a$>_e5NxB*6Bk32XsLg__$f zV1MQl(Wm>EfvF!Zn7EQzFD?eh3*6x^Wfd+F{s!%CE3mh|k(?LXfJ#@q@c$wYfCz(Q(Ce#RJTR zK_w8+^noN}>RFvn`L6ZieBRPU?E2sdaDQeV3>h|(&r=lflU^p${sboKvL4*0?9NJ$ zKC-QevIwN=HFZvGIN={_qx)c+D2BsHDNWb8Td^**ttXa0A)H<~GFrw zaq0p}kJIP-1n*%jw64NlrH}BYs*U8j_@Ec{rHq+$fe~|3033FQc;|L3Gw^wRN2ydV!*!=0{crU$@4lR9H##2GtOc>Im)5c9W@KhZ1T$$MPg_l zW;NzsoXx7m`@uz94&pCd`skZ@5SC*Bw&#WPKC zO9SPYHC$q}JKMQMAH!hV!&b89#U9+Jm5LR8dwF`ZsTXBuHTG#1uzly#;r8BNAb+)) zICf~D*uFq?>s-x9ZENCUf)~Tk_CfOZmJWJl#p2A_O5Al`1UBlZ@WsAZupjwi5VR{E zWKT2^sqiG+enx+MJ6rD0rzayi*P_`3rrvTv30(!Q^<)y-To7PZsS;bZ#R(=HiG#^5)c<_T z6qgN#V%42vyf9mN5Iq(IqD#(_WZElnZ5qubO?G7*4Bl~Xj&6Xp#XaP?g$ZyLo^Zmn zp8U18MC*4U_~>4Gd0}A@?GKg080A1_>g#<_t@aq!w>1;Fi&oekosLU4Kj#%|jpuq| zQ%8Cew(|=?xnUL-ofG9$pK9QzYgB`GA2ZT(as3PjhL`_|GmCc}xhHgORzL;&So~-&%1P^8 z!237H^6xv(W0z9aQG`=J$h^8mq%ZoQ(#f0nyPVG$-L^$%-86K>@UrT}NR<9QivRS` zES9O93O$wCaGA14qHR$caZgn9}F-8tM!Wq1IBZDls9F5z~zQ)6cR9VZgWsusI z44t39k=;ESxc>;%!L=fI?FEq-Br3!gKOVqt!L?xB^$J?%y(dMRO|Vre7bCZNFh9Qv zIH$A!&F41iN5Y9LEtmOrgyg;_2lS&IZX55;g13h zW@uOoj&7uRE6+Z{lo?`i+Y#y=y+Y1ZMWO7T9(*h^nbk0qgEh+k&FXLs1FY{#K=;`h zHus)KpfD=)4J6aqg8GGU_C*6Ye1Ao(`jfD5s1ny$S+Yx>g@Wa#63Bc?bv+qljIZ)X zvn~l{p!Wl(VP^%0ZT}GCKl1Q-RuK5QI+EQp3^CEk;^-+wktXdTePEVpU@3|H~s9DldN~m9^4%wKo~NdB!~9zEUoF>Tk|g zmGU+(m&2zhF^sjnM^?8O;Uqw~3X zz6l)P)sh2;wb5{8DjH4kAYNB5pvYrA{`uNn>?XNukaq6_jHf&5co%alf9;1#hwYgw zZi-O*p7tEwqxqD38YpMrj}jhHWW9P6Ry&X4|2V9|M!pdT@8l3TAtfMdT*sjmz2yc+ z(~JXU^RCt$%g_5z!akFe!Zo_qSlWEIRXL{jP%flGRn_&pWo?71J}@Y*>Ze9N22b`u2*o5f<#8y9AYv;kZX-U7$= z)sewt6R=h>1n*unE}tZG2a<~@A8OzXvpioO)GUs|_wGD$wtYS)!hbSymrz*+U`TUk zOQIAwGcFlVW(#o8LYYne=?s5-<6v2PH#xOi9-fs3!jy|=NYINJIG%d#9)`Lyoh$08 ze|Q6|*i7~7Bje%l0#Dfds-8?3Jp&i|gy8m+^zsK2X;)RDB;`{DFpnSmfSAE!xUjE< z)J~$e+iU6Q*!rAzRc8XX&^&eIuDeS2F1=CB#+%M!oSrq!CR0vD)1GuDp>i$Q+ebmz z1Imv*=7qs@r(N;)JkPr*8h>?tq`bus>`NK|cz0bA4WIRp#7hg1jmyRANCzgUpR%ET zxs2q??)fU>M#WfsoEPyaSW%`#|{AEwU_^aw_DiC<1isqn zcR2{xDMT}S_5O0ZsgA~9Qb$^p#PRQ!VC*+tLvj@((DsrNfA_E(>+r__wk;}xs$2DB zMvOdOIK-e*fhMzjxi&0zb_dtMKGM407+=$wnY{2C8Rr~@-(3Zi)>KX?SDY4V%0<5xD$`5`Uh28oToOA{cMo2!Z>mh)H8I?x_;s5BV8vhAZ7= zUY9`j(Qb0}pCKN+e*|YXiZiWKKXNvPR^V;^hlH<@hs}wB@Jz>nydIo^tV1qpY9uq7 zV}`hC3Bj;+QahP;Ujd1FI{M$3O6qPVp7Hu2#-B< zVD?`Zhap=Jc)hWSxOvONukt`R?IlJWODG3eRf2!LK%Z@^l!Lm})YnaK6uVtyFmzf9 zMnoC&_Ab27l^Xu0tY%?uMkaxJJ28B^>K1a6&FHQyF}umP;q`^*dlg!#3VS#=7DiDLxv@^|XPFQ-)yTGK~z zo2Mc#j(XAQqxt)cg>Zj36)w_0c$d$_l%J`1=dH2LEy`Gn`ykG@Y(C3=z32?2r54)e z*OI>}+Nf}mdWqY&GG<{X;or7GP?*zCN}two%~3|+b$Ar#q^X4;chDXXIYn;ApM|(* zLoRkJBrtw|dO6=E8)0)^4KZ%h!K?16=$-CCC`k;Rw(IgG&3CdF7hi{QbS8hw`ASv@ z%yIISBN#1Y&$!)Ff@I3jxSi8M6834K>rcw9ofJ(pdd+b1o_O5aT)^CTAOXv_gn+J^ zfEdhEMa{%`jGEeKQy@z}$IEs3-Ox-nJ4 z%^aLw1nHK8BzKntUR4Ug2ebc@*OWJPuT+t*lr@EwGn0gWw(;;|6!mgo8q+WYX7_N2!VUU8HuH*-enh&Rk2xEQK7&B5im z;@p=j+W3*?M9yWWGuPeMgYcp#FkaV3Je@XS5oH&w-g$wyn`ZsIoIYU7^F}ss!c{o! zFNT{RbrA7!W@vLi4ijEjGGPn9aCf%3z!T^rKZ=#`l~^p!IxfmB^1Oh8zdC&TTpsJU ztQht*^+SVcAz8(b#;a)pTxZn5xC}YtF8V!)|BEQoJZOf7!tofBU(d|EZ3+3;vtj4u zCZh6j9VfY|kGuJ66sJM&&xtNG>774?{GvJQ>DTDXW{_frzq=uM<>bt6p3mx zhp`-wuzs&SpkY=O_<7Y6rLCsuCr2~OQ#_f;=c>7{Ry&~nOE;-WS&Y>^Vc36oG?RVf z1t%LU51wH{T=rW&9JE!!C@3Zy7we+I!XQl97|q0(j{=>U?(pjq?TEi8f#O$!(Rt?@ zqVYBYU)n12r=_^EhSTXysgL?OKGqZXCW8tovrr{lmC=2m1D_MuL&4oXa$3X$-z)j! z6Yp!JdMFAH{rHB<*omyS4b8UP^oL#LRm4y*5jAM`s*20D5vE?L+a8Mipud+{&p11f zqC4}aq$=_=?Gl!U2v9tI20ORy7|gp=0@b!XWd7uFD1Pqr-UQDW*_jv2 zRD@{@0^wJr16dhpjU{7qQFUK3qaWDMCEqwi|LrHTL0B1o4W^-@=rrQ$a|w+s1X!V- z#Fp;Jgr|>MAZp2Hl1RJe`6~{hZny&@vP=?MAG?G1qbBlDl;#EA1dPn*rOA=#S0~1o zd^nb!F-j4p%#8;9X# z!5251pJRqrtAWEFAGqgKO*ZOMMs!m!3f~VQ9akdJ=(-qxW!6I0{KI6Bkjw);8R{i2 zQN@smOx)@t!uZnt>Rht($o_n>XeuW8QXj&@ax%VQ5u7eb1;MGWB*kP3Uf&pp@0V!X zU}YpusTAX9%AI9RqFvy}=(qG1QA@5W>!Md2?Wte3jZrf@1tmkb;m-1YvR(N-H+Pv4 z>^nD#`+bnk@GJhP8K%e`)t`dy?r~V(dYlJo@Pfj5HRQ}LJv@Ij727R5NmTm< zJTO*=|MALpHh6nBWL*3Jr%l>P(_>}0YT^M~^uCel_SDzCh2BrbM~`?5O&7-Dx0Zb7 zBT9mnO$ant3&`x5s<>-b92V~CwK<_3fx|93{F$@wv0L9u;;`8aOdifHpBfm0&$Q|1 z>~?EbxFZO1z7Ys~(oW*W(!Sk?!8nFdW-=vZxT%#sBYU!#`ZX|#(8f>py~OhIL_E-y zgICKhGx>u(oXVLnSg^Q_-0oe3n@z*ecwiy#!qyl(JY0#ZZ{K8%k7Yp&`xESpTPTB6 z3k%Nq;mtR0%HWPi_eC<&ZLa#>W*bhGId(xra>6F~zXI zL8zY?%A0mp5h|Sm!J^{~*(g2>k1n9^kwb2b<&Q>g*Ma|L@}8|qIKMj;yF*5E$KIO4 zQWH<;YiuCK>!UGFtO1XWwqy66^aTg`#}H5ZQ*7*~p!9LtpOQg%PxB{o@b&V@OcsnQ zgXufwVy>D5Co)wR_tLD2j7SD^#@8L*^+dwUeSL(dwgnH)O~dc6F7W2iY~Y>J2FxsO zV7JL$qs%}toJl=P4qq2z;gwv>KjO$Z+ck5~F02}1;f_{SL6-Vr^IwQ^4b*pPou|$J zxXFe+zqS}cE&8B$^KG)WA_fh^sZNyG!Ti4Lg5C+V>ttzU+1WHRtmux#>Cx|*3Vkbh z9hnUhw3GVjV|T83R^P}?qmbSz%jK*v@O?6Q{gC|z_%9~9usNlak3wg1&#VS||Di1LB`hi*)@B;=bise#dXS|2itAKA zav1NArcKufUoILK@;Y$kMpO12eQq5*?+^1RCvft@$vA0$DlS#KVe?%%64gx=_=UZf z*z2_K)ah9RT<@tOd#b5FG(v#G6RlYFl;bdVb_twY-$NRUP4Uv@qnP0>&1`Z1%r#Y5 z!rWIwWX?Jzu%8wPU%MPgh{kLjm_&Dg$H~mM;a+aM*narBt$`%GRl;n0xF)R-+ zCVj8QW01W+&iZnJIsRK6t{5GFZ0fVs@l(YYBJ{b{Ae2~DP~Gi{DBtq*0yg6K6v&>C z2f_&-$Tg~o{Dn+>_DY2Dx?=!wy-u*=Y#*^2V~MG?{VHtZ?3E}#a@iR++}aHsD{A3Gb1nIGObtbRUm}=r8T0yk*@E$ z*mNTh=O5`)PK2nhLA{Z*#D#^sVs>p7OMTe6;Hj@`dppTL^KT3*b zd#Ns;o@I#>zvq_E&$x(3%>=04W6e5t1;ge}0(~wW#E?E4S{5C_#WM0tp1lk=+j0Mh z#^<1X9g-(%;}G?qr!Sj~ExkFYC6UUUANbDkc80-8%Ex|_qkvwNQJ%0&p67M=BGyp9 zVxUGI`^WSOJXt#k=j)nDdx92@b3TkuJYAXXR;}D+n}s9XhTUI0aGLiAylf%L9$GF9 zk&oj>_T-7Qo9x^6&2UEi9r0&YW7zF9toZC$?!V;@M4nYZ^-rgm3Tb69`WOh~D)LFr zC<&~kH}fj1Jf45dV(!qy|MujAGarM;F;~=0P~>LKOGQsYXR@~n`=-VX+-qXN>2?pv zRkuKEK^RI1!g*G&l;9uL*8hKJj*gs-LA+f2QRBvV`+nrU3VDv`dV%dqC?=9h`*4N1 z-MmRKW4$M=%xNUL+oS1?>peabUBdDY9f5gtCKuPYlBeTsuv#($zo)+BIlr95Jxl&? zCf{+q4{@Dy@aS)GF88(`ic-$T7^e*8;0F)*^CA-T8v97d_-(lMXc~^)7QqYt8;vo` z>T%c0dUl(}H5hLwisC-)L^a6{@lGx}{&HlUF!}bVEKl`{5$4qqFqbnd6U6psgVL1Ga#2Hd10(aQmJ2()ePmDeNRz|U zs`R#_Udr2brjoPtkcS6vggEM9bo%JJ#rbP?gDisS8ZcI#~3m zj~wh8Pd(25_+rL&5#CWgxh!qL|}=z zJiq2g3j0@VImFRDxl{Tz(eO^i*T1Mo{i+qKH7*=P(o0~JL@yBsbNqWg46jXBU@E!K zoaKE>Somd#3^yvlrO3dM+w!~z;%IXv0L5!IG5rQToOPBr>~o^**#RXCr+pL47g-Q> zUMemt6`=dSB=(r%6?iPw3R~uUp;<6vtV=zJv)vt;**#M5%h>}KbbTfY*-B79BM@eH zh>_*=*%^KW;IK$6BbKfNrOwgt9@L2iMKFy|mr0`HEF z!V>pm0qtSQeJCv=`VW)-LQO;f}w9_8Xog3_E z?@tc81x&Tk9JPk>W@{m5?pxyUYb-XVQ@vYlJM(_-8OYNw1pOyJi1o)7G2~*+D)vs6z8^cX%n%NsM6Ki5fq@+1oJ-dh+ zjd_gNZfWSJTEPEr7jrgErq5zG@UD*puiZ5Q#b0Rh*Hjm=VWN~(Wo(IW+H%X~3t~~6 z`o@oJoW*`Br+FGa0n_Xbl3TDA8^_$l71Ne5zK3MF3;XtuaLkmM z@QGt0ib-5xSnTIM*@VHRfHv~^mK3TMPsi>G30~sGSX7s!uOFYs^3<<_=->eC`qxa> zP0_~cJ-!$#?aDmd(#B2W7K~&rv_S$791g%>iC^TF#YVJi_=vL>iLnZcWnlBMIQa0R ziD+$8LEXhH-kY$RN$oHO^jx(1sScrO% z36Wo$$+p)LI7BlkZ>Hw)8phgjtZW4*(>#iM)mj064!WYj6GiU&#xxA7ptq5?D(p3l zHL&AaEO`B;`86{OOzIA${SM*0GjAnuO9tiHZq#M8Yd&!cj(b4yb;|B|EQ@RO5^%1> z5LtO}G920L32PR9AW!nF(RY6Ehz@vjPc-gpt;1@C#cZCQKYdR;f?bo_$dem|aIaJY zb1ZFnR!b&xcb;A1jBbzOe3lcib)AdPLL|5>J$)RaT|F;Vs6R{MS**^}p=kw)QHmS~@pOco8tVo{<1VVWvi*18gk-%}Re zm@e}4>2j&?``*0nn zG>d-4(KP>iULG@OcBrtogl8T8irXtC4=M7(T!D%hhTL38d+Yv?wGra@&ejzfb3aDb zaWu3$(2UZO_ry&x66ZXY<@-c9v6b5lBJB?k{9ltl)L)UTnw zWceLqQdoBpNBDcA0e%I(CU#TOam7smD$Je925mh7wvr_fvz+D=S6blU@=$c!BG1T0 zHgmt9P6w6aL*!Di1UkL*!|vXVOz)IlZr#M)F#1j%nL2^?+fwi7moy8a{U;5X)dIY} zKbej1x(Y>EEznx`g?yZBfq~;fF|uSmQ=cOPPVycw=hPRnIXV*e92eoI7wNEH(^Mc# zDH?S2o5}D_C9LmH#w9W1c&pBFT#x-Am$X!v3r;S9Ii3HYRVAOYUZt>=TZR_rcQS&P zn&7kE2UM=SAy1AJ!4Gqqi8a(B<6lJLyATonkd7_ep*a<<<4v%8_kpBPJubK*6OEk5 zFyxjITsr9l((C$ZX2%NiL<5j)1hT$98hcyb;%QSI)>}aPTc@Rh!xHKpqOUJ(L30qA zm*?uzZi0jRMEH}}o?=yBuZ4NHYQg0ETXOuc0WQzZ!Oqa_jLhP*ux(Ny>@OQP#*6xEqe_#+7_Mbf?cghLe>z>w+Qx59&n-7H8xsOGof$1KoFP$w0Uv zJ~@zz4)z@!{duOpuG&lAe2&7tlBY1K>9@oD~wa+C?v%MVmv3K9dOxAgR4J5W{ zpyb0&;zsYBbBYo$sQ5fH*MESs`4tL#z1m1PeLu>FO-H+b61;$Gad_r$B@X|~W3v`r zgE8+1K$PlSb$@8T=hH)YYS4w*f4-f&^KSvDE*c~kuS?^hoFM$3`-gN!ZN%DTA8=8$ zD7*QHEDUasgT<3S6VbQIc!%Z|vOHWFwrw1^wr+xm%kRjzfc4bdoQ_)6E6Wv@6u_<3 zQn)Gl7_+-?9`r_JLXl<*G5u(WKf7Yk^6yKY9a+jj$761xgb=qi>M1xccEv-jikvvr z-)z4Mu+o+K2h7)k^YU026ze7Snp3eWjeefa4Cg7t?T4q2pF?l-XUe;?!NC=|$d#>T zx@UgoPWRKUSeik8I7SXl{>7nQ!Y}fin1TB~Png;HfmEi>LZiMQT*^-`KO7Q`$s68c ziqRrAVgl86{yqYH)J6`|Y{iDD8rao2kC(D{3Ky{NGFNq2h|65_0Ip;+m@rYA`{ps^z#CPeUY%^Oh1`BY8T$BPD9sSk-SX0Khp&cKgYjg76zzbX{@2F`Mj(IqMs#^}QJ2q|w zXS*ucq0vY_o-jvqE2_)%Y+xFvzvuq_*ak8BJ*3S|5$)*y9I&H|7vECFC3VTcAv#aA zgT?WN?IN11{7X=qGL{ooW7VNR=Dni`%%DB3iL^7cL0c9d9ty^bWG(q*L_K?#W%#3K ztz_rOOa$e7g>X^0k%+&QL**(f)c>c#{9yGdb7mdf-_lRM3rk_fJ3D-`_7vGXKN_da zZ^5EQ6E-hK1xyV5q4)1=a@%(tc2ZtM*zz%3+iN61a?V=nOlE zdL0iF7UiNFrZ6UyS8OP~6WWZa=VZS+j_pXrexYe(`V{*5UIH{}O=f55T!%T)Eihqy zGa2P5h2xBtVvWyaW`BV!Z11Jr6CGb@*Zdut-_*cuQ?tnF)<`^7GMax>L5F?zLKVvT zqu}xCW-{}&GK!0);Hz)rc%xnbS3Gubgb|TzTn1K3qwrdOKG{LJ*3x22@$J|h%-eh| z@c+0UCf<5Oa*o~s)i>(6TwROA{f)%-*wOsQhVxj(!fCMd)lCSeo!1g^+BmTz6C>ls zFv5+-ARg)jw*UHxjmb@>C*nqeb~DJR`u18 z)jdYIiq7z7g&RnPa|HeqQs*BG+Q{CVln1LkKfu|2-^en$ui5zuP}%GzGcc?UH;{Tb z+dD~+ssYY;AAn2jFOq~Kcc4a~j)mi=GvV^GFf1Jm(;6y?wWm2I#@s-Mb_pKDM_}v{ zb^Z+B+w7y6a+sVp125ayj}KJ^m~k?nb$omcJn#R27vGyn+7&$F6|{5)1~nIO*_0n9C>#N55S48=U_DR z3sK#~V9xejoV;)i^X1JK&XDFz|DVw-pbR~kiE(&8>nG`FS=i})2&_+2MqC)x{hWev zacV~S@|b8W{7{3TvlgG1+}JS-K2-maRA?4u4&^O!U2XzC*;a)hvJX#gHJ|3cckF5sP5HGb1Z zYj)v24jecCfY5+@_rn9cp4iWHwV=JUI(A|pGi@O9tKZL zqFI!$yt`4Gx!8(c?wN@Y7ilYto!cxiS1W}GFHgYZMFQL;rN-`mz6!o&CPCS2%1K*b zh@JFCtt=AFduJDgc49xUc(M;`dRPv|uLyzM+LOe>U@E%U<)Y_4FXm-aJ-0cXGM&tO z$Y#DG-Zq|%)2@~AnEom*JwXnGook!+oN#f!qZum$)fN2vR16dU` z)8}4Kw%?J#Q@%kMnYD&oxEF!*pGfo1=&WEJ^CrS?K_O_(qwL3aMQn1NjXM9-nZ-W( zQ1@c($Q~~CWHO!>3&fuXZjfH;k`E9aZ-5yh)#Q(4CWe^3!bk^eR_De^$dNCBm0I7)e0wQud~Ju` zdq45MDAMPnInzOM{}5?3ybeFJWH4$9_1Ruvuse8mc1-Ny9%XC?Q#xnH)7}Js zdMCejekv)b$iSaCrNt+#IqXsKz-;8%*Gx0T3!D5{hG*vd?eb|j$s>#5}jrv8+eVDLh6u$B< zAgSY|QIB@w{C}QT1Z%_mMf*o~@_D*Zn3*cf_f==vS>L8ZN$`I&+{j25rR1~Fw`&YD z!+jjoq^^WHSNe(2x>>lX(I3riku0X1gzC?4Ft9|6ol$)~;Ju{sA^NelOX*^_z3bKJn zQxxRNLLEGx6N)c96B+YPS=e+o2rj*&Ze=G?(KEzJ;Q{#Uha$6inEJVU_Kxh~qV?Cn z>W3hElhCvIP;pfpm&S)Os!0prmRTlL zhPMzm2@@Rcd=a0x3V4Y-?Kyw-$0NRIq3o9sTjYw`dGz^6mj1pB3edw+jXh*S`xEqH z!EvaU{9NLQGecrg$1914%ML+X#&ekK@r9%fvbcpZ&E)deFuR;vIIZ#j?cR68P?A4D%3gU>uR=N=np9anlQNfbH@v~4P7By=-ofzb^&_~NN_!G* zG|=VBQM{X%&TBBY;Ci=S8qpJ()CZt>WiB2&EXiq|H%2A8dsptvWW204!z7JJ@U;Iy zeXU{`c+Co5HW~9yPm4j{Nj3PO;4QmT`#OAY7RJXfT8QpC4V+SY6a!9cGIKU`axZ2$ zgVgAL@-A5z%liHCmE9MTAsvBPYgG9Ur_5x_3jp?8|9}XWyF~o}%|y_9{=%9rX4{1M zXj~JAO4cD|K{io1QKSzYqo=a4L7sLphXA`Kmsr%(8@oC6qF1-^!jEj_)RTI-(+h<- zp-r-wwqQE0IY*D5-if%QSb%l=Xr4vh6-u`xftOe}+3jhB>Apwtjb${?%rgoN=k%dp z>poV^K^|g+L*R79NwRY>?cSx?BI0SstiII9<*(ZY+73OWGhYD<;;b;Ky_gq!qMD2B zksZ02j6PBhiwDK=h;<$@p#JpL#051M_|twXQJAoq>WrkG$XZ>%D0d0I-IZnRp&yfB z((yt_3uz=LPb;9mixtN2R%O~=8$e0#8d!C(pY&BvL9Ghftvq~#G;WH<SJ2X*NcGF5m@eNxsq1cy{TjRZtt)0P>#IWb5-R?0+o4 zaO$m^HGB%P{EI<~=7rxzOhIG&09;ln&D0OKap*V={?BJC63V6w4QV_k^p*CQ*wT)b zTztCo5@VU&%LOHFg`M0R60%bh`!!PWdcjnpo1BGX4hyiSI)#03=mwnF*aBMXDMReA z8ScpN!vRUE6aA8hmvSC(Q>lgcrK+Kkryn*Ji*Xy}qtLQMh;P3{i>*7M0lxH>vfI6d z%-X7kt6P)t?-~={q2qk6>cNkZJzUcAIVe${Mas|nL|8TkuXt2rl-d9zv04YjOZSb; z?JmnGT$Lrn=Z#_5YPT6+?{yPi#C#;7oE|=%mxXIqh%$A{OyJbgm9V>~pR6&Y{2b~_ zw9o@GhVCJ1q1C9Wp~Yq|aD;%N%TPs`qM~}XIQ1=^rCQ@{_PWyDn=iz#U3Y@jDA)i( zHMMZBv5qv3GC@;5?X?u_U=H6pPdg-U!}Yy`D=ez;fP(SB% zDI@d~q4)M&We({Mwc>aHdYgDLyn?^niat-+x3ZR$QWl!flLYM1T1_I4Mc}$%6~26s zC#$r(0KSj;0Fs`aB&0?b9kX~C*FTn7bW{t>X*TnZdpBW24N+yPKYkvLA%!$k9OD&= z*ViR7Zgp}Hpcyo>dpj)GN11tv*!bzE&CvY_#8MUh80i9bm5@B{8*Pb`Z{?LctxTes zZvk!&n!~P0KMof81a8%K67^eN=x%TmuNp387WOM}s%d*i`0%13^3bUt4A!`au=19u zJU$n1Tuo#8CjH@}y#Jfw_k5Kwb-gw2_$13)J0%Hc%@APdxdQfM_H{7y?1LvYU&tNG zwCug;i|=$+GphYvoWk$5YTRr#2k@8 z)@LRj-L|WIVF~pix4y=U-t*Z^rQeJLuZZ%pI z*0P;juEBz}LTHirg-m+h#o3fQjrgV8m+0ULn&Vz~TAVAJ7=gY$&dpI?vC!c~KX6|6&S0xJ~3{8vZOvpJF}x;`F4vz%b=!3MH=1?|po6yg8%S;oe!H3Gw3w?O7z zBhimlLY>_#3aO|wZ*sN4Hhd!}T<#}_tW5F1=3v~t|2kpzMdNsv7M!wY3ab#W0OxFd z;8{Fng9t6aF@o1H{rG+Bw%L(5PEm~iP<$$`bI4*N;CubVQqgk{Uc5U6n zOsebU#2a?P&V4oHU)5EtiK;-W^(pMrTi0OS;WjX&-MI2AjB&c3FN!U4U?L2pA)fAj zRnOaq5bc>d`Ilx-o{#4q>(FdYxd4Bmw-U>hDuFzm&u)*~$U;s5KMh^Nup7F(b(i^^ zrd9uFhGlv5OL#UQg6~{Q$WPic0za$JMSOtauT=xPWBVcaV+|3d8b-7w_1qp0B;)2r zp>(bQpa0#OO?hMvek%)LcT+R@pr(nZY%;Oz+&Cs;wH|!XS__)H2B=qGlyWr9@v~_- zQC5jT>wzj1T&Kh)XRd*D&8cv*?He(?vJgW*rQth&J?ld|qtLcOfNzy{l3ldf1)dka z1y=DrX*onWTIJVpmbDwxSb@JT&0}@EPQncz0`XcuNXm{K zC_23WAEhp10;WiFUbrs4me0C`zt!n&`r8fm^5PsgqS6Cr=Y1mcKWJiOy*F}w4$SkZ!M$#!~l++cNv|@;|5L9 zG%gsc%JfTw&Mbj$nGBd|*G_(KT*FOEdNQhYRBWk&i_h&**;1A}yEO}E)BV|QyaJn` zvJJ{cVqxA$FWI291H%ubrv4%n^r4)JlugVv!wxQ*?%e;M z!|~CyOJUQ0`}6qJh0t{DFg%GLBHu9@&AqG8B5VO`A0Gni44=X$%I~!lR>pY+T%%Lj{RGEwJtLGPIh@V;<>jB`7P!qd}n zsYNs|)iwsD&E8<@om#doJR2UJ6~O0NpUBE%O4$9BW{Nu%8OPb(T%5yybNH+Gc(e^3 zDC~>vLRXq0+FCdX+L8j`;pIHy;klQSrF|Ix&lOgROv3!C*%%>|OcvuMtZAyiaqAS= zl`)Rc*Ov%F$GXU(ay^W>AA}VbV|fBTQTX6S7an%*l;dlENR&E7UfeUoiT3%J zcHf2B{HcYzbY~YF^XMjz;-zuDusJ#iKHxngHQf7M5>O{B#6=$?@L;nD%@GumgM69? zDLsZm;Ze+!nIhoW=mhfB4Mc;4WA)zg{HJr4vd0IEU~1qkNEm7)WA{kmj6T*~2OhU{KfqkwP`(Yi1U{T2V>!SC;HphjXwq?><-@=p$U@EWBkOfZsPu zFpir#xHb1?LB+qHq|-YGzGjJ`MIN1*YsTX?bx%~)+sMSy&dLXkJ3;zf4RJZ3f+n=X z!oznqQ8}1}+a)UT;j0xXrEWpI&aZJ%IX;=x)@XWQH%%y$x ztygIt+*E`!)S7`h<_UPY@-E}7p$r@Kqha!&HgYCqGA{N>K)ta#yh!6xF59zzbWfHn zc?Ic@M6e^igdC>twQZ*=(QlxSu{xj*&JO!w#)4Y1GFk~8M|^0WIfyiFjKbU_|M1s0 zEB1ne1$=WXfDDHgqChk0Q6ZU_Gc=BonV=8q=cylv&f$OvD=g!Du&5OYF^WO0kV>4I zp~#BU+jL%XD!i5WPOLX9MyofM@oSB~wXA;>ZoByp?|eMLF7R>%g*R_u5$y<=B4B_Q z-(ADqcifn^=@%gAZV@5jm}R+8UB;hEv(D4o6z*W5iA3K zkd~Fw_~HzUnOn7)o`0(FbsP2Oee5QYFZ6I+U?3i~xJc}SRZ;6XsTgt6f2WS_$iws}seE}WNh%JK9-YK>>m45 zAnHhMl;J;!{Zk#x+ItMIYDzN;Eo8VPQ7>-nS0Qfivq>=hz901CBC=SS-U5v1?PEbY zv;Cj|oKFma1lkd)e{?e4aV*gKq9m`jx#OYOK!DB<3Ytr%;V2zbDTrL>-`h3n)i)FXzE~`^$Ap7o5%aM z)`UB}EqPR~~s$Q$5(>W2*4mdQ*~rTz%t3*fhSkStAi!}ITwaLb1< z-cIKj3@)vtd6pX1#U&T?`vq|L%V+8VR>sq2e)#5#BD3{;5BH#A?P!;1>qimPdrX;N zmuP-%%>_JAEX{wEWx_7Ztp{1^4~sE=MdH6F&+eSa(Yswjr% z61{NwlFdxB)gX7*a3}1!SVJ~us^M{KI@@735wOX@vFR1)xiFPYQ7Q!9(l+2pd?682 zj^d+j1-Ri>93!wp7U=W_-`aL!5JS0A<9*ShM}*s{O?m#*ui#sMhj}fp3YVWn!ES?g zvesP=&6?tI%_}Y5>C93titQWqlZ5WBf`58qs4*GHr42C{VpxHXe)lptwi*yxwr_N{ zKRy_Rw_^TaSL-}B^Q9#mU<$zcN(-6osDp!7GBIN1c*aQ40A4z-f$D|$mYyXz=C_W=}i8hVR$~ zTkGD!Sm_U>#CIAtR$oII1$XA~>_}j57s1=;VbT#d85IvM#INFScwUcNIo47Wa#{qq zGrD^CBGC`Oipp_1gUT4r`eNFF?M%;BLC6-~3Sl?ik~81hiyEQm-w&c=FbS8ev%=ff8qD1}>Tv3yGfWNdA*&|oVfzt3Y<(O@a^|U_ z!1n-L_932$+93m3rh%YhSVzu1vU)a>I#>K2Uh>#i6}p{c7c=5PH)M7$!=i)NbKS4?5Y3dzBD zqj(rnZzcOxC!_aCbKGFEmT66!4%cpNhqAU0WNE@qOnyx}NhR${GU9H-*&QONekzn% z@39Or>aTztW$f#A%)n63c+Bap=0&To=iW7zj_%|l4fSv~!3q036uG1Cb1->ACFQOw zu-YRokbEN+-j?@~bGEy&^KUw)bmZ`!1X1tDta2!R)k?-QO0@6q1fF}O&z#lmD?HP?x6Vi$R9+qTBuFvw!Cwr~T4T zU`*^cl5VPo1-Opq~XYYkj z^$Vc8Wsod9<%TI)iFi~ejCa&A22aeaz#})R*}`&q8qZ-)d#F6ZgfRCl#5h z*FD@{2fF`U>LrcNFW~ZRtN-)PNR-tUto_-D$$_G*x>zde)Kj0{!5+#GpqZnVK-A(k z6^CAmLYJA}@$q;gc58|>_%zb)lFB@yFX+h`G#4wb zGZfjqyEenZ>_q6A)lCjf(8v5`a&!&A?SLf`q{v7q0bbv_^swo(2N=6i~`by%Q3 z?fXkB*ul&fY~`lD+BvFSUlEeWoPV_Q%<~b?wWf{}zB6&uPjXz258vjApv}KRl4Yll z9`v4Wxj&ZK0b=lIw-a2w(nxyGO~yGdg0TIY6B)P=K^ZDz`Nkg?vn_XL!zra(a5u1t z9Q>q!$#dso=>}zHZ|@X1QtdFRjcnd%f>AGh@wPxdnRK1Lv#!_U4LNPrB10KEw;qG! znKfigrx8XSjK?~=4C@7bkvP+FJbz7692>8^h4Q%@!25L#S${hh4S!YOpwc|HA|njO z3*CnTN9rxKj>UuYw=wxK?c<*PgOh2WIeK%9TABl{l&3MhQ^Z)OJxsvUWezK+u#8CLht*rn8Q@yclTS& zJHN>gZR!jQ?Y@vBxzx)+ITeK(qTHp`M%er^4*&MtW_BB@LCl3HkY(G+mjF5JNr}U% z5=~x0z!NU|LhtAdpJnp~PCpREEq^((WNR$8%2WM3ppUs9rwO7R`(SZ%EqQq^3R`dg z!s8$3vW9c#!FY9gfBf7+${tTa;gn4LcVaxl&ouzKh}GbmK0xLMh+}r6DF&&8lU~~S z;!5vg8rv1w_c!dIczG%)T>nnusdpgW@fw!onp$s4i^AFOeqr&>r`<5eIEqMdtAF+2p0D_L(Zf+GS7#y@+jZ?qxlY^-$ifMFDLQYZyVVcI(NV$ zwh^9(cagSa+C}2cV2YhKle}94+`XNlaau2Fpp58^%LCBM{34m`seyeKLHI>6f#L0u zg`uwja9~pDSn8E_rxkUnMq2tROAFQfWte1zyXv zW+nSiLrhr-#EW;4K#uPG7k%-syexAeLzY{5$zxPA8I+I#!+1Y7#|Xd4-n@_t5tlmQcTx-ad}s>V z7IBxitO!OuCV%iEM%JXlXJxbiq$D)f}1(pdfU`?$~z@yA3pe6U6kX0IZOEZY}#AovCkDGBD$feOe++#ux z?AWS;LkHW)5?w=l{+H@)V?r`%xX*9a)TIY^q1N~83!H8zqNypK#Q>VAKXr+cf} zJx$r5_T(3o2RDTkrSA+Po9-{i?1?Z;ELwTQTULAPtr5ig$GkyBBt3^HZ6!}~wf&p6om}{!b zT})1hk8U$d^W|WUJrOYyLVi6{zMRT5#p9L@?n-IeV6ULPOL+8@eI9Z zaS_qXxzpm{H^CXq4mOe7#u51WkTAdWiw%3&+5}d~(rja56Omdx8S~uCu>P1lGk@t+ zD0<}p@5}p1!vPaqw#^sMyuC*HW>FUU;SYFnnHDSAt_=F-|IO{_^d(rdl5*W;A6iTA zjl}5Car~wHSoV0&7D#^70IR3fl8ZWdIHX;PGTY~|4^+cp%F_E#OZ`6uHLn)bD`ap=oZzr;I5_L7c0%%7JE zgKC|m%-Io@j?kVg12b!fo79&w=_d-@3uVJ+xIrSlKYnWbK=K4taaU9lwp-aTzP8ce z`J@OK$)7~8Qv&x&Ti}d_r@Z0*c20S}#^~-nB~KL3lr6)9Gy6zcqcZl}(JV=WGvjYN z2Ev~^Qzl*=c}n$-8|jk#=;My;X`{O^(~)v$2fE0BvkZ={vBrcgT1?zUO*&7U;oI9@ z@+eOqtEnga$hA1KPnLTBE(W1XeFDQjH<_}9Xy+imlE@{9Vqt_IreAt#{eRz1QKuyT zcv>FYA}>un3o~)Y@q&^JgUeWXy#l4@@>r99XW(^P3H8Bu5vI_XGVnuCc9{|*drpoM z{^-fI<&NR>)n(zOpC81b4e8k|ic2;9F!!tn)0y7QiSF|Ri5<0cAEx`Zn>qSyl;nAh zq@m(|nw^xs#is4N24w+1z~j$H@?A<7=dC(|=8l_~kF9;&_7E1#pAL|;6j6LnGcN(& ziHu`_0_73LgYlDA(%`FrmXj@T>U2A%#bgG!(@xC)&*uhx>iLPf0znC1NXP39T)obJ z`}4^U4G>Yi36n(?xci%^&%&eyv$%$Ba{Jft$dg+D>l&;|7dODLY1VNr) zIhaMY5wSi6e6%S9jWpo5PzzvVpm(gh$qVCIXjc zVECAP%wB$#;oomMZNXm6WjlogV%hCC74L1#m`>+6GR*rKdlc#-@Yeq#&y z!>FR*>0|heQDnkD_HnQ4SHb4G9um7-9KAjUQeR64DK;wywrL2axfhePnKXl$V2vvR zwlGps%khF}JU(9$Qd~fy@M8TJT)fF8zD zmaD`tIVJXRs51yBCPIyE54r4ThzE8B;rWC(URP-po@o1mt7G@FOD9|5uTwM&lk3VX zTK$EqGu}CRE8PEhGRF6s;JLLAc;1Qcx#x`&;QMSLPEqFxsPCk6Rr&_$+@X&$r;efA z-)N>|%tY8vyD6osn~3qZThQjJh%rmXl2#`%l&2XwC#HnCa@GtkQUC4rfhLmin!fjE z%)_?=s*K(ZU6?q*0Zhja5Je4hG#2s0*<%Vw7rjAjjiH|QQ<`kFlPZjJItquZYRFyL z+pzzbBL1AIYkgv+7<%oX+GEcI_FU&y@IKi9%VKLuKD|FoFRs89-SgPyf(US#a35l> z50LR8@z}br0wd+!nO)W0+&%06W^Af!F8J*khdbL_h^M?VO1g$()x?90N5(IX7wQTs zbZ#$g(!#P0X*l+U3E5453;wU^tcEo9%7-FYwXh9Lo4*pxfOzb)ry0o|w;B8A@-WST za-q+CrQUCKG}!Emi9%xBT>{Egr^rXE|1RodnE*UIsk=^hm!7edgB-xLZuoDwpD@$ z9%*aLBJ1HM5!LK%QU^Albf#`uo@PKY|V7v^j z6ShK*)nq(QYJnxq$SjoVBVqLhxQ6OT_xtF){i=>NFX%gKD2_?`BnMr3f$+h#id0ADr^iow0w^&3*KBhX?eAqDc3~Q)cFP zH&K#zWJ)@oI!OPWk+;}mRDS~^+7IZFca_OG>k0lP5wQE^5D}zzx6*_2P+*fGPnh;6_f4k! z7K2*$;hP+=4jBQP&?fRQTMJVpgHZIUDic&T!1+|Jf{3NP_9-F=FW}Fh?RDtuKcZmp~NCPHxAfjnmm< z%a_2WO*x>E)<$Fl4{}px{x`QJ<|v^+g9R$ZWsuBU=@?JnBMT#y*za_Xt=pdnFRu2G z_BDn$a3uh57sT>*cSNCzT|3qv-^0c`9|c>%Dw-c|AtcKh&(RqkuC$Y>5b5AjZDMxF_1i?FyB%+8elDgJL zKWKhXLYN;{8qI3I*bcY%H^7)rwZwxm=9k}kg&i4lS-;o|)CX}7#%TrzHYZs|qbzn}suPYf`5w{_spjD1i}yWSq&*T723^PJEYOxR6#Kw?M% zn@e1ownGdQJjjPF*&m6Ik~-S=B_eeEWRgwSa7>m1Yu6UNEdzg zH7>HmH1;_!ap)^|@7RBHn`bPF#uJyIO;Z>7)TWNk?~dWDDK5+%?XeKF*%_K&)e(!4 z2{;fEfZ_sXRzF5UWO*Jg-UOOYPA#oyq z^5GozUaK2s(NtI$ylJWo(My@cb6MHyU+zXFt-jJTDs`y)i?kd$Xyn;Pf z@CNk`Ej75!20h9Lk$2xgE9xWR=8NMq>19|vOtU;WgWT6!4CK}g5H;&NkU~3MN)!{x zxSNp}abgVL<%lLL_E`xgzKa7P(>Bs3T8Kxy=^ZVrmwDs92vmOi!l397NqB6HCF4UV z7k+w)d~Gz!#Jt7gnlFgJ_!TgY_(}@*-2o9%MfB=%;8{jEas@7rM|Eixp(YqG za>Vl`a-2wS0k%6<;@)pc?AnKWAW=US%+3rD8;^(CQnh>lAEP+X_WcDttcBrmMCCK zA>ETc;p@d4=7{yZ|fw~@0o*h;thCTvMyq?QU#_ytYy0%=h95~ z2!tjz5l?L`{AurxGi+5D&A=hfIB6ABp6ey6Pfx_opPA7GwtF+fHFf?Q_W`LT#Q%0N_twZpwaY7Ecm0uzB^5O!FDIY zZgct`R1?QVjY}~{%8Tb0UI^vN%J777k4t=G2gfq zp01->hv`o_+)8=+mX9Csd?(j)Uk^?g)vMorcm+QHCZN-`yQEY@9Ot$y#cdw@nVp#u z@bjY+tRT(A^$_*ftr){Ew6$SlGUh;8)lGPKsF{R5l&8OE`u&wuV1D)Jfor-wto0Zm z>g&hjN8dSgrUa6uj&z1M)}qQ74Yqnj4F-1}1&vQNWV$+wWq&WDO#gN3uyc{vxor%8 zvr;tsfpdX>uNpvO(_12|2#oN{P`r!)h2 z$RYu4=?w4PdxwdQQ-l>m&akwhgA6~@z%)x=JiAhi3*al`+3XO!o0Gyw%1?qqsSs%J zenrkWY0|&@Wc+tapBL9w#wE3NaXk(~+zHyfvf9TO*A0x2106KSM|}lvj0c&)@+sgl z;sq`eb;M_~Habx@zJYuw(V&{ul!g5`r^=j7(V7pQuk(R1`9xd~8o|G#tKq|@VKOy9 z0&62p@LzH`;r=C{+U^QmGewyNU79;iNP$C*oy4s@3e7|Mar?z!){%OKH*5`ti16cN zyWVX2#=3@yJ3JXsh=US`BGAtKMUE_1!u`Pu(5a!C_jScLuFqV3RL9`W6-9ok4P{OL zAj_mR@Z#*Fqdw|u6UKprsxw%QeMjV;NZ`=bKzudLoQz0EVE9xqey-hGcG>R-kZ0Hk zsWg{rH9-bX*;`^sojNo5unugDaDvRVJ|gm11C19S!?PN3%#`tp5PmZNY+9>`&mw)i zem))<3HK6c{@YDf z*c+k4Gk-ktT#osttH2d@x{dlk9yaAbvC~9M8f+q8b6K3fBOgsxW-v=%^>RxN?uCx7 zH$=iy0ln2samEV?p321xyc=DCS95Q(-l+vJb%KS)HKc0?Z5|p90)tQ+hGt7yv zXF#oEfPC65hr{+h)Hm~+WR*tZ^$;Px?HLVrz(fV=s_Fmhi?qXQ{dL+=S&64T`j|a2 zHt;pW7bLe2k*L^t^miSI_1Xp{H@l)K52hApbkGj;vb8|muE3F=uOx25CN4+yF&AJc z$UXEeg};T?C=f5qNi4aJg@-F~`5|TYimw~2Hi?BS>aV!M-;X_USFo?}8gE(w&2<`< zL))q^mu2^h431`mV)K6PO|&d6zpFggv2n5XBIh^o277xD+?Fo zYM*4oN@bci*hcp#+u696&SdpvSxnmBeV}a^0p}MElY{{&^cbYx2-#`871WRKMQY%R`Q|m~)yfg!&lm7w zyEuQfz8ojTt8es@sO0$zlA+zpHMB^fVD7M23zEFU?c6d+&ldU*O~i+)295o zjb^H7{L&I5w_hc@R5Ee%+)5ndt<0YM;{pPU65&=#FIll~1`7H3;a>Gv-bmSX;7f|) z*q>*aCF*`)TUiO?gFlk39W3>|=i>q8U5wU@POeb+zj?c&ULF;aXJbh8177Kq2ClF{ z9Ol{!aYX$kG;51t)ZJTTIEKy z)s+oIcO_+4Wc#CztUHr%L;zgVcEBsDtGwXpVvctj&i-mj7FAtGkq+vkX42WdQ+MFe zuU4?2ow;c}iL{T8=8W3zFvV+>A^3z$^9bJzM~X-X&weoOTV-(FnSV8$jVO#=R&AjmS#CT&?7==?eX zMF;-ym^;R>)_*k+l@Ss=PXa&n&qCqiFfyQ)gj07?mfBfm_IT-L5QV6?F2MH@H9Y?X-?`LVYNNM8-L;}PVeul2z1~UIz12X^fFt-*cst`iZajnyI{~-h z9oa;)Z+oq;VaBeNcs^!?7HeTmdtdyHl6i^CvgZwdUm)I-YTjWF@7FD|c| z%nT_ha(eM@+&$qjT;9JNh}%2?(`p*YQvNvHX77d0)-KH0pnk4Nb}tA}X2KdxH5|NP ziO){R@FL4H(JQV3pBmm_@3<6#*yV4ddo@zuMTe~~7LMJ<6jYCJ7tI)WwRVuSACkwr zN8UF~E8zfej#NXtD2dN= zO;FvyqeNk85-O%upyiWAtn;%o@UgoT0>plh`jt~q+$jLdC9d*Xp3dXK8k0CKLy&v5 zcM`Z+2SM#iYf}Bp1Rv16|AmMwMtsQusQw-fP8Wtrcj7XPpB#j~7d?1GzYCt5h!*f9#J!G0l&-qFkSy^I$m`i{?O4dOMNn zKgu~c{21Mzy)sqt)n5x7)V)eH*IdQFOeJprLUU&kt}xLg5q|6Rk&GiZpo4bg{eNd} zFbjY=t(8zo`_`+%7a%V?9~Y(UVsvVMa8I%+TYzdH{fDT2?`n!ye;4zDsvEhHlj5Tq z$Ws4T@PTp${;z@Lw@0JJ;WwDg{9(d^q`>c)6I}SyLh_cY;W*l5*4E%coaaPgtezkr zCoN=6ch7^n+i$}A-_7Kur6Of{&c^8<Qh-FgPiWkfF!7x!SU)G&GBI0@sL7(9Ego_DovfIE2AXq1DR@F*9Ql7%oN zsDYf8P{N08ekjoF#=PDn2+!?zK;@%avd3K$?Jv;1cJ~ajZ)y?B3REIjp3bT@-GyqZ zfw-G~C-?27apIu`So32VGZ3f(nt{$BHuQ~Te$vMI)PvnwFUB2yqm1V%L)dQmC1%2D zX*gvQ42|nwky@I?7WtTf9>Tgj#{UJ^O>;<~Mb!2#mG8Lb9qwk0*t70|@W{C&DilVDz`Vnp1ZTJC$!OZZW2n|+`yu^oy8{D|@k>pJ^#wH`mF7w&O_$L44{yOqTZ-S|L3TUI{ zgFPjGNbWDH+s6v(Y?Z2b3bKD#J(zcTAjkAL$*(=a;yo0FOC?mTw0HwWe^DLfi;chtaNB8Po zb4uadoVhepDa0LmUxeGKx4+1PvSQYFg4FvMD3~-vE}cJ&D&z{bbNM`pyC6)UB*0S+*hxN@2kh zQ&h3_Dv8>C3HgbX!@tOeb-r;Ho|cw^9o-X3ZZ5)ulymp%OewD_*@|QAl172<82 zKpq6V?Ssc*^~ChkG|aLJMcZ-O3|IY&JGFe}sMg{3;5$@>tj4-Vj+|GD#3@9S&l8x= zZrb<;n8YEN{%f$V9L9=U1(4YtU5N@VDy)sxE|{T}2n+N2i1=G$ z+&0Y*ALPdJwoHjeqnph*rFjRtlx82biz?yA`cLGY_9A35Xot1LZibiB#hnOo8SQx? zKk0im!W8Q^KH?p^(8P_oA`b78g}Cw+6;Sd;42L)0Ar}Lq(RzIq@>PE`^DL!7W4SXN zpub7yj74boD!< zUu*z>%5(FWJ`Xnz``|;SIMLn!T4{CUbLVxmw|R|khv}@I8Ur^c-3OP%Ve;`5?JV=);WV=k zyvVQt?zoK6Xs$eIVJ^rE3ZeeRdQ$UR6D`A!xI&lCL6>5M%c2Hv#STHBhzuHxYe0iDm|A#%fFixe=O7?^%>Z~@A3ekpKq ze-}xOnTC;LLU7V7ackYF(MU|XaHnw~dr?*jc7*tYLq-TmZ!*VOlk@RWwHI?OCjk_> zBFI1bmy}(XMz-4&jo>M7;nN?ShO8Rg9TebP`#E?KE`k*sGRe~pEgakCjkY1%nWa-i z;RR)3-M4yA+FWHY;%N}drCX5U0P2?;5aB1~u3-~HNxA5AlN^H|zOD0Xv#-5l8{JDBQ8+RoFYK=-DHLjN^%$to`MgEvoC(o2NDRHT{ z_m0l+=~HrH(=svK=U-2zP8*MBjoopH&NgPz49amzrrNGUH5n08$3;RG=wu+nYgw30 zwSfw3T7H)e-g*NvK6F6wm`~)%ac|laUVxMSU1Dan{NnWMtw(Q;>;0ARoVG7Uulh$G zzny^ta1oCQKVrnQ)xpa)4lazRpec=8xcW>bid-IGe7@Vlx&1znNHu{|Trysyxw%C9 z^Cfx;F=(Gsi7&^kWTi$nz}L^|aE*2)EMMr%U7qycF5OFaSp9XDsJuvs>z2HQ9NpFT z)~T?o?s`E)b_}$84Ux@~GPw8de0-<3iuXSDB&;5M0XY>)^ zKrHT3W9BCQ;W{){f=fd$X(^V%L)ii7Iqo}oVi}2FZi(@W6I-q>5R@!NMJFIw|ZZv)tY{J|*dTjTzRj`(FzFxU~Ar;?!xqsUK&Fw{d zG!POj@!*Xtvf@oPZrMTKEFV?aJ>9#(&nyv6c=eO}^P=&oRuc}tbYYLQ2Z7}IN|>Jg zi9C8?gU*F?ua4f$xTV z!exbjQT$5;tCj5zUk*3Gy{0YF7IaFd{GsBkdjfJ@N_rSGwn5ayUpnm_kXgBLE z@3G<#H~7U6V#0nBE3rHXY81es^B+jYB4xZuS#Yx_xG|5F$H4R3E)XQ}mf*2zSnNvK z7js3Tz?_0c;t5OwlTkTR8M+-Td0wF)Ne zw+<`Q|O((2BsSQCd-#d;kd7}P`)*s@Xn;55@lRW zELCCGT5f}>7Af%ON*9^S8sHC+AZ*?tYTafPjgJF5QT?kwE958*F1h|N<#!0#e$WE- zm8tH(Y9Axil?YOUMPPdN9})Sef>UR)*mS3wH-p~5H<_x!aJ&Gg5QLy~MFcn3Ws;>+ zbx`M%H|0dTFw^FXfvcc1B$U1)E5%Sv>j80`vL(VtX56lew=|-7veGB z=%@AXHtM@G7U2&a%V4E%-p11AO0=(EOD6KNX(sG7=3ii0r@RaB%Af=unDmh)CywIO zxB`3Gog8$SoXrZ=5Ctaf4%oG9%8o711j4!@(=9#Merk0vuMj(<4klh&j6 zMB@-;oL^15CeQsNo_#ZDJ~1A({ybz#M>HUHejF@!YbWW4Z{w?kN|Zh@$YhBwqg)6d zP^Itvwm8cEt*5-!!oEijX$Cgjq5?si(~j&Ot$O@_o=}iih{a`Y?3HWI}n7sLhFch{c4!R?1#bG zzsS8Y()i}}Y%~@1EUBqTK@)xj+8TIO zCywS^-Yt`c*l2$^_t=Vf#9L6Gcs|x;WHS+=-jpL14$Epr$b@}LXk%oJuRqS@8HT2y z#umz|Uooskp z@P(w-%s{6T@u(5n!87po=l;ZfANBGr`LGcU%KcEk@e}zbk&BPqD)Ek^DywR`7jl0j zz_cs6IM`=-4>Wg=5Q`oO zG;Xm()eCQVSCfXhv4w_E{O%_?rj!RlpZ`I>?|bsHN(C4C_~OS&?u?(FFi75Tfmv>E z$=ROiSnigF56#R;mFgXwVOWVRdooy$!iTV^q7^Cxevp|Hr7$+q3O7&IV=50CZIlPH{gEWr zaYlIRz;E*Ay#XAu^@P2~??_Co0m_aE#LM?jke@T6@k+!uR5zT>hMLQOmxe!lRLCNm z*PGy$?^p3ewHRan)D+GHtcKMZze!A?G>+Lc8HYNU3N^WRsGLhAksBDB2kbpZgq@b{-9@T{4S8 z!~A`IzJEZ^>s8&)dCq;E>v~`FvtT9VbeWhKpwqE%9Jfod;8Fpxv3T z2s3yZzi82XU*tLV!tZ>vO?{50Cs{V*(rJiOtc01^L)L^Qp+jg5j;#%1B!*SEp@wav z8I~=}E<@BJ5e&9!Buz=8*mKGU4YqqQWgP?D9Fy(f2(O5~m>MRko1yGv8J<;5J}%n+ z951gZW+lGg0`KST;5Pj$;b<4kH+ti6i7sbGt_*XZ6#kpf`+MkYHwnfY)&g9TxG}y8 zNyevrWsI|$HVDfkLu_mdDf?QC?`dv2Z_6LX)oL-+l?1}m-oHezM-01G&%)xry%k`Y zgu69saB<=iR&?BYP`Q%}pL04$j;#jX`VxjQL&dxr6%S5*Gmd)pR-DSGJ_}X6HPT2_ zYK!sUbv`QpRbv z%n4BT=qIA5Rq(}Z8%+0}$gUJq86}dAtio>>Ek5sUfbMABn$iXfY86 z0iLABA$F398%|?R+_eFn(aS2n{;~6U<^=LkP`q@gHhQqjZqMclxpCH#z?t-S&hy4FJT_~iSZ^W$H*v$dG%M`!uAa-hBII{*Z5E>NXE^idUYkem8I<$jWoK8ZKv>JL79bire zO@IzfH!xTJO3LEaA*Xm1Z=Fjc<-MoTx38aa#d++{a26cYZh?~IXA)pgf&z-QI8pr; zLlzi=<8mi(k@!o#TG-;JfKas9c#~AcB%yU&4LYT(vG0{9L#eMnoY$@+tFNua&Q!|V z?5niVQj5oLmIL^1)d|+mXE!{iyOztT2J%9+1ZRw^MV+~}?8Gn0AQe^$4nO~qaCvDA zF0sUShw6B2+h5Ky;lJ7YXzpbY)EI_rk#ORJu zeIq1W26rbJqYvdjXlhRfm1VnN7c`J*)&{ubS}2CCJxpZhCt&l(He9x7CM)l#0P;UW z;LY+pGA&1xW=TV^A+DAuQ!*Pml$JyIjzJRjTNQmy+MuOe8hww*!7CSPaN099_HC3W zv>Ii>yocT7TIX~WqYJOpBr%({9<&=&x*dhq1he+16@b4j6cRn6h|d{OWO76B&6pXC zhG!P^c-{u*M9MVysep1X&9KnwAaBU)@m{2koH}7mA&+Mn5g|k2Q zCv9dzHcL=mwJRhRHW7VI2h4RZM2V3=GXJ6|j?j0j<``r?%|K|F_71qoeZ=yK0v=<$_KS9y_V_C?r=S0metv;i1!G_?0LOaff(!eb%xc%bhm;K~ z*d@s2=Nse97fI+CUdAkVrUM^0CWGDnR`OB06mxU<7(Muh=`vaZ8j}LypX5Jsv`-W* zD`#S=#;=OR70H;PLf`S_m$KdST&Uk87dDa(67a`^(>M*IT?2O{E`!b_RaB2^BA$g( z$cAZSZo+=X!`crj*+iKA`7e1WB8%;)dHGZzGl;-l@fYv$N%@_523IJIpLylNaEZ@T3$!E+`?9o$*@&O8Snf24o+ ziwjw+b0=VV;C*O&#P@N40sZ8Q_e6A|oUE8f2E4e}+34+FgF}K%?ECqJkP`6&`ad?1@w(H{ zUM2*yh1D6m4gpwOz8K`5{UXFf0YBWQOefm0*p)4cru4hR{>)+?ey@X?&OSIQ$Px48 zLS(3JKe6y1GhtN%w%ayh^^?hL;gPoMgV=BBGC-1v}dM*!mYF@Nca#JJiR@}tyeI5mKR#NZB zH_8AXtBfHL2XTIlF*76XC&yN7g!7Rd#8&JMo_NT|+^-v%SMR@aLJndOD=*9yyNIKD zu_kR*|5xm zc_2x(%FM-|$$0rYm`?Z@fVY^kp&20ZVhz+5QeA?2X!n=R!rK86gc=-qJWFIL6Iu@K}7ZcE<5{GJ9fByfj%_xPys z*_Is%PlZ+br65B32`QGso)&ZLT=1HwzzlF&e`qE|Zh$N>FM!XMgHY*KPt3dZG0pWb zT89NQBQ2D(ExH*#U8y6DM%0J(Gy;$3%ae7lN@>oQkE+Kmu)RwvVRu1#NbFeHPcQeNP^+UwKA{WmV)SxnNfO+hC1tJv=wp}4)zoQ0%=x8b9-5Eni$0pW=m z=2t)D9gqFREgMl8ox_%)qA1X7jVl#eh?IyP=AYS*oA+#Hqyr_vmFmoIr@SRARuw_) zc4fTy^L=GK&9*qmjj2j6abyq2R6&6DJ1D2@5qHWxh!mfN2fWmoy_M5oSB?v8Yo~L# z${gckLnu!>oft)kQ%}ak6Vj$U(~f*XN^<;(T^EBLNaWRzMKVw|1A(K5DA-GwLBs&K7lUck8xM zO=Dv0WmxJy4t+H1Nf_-bId)tbeNM~keS%8ZHYf(a2_4{e zrJ0D{PeBW+Zwn+5VnQUAs}0Zkmx4Z+C{f}G_p+EEgrjG-YsW=WYY)cr|< zF4~Qou>TG=R`BuUr@u_0<5IYFU2zQTJf6T;qYkpunDT9?@3A9Dn~6>y;znZso5>Fx zC2-fiaP*C?CyTUKLtg7{5LTg`yj#`qY580n;~ZM~$txF&T553noJFih%t^4fy$@&T zKCtGKEq6RFjcf7{m7Fi}3(SI<1KFi)P~-*Xg`pTDi#4 z{Vnog6AR6S5T5xRR%A60jb+o&$0rDrUDTLew*dh52kE8bp?|!D**b;w!498##kMilR3HbbaJx&_d zWgoP!f$+F|7&qKT4yhG^h_y2MW$oh4(v9TC=yr_m%-@VQq0Z4z9LfDg);3+ic?o=U zf2q#$qjte0uQc$y*GH;r_Tc)U3mEwI0WU8w0cSVVv3msxz+zOb1rmMns$ zM#`A__&KktsE5n_un~4DcajYo%JAV+KDMN~GWPAwTxXXktke+Ze7wbQ)f^MtHM5g^ zUXh9dG=Fz(;SduUsRTD@2XyU;X5uAN4C8HRcT#{i(-}M;vR>YVa@vo)Z*3X6-{#{& z``e8B7&G|LNx9hX28d0vBv#Ivg41ySnkonAf2DcBE_U)7Pb&GC5G z_zz~(#IpMj`2n-)9jx$dB=VkRlqpX6a`E%n1@UQ+s#6M*`v!=TfHVsB&c@H=6;CyN zkh@12G(YAHkk9i90C)65?CLr)Crbyt3?p#>d0|!3SRh-jMEky zk_gQ*d`EAuFT^jhx33VO?Z8kh&`pw!Ke+qY%qnJ}g7C%LX8j`L(3@xb4vxt#|S@JZn}6nJ`o-J%o$3Ziuo^X&sEuBSawbFSdp zrM}GXfoxd*=r%06EW}y7Rz%mkv#8(tG4J8~9`0+Y%4iNTOpf{uT&=OI=Nl_g+fH?)f!%!(kbF^{6X^Zq9|HwVmV^uqY6og3^B*dCR=Fa=W~M z>)J2KRkUA%Ti&z-F20_exh{q8=Td)U;XWp1ZUEf;od74OmOJa_1ni#9Ls{LWyx29z zX&&VX)ZXeKZG(C!zAg&&(hZnsd#c~gcN+CeOPrL%vpL}ysMJ92d9H!L^Si+{eULag zTtlH3d@K!;AR-se(cUnchizEI-aC8>EDY{L8O=~9D~jWpVFwhr70nx&Wyi5Q(nj@- zRogDZRuO4jT~|k1>HfU;zyXXb+s8~y4uOG}anSH~k~WwK<=|;dJ_& zxc4nvbLR?V3;j34|H+7BZ!hhcDj4Cl#0o*(l*Q0z)I;WPDTcL5%J{Vc%XtL6YRjq;YOr`KVzr7jzFU@f=>=7THEn1`P% zhKE+lSgN|4*Jyf>E79l}^-*u*x#O1J5Zqh)jf|aojqXa6VdbpBrfBbh6;5d&wB|S2 z@X!~JW?aCWlhwTMN2%7avJRDfT-h(xhe67W57LjC$>eaFS)+4Xc+Lyn%NKpzkzX4@ zG`Ev-Kkni=>e^uCeZ3+OH}tb}c>H)Er+08&5P1S4_UJ2vMow(x3kUHffjkFOcX4y=X3DT4$- z5?6@M!nj=##P(k*zPd^CeI4qouZuoxzr7zqgzL!%%H@u_+K1udv8;y2eh51G4h*

    (nb%&12CaNtopq7jx{L!^qi>Lx(oL%TCg6eh zHptzc#t8W6g5ioyuq39NxTT6<={kG-tn!gu^U%bz&x5dkUOJMd&HV?c1i%dZEhr- zwy6WHh}-zaJ@h4lAU;PZOe=iNtM;n2qrP(DoGub0JR#yDY`bU(|k6Sf(+~=BSXMz+2aO z4JRt_@zl#QcGgCkixTO8|97<{3!TBwbZ1UGQOS&(F9ct2Sp)0&n>?o;A*D&dSiM@1 z`|w#6JI)`(!Hee@wpkX;Xcx?vDNjh8NjY{?ZDb^&pIJpYScUHbKym0Fi8?5Qs#fNx zJ-5H2`6d0XQ6AC%JPzLDql$9R#pQ|e)uw7ih6^%FPhVUT+?2W_9)^Cm8i1#inIu!!#APoC+a zy(#Ut4V}gmtQUZv_tuPhp5^PLF!XgeCSPwLkE5Ny({eY==^G?*XRf3A7e40vlprGw z=kdo_K4pM9uv5KhXZWvs5RvKSBkEb=x8(6m!|k|p{;8wfB%zwiP)dDEE0pSp z(^cBZo8pg$Tzr|Z#bIFeI1c_@9wd(Ql(Ay+Y@AX*op(OqJkFuF5{8bY;mYDp zkc)00t1X4WxBw{KR7}`Ozhw7V{o9!)JyP+sdG!W+a>!mO$-xSB+ z>n3tpXYl6s8hmhNn7P_C33%3SFqeEIEteL;3(7Zh&!AmksudXANHvP1MU27WS@86d z)97yOv5WSMUpGZb`3RDI<_xA%t^VjL4c2|qGf@~13|Xk4K4E9+2%;@pflufi8Q$2jLV6iskX8yBCx^&JZ6*BqmWPUKKk|O% z(A!Fg!RYM0FC{ZxE<9{Xz@!p*{F=%>u{RUnIroH+8=r%igR;=)E_O{&@)|%FhxO9#{%Y!Voz$Q5{`QSYm%h3b|2x0psXz<%>)WR=aTr z)O^f@`Hz2*?`IRR&FKqHSnAInpMMZ;vvqJt?h`q#F%Oq4zk;>y`xxDexo}72HmD8@ zakB4eX2jfdRLAh&^_yF!rZVc66F*l2%UKD0(@;pdGmX(Ef@*h%yqSSFGB70J1_71t z$k(T~_@O%+3)Xv+03E7vJrk_T+q{T%@~MUcuiirc>p#R_V-gBfrO6-282L;-fPkrz{5#1vT(8S7~XPQ zFjBB|-n#;_EPs=bUMb8nWl+VW zo%i$cWmt4j7{j|>k(sNMaof63TsPv!RId~QpC~WTx1+nUl@_)forzkivb=HAZ{Rt3 zKCa(%mwnDJ12f|eNGoh1CDbQ=xrnmtrV(b}cOfw1{Wp`ZjM2d}l!vLCO7p+M8kpu5 zh4F3YnV9EtP_yN~nVgbYfwTY8?{(M!Q<%I0uCES&-NyYys{agnQ15}4-*WcMS9f?$ z=dkO)@5ITGGO>k1QLeCr_jvAh$`If<@fbl)wOR&zQzO8|dNxV_EQJad>gcKF%M=_9 zg3^}>@SEy*t0iey#SR|MI<|}#X%PpDB%gpP94=T`cw))gJw1ZE#8o6$HSpABo2Oe3=;7N$~fXb z3j=OX=j|%JfMI8A(6R6x8|!opqANPUB));zHyB|k<+yI6eIm-;!jNI~-yG&SD`JIw z5bDt`)TK{PUI=KsFhkm)HTYfqt z0S&BQ;kkR-EEBsP3TQuZ(2NceY(5DyYr~M2SIyHIcZjQvY3JCFf?SZL4h|4AJpA_p z`Elz8y+89&V3j8O>8CFQccj9ZF@H#2n?HKcOcW>ni07Q2fRmQI!jl^|u%<;vfHLmD zGwB<7%%6lQ{BTS~Lq?(HALsseBYaK#PR8%9#E^DA_S9}-ii=vgBUeO5wdJM?DO~(^ zCcfIxO+G$K$B=*;T(@n6u@z7SDRY`HSkywq{XMZpjPe3@XAr-Rczh836RYo9vd<37 zz!vv#(Co-1by1bH>y3}~hQ*BCve}R)?*uD42Z+^Us%e}tLAg(%SJ(9!H0Hlq zEiq_|LE44r{%HYal~m#eUp}5F&11(et^(U>&Cnk8lbm#tMg5LhSpHjw2`tnDYt2nS zjuW#O!>J2k4DS#;d)7<-)y~3Wm650>c8nCI zC7^J^C#?8Nxm#~nf4)yJ? zpis>|rZ(#wG_~J?TXw=+sEh{Yd01l4E<>3{^Q6(gG{W6F!W8M{m`zj$)9{J z6sj`8{4N=uOW;lH*Q88<{=4i=!*cL4>j2@kt>lBEEY7{eVr{(%<9&nrHh)@;@0(!55SG*I@SET2IJo2>3U{1i`c~4+mk8y`y{#tAV+h8I*WzvWK_;MLCDeEML(GwW zk|{2SO~+>Anrrtxn-h>F@B~E1d?#_! z^sqfJ9IeLbGiRp@f#UWx;Aq`VG}m>42KB@I_;`aPK6VB-k6qA_KSV@^HE0Kj6&l)y zRthYpogI^?SK+)PdvH|(Sf0NJ0f&B(^eHBIlTSUR1NpoGdwb5#K6Ui=XE?I}s#i;3 z@1)n{iOD$3_4C28%eFHmry`)mH4ajvhRCg2HC#v;Q}3f^@ZNS^#0z<}mul5}c9G+C zShKVPvdSAsxrZ@6UmS$DpQ$rbxiMh+$pMm=^^oFVCHy-Oh$mt@$eT8r%ZL-G@?WCE z3e9PN+l@b-kuuGsHNp6~!IP&9R#3ly_fEz?!OB>=V&ujYT(rgHApa zM0XIeP!*ih7KVo=KjdYn9^x*aYvbTA&uNz5?z$f+ z)44tC_8;Pzk%1K=eEeHK#FKuQfCVkJxX9Oq^(=`2uDb?;rCP{Rdll;A3&Yk0hBQwx z$jzDQ3Zjlbh{_&nUnT>AD4%&cB9LRT<<BflX7Ocf|8ORk4gOk&9$qzSz7kAg9 z)8k@BM9v&A$_e@|(RUV_1HBhyifWr9$e{xn*hsaz#QB=6_67qOiSvWd)AhtEJ|4>* zx>3CDDEoSf3}{o2YYZDgzS$65;<*_L z(EZn7^bS}mQ2>`zdtu3`m&C$Z3l}E(V^GNsW=@kR7zlbmS7tqtzDf7V?S;5^u|4UL zCU}c_P8K@nvzx};1Gj69lah)cMEBDSqhio0jc(y)dAKC=jXQ@|*W;X+yXuc`$ zE%ETs#UmEM_$V=h=~$}{cb-H-wdzY!yx|qs{i%gpQY^#`8BW9%uXgNNa zOTGOMGMOXR_OMLg5afbGa+P%X>iuP*F@wdVQwrM1r$;ZK`HOPzAWP_S_f@fwXjO6u@ zs3-Iut^X0<{N2aam>q&!5_LdoK9Loh7htC=?SkCt$NXA<9>V=^0j?M3Hd5Y&J?(f3 zcwEENEB(V|6)8jeK><$OMHG(+&c><1pGcwv620yYi7a8>0Eu`;#AAG8DG=cjN;0Rsj93%&vgrYyOZHGZ{QIfrk?$+j$|>8^57Q5S<5V$%IH%ER7Gt zg;oKKnbH`j`LGp|sb-=;{U`5ehU-zJ0xuYD((nEYY&v+C?GCR1J%bK-(%VXwUzf(( zEjBoRnK5IqZVbE#{%<~4O`VKU5kc7ABFOostD&%Q1TIU>VNRIKLD7lu(fK^Eo58p5ZZXPVY1s)i-JzWnhM3Cw)Z7KtFW?HL#-oIh59&v3XMS5o!f%y0;581B&ZtRPPTzy>YfR@^dfk96avg9;v5~~|%tZT$ zP<&~r#Ym=&h1hHds6W+1vg{_|QJQ5)>ggo=X+MZ1WrS%uBV#B}nb=!?f{r*xR2^>P zlY4yB^BQI*8;PO_%{f*))h?e*XwJ)#kM>Kn*!krfVZ2^Gtf2hrOR0xB3~%E;*9da+ z!*x+V%M_OnTp)Vxw=w+#pZZj^*n;K$aNcze z{y62~gC=XzF&)CM?}MS+^d{~-9YOjaif)g$k+V)fhZ#SxN$V(k<)JK;ZwLjcpb+xV z7SNMwGIcEr*er{)V6dJ(^6#QUJ&WSysyKytUU;ZK*C34848u;#s zy3D-qQ>ovO^6O;iGoUVt(Ml|uQ>@AlUe)n!6) z#iAp`=S~7DZ+MSrK>GbAeJ5>|e#K~7GK-L-!=e2U0~Zp~ie@Hzn{qTl0s&X=8Nau`nic>_k~l>Inj zj~D117VPk2`n%4<>bjfIwL+MS4lSabc|O$*b~47x|8gz^N?SADck2tP41A{!5~R81$wrbP3fgGEOfM#b|~%$z72B_mVSq|?-F&MtHllR=T08TduV3%wy5vTdYGMdZo5Ab7*6vu*2N`b}Zyg0;lucA3I)ibu9Sfh_ zt)N2g5BWsz&JP8GF)~1ii!f5h`-{V|!!Cze^V$HQHxYFG+K690;CbU(yl*hf*fDFM z*UcaD{RfCpvn3h||9p;-g%0c&^(1JXb`OMS_mGH49~`#7i2m*$XpV9bcR1+3`F!+H0qox{ zhKrP5lHo}r$ouP!4Y-|oA#f1vf5(EP*D#SbrM@G7Gt^#e$P>)D2}=gsp*p#d1e`I& zQ`EzAajX{8>NE~KW;=j>P7gWpRR!hKgRxxc2l@5X2(2lrG{hDd;XqNmB0T|TbbTk& z&KBX6*L?KhjWA}#;<)g!IbIT*T>frOB5L^1op78M`_9%4D#z!;1piKQoOX0ZPC87P zRD51jYBcwFeH%A2EXcVi>0l4dY47`aj!eBKL9?9NXnQY+;SU6Wdvz+{hri^$h&x$W1eRxntnHDFL%hn-_TGR&L=xDGcblVER_R! z@lfzRA3}DXM#}P``a_I8yLsR&v~`p~R_+MZdnce4&5~VNU(Y*SD+mqkQ%AGgB~J?= zWpy_gUgeY7<0qqvQUE$$@nJ3)Nx<+Jcj*0IPxeuNvC#SyoZDhda7i_Ei8q7Wu^ytc zeFZhs@Wa6k{2zstSiH*hBUB}0H%{!T-RsXn()Bnxk_}yYS;hhNc*#g&DHIFuhoe0EX(ZTA2s4%*Q^_ou)ueG6Ki{bVB)nUvEg z$CKDwjGk_MeEPA16*Az!o$Aa>=e3i$12VXD$K27~c;2V65ZY}yI){xW>m!eHkc?Y| zxU^~wEbI?Q3z1yr{Z2!;VUh$l7qpX)npK!Ry%rU_hZ&6xPH;}ZAK>`_nL9%sg>}qO zao@j+GdIto!}%JV(Y}&BaK{Tes&in_vx`W4n}+AN(rmKwU7p^PUEHRHgtIFY#T^Rhoco=u94^La!CDkj7GT*V3A8FOr+50v<$BIZ z=oV9hT47r3+@G7kV?sVGm;O$^r0Ak=eH2dJP{ZSlj&O-dt)qK#_5mNNe~00%hE8%r zMiTwLXyJp9ASP~4AOxIC1&2u#jxCi@i%c3a!FiDCjK+1%)9}m^z=^R#)#k~n8 z`08CZF}2f#6A#@$>p>eaD2_)_@eceWY|d&G%R{$L7~C;EN0Jh%&@jIiAD5Og=7%ky zwPp3_J{)pR1^@3;?D9NHJcY6`MuPISuF~I~H}k-xEC$r+|6NO;0s4nUpseg^o1_Qv zxMp$(`jI1S+$?!0Sr7^v#)p!}epM)Rq!#zF3)!qQ*>HDRDWn?0E@!b2mV3 zkucXjsT5D&;Uh147vsCPpF5=b-&_^X7RO(7{}-6>nfMwc;hbyFQP-%7DLOe3imcpV zDB>gevSA%6-!4Qihj218E*`tb_oGz%Jl3%O88j=tg+_q^az~>SB?uok{JhJQd^LmK zau^%bt_}#YZ?EXXX{Df1&EewR1xO35@Ri$Go)3Kn z61MkKpZytD*m^Q570$r>6(yD4y(L&e=c>4+13Pm^Iy`$+4*g&Mk{6(et@rHk!mnSv zuF3*PJUnZ>quI&Ib z%?>ggE{}CQ9%e?GFuTr;qj^S4$es0vRK)A!hVDSTc36m0y`+WOG=p3-kjqS{H-d;M zNpQHRo$S4P53jGQ#Yw^f?1#9u@HuurG*W-jH7RvGF~UQCr?HiZt=SltTZ304RcAEf3bflRWK;)k{TTrVztCISydkn- zrV9Q$Y>mpxmhmKP;^AZVV>sXagRE0C!g~2gT}C)p^n!Q>F=Ow7hwyG z@qA+vzW+uT{4I*fQSvB0(n-dyEJbH}8@&=Dz*?G$;_z1!JaR^}JUTQPFHkS~(H1S% zu+Rgxisgex(s$ZDt%rj;hwpPPRb03_ z5KD~>n9|pRKn`w%j3C;x6LlX&Eo(8T#*>*-{hceS88@o^x@XE`WXMb$zo>^?F3mwJ zdLzy`Dae|MX~Rak*BSb>6M@wUlwaM7X;QP<3f&d7zwZXztNcn1l?0&RqbQ8nyNz+& zXay0QSA!-QA~v?F`0u?n-s*@UnZ-HiMDL`UYTE4ky!r6TG6wdk_mZtKM#w9QK!?`T zHrjsl?k~}Xtke;9Y2bZ)MfI`pKMUFCO1W_SY6;Bn6X3`cVQ|)-3W9C}#Dr?1X{tZK zmtRA6?a;^m#RpJvU>D=5Bt^NAn_y^512LWAh<9xZakls(a_{VY{H{@pV+9H*f8!D8 z1bu~E|6X#@O&Jd}7WjAlROXzzA($Gv0dGMs(WJl2>&@q)dtE)@nNP*v9)URDD3kHH ztqtx$5um33l2~o4h6e~%%5-Y4LMGYzO;Je57$wjO*^3t>6aMy9hxki1zL54j!WJrif(bgLt5 zUOqxR-@D;`t5B3Y%_nQE{Getg)xpp9kyiOc9BygASkK+8kz@?$$Gm|=n=i!Yr6Nkv z?7#il*^EfwMc4t?0i}hx714K4lX|Plw(n+6Bn@ycOBG?kQUR{zAm!duX4<^4&-C7r zf)VR!?vK6CY`&xj8q}+1KR~%MXdZc3ejaq~(m!<FP1$^m?Qme9?au(S z;&PY}^^drP%i;ATYaBSx#+&uB046jJLPPuu5?`o}c4k5NLTx{DwPQRaNo=KE;nepi z<%jL3A~CiG zSJ&ba8C`ZqQY2tvJj|r`tT=VbXOH5wLFZmC zWw**Yn<{rnS8$9)Oss+PiK3{r11R{$;B$K%IOFUT^pBDm$O zjHFJ9d8l~^COE`Gf58ZmFQ6S6lRMx-BonqnU#zL;!mhj_$58o*L-v zL_2P_b&)8`BIwzujNhKwF(q5YaCVOz`n>BT@2}D4mfkcEeivXBB*byw@Jx&o(JudZ zJ_XgOUK+JQo1H$_6HL1D;O_8uQd}Lw4M(($`qP}m=VET@LfqMMm*n(*M$OB(L+-@9+Q{*I>rzJl)+pYi2)vX3{*cxJtyS{c2pRQc&sH(xP zUxKW&l@4_7bp!V?9Yk^q)e6`a6w;l=evw%PV{hI7r_g5dS)>~O(VN#rxiV(iUTe@) zTMe&Ghsgs+HQZlqjZVx_nxW3c$P&t*%+_WduP%V#t|Op9`yZ2OZ{|6vFidqmWpg1e z0b_Qwpuo0hmZuv9Q_J3hBfcZAzdb$%NVU%B&D zl)Ke835BGMuz+&EJx*N39dw_U+AGNF&R7D!)T2P@!fz7!I{{ay)}vjIK0CF11K8gz z1jE)gvcj+!Zv9fiSi6I~m>&#$_I89y%B6Ya?~b-iC{DMkC4YPOgX{E6Fr?YrF)E38 zenmY_HQ&XaR6GjXqu#*pvMN^pC+8%&P+MBe{dhgvb0 zv2$i9@e?Qp(Pxwq@4JUl@~eT+M@>+%bdcCKl%dy0%3!ysU_Q9dhDYA(!Qc?xZ$C() z?n>%8Y4#-Z(^ByTo#&lJLTvu2X|PQr5QH4wka2IdFxf5?_kMh1^Svt`{qFomiKbLG z(NqtgIn2O0CrT^L3(D|XAs@3+9od~1Gl6|p4!d3Y$?F5kxNNc=R)qEN3akqu?$iLd z2)!Wol-0lHKoHt=?q_6cMc`ri76`rYhDb*Hywvc@FmSpDPc`jzCkEuMp@*G-G@3$kY zW)1iFz^CmwpmnR8=1j#gV4NeKd7i{e^7G}Au2+oew+2TG;HO!O$5ID9;#Yc(Fa z(^kPX>f6lgFM??gl~7Ub5J}-Ef2G|U-2RLZ|4&!3bvMlphc07J52iv`bQMe#>m$4} zKTMI!!=#eWJk6;~Iqwt6+*Nw38WAgm*0gcRD!m~8rWeC@`V3z~B_@v?0;fO6;ZNrX zDYm$am5XapcJEW3gL*00EboBR^WKq9s#17H)D~sB|M9F>i^AN*g;4gZhrB(hiLb4L z@m75o`8%%|N@%Y5!#z8u!%Gx>KFXlCV>@{yeHZi8=&jsMknPZrz-1Fnk#|zNT=;n^ z^67g-b*(mATDJun8uH-6-XCN^^-=Dia|?HtX4PvP_TUDWP+b4}J8=_}M8-!Qt#$`6 zZ)L(DKs%Lo+w~LMNJT8op}v=&yLj_TQW5F?ymIaacEN!Yuw!BkJlN1i7Mp3Ij!g(2 z?=@tq;)TKd`-V~W=HIRRaiv=%uG=HYs4ec|#%vh}U0Z~?q=#}?^2ivqV!O#}nv1zO zg^w1?h1globzm@$a^3fJ5RnEkRDJ4zI={@xNM}4A|JIBObIjQ1V^>qo+f6tk^^MGK zuSR@G-}kTokEHYP=jwg`xV>exkcP67mL2gvM?+gXR1_r*NlDpMR1$?$XfGLMq+#9X zx-z3|3H2$nGBU~v{qCRdKX4w>ah>~qU9Z>kmBIK#E(P<7E%0Q@7^$V`pJXS_6cB z`AnM13vl}L3QRw=h7F8(00*;Pf%PaKm$rE-o?fDl&X%>jtpkEE9QVJO+;}|+<_mYi zufQ^5Pv7Av;kB6kcNr6LNCr5kJz&%Ri6~xq3HMhhqO(<6PDgM7uGv?C2U-%?1+~Qx zGSCcat$)ZF*{P`WQ;%{o)tKL|3&4i*7G_ocCN1XTSb2~#X^(y+0ey48bjAPX@bjZD z;o4l<*TW>3eVF`-(^=cZ4aCu$TE;XSPMJ^hmi(Mp_j9Z;C`b1We)fdX23T2h2CRzu zNs~|{4oB9Yr=}+RLfIBFT@&H`l%K@uv=Y8~>W}m8*7JtTSm1T7fhh(5NQ0t1@)mhx z9v{t&v_8lE^XR$y?i|*~=@j%2#6nXH?ON52MC%VVIBkYA+dOs=+*Z~==|~e`Q4P+L<>| z$d2a7R^`)sff9&0+rjS*jbyU>D>zxIfGz!$FO*RZy;1dWn)*VcXl7wO&B(yVY$ocm zAt$k5N0P1Hvhh@ZGhY=(ZMOrWL(ouHt8Zt=|dZF>YXXew6$(n28g&n&O`O zLOCWO4>6{=49_@jV<#&d1;JhS;1%uF+S@3JBSmX)c=Q@?Nx=#3&$9o`;f(E6KcSib z`2X-Dj3_7#(C$K_|zTUw4R`ra}!VIjwNU58^uM)3viKV5@4sMFtXd;lNYpuSi|Hj zZnQefytE1gf!miLOpcG6d^rnkHdNq@DerlTzHeZ?T|4kPKNB@p1~cZFV<0!oTc|BT zzvru9ME5sY9i)N|rJnd;=oi^Ntc=ba?a%UxWAtjp@$nW}yt&{fu{@H6C37oq=?8xH z(TFtmXzAgK(K%TPzi;BaM5>Lin8Uhj9)RM@PvH0UE>iJoHkLm1#yHm^Uiq?M?)28y zale^gG7mLhtit@+*<_`XG)mb|N1;e}=A@e+yllJ;3)5Y>rL#S zY@f$1yI8xUVX(HV6g0^X@^H;;w4e;J`|}qt8BWwY7qJT@fBz!!oo@JYl^-^3lwwvU zc5@SBg~4%yAb0lf6#V#72P?Dw5aFwqI6CnxrcZjv1f{A$N01$OZtNf*&g)jbYE4CWhH6}|cV#l7{AOU#v>608QT_bzHe7bW z8~vZXCU#bj&>zaM`tlsMesmSg4?GWRUjHWQNfDSlsTo6L1KGy56?G$@Z9$xKGXTTDPB;Wr@#LlYV=F@=~W7*8hEHa1L=huLYEFTx` z>p=TRz3{PT1tD`%XaJE@Aw~t{+<2`({RL@MwSr5k_jFRV}*(lUkj#i#IOrwnv%ulk0MwP!L%XtE(x#;5kTnFOY z9F6LS%TUBwkd38%(LzfufnY*6dGUNXP7S_}|Eclwu1t-TNx-i6E`YS)c8HkVMJz<+ zQ2V6;wzdFcpIdmU|(wyEIr>%)H4>K0->apFEbbVQGw^dl*_#kU-dayPQ7lVhNC&s#{=>nBIeWKnV|%~jf- z~# zdAWc$nvnrTymmNyfC^8TxLV)R>9E zfoHM5>M7%QTmp-GWw6rvC*hT3qn;ssH+TZTGZ4u({uz z;KtP_uyFA&vaWj$4&U;|^oAndL7hvSj7;mejxJfnfeJc)XvUwR+WX;Y&X} zq`H{#F%t%Rqg~)A-%S#Y-Em)?FAj%DG1kdF-14Quphdl)ZvIp8q%57)S83OnnI(Si zru@2T4;Zr+b(nU>4wAojkiq$S7|l;Rdd^dSKAo!;E{(`t(P5kTte`(C1r*-568F`` zXtk{ZgN8Gid~qISacqW}ug1vbyEAcBhzUAgxkw(}e2jPKyO%4k%1TMEfn2lmP+U*B zF-UoL9*wxl`5gP~Yar-IH^7+37qVkhF{ZAmz^`p<*}?aZ;AqlIc(jwB+cT4%(c*Qm ze6)raktz(S7c@XO=Pw!k`5fF1x5Mu1Wh6&uA?`_`Y~))fnDbxd;EcZ=I5^Z18qUP? zH}0Y`zbWxjE5;Cs3S7A)iJdG_3Ts81!9#k0zy>Asnx~Jc5gN>2M;+kvumhR(1LWmG z39P9%LJ+52+fyUar?L`_N<`QfR2$Fq41+b@og^u~j(eZ?ZT!q^oHHFWedeS0P619T zI29`?k4X2e0P8q+BdlF?2BJIr$&LBcyK=u0`=6+@M>p+-Qx=J^w(}?X>opsbjRG;s zmd@vk%fPjHHF#2wF*kn>&Ofb-3HzeR!_ZVTuqwwJS*q;O)1F}VI2LYs43PJMVkmEG zfV$zurl&0;@ohmRs{K5~mX2Klfyp&6R@O{fY3E?U5y}~mHe?!dcR2PBbz@_R8JiYZ1uvZI;fu={sT|C~aH{|Bm`j)?-b*0*lr^;9|4R;B zlfh>pYLLUv#|?1Go@Sn3(;!JRQRk*VrL6L+iJ#v?*s);1H&)pAS-08RYur!{doZn@}f6P`r%)uzClSCn~X`_X3 z=21J;wR92f6O*v#`4ar`dI1w9A_4MyjNqu(02!hlW&w{CXq#0=x-;jXp1mi&et4G= zP1XZXwMfv2XeY7d#c1GKfzbv6tnHQEF!1aI{dSI#4*OL6ty+$E>?3mWh92Ym2D)2$ zvYoXycZEfB?m>iRFL7vDgkn#;ab;m9)$!ap{?}RKUWl_l65uk`Kn1=QlO0*ocyb5L zgzP@R*x8-~+iO=L;LjK-r2e!Uo_aXRVKpy(^>tW1^&M#0_mEk>I#|}_iy0*>4yc84KF4_v?Kmj@;MZ= z4P+j@3WB`~mq6kKA15EEf{Kq8jsVSWO^?zszMSl z%>oua{!KbR&%p&zo_Oa|H_;K9iAU|v;HB4bOlOBU&8ShP*q!erTa(}lvkIJ)B*0F( ztb`9Xu{iK+QI^qG+GA2#hO10f*_x+^z&i2?IKBHttohWj;FAxovMlEH&I;ku3tPr_ zc?Q#^Q7cUj=NSi+NvoxC&|w<(j=3>~<^ixj1(@5z~9Tm9;(G z%`u_zT^^=Q!S~dw=G@UozL{8JPD}vie7eu9xT^tnKkXnhw3E1V`eK!>6v_E<$JR9$U`;^F}^O>P=~cu#Yh%QTr! zr*+|#&mNGwN;#rWDVMU@5U+?sS#8VLb)$r_MZ*+SB`PQw_wPh20W z&ulVyO7BET!>g<|Aj?OsRc%x zUdM)0{JeEW5jb@F7jmiB*f$B%7{5UdC#py1Xlrxm{G0X>9NxeN#nO4Ep9N3+N65Fc z@|Y=NfQoL-y#LgP$oXYz+%EwjZ5IU)U^u!4GIb$#EFuNl&)XDf$kR~?x~;XoMPdKJ{y{38KZXQF4-5)AC6 zS?L`&V4mVT2pQ`kjn2Bb_p~o%SkGgQSV_Q;*kmmNMuQR2@6Xzt?ky%v^uq5dq z+&js~qDh@uGNwqn{o?==DvlA76U}bXA-^{S&oau&hrWcH*+UCBFE?R$u9{o z>68HWUwB8B+biSli@tbqzCROUBJWB;X}MH`BEVJ!~#+^{}3@bHQW~Mi31K)C$FX1?I~w)SyCKB34AC|XXxIG zZRGJK4zqSupo^LyJE*FRYerdA717CRI&lk|zS1s$WK~wo@Ce-Ze*#-gyUEy64cyo2 zgCE`%^R$I8bLr<>#{I*mTs$zO#t+5)`^bS+(l~dg66z_rF>ZqaaA4PUm|`_T#O&qp z{%t)J-LaRq_T(*u#xmU4X3HAv42S$Hr4T{)ce56&;(?VOsN^=Exhqfo!k>1+!uW1d zZ$1Ho7&**ad5`xkzK?t0F9hkXg4{-$L9m)c+37Spvt0Bk@`=zq>32ca{oq`9{M-&s zZtNndPb08&;(u8CVi6l{v=eUnr$E!=Hu8WzbBnGV9=#{P)GMJ^Wt(A5k~> zfO{P)uygl%Hq!73gk`3~FCTuc$a@C9x?zY~hF^G7sL!y6`u) zCymCZFk#0td}R{P%b;bM^Scgq-ctotRjuV*ZPBc=cE_Z=Lc=m{YhKivHu{oNQF_)dn3r zV-rPw%}B>NG}FDeP>q#u^nsaCu`nxZkX-VXKy)y`R}V`}zwV7hktVudD|cdF4qt|) z9o68Q*g`ghQa#+z3kTlmG2S}y&}N+k2UG;PHLN=}M+PFl#Wco9f*)**CPTe59~U}N z7RBByMjz8g^1(nB>$*(wd8`4G^olqz(lgwf6Z;5r^fpe8qip$` zLhPKp6;Q8t3FbTWk_LS(1Y>_3l58+LU=cxiqMZmoB3Yjxar_}Kh22Wma^wR6w^9A% z#w1Jj;Pd+sJd2*aG)77Ko@rS1l!rTvdw7ALhe?=@8u!K(i0a!!FwyUW>0$3knW!q3 zs-41RPA3`5bZKa-+XrnEYsvE$qUdQPflkkVn7y{6c9M5gOP}$+UJbw&^CX zmrcZyC;F6UPUmx{By3z`1QQ+(61P}!T>6H^Y51NbSgGMo6%Wi0z035iH-ssa?Q_Sb zgRm)fu>JXQSeHIVa)O@X>*>%rChmpOh;p3sv3i$6-> z&!Y*=6Rrjw}i-o_7q&U(zuv6MiI|D;fd&K!#7M2_x^mPZM)vX^NG{Z}3?zP2bU_vvjs z-Cu@5i`Cd>fukUE;R&dGrM^A`O-wlMgKTRtZ#7)z%(|M#cYo5eJn;$APL}n3B$3{m z&O0mO*MldRb??qVfZ26O{XRl|SWd*6m-^^q<-ogr^ET>!E5pm)cI>Nz5s(yE3MDju z{ljlA?sD+Mc{6mFl@elbE^Q~U!aXF7_nTvz1;@|8zl;`p?DXdLkisI|4xGVy>Q7vUz!2f&x9$NL+j;D z;Qr$udCSa3nHRkZmKrPgYCXIw2!g@(KV+yY0{6c9j2`FDu+#u^Qaze)FZr5#0UO7X!~x9_g?Y`hQcwSAqUa&1^rQrCC(h7$gPwmT z&NR6^66^nzqRVb4Heq@g+!CmPlj|w_kxv*3=77hf4M{;IPefqKiMj}cQAAW_7df0E!=R)4^#8%&9?50z#Nqh+^QML zzAh1`d0R=W{4X*`{}2y=9$T--Ae7JIJo-AvrT9VcbD|+&oL0X?`OGQG7=5>Bk`PnJJENi-%nzB_zL6 z9q*j-KppjaOf_YqR#X0P9bYF|WmSf+GAdB*r69YdWDk@qI1Z(J|A<$?OKhfol^aIa za<;5+hd{o2Fk0J3%&I)O4Z)e*o*aIz)iDwNs?ZrEUqlQ&%22d{-qGwd+0Dm;K(h7< zM2Yip?7Nvb&C3w$!#42JY@@;dV-etBFS(<74LQ1FZIignxR^-6^HkdZ;nGXHnUqms zmlv|L8i;TGe)!|<1pA)zap6+x*w>_kd{v$~aw#uSgL)S&gSW6Kb_bpnASf@UeEVt{ zG?rV6tD^&WySlb=e)*AHu%-Z)L-!;-J$zWFR7AG8&cxS#ez?jgfLVF{0(fc!gAF}P zY@e=%291j`WXU34p*aUp9__Ge<~QPYZUWA=GRD!OKAxh@1lZcK5>|NrA@l1rke|;B zceL~p)g7~N?36#Mtbf9oMM$9eTq&HhvW>Lwd5eACRAZMHV)-X2W3?s^b&f2``cioZ zw+xq|;UhKnYN-o2g+75_XL^W*^gR4r=!a_NA9#7*p`6av=5dWeJIM>LhWg?O>izIO zC5?-nD04O9IP)j!EVwIPhvB26JG|(R@uXb?2m+O+fpF? z?PQLrHr}Cox(+El=H!qVJoMcO>YI9qTKI2HJm-Hi`5WcAPP@1e@B02GgOUlTNOgOq zmqKj)wRzBMy$7($f^zPhBu#5z@q3o_4)f?tcpK|M;>4bcAG=) z{!Jh?_>ZUt@5GWR-YD}rgQ$ydfTYwQct7xmbW%R#m(vYs&=kOCEWQY3we_G=^&dGA zN}1C=6&O>vfz4k+yJnWALrEMzry>0cn-|eMzO5f4JW~wLzEX!A+GD=EB@NOI+hK5i z1yR2ei7TT^asG~CCNh08Jo!R>(Y6ibOy&-Z`;>@XRqKdeU>RzDr@CnQb2d)33Zg=q zK~QCwdbeKT#@Q7ZXPC=OZP5qk0$bRcNxRHWNK)UU0p9plMV>CdhCxwfD3mYEmc;O2 z=CUxjZuyIP>OOOWKfa9n+&rJDp#7jW^*_*i#OqgR=~<4s&h&Rkb1j~30U)(*ko^56 zj&T!oX*a=ga&~eQ)nUqTZm1eN*m?j2rX+$fW!1{ZPDhzoPulrX%NtWz1@DJffeFLU z4W4$!2x(vZaqA;_&?=43i&gM*tv_>WzdwAO6H7ZXhlmE9N!L2`aA0zYscZK&Y@iI8 z=wT;TS>Xyq)Kx=xVk;@xqm1zQG>*N|WnAbTcHYs%@eG}7+zEWY?F>%zQDAb+1i&?5 z(s*}X$`3gdq;uF>yNOgypNM=zW~hI|i0NLS0&vX^QcGLNWlwA5v%iObPo5zB`Vkl_ z_Y?258?zFMbud?^9=2!kaZ%Q%(AM%Co^C(E>{c*^H8DG2)MJFyUYw4+NFF}F=}r;~ z?&8&S+IPG|n02^s0b=gKJ!O_roNn!R+ec2()$jN%;;D>}Bc;GIf_kd#`Ib zX12MgHmL$jE^lO;(jP+1`%K_BA0tXlQ?ccR5lX!O!Anr#=QiKf;67~6BbT-%!R=$+ zki-@d>o#@FdT|OXlut2g$7JBh#Q)9VD~Y0*utE&4jkKBB=Y4?J*bc$p=&mhn5)Q`E z4(qmgOoyv9Si~9vks2cRdE&Ur-i-SFipjjynpg)ODE8_eV>!G8NPPq-&h8{egXO5z zLNg94gxI@c_K;iV3X_iiBgLw(k*~iTcV}J8an3mfUL|+Ib@6Y?A@t^Y6#qAS&x|C1 zVwM>Gce;RB(wwdmR-o}$O?K8$5Iov{1-?z-<9PpOQeKDwuI1mryXO@HtE-FPPi!BF zUJ^z9!&KwlbD7yuF9i`&n_vOcOBN17krowr;9Ku7!23wzP{{NE`Ftcs_%~Fyt{b-n;*8rfzEHFuTK^Q zwU*+!s(zlf3H3@*@9f9oKO}qdTs+z1iHZlQCh$jv?&bV(Op5BmP2zZw_PE^J+(MQX z=OVdKfj`d+u{zUcAm0iG!+$T%3Z!f*3wj>Tov6-kb#{dd$Dcs`AF8(;3gb>lG>>Zz zvN}FkZ0U=cp})zibJDb9YAOt9T)2Gmw5mi&jrJDmwM1P`%12rR^Yz-)Vq>x$-X=E6jau|fSxz} z+)(FhR43&)L(!i(OnIN%yVRhdeuO-(Ne7?2pYSiYf*A8%$5EQG_3bKQ_8*-Jj-GZ9 z($ql8O>FS3Um`xxT~BsISKxk|3e0p%W;>Z0;Q!SGCpw17LZLT!Jg*#U{^T+eZieuy zlJ?hAE#gL|6wUAJBR8d*@Q+5}fI%6S%@JYaZ?jNc779@jzlfovDn{K3z+vl&yfedJ zxMc^vjGv9)C(Xw03T>?I737{N(!P>#%HeMjV$Tk4gOv*cz`=WveDjjREz29~f=C+cB# zV;yu**1FeF9!}d#^92F4E`5R-@GYc_YkD^R(mf43*DS>>xf5i`zk4WEKv|$U!Ytdm z3S4MkMN(WZk;~J@2p?Z;YpFNebe?v*=Y7YWDdB8fp*SWwi=#$)M2<7$Vd#_!+`!w! zuFib~m!DRD&`21?#g4N&Yeoe74se zH`uu|Keoxj;w%R^<5Eki=89r?nFywAXf?~eLbFJXw>p!Xy_@OuKlWF;z1GzK0RuyrGlC zJ6EDqBi%7&2(iA74$uJGZEM4vR&8C!+D7-uw^b~OnJP)@G;6cZ0O{*9gc<2 z>qYQxxQ~=sU&o71WoXV_W_07EVeQk6v^%DkxOC1yE%c;4vJE6t-3g9fJ^)W;__;$r z3bE^0HNL(zh0Hke25Lzdutk>*F%qoP3@)6tSJN%8K9~ zweoZKk0gTS-%)rvnossc&cFnHPs+^kWj;<1hWmICvK{%kh6DL%TTp=-3o3XWW^ds% z*A82rHeI(tX*B^&Oy(iFY)Jx94 z*TVYiURYRN%;Q(P!il&vjq4Q?o5fM+BE56IK1Up~rEzKG6x_JfmAR994&*mS!Ebv1 z+PQT)Y7Ls=$JZ{ref0S+==0y7*vmffi~?hQy1yIjAnSAI;(R&URqmKTFsr5(m20!cn0of=-%W@EjBvMXD`0r3#PmjIBoNT*ck`l+~xk*CU}Sm*INOCUK^q9G9UMM zY!6=W@xeEnvdKc)zqd+@?x|;Mu#u-WLD;$=_$xXjrx}OI!k_R~ zf@vA{*q@OGCiK2mv@!$LifN|_y|WwFh{M4U zHE5vRA#L6(Flhb>?1@SuJ^cnQu%zBsxA)9qcLn&pk@izCpNWQ*4JMc;;M@i4$YZH0 zl-^Q-jC2Ysc;O>_PicZ0@4w{7;S7|ae}koodCc!KbSHCuH>{-{H!IYo(U!6o4Bu9f zWW^gOVMy;jULx#dDe4D!7YdQnx=GJ-y1TzbdAY}AdDG(m<0fAG%x(N4zzIjr!GNpU zlyfA+o$<{;pM-MEwiRYi?Aiej6zPtZcBRQzN@Cu39W?y3f=pk31J^F3S(|<8?AfJ< zLFP{aq~>;#x9?Q&)F!IE|E}kSE~9zs?W@3s{!V_H9z!vzgAJdnC3pHKAeTY2obUV@ zop%A?850Aq#fHf=?Fm@=Lm&Ta{9xK*dIPZnfs?z20t zFxF+N79~M(Z~`bt3UW$&D67N!4CRF>GSfVL$?9=B>q9!-}NVE&{LRw4(mxCG7P621ux{1Dim8&fAgZ zk9JnzU7ESxr^Exky6qsYK1xo!nT}?PrueYjjVLdsT_+#PaI%UB+dpLu49*CK`CYwa zJDHEyg?w?5Ak~n=Bale9;is;v><)%@;r$Xr$qx}ZiFyU-Of~As{F~W5sgEJ}U?!|x z_m8M&PR5qAR96jY=FQ6x;Jz)_;Qo%}5uMOy@GiP*d~UB()x_|MlPK@#&a7W92j#8~ zQ2(HoqzDyYDcu_$D9K}`xpMec)()C3eWcib3f3Rf!-QmQX3@6^aJJk4f;SJ5$C475 zox1e@51ORt?L53Z!waw2K43VjrEuwZ1k?m}5}lSRJn*FgH!l=sXSnYJA0bx|Ql zW?k#0mq~HB)VuO3M`=fx-4JjLS`_W zI(QLG&hvB4%3k=_?HukocaB$jI~UevwnN|MCZhFH4pm*LH?{Q-Z*GPxG*+#E!jV73 z`@IB~bgseod3nUIWH$1(_~J47CycPRBz~hl=INhW$PFs6NKrn+2`^!`FjN6O+6=H} zxmMP%!w+zY672z*s=+?>a0Ah)PoONJmwX(NKvCVbC@B1hw^9BocX>_|XG=Y<9tGl< zaY~FDDbEqvtO7KDNf|pk=CX6$1A(7<4X^*BTA9WaTuysBzEwK#M6Dm7m_Rw^OW3oc zUf01zt`x!#c9K1#5?Dr`e@{k+u?Ua^yCXK>nAt-T_DNyr1WD8(vAib=gWQA90uY)g z$bF>zz?$Dw)36>O9ktIe{x0n+?-OQ4*DVC4b$dV}zlYokHKF+h+M$!d{ANTyKJx0Fq#i@sLh~kH5 zm>f|~aq{VvKDre(2~GX=Z&l0?n#E;^qndtfD~(c%P^G{R02Rn*L~Cmw!gr@_(&dOwLCd(ax)bmNhTt|hiY)o3wVf!DKASpAS%_>4Oc7xTwA@X;LGzz@X!==e|ZYSQrUn#WDu0e#I@4O5Q z>qEh8Yd3MxpN*b_J}60Kc^>g!xqTBpb6Z3NIrm4Zn0QGWQ=^2qS6MXQ^t2o+QJ7ul zZUsS2l=r%Ah%9uvi95__e^#wJJBxA!M(Ps4VqO=i+B6%B)_SAv1v;yR)>7h|1uTBg z&wX}t#ZwYKxW2xY{NYKX0-28XAwG=LlQZCSJq9Mc7$(_UZsN7sWq6|X5W8b$1jJvh z2G!9va`KG|{;~DK)e6TM-G%mGbqjJ&+T8HN7JsygnaY@z3WAE>MEL)nQy-eO zDQwZj2{fnQ;7)V*jwX2drU3*0sRCPS2M6=p2!=}Hv8XjD+oVW3XqVr#nJp-%ZNy$x z_yQBo*TFO7=Ttuz;sSqqcItY|jQr)nzXRLB!ETh)Y~MyZ7JTvD&xa&=$3yh{REBE; zMA*9<)88GuT7(Z9rQC9Z-btc&3Qbc45B2Xo;2E)Hf(!X(2_+%OZ zb5lEM_Phpv@mJ!N*TU?=efuGL|1oGW;Nx!fy~7Jn8qs;?gPaR*o@4&9a+KRiv%SII zkap@W-L3y2H&XpL-Rp10{mlG!i4gZk7@723viDF8o*bn2$q!nr^z@6Mm=Xq&Ni>sX zHVfg84(4~SQVDYj)q%}qckN23XwnYX;CTxVSCB4LHg$jnpdt#sK zXX4^}2)f=lLasMIcXCw`KI*Q(z_Q7tWqKB_q<5KsH#%Wb<>@J~W4} z8Gwy<0(cjM@QdCWzc9-n`XP!hD94m2 z4K{a)JJim20=G8w5!1u-u|L}jSA8$xy@0FSn#+yjdWe#O1S)+MMRSpJq*}HJt?Aru z`#P6hy*LOCf4&BWlx;h5p;yNJac6Kmi^@Yf&eMIv!6?oAlm3>Kj zUS7U#f`fENKSrNl-)wcmu~rJq$4}YIs~r8y&KRIHSqg$R?NLRUHv_W~Mbf&G3hK z93oThN~24P4!%uTNp4> z3ES3G!>HMJ;zjv93158i)u$y?hkOQcpW;FLk096j@FWU9@S|C#smxJjA&@&GKYnJ` zb(@OOG{@TA)kaJoPQ~=CJbc|_%xscZhoE9R__Fgm(c#hDPh9|(aw~{fPy~8}G@;UF zL)ORRKk6^2gTxsE+&UdEoRNNp-mTo2(jEpPs0K9Y2|at9-G&QKd*epiha~XcBi#JA z3>Wr`u)Uww!eN_>aHP1Gn9=?PGibu;URT(ea_{iy>I!@ou!Xe@ii6Uo4A>&i#}&|f zw8A+PR8#8a2?z;uUR4^L%IgABB9RO_CY|7Tt&qsg(#B-|(-;pP%*!bgA@{5O`0Tw& zHLl5L#BrfrrXC!LTY-%O#ubjsQy}1YlTf#uBkdL$YHwz1bbsy(vQaFkj3IS5{d(fs6_F%sQB z72hZ8;@g+|cq!$NP|1kit-KvrbJv@Yp8o+PR&w-+Jj>5HQLdd%rr(h&2^dVCIh zv`OJMX>pY6h~a(l8{+(y@{jj7z56g7kLxeMpq74eyD^3C3d)fy6JgIi(ua(h`(SDG)y>El&6GHD*0)aD2ubW$Mp<4@wnN#mp{aonan#`F7W0XM`f z;Y|l0r<%4O-&23`WO+iA>QXS6e(Pr?XtH@t+aSq22>6Bu$;B0sSRPb`8%ljxgXmBg zEUbf#SHF=he`-ueDLTlIo=YFM(#{bJ-2;Ue7Z)`HWo6>ub&pVPIJ#xyZ`{4(N2(r3t^eGL7+cK9;$7oUR+{TL{` zN;`jdE93CDWw>?dKhx5L7))f#P~Q9q8zXfMmT6T(PU3fRNpS(?n+0NWo;j0n|2f1T ziicAQLfjocUmWy5imx(pe zfYop8Agk#+Q97=V2_yiEC`)PXi+2D zmxZyfB8$<`p#sh6-YU@cDeOO+0eOaeoagCj_?&ias5{gCCNUB2)^`nVqb)rfHzkA2 z!w&czT}Zb1EX0IiPrS6-hj~3^5;Q!s2icvpyUj-uEv!V5&-165p;Iv$>sL@-TLIg? zum-fgw8K&E4{5YeLTNR9+Q3TOe_euo zSjhvG@^E^mqnzQ8PsmNK#Ag{IY{i2E;BD^$X&3mooB>q~i`Pe)aKW6jYiPz~8_fe| z>|#xP{h(L$E)?zPCl5sA==FwX>pUZPTWtckp|RKFv$}OjB4n2d;+P8(dEZZ%M85?# zleAgw5Vyg^*QK2zXB(;>|nDt zKZ03w_53mJFVWYM!{49uae1~c?_s_TSF}BR{LH*^S`sV>AApAPw`8fh3f3pOo>tv|3z7;Vo&Jqq8uNGYqH6v9&qK=V;G}ay~T(QUZZ@}MYiR<4Svg%qXJ8@zj`PAJt~$){+zFs|%bM=@d&w6I`dv^JrM$$OJgezL+`HF& z&{ZP9rO@P}i{~Qja2O`TM^f1{Din8iv29U9CAN*4oB-M9m@5u}!oF}PGTqtip ze|;r>*r3JkaXJ7ylv4nI{3P3y>u~A4N_1QImRU);>-qea&??T)eUzGmLzgLg-Qzqt zdp{K|vgy5EcP`t%Z5vFv8wkF9gJkvwFAN zMr$?o@XO*=9~P|-GtBDC%Ana|2d^*vM?Pg)CDDw4~n*x(~LRP|% zUM4rLdkl0cp!QlFM98^*w1Uu%cf2I5FmXuQ}XZunknUj1fo2Sy;?xf(E^AgikIG^(1JfgA--X zAKCzh@)uzT?Tq*|Xp0Y*-NrThC3vssI};TC75S!zvEB9(IJTW~8wRiDsL8y?m&Yp5 zLtz{Hcpdc(8fQQQ^FBGE1l?MYE7GeuHFrC~&5kIYKm_jM(-4@XvL&_ZcY zw%_~L_YdfPJUY&K-`D$fyHIfnVJARi7fJR&?Jl_R;{eD$5aPC#(f%On z|8Z6qDcdwJ9}Rl=Xfm{cU0UD|t*Qy&I`J>r`&=0zk)=HoQM|*W0i1f+|IYBl*bJDl zP6TaBIC4b&4N6WB;OR&DtglfRT&TYQnij%brOp(5y4?gdESK{pf4&9Do1egGC7OY{ zMKc}a7z|$}#*EV5E`gE*m{T9c8Jd^zwLO9I*IEg$c|Y8q%v8$J`jA?5?f4y#U*g zG|>#~&sr~3y>g1teiROw)O#m#MTE2B%VTE zq&^1?U3Qkb5A1uG0&aJD$T{a|ZkF?VZlZw*_q$adPu!Klb+%_HLqHyjVrgE(U_axk z5dx!vXgD>Fvc+08@cTAX49;`sJzbEBElaEMc>Q+v+TI&5Y0pdesoqU){Wd|`sf3!B zXr4%25lXkLg~Jbj5ud~Kj0%&%(j{{;_Ytx@2G{Id*l*cM+Gi`^ zxD8S`ZQd}i&1DJn-dX`h;lf;k|5U1(o8qx&XGv0M0q#6pjp_njHm-LyomYcF->jcJ z%#uM>o(0ZHSZyQj7L8BORpan+AGV`50&X@o!MBVLM1E{D7XGTiKY^>*aidvab}J7i zY!Ts%#sYqkqI}M~fsCcTJd_qs0q0M{WQ$rEl+Wyh6A5+1p+||{qiMciF^|!4pA3dK zH-q}zcjTa?E>3mwLzfN>%5Hjt$M4l(O4Rm)6X*@(F8Zh(mvL2u{ixK?Z@0F#ahl>44;06LwMv*QW2nw>OcK3+*5^D zqSnqu*fepOmZF^1F&T8EInN6g+YWyS-8e|pb(FAg#29Bp zEFxFc;;{8F&3NK}EU(-XHjxadp}7Xfdo%H#M*x0wZR17HSOH&{1#nJEgiESAjv~~b zsioOMdT-OL@hc5H?skHi_beDB+pYr%r##8~G|#2V!^=f)tiMRdQC2Y@EtB@MS9Pz# zYT?%qko=WYPnw0hg-_$-dX`yhn+M7_(qPFxG47kV1bhim{?}D4_eBGvW}0AX^%s)z zLltj*x4?{f=1k6@E(B@1L3c<8slF41hBsTWE6R-BtltjKE1O{VX;Du8tq(e`rmRst z52iTK4hpupK-jiX((_OoORO!iXXGf+ou7vL=ze^vwiKK8%mJ1R)2=eb9(q4=!(V1` z_$Nn(_y6;%!$2!G@4LVT1k;^6WlMHfM3*g#eu=y2PG9D$3u|kh0q?)wgQxLATtek! ztb1jF*~h=}lsD4vC}?s~MTGX><-Hu{~*i2WW5Udmf3pN(>{ zx@B=oyEvXr{%SLO^GkGatid6#Cv1~vBRFe!!P9GhiAeDzw2q#Qeon^B{-`l9N7Nju z7Y>l3$1+&bHyeL9RFIVl(O8^7cMY4Q+1zusAd_+lJimM=J8GLTc&PxD8zk9R6ZSwz z^a1GW7vhfXn2PSfCir!-NE!R40KGOrLv=fQu8 z(y$7KXwJu`3JK=L43qM9XE03T6V?CJ2cb|AeJ;l#w-|vM-t8O%u!!n=edpCMtUY6+#|yMw=D}| zR`!6f8IqezreKGm7fJ@4ViY_sK-AI@AQd9qJzWVbyC;Pj<79b;f1iQ8W)~c$9hA2v zC*Vg<9v-B9I)QvuSUKAc4(a?Q^|Rzq_1pr~XhL#7eL7|@@WJ4VDU{vkWu>2=go&vs;9<~9-tjJTTSVV;O-pIVM2tLo`$%H% z`C#%x?iH@5`+~~-`mF!E5U@;)hC`P|$%7P4oK!OhYuE4RY3HWlNI1>uJa%ViuDc1* z(_g|Y+5_@T(+pqoPhs;LGiIbs5yo||fjFx3KM_;LRxRokY>DIjzBa(wTaIv+t7$fk zGFUuEXW_lqgXH$xLR@pX8u@xstV7`(*eACQLNE7`1N6PqSZ{%=hV@DJ?r5~r=HvRt z|Jasydm*+v7nV-$BEESos63ALR~DBuot;ZS_UUq1;Z6NEsnhIYwx5gkt|PqpAgLK%0~g>3wfw_yJ31K5_0 zlG4kFhLb73G4%;ku+awWr>qBI*+FtCSPAQn8l$sKE!j0b9$!ZAQH?LfYH8BWnaFUM zbLJ;W9@fQxQeUdksPK}0wsQd?jhqN&%O`A# zfBqnwGDxiGjIh|l1iKUM$*M*1xYd`Bw|Tnk#^9sysW1ZyK2Z-zm>zZ+`eDJfcf5{) z6(Esr2hXYA`_7zlp62o z5^lllJX7|1`A6!vX#%BDQSR)kllYP{msXg2Fh-vjK>H3CSTTv_AXd}wXY4$T={QP^ zL({Q??%!J@q*xsTCy4kQ0y8i6kYLJC-Mqa8Upx$FHCcOifH58#2cuuNzl1i>>N`^Ib_mMcX4=fmA?e@SkP z99~Mbqx&Ny=eA78<-d<%&CX=z-bBjzRF%NRJKKpK&0n}F3Q+rq6noIi7gmI&z^}Ak za!qiVn{D`xdpL>S(+d>v?Nv$in0|(Qy2{6S8UkFcVZb)r4TZBl(QuaX^p4-xM2DLe z*mim!FX&Y|^`BH@)UqAylF(Qxk6Q3M; zyc;h;waXj4Z3ctfZQ~K{+zAoxJk>d)HW=aL+e1X9s0d>v>2CeH6nkviT$m)j4L&^Y zBX1IA(V%KJ!gPJ|dhBK7h4At2N?rElyM3_7A`g6Xy2#9~R&04Cz_~XcGy0xOA*X#g zY)lvCtTOlETysB+-Hn8AN44wiIyh={nz0vI3+w6K`?Xj^iA%6Y{|&66TuO_IR(z2mz!(cx)?YsdR2SueZMF#4H2w(gyBUP z2ejgxJpz>fUC8Fjyoal0ZSZTC5VuLg3o~<0HcM87#$Ss=7f@g&%l-7$o}VC*jYRJlbQshNOBY;J#2kJ}lK`?+tjt z8m|l(n(>pY%r?S5vw|?|*k@koM+b=i&kjD)dB%|DhJ50Dacf~KF|CxxT)rAMJvhdA zEjSC=JFkQF@?j#bpo#gnspj+jt#$m41hn_$W7Eh1cHhZsaAx9b;J$Z|oV;nMq3DHG z0p`r^*LUGkX(}u!rhCsp+5<~@BBMjeyk&Zl(EWgRaMB&bqS=#hz{8Ywes>bzZM38I zojF#_HDkJ*^daHLX2^`8J;D`H80Pr~H5yIWY2ly27YUl1=zZ!GWoq3aqt7x>nlkrJ4ok5eF)P8Zo}SO+dr2f^1K#DoL4jg8 z`$$0vFLghzfR`m*IZlQf-M{Ak+9cu6@W(yQJH<3-H3$Z205;d!*^7Qx6 z?BJ0a92|Mdmdk682qkOymcg47vp3g(7FPI7wRZ!k<22E`PB>R#azQ~@9J7X$o zhVe4~{CJn5Hgl&IM*f?nTgGKU0PSU4 zI7EnI{B*o|&>J0w{FpJ~5wO4QEc{&~${7XH9xB>9@M0v8XC(fL=3l$OE9DFME|p$W&BXowbl-PZj}5B!gZpz+ptiA>*pn+Hr&1H}C+>eLFsArfD#51e}AKk1*@!*-P zDp?2P{7(PVI?^V}QcjL3wy$@wIUG%YBSL)a4e(*b<)R_rZWFAU&`v6TzeCxn0yI@# z&2Ep)h4P48sQ)Fx^@<$9E4=~upVJg3l2rt+R2|5O93k%+gx^*)qZHCW$}cP7yZ7_( zv6&UKYg8L}lwS}w@}4|BZi2cMK`0o}Br2uv@IB4OUdt(BPkXh|zR)&UMems6fsfJA zf&N`}pD`X03|L04gPmQ29|2N;EWzSHUAhmZO?$P^q*vLtueOB1>xn2&%9e9j<9>% zd^kbBOWnP``2Daiu621!F5Hku=csX58|cmOI?jTj{B=n18zv%WC!#IwWRW@i#`@Lu zTWB4?M}>letjFr>@aTRmq>k?->Q1`Y6n-4Fg6A-Xv^T9KG8KNRh;wHfeKFd_7tgh7 zFlo;v!ET2VRLBZ*kH1s@lCUYpD0Y$i_UfoPZVoQ^Ih#pyF@T7q&0x~eNown&Q1nwH z1`3(55c~!9v@}9ez8JUFR)E5)N13G? zq+T>^d#X4U0|3kPsuh_FcGa_umryn_P___Peo0pMzk)BOa7` z`iSRBswX_L!pr+2c`Fi6b1tun{^eZ6cV@!G@gtCS?IF3B^&SPD0vx?Di+!hi0T#Xs zhc-CX}stOTxGErDys z$?y^m@}ZO01=AhBlF3WP;$CkvY}@vmr>d_8`()?C@7sS#c%2OH+rYyEhGisCTMuW$ z2`t!lhiNL1N5u*;6l!iGJy!&{lWIO!j!CnJz3<^z$`rl4tE%)UFAL-LS7VRXOm;fe z`Arm3VCMWkWFY1$H~G-pf4aws#k6l%NgAich7hk<0e+e#z`t&W?44<05ZW6Bcc}k7 z?|BKHKT3TFrIJkZiY&CE=f6|#PS&b89-Nh5f;;<@$Q`_jP(pJSjhC58ug8G?o;4u) z?Kc7UMfh!CE?!;Iz-#>3&#iFi<2dSJ7V4db3F)(NFa116-`>OX#nspnD9!rx(QaOY zt+8b+1>5r(A5v!m_k$E7$I2UwGMY(8x1!hw1Yf{u{=7f|Iyxy(@ ztv^OcO5-CK@7oDe+#5;KDphP;V}r9T7^c{03iRb}2AjwaWVah-+D1>1K?;bHH3 zVkK9JDRd{k{IWEwUAPs(|MPd#wn?e<*`@a1!diGRA(hPVzcL4Q)S|qv;}ZrlH>uzUa8Ygt6ZU zf0ZTn&+tcyn1$qGR}?mFZ@_3{W47|^S13zrgak!#?!ntyoJPHxQPocv`(S&heBcZ< z8-=)-sIB-)#1HGE(#Vrl*(lAUK8Jc~*3aAp=3WSajE-JXMVYI1%_GR>I0E z34FcuN||VCEqN`K%muA9aRlUfL;?xnE4Zp6ROGWUm4;ceofX zWOo8z^cj&}AA^&R@^OCbYepkR0~X}E!JiXN)# zZhH$#?>pi6UX#^yr|) zdg+f$*}~2#pfiqrJdEt_C#BbEPv3eQ9FdITX$_v{YJL^|^GN?{%7kMrL$FTkA&K1E zh6dN@u5gUkoZanT8k*?1b0A7AI~)xHBh*Q;PkT0fC>SH@E|^JssQ z2(!a%9NY_94lTEOh~aY?l#*SFhWCqz-aAjq1lkJUCy8sy#0CJ%eQcv%l~&)2b|7Y9ltcQ{BIYZgf%g@N$4kE?-Z&o1z_>L3{(CgX5{4LbA-G1L3h z;8?mXe0=?v@GjAAm%lc6YC#$KMR(S*pX;&DTZxUKj2ilOhii+PiMYyZ?5AgSL60=+ zANB;#)P2C#u7=XPvDp}Yh0ee*lWn;Z0E@?_fEMMkyT?c4<+abSq4qy!i$@H1P2?>% zmokA9*Q(%h4Qb5&FOnDAu}$9ZT{+b4D)gwGid-KJDwF41{{cV8&cc33lk~z>}vV z#3ZsD&UAOuf7?i;+bN@%&e-|&R*XvB6xgBX2KL6Z`vYZg+t3pHYV@~kzE2xg-VvaK zNeP?V@)0JyYy;P4!rbKiV|Zsdonv!+nesO*G|u|p8NP3(2F;yVVE5M+qVJG|6OF5J z>uwpgQgH>?_nil`Bfm&=xeR_CU4nb&blFJAf8j!Q)NyNQ$8y{@36y zWebPrYG8(*1v;d^w$>j?!XvZ?EkyY+>wE1coq1~^abXuxyCRE)G(RF1HICU5PzV$9 z@4&ik;#^9mG~PZXiNPAlylio4(9cqY-IObGdK%U1T8z;{w2OGysG$#IhBgLf%!d_5 z5H{BhTm;|9V67F#Tl=H1)gtm}nDSfR)#1m@M(mu^onUjl5$w;2bK4HqVS$tYH(h(m zq^?;Eb(+qgyHALlr%3t0LS`5|^$@w8n1l8!>5hJ>412i96~aS8;Pv@Gq|z!HH(J$W z^u#cBP3mIIaGHl1Vf?cExpmkosKHNzYgsS%9FXWJhBvOlT;q=i7)Sf&W>tkUyhD`T zUptmd-Bm&CUVVrAy!#i;MsRNypECAC`K6sR~Nrv zd2;VTZJ-kzXop(Cp9iQrhO*T3Uol2!$AQWYQ=0P{B*z-$aXX!V{0b|`V*hJsM|Thw z60+>h>5D;?W#!z4edi#|DpYZQVpP5mbCu|X;22qZv+gJ{Ic8n0dJ!S3Qw!+kBXLyFYa=?`L9V{vd@wh09inPP!`V?ozwm%Zy zw4Q-8uW5%!qBN#ce_h0EIbP5u0lYfW1?&4d$lp>mw5vD6El#~Wv2t}Nw6}#ii9S+6 zvxm)6))-Y=N&@IEJAPXo?tQMvx-OH(2Zh6MboCozP*8_EmkH20M24-8)W)lq%+O(u zLFr-IJ)}l;H1B2ltU*Q~cp0WZHRTL@_ZYLF+$l#DR8hZ_<*+ zIR&9aD!&dF(p`X4{wy{+={!gsi=vDI%Ij0m!awg#aKL^yFY)tJp z%z6PW6MvCgu?lEk$l^eyEYt3z3c@j~;ht^}xn#E(ttZVz^0k3?_H94+@mUX7bZC_1 zJIUd3?=dJZ|C(sWlwuvf8m}IdVI?}O!Ef0XIAu$7$15m%$|Wmu{V6r>I;7huKXaV*Qb1 z_k6_uwE~pAx0ZdOmJi*la^TG#QLcgV?i^{qKu70PhOes(JGN^7o4sG$u7J*yov<&x zi3Crl8R2v*l#JvtmZ{UgsbVuYSGN&~3{x~J48TWmlgVk5kC+r)gO3AC*x?VKLFmT^ zxT8gxUAIqQLuMdu9rk6M-RHxG8EfGj-D_WpQ^SZXQ=B46pRZ2)FCOu+;FS!k&U1vJ zYv-Z)$1n1!?F)B0^EH>fO_Y0{D~m;^rEsf$BXOa9F$d_p?cp!Odh5AEzOyg*Umhk$ zT#_-8KBul~Cc9I@7mnFxz?s#*iMq-x6mmR?>G$99-13}(n`;Yazl(6X8I<+wCxtpQ zJxG0@JRYl6!NUDVnYFs-AaB(*7|I$UAG5S@!ZaIPd$iU1y?HX`Q;lWO^TX`oH3^9mdYdrEjvFA` z`&GEWtO648-vd~&vI`#MJSW>SuVWD1EzPa2V`iMr=e4Ux?&A7b8w8rp~Tidiv64USisQ19j-85^L0L*3LH z&sC6}@z+uK6wOg?k!2rWUjj!)BH^vgPco_C6LzHw@b`bR>^I}XP*%Jb?rV#1=bWEn zc4iGm+`L()FZ2+Pb5x&9-pamrJ_94Yagam3_mBc;2dfMI<-}jM zWP+1+KWJM%ARDiL!evncR4p`S-%O4GvBvW-ctM17f8m9Cw42_Qca^txUK+I7R>9ES z0Wxw&31jcf#-e#bOs1$hr1dQWQ=48Qk#C4$k9}}LW*Z5O_JTpnt?;K6E0rI689;8m!;hOfuFVB!5v>ZMo5{s!7@B=?6G z9jpOvjVyT2=p*}x49*{Gi7Fc(khmvN_+Y3O70eXb!SQr2w09WRbiE;sHVs(hBEZjb zvTRQ16kO_SjxH&NrPGY_Fe0ZKFE{A33%rA%Z8RDFGw&nv9nl#1vh0#^ zk2^D28yzorADIiQhrg4Os?WGEPeAYOPZ(=gN07`}0>8|t--h~Y<{9{5k{sP}ODdwK z=w$r*F_1Cw-3;8VAjt6?AY~)!XtS8Xxe+^TQl{TPW6CuuTd?t+7GKh z6WYHP?7<4|#DRrpEj%{*Mg}YmQQYM?x=xzM%)C+ziqumjP?6x$Cd;9nloSqhr0}wA zWxzpH5u*HPhxi#SJo1-zu-bJ|=G%CD<6w^J_OqEAFXuv!_-=6Y?IYz^4&!d_76wM1 zBraNX4(Su%>sN;C^IhM;ba5jTxJppo3GD_q5}>QzbEZRkDY#Es2|>v;>p{6yI;-iK z|KJeWVRRS2ds1ecp)A`ev=$o2gn*6QUvep4isq7L<1@=7o7k1~H^tQAjMt&8`jka< zMm0yZ)aPYaS2f}_n*DdoTF)lWq4zJxVvv4BcPP1K*h=-ub!F!m6Yl{MZl=QBvne1x zhe|=&xeLDPi{}7Q53IF(sQPf-HTHkDd00a%L`|>Vp6rS-p!_IH?gGt0;^tR z&qtYZSysPgDO9#Z!kMc-$&mwJ(4$U(>Xou=M}Y_INub@^XGFM}&hl7pNc&KvnjR|c zDx+L>+GFmwjrG(#3kkJxaQN*2xu#7!1Vkva@j*E6Ps17RMP$K0J!Gmy7U0{zP+WYU zXd8XO+f;8+-DbjO)J1?)?0L|CBEnr?L+5<6F?c#zpSQ9<4O*X7f*tj%tf0G|FSM&y za{egKJ5L=}djId-{=I${PNF=z6&`IQ{H8a|%iIFTTSd8fC33hfRti6zUtD%5=NUf9 zq5SrSP3-x?ESTX>pwMWPpp*t4`e2Hy7X|S2<>a}?ZAM&MZvr`KkOw!IZ~wIGrjl8x z=;ed+6M~rG#Zh2jeFm-=i*fYsfkJ%}=$k9Y(~YTv@=IN?GKBJbD>P6T%y4$>AKvv1 z<6+em7Nn2&k>EoLxUSR&clr{d_bduaeFf-tR)Gx@rCc(LQ3zh#N>-6Zoa-*Yun1Z9 z&sH7G6Ej8WC;Fw;`|qN5X*FKlY{1T4cpB8&lHpEXA8CA~jIKuWQDtcouP5y~7vtRW zPscvk;D)|k%P`C76;XfOh}CPXE0GyA}y^CAm7ddz~q6b=}LWI&c?l zA68>p${zMcH&tC?Ucgl6-^9RO5&zKjK!vR=Gpsfa);)2B!#jFNx6~4J)0u;|bqzd| z(0=YN`-@Yh{b*-xLd-n6dL~IL$ei**kx|K&CJk^tN=99N`F>s}8~``%W-R9ymhK?IobOlI{d)rpc*O z8KWO;B?B{-eeDub~h!;k23$~30abNrho274s&47$`Zd5b;NN%dpoYSQM{LwL)tO)sn!rukBCGbA0!+wQ1o*%$|EA=PS zj+p)9#$d!)Mdm4Q0o?Rl3l}~QllhKnnA%MDj29coy{{?w%efk}Z^^Q%&zvB^>pYy^ z|C^Y{b#S7twOn49C^tt;79+(a@P2+B*+cy~@}bITs=_j^(L3Qv&?$N!r=3Tcn&`1< z9`34hA@fS^ph!I*msjbtS$F)wO)>*A7}{6+*#s|Y`eN(eHr{0FK_0Kk!h2m&u5(Bp zyFW?F872{KTzT>(Zm3v)jXX(5|53&&V@ z5`)a~7(@Fa4@u8vHdW38w@bSqy`YaIQ~&-VgE`2|R3cjX(fGrg-i1dE*nzZe82`Be z*fpD?{lW)%ToFtaf0kjAhv$4b`$>!RQXxd#v`N?xaSxLi%Shn62O(dU{IlOPev0_w9@!Pr53iS?TS_JsW-js#tNVvE5JZuydW zn&t5Kb4h$XW^q}U=?mOjS%V?@o7tOL*)Vl3fxKIzq=EQ%30QU|9M#8KgG# zlaj~Em{-MO7cCU>Pr1PvsI_o^kBe|IISyz{bB?O*WkhVx8+><`&Y9)LtW)&`sJ(j$ z6nuoa5txGa?MyMce=o0}%g2fr)#$fxFRL?h8<4Wdp9_AIDJ^nnZA|-N14+-D|&9#9>DhRQH)lc16UZHsy@>-q2^$JCB2CaxO^O{U8B75tthmh`UNo zFj?X&LGjdLD0CCyWKSK(Vlh9ISXfE=GdPT*vwilUA$u})3uMX!!8-a*?^`|wf6u2~ z29fJ*_MVBwNUE_6)cCRW7S~~MS0l{6`iU5tc4Ac-%@W?+z{=gFj8p1s4N(?H z`66ZPw!Y63nXCfZ=2|etYn1#@eFl-0ozT+KOj2FwUZ&Urja03eX{U4{YMdK9{q&It zif5xhECzIPtJE1)4J-nkFHGM4w%+goJ7nE%k61fm~x@+KA<1mqF)IhTfCY0UU zLpOTYfKg+Lzm)ewHAk;&2hB~#Y1)=iZ_#q4^r$5sJLCn#gE z9?P5y*addnN%*mKgqRj-p}FlmJiN}8qz$B^!dE`FI~%Y?`vL%8ro*-99#VDN6yGd9 zg!&w-*`I^_nO`6z)h?T1PC8U-veQAWWDPsXp{JaqKL0L~TSK0MXN zw}F-z;@D!X-jRxzYUvrMc!X^pOn_NOsRrWloxHU$!L^HMujnZ&=5pXYdN)r2p<5E1 zsh%88HIkscCdoY6HL|c*M*$L}g}JQX+L$kIgzDj4rceH>7Wu{3t zE0HO*N5)XR8hP^!*dFblaHpUFyu>8A-27%du|$A}$O|U2c^SO^;|OQ?LY!61H1ras z_d7#RBKfocmCsgVv638{8Mhu5<5?(c{!8vVOXDpobCkN6Xmj5)8do_~YG5S&u`LW_Dyki@iv77Em z9k1}&V|AZF+NTQyR7k*$QkT1`;fypm{Z#o@^u z%5J?X$NrbN0$MU6LHFn{x?jGCdmRFh|2KmP#v_osau3K65l(cLFOEr~+5Ak~vLr*m zS9GUotl-X`O%DNy?Qu|(HAq$tsAG|qHO?O&&1*0S;VMh=|M~Y0KFfj(nO<=9y+`K% zy@=1Y1fX8c8zy$sC8*Il4?6auob!K~FyTxkY#kgVFE*-Sk&Y#<^%7%F?;B4!OiN+@ z1KQI;XTvA&PhynICvs}&I9y3{gXpDV95Y1`A4*B%@ua0?UkhGhQbP@%3Uy=4b8|p? zxD0kt?{V`t9UM=06-$Ccct?-QaX~2tTFOp~PPgFv$AnG$;NBcAtTJZTT0iG(AV+X%Z!LnJj zUuLX9sl)g}oJjL%Dq)7K{g^Y*%_YNx_I{$6HU@u$v*=iv$jer|$u&qf|I01@_tF8U zz&!NZQATbJHRFm10rgp#u%;(3!b{qBWgaigsnfH1nWzaCkJ-y>kfj+GK{bAvv5$3P zQXn_<1?VL7kXV$3INKJA<=x=1V2~7BE93eHCis0L&6PilL)jpj zp`f1dHy%FVxF;79&i^33ya@a?>W^W?$Cw-8&M+rzF$lGba2qI-XYGJ5ihipkyQPu# zo6)o*)iA?;ZH37#fzWI}ao? ze+voutcpVuEO5)PCG+`?9_$lxqkF4Qvq^HS<~oMdH!ef3R*5lP3KAwC8M$g%dzU0~6VFwk@CA=g7Xxw*zQ|9l`@^=OX3 zOac=l8^{{zJrJLC63o;`$&qi`XuWnGPMffrtguMO=%0LSYcOE7P6on*Kk2aNNH58| zwHka5Fi=+{%6+EqPuEK7laKHqQ{KPAS&=pPaE3A4c_18GGGk!UP9e^AdOF@|=Hrtm zM_9QZw;)Kr77QPKCymm_adbg8?TiVc-HWtCc~=Tt{Vc&9eJJ0%*Y$?-9}QJ;O${R@JgH^AoWlH54Q zR^-#&f&ayqjPmE@5Ehbs?$A+0X!uPw8uyq1uJD>Q5wciAoa7>=v zr0oTVM|Q(S8TxlTMSb_~0r+OnwycC^tSsofC)McAzOe{}l&`V>&fBcZV=#nj-EGUm zdE%)d+(WtifBV6z&sh+;{Ws_ql#tbS-*C=D0dAz(&nM%eK)Egqq)&-*ya0cU(hJ0j z#W#3|JE$jQqyp;443QuW+H-e;>iKD+%-h8iV2RgKc;4Sj)K8n?nBR;ul^a{ zu1)fscZdNOV-rt4Hx*E?V;9_-2jpBsG!8oP(YEjnvp?xFw1ozPxr{hB_qHsa1~Ihz zB+DyudILdR7etPHCkhco7)tZ?d2tcU+fNhW&NT)!m-iE&?Xu{bI2+sfCB&yO8kafq z@x(!SR-E1mY(W^$rneJ~xKH9JbV1;RO~rxOntxxr6+4BPhL?6|LC7(7JWSf zvu`BBb+-W$@=68ArL$PQJc*}2KbAYE(agDqig4v09Z_oEJf!Ax^5t?X8r>A&1szj% zmUaYK(p`fICIv1R~p?$y>Lr2-QATGsRuY4t{)NOTqgLU@m+s> zlRJ%xf1?7+ZvOAQZQu9;UbuF_cFOfyETM{`1?EVy<}uZmXM!i+4KD8fOoB(hq3w3c zebRWy+D!Ql=I$Thccmyd|FA!99Uq7q4{7hfK6|*gZVl}x9woQeOvImErdTB3LJIQI zQ9$Rn3%}*q7r8EwJRAnKAw5KH>oz<)IUXBYEO`q0UEGw#)&KZQpXMsyjs+5k#~Vr3 znrdu|qFxRydG_Oqz2ISe68@YXB^Dnxp)>VbcX>n+E$rFZ#Y>dEw38U&h8(y3P7 zOY%F{K;2vh?A64$bH23mH(DI?mL4WL3obxYKn$c&7UlaL8QAuja+uE@WpyNzz*MOg zJ}m4elbSE%9}~*Q>%GZ5+3*0?OVPZQmLxY}ngTvHmcTyMJG@a7IZ%_32l=DaOKCZU zGNBF8^;Q>Y+)c9;)JGI-_nL`Qvw@2_J0a?AKhX`9!L?>)*fUFkn7+D<;?!3;xYmF@ z=Gp_7f*WAtA4%$|ev2-<1o+eK6(jp<1ss%cge{uFoXzs-m~3Z)$y+_hmqW$)JieOp zmE_pqZ5v^J2i=X`qdZ&6+5P_B3@=Yeve}t=8MA)8!nJN8toSZ_^tft_XSY8qTbub7 zZ|Mq9aolFsJFWosWf#I!>QPL$_C)>7ff(ax$V4O#6WvZFE-WUW%%zBDtI{rb)cJ~- zT^WN;SvJ@^u#gdN)&fft;N0fT^+`B;d zq7Y|CL!|S3YVcRMfVq}59>x?I!Ge`TMEZ*|cGVjH^GFMwN}wqUK8|dcXX_6;!M;&#R9pAuu zj6RJ8D|U#)Js5}0MHVk_L#D@ zwe)X(F^MFNM7S z{*Y4_m2h^QJ^t5FOpZSB0dLLCkiJ)pGt*K+esC3$ISJz&*ynJdGN8PP<8;OCJ+YmQ@#mZUD^_Z3Z$td>JLS^3lw>nJL|P z1y1vVp>lyZw?c9edVjRUPo)ca7GfHNM>2ZBp6)EKpypm zeX68=0Q-zrzdajPc4zeUd!w7T!+e;}vZ~R(z))xYNC1 z?BAbcwM`Vt)Cb@g$CFHZpbOl&Y!7ECvm(vY7dPblVz&Ad!h9-6d+8c1;Ty3Dk?!z0 zI1mbG4opvf68hYv-sV?3ZT^p>^Khu~{oi=oX`PmkRSNMz+Jovm4@o66qG;F|g^ZNY zA}JCY$cT(6m6X!BpZ7ZnMV-?UOuhqp8fL! zs_a`qN>Yl`A9)xTPCbl<%7Ki%oCAcruZA|tmst3dvhn?lu=HUgi9DW)10$)&z*CX^ z(!3hRBt*ht=^hfPx&<$^UO}H-mV!RL4sLCBSIFQhw>Kp1jR<#Kq2Ifk zimc|5ogh_o2u{`iB{%&&Fz@_f>}Af8$VaI-S4v3xz4X|2^)S#me-~KuUQ(eGi+1;4 zqGp=~^ZB<6Jbo#F>no(Var=~TW1tLX*X$+7=snVg=A(yq8nV9|Ps5s#3Gj^eRpI?( zsFfLy`uB~k%WtL9p7~0QusgtpXe5JXdlk$t{y`K5Y?oH4swqA`GuK6M44LV`eXq-T(%W7 z4El)Epio8YEwCF1rw4*iWQ(e}+Owy&lKd{(@M0S_LhAK!`+hpX`BoJz)~ekn9x zUJ7THi*pi5-k8!Ih||MU$r@)q&JLY~Pug6VeYf3Ve;(!Bj-s3aX+^A=V2YI~$=24w zI6OW~JHp@u>mRcWox;sJ6{d+*u~xU+;qu0IxFjadbxIt>BVu9LJ?%X!xWONvR^++q43fQm=4n9qlL_(TRSet8sJ|pMAOPAauR(0#)kU+<8_O z$M2BEX`z*chkZ-%^(?BNAKuFDmyCqe!porDHAuR0)$xEn?XDdcEtvT^g4;Cue=}Ss zDGfI7`vH5Ba!AhD@Axu|X70uqQ;+L;C|(i?*}an7I5}DDqWgGX z_;@VZQi)eSH83Ii@lYpw3?$>FIpYsX=uh=Jk%^Mv(3vLK*GAcfxs+*Um4~{9^p0~b zhOrKu2y@B=AfEn*oV1h2LYkX9Aohsh2W7{FXx* zZfp7M=c2d}4SZB4y2Zxq?>OBTS(|)D&gf-L0=IxQ;)9>D_!|Fk3Bo6{KcSzx3>{ zq)ogF+p1}f$jFnGiO7TJGHKu}Bh6jVsm6O{G{gJ%1Y_k*`>5wk1hd4y2bb zS<+0Dltv>*^Bu8^ESW>Q_27n*CtP;n zP;!riK>HptU$hmKzg^;kHTWF^qhGxU8#|atvE6c#)#}de2LpwW?cB7^n?MPC-Pgdm8okE2c zdMCRuAL2crc-8-A^{)A9c(~FM8};s4TmOp3`y(nbQ!9dPDp-z|^UcsQx~fRC_Z`ll z^Wyw_PxjZr9MBWXh7~U*xbq|c7lnu65;sHUz}Z3Kxromt`ec&U&re{+MS33>7n0Z6 zBXQe3YgALTV~YOMfxz`1Ag_KDr|XzNHK-msLngI5!9L{} zXn5C6R#tZ5o9WePxm<~5Z0Jsh?*-jnl3bUFhd#L@u|N0Tx?_rozFh)d3aG?$k&Vo=ws^Q)7zVK-Y0k%M z0lt4~hP!I!3!*GqV6=1xSY7QTl7}B-xt0h6`ePV9OHFWare~OnKScCH5w!+QaQIdp zVHVMR2lb^JU*ogPDmffe)CugVI+AwrJ-WT8&xW`Xt0y}hL+%@5L+$JW7_Eq#`zPYw z>SIi*Ndzc1Cj;3@c@BS-aKSZmOEFb ze~y~73ELQQ7S^ncfqfygv*}U*{@xpgpN%pFi+4Rn7ZnjcU$u+X%)JX8+ApcMvX?Nk z)lqe!0F`?c7#oRk;ApxM;>Pz7$F4t|e8v}UoW~zhM|&Wlz9YK~}i%m^t|}>IQ0zqaAS5XS33ML2&JK2CRD4MH&LSslTHd z|CUxT=`Wn&P0vDT*)Pdm6<5HB7CAiQxQ{5nA0y#_OD{>d;Dv2wSJ8f(l|cX7 zcg|u_1-JHyB-cwjl$qaB|7P{YuQVG)GtRO(e70%G2jZFn;HZ-r<#lLd51k1P4lBw0 zh3Pm;i+b0k^jXKMW6k#wdIAwNQx^gN#{g@4A~76?Z0LGiOZEO;)?Ni(|G z7d;yXXbw6mBp>gV(+u^2I%bO#3rFs3f#pBw* z{y@9ks_=Lto!iHjgJ8oF@S-|Qal<|w6&8g32Q$c`fPD0(_w9&{e0Kj&PnfNL{GZ38 z)Nmv|yJd-Qg6>&g7*BuZQI$A8EP_4%M-gq^dO_;x>7o^`A8_>8Dr6$ovpqW=!Su9; zaCQXsb~5{MPi_!~RL)}jot^?*rM$cALSiO81|6x#RW4x>Bfn)beAwv$@~KUvO^1(# zw|XI6=DoFT&H#iU}&Q+8gz$anB=zB1f$rp}?Py1&>L*pR9 z(Hhu6J;~$TUlG4C$>{o?@e)EVAp*HQkVZC^B40m@Ov-J_Sa?JJ`I4LYRU_y zx||-(Lq&Y148VI8g}KX~q3Z&=E7aP?R-cZ7sWz9XhC4)#OqhtBH!bl@W2`{YJd!(a z{=c~$_BS0O^?$&Db&trXReV$)?1fx0XQre#79y{ogydyXT#pg;bkTF?XEj~H#QF?) z)>Hx?>1U2OtcmOFt5*>IqjOme0DS$a13?$<-2ck3uPRJehhg*12f zizC)}TVd9Q=%Se`YO#NO70xZ$#C}}&5K^5AA&znegoiXyc@N#=h=mHm=Fs^L_$;aXQ90R7F7c?qv9Kbb$CwQlq}Jx%m9% zRe{OOYuvT__5bt`#VSSIF}4?OwH+nXT|S_+MimaPH(?cw&Vk(DGf;9*f|J$p!%UjR z5RSVqm{XpQV>Rh{b@FaDH}@XAY%PaQk3QmVJR0`|F!*CGpOMNL2hLZVz)P`**!u9% zS*913*vASU3j4YB!cUwR?VW#rPY%ucN8sAOW#qB*bJX8Rd2S#1>`J?Zko(IGOji$) zJx`MnslT^7Z8m#veh4@kX29NM-DG$PAICrLf$cXs1%lW$&}X#}9#l(mKk`}h{cJ_q z&GF=t*>ik5TZFG38nS^@pIgx%42s)^Nc$&EdWE*a_V-@a2lJCLlkQ&{XNRzF%#y%* zupV+|wUM`5=;y!e0V}OgCd?@x_S>Ywkv-Df*_u&M5;Osdl*PE`YSpksj^1G{TFEMg z`YtFJsD8H<^Tv2CD30(3t0}aHQQQhU4;;nL0!=csy$8jp#`1j%$8J6U3qIAhzz913 zf4kM870s3VI8-x-^Bm!5)+%`Z^Dn8$(!}lQ23T>rk*K(5;CxHk0hh~X-`KAMEw4z> zdPteK?mN&!{3_nySqt{;{lSGTdi5{QlB%tO%9hgjn*Wwq?W)74`E-6-DzPTCL+NX5 z0Ei{hOvjlFd@zHaOV8@Ft>=z|^QgNp5Z*^j{FHI*mwEK8mMP#xtOXSvD`-@b;wpC6 z;nG48KG|i=p0S95;PvsK>n+Y*Xr6>)>y7Y;#cQkc`!aB%yb#mQ9%LJ=Zo@G1CEXp{j@$x=w6LHR_)E__Ug`m{BEK>ck03)gQY2XW=O`5&|wEB+0xwpTG z@0Kz6G?77*xOD3P!9^rvD^c@Z1S?$0M^!-&xMrO$(p~cj-|eF;^pXv%tZ6O`=|6-A zlO?$g+i6DUbST#c47<}g2SKMuY>iup@In7HH#P&0*g(U}a9S9YUu zv4s)7RxcwJYj5KIA<8b(P-2HRJ44g8Gf=nn7a6yYj|2O9AZCg#b1&@>#K>)hjw*U) z{-l64wAa>VT~*QFU^f)WIdo)j zp7dTLn4JNRSshdx%psab`PduY1IZUxF_#|4L9F{p&^#l>`At*6P?~Z6wRfsO^_pZtBT!s&^Nn$iWQfmD>mk>)m8nfH$&OyZGGk`BBm(t%4vj>83c}|)@G`$c<&7l3x zUAtNN`c#l9DTl>G_us^G<&^O^Tc2g8 zgu;4_3^-ary9~bb@w##k#P)Rxv~Ih=?WpaNbm;9=abD^Y);i2seGdAFYd zOv>PP2>KKZdHiAW>dQ^+ruz2&lOb%|=Ibzp&f6)^+lb>CK5lgR1$SCQnCyiG;Q!+u zJkONo)?6G7BaJ7(YDSDxOs#=|sqM5>@f}$qHx}`j2|iA;Vzfdm!T0x0ur28$;ru-q zm6wE#B@SeVejln9(`V)v$JXxbg*m@kAd_a?w0mFUetGI$*REkwGZsU==_28|#$*A6&?ym;Z7r zv|tQbO-W4kdQF_f>+uuy=ng+uVxN`ofuoB8AmoD>H~eD~TBI1F)YuiI?oB3Ynh9~W zwgLO#QaEh>?=DPU^_#p}qJn`}=HbcwOhIYhIuNU}1poC?T;H}OX!f5a%FIe55xjc* zA{3#Xt_dsmHwMOQ#Y0@OICp>iWZa@;g2&z8SUtu}M5>dNtoLVqJnulgT@?hRb&>=H zCFCav@Uo*Sb6<>un@lo@Z{%^2iVk>G-yGf2zY5CqlwiBMJgo1gy)Zfocuq+LJ@%H8 zlM9PbiSp&tdtNh5^X5Zi#%7RMH$bZY@NwogBh(F1A`!8d@Xz{6v@4&@2A2MTg0vcV z`+>*Jcld%0TovtitYXsUuB1%LC7?~&JF1NVc)K>3?mn`pZ?*_!T7+1)PKllWXd`I; zI0h>ss2{aq3`z;<_hn7G^-r%$Xf>7U=L=4*VLSuoi_lJh)XhHq$gPunn>5gvFB6@%^2W>`f6mX5-umo0I0#6spv=Tum6!2=w` zT1dI*Gxj)DVOKycd-HcE2;{%PK@ACRvD!hLvpEQ#8HX~zOeVseC_T8XGej;<7>i3C zOi)Vp6=hT3!V(D~@=KeEqgrhsnO`P{3_&Je=GlEHs}} zhSKgd(^|frO=3>NuFgcrs2V26jWqC=sWHk+o)OHr6vege`rqs=So{z&4|l?E^~YqL zZ#>-RpQPV^DQ-FS`X-5_@jhQi(DUd4)Xpq{{C&g3I!FVJVvO;-w*<5Ht0tUCu>;Mx zUUH9i8!eu}qW#z`l3Ex97i`u+l!r98>7*^z4bomTxsyes57y%XYuammY74tQCI>tQ z3Sc-@oQt}rjZ+UAVSZegK-FG>3zVM1WskW?ZeA;ZnGf2*&EN^~NWO%xDHo;Ox|#8{ zz6b}qL*e;N8Lnir9U4$hApe7nVBME4klix?QG3NX(_2Lt;w-|7pmU67^du0{U_X{sO_~^F{b(o(R8H?qMyO(;zpTdcwSZ zla-CCxYofOHGlG`cXtBtf2@Go<2~g6dC}v2KX7la_K^*&98PeQLD>6(e0EmE(MweE zQu0Eki?f3bfo>4nIz$|1Y2tosnw|V%M*hpcg>%h?Xpp1N;=WK&R>^>-!EUlF*9FoJ z+QJO_ER`%)#Od>7ag@qBQn^PFySAy~Z+-wH7q$Zg--6-ss$tTzauRMWwZg@Zwpk1B z-ojiR+GE%o!X7TY4ieJTn<4&<*lgnCjjP>Yc`bw~c~t;G6H>vwSDI7%R*yYtG*>k< zk{P8p21<@kfD@F{o_?$rw9?ukH1{2m88;Sf7nT3!{J{i$ITq?SMjvkG3AiE-j|4X7E94Ib}sUkq>=Bp-r(?8+BNguguRw{7HS^GK@nwDC6{Vr>ncNZ zds1grIVuak=m~M2c>w!uK?-Pm6oJ&2PGVNZf$x(WkaLp9%@W$9Q-&$!J$(^8d8q_H za^#>_Rf5|`_jf9>bpPj9O7xNm2L2M_+SGcc%*F;f1e>AjD)qPTRYHqAL(E;PM7T$Z zD4;X;B&*LZi0X&Xs%n`3g~zQK_=<`&PZ1kl%_zF90-4IiaQlb^_c28g^RB3%!Js|i z-z2!FM~LPvO6SwbvctY&$_C1-bgN@~l)Itk0PSBB(0O}T z5vNcdrQ0%fX30cN_`O08%4oM*>!fkG*~kP9qh1lm;@h}QQi!wKl-NgQl-ExERd;HC z5#34sc1Sh?kAosnZv5;C&2dN z2r#31??9(4&Q+F1?vb`YK06CGwLSsEcf+LIWIW#AZ;B!MQcS|ANpR+Y9p#qx5yel+ zsCAe5H-~i-gJFrmI{4Bo&DnU_;Qbc{xI*hhk%_`v%ve-~J-fHEPa__|P)Y$DqFhsl zR2^Ku%m@uWh6$WM@wue0Q@JvyM6$!62zFEN-2I*>L_9_r~IMm7oP5d@QSzOhH)FViC1IdLKXJ(9Yu7xtb$5&RSFE2 zD&nllu~_{(l-X||1+EP@Am#NS8R}5Mr<6lDaY3TsR@im!=IGb|GA4U_>*mq2XN}SYCLc%g!#O5fZH1Jj=Q4TM^;>x zNAvMAcxQDPvFcRBrbYD3vt}XFVB`QN64pV<)L}C7jwX83{bQ898L{)agBssx{#szb z`koB~<&bpPWciEm77pNAziMnfP{nLkSPR=XEP&Ocq_|QZ&FO5U8gKtva_J}S!mw7s z{d@fx4_9xP?Hvr8X~z7^`a3wPlKO$&LfHlJ$*@LP4`*L}Bj-NwaZGe4@VrA9uW3aP z>_8bShB90b{ryWR$YS{NY=N7R2K6tEhjR}oPrHcvwidO6b?kd$vHT&LpBJK-c?0w3 zx-|qi?SxytluuqLk6Ml9*zo&HQM#}nA5yRB?mNh4%%!XX?-qC;BEv0GpxrK0sc)RC zWsXEFg?_V@AhA}ACCf%RwjizQ63BZk(>Jg5CQi(5&+{DVWlLm+4*Ue48>m&U7El^zet-3&c66SCgq{ z+Xy8sR}v%NhxmT25R)7XS4G_J{d7a9$M$KZW#NaCtJ?Pc=e^ZS_`y4G+=NUWgq35X-K*3yGy7$k{>J zEHhM4GE0DglhhdRGyv!AHz42{k0VzdaG{YYzWe+|5Z|c;F5hMUX~kz}%i~d+!x_kV zLY|2O+AD}K!RHO5sJnoAPBuZ#vjOt%mI{8dG{%%3Ws===8OKuZO@9gHsu>RgTV4%1 z-m=`%o8J&WP(5Kw4db}q86<-i!%Uj32$lf4XQO!yPi1zG-4@V~KL#R~eqt3n5`7xY zFz)Xi>+|`S@sU04AXANG4K!BMt~3+$E2$~^xt3;;u2a*mgKz6 z590*;U{w63&-^m(At~O{-2CA?WL8?R{7~ zrMaSgc9gR+2} zyx1d0bK&IX0+7^};9g$S!Fg(i*x?x_DBY^aDJf6>cTS#jjKImi?a&!kLJZVsHldLE zJTqIEl|GkX483DN{UpP^v7zjurQ$e~_DtG)0oKv~`<~F^=k8 zI!0dBJy%kYp&n+%;!t*6EX_nl)q|@}JMrotq@1y8JUwR%>pzOXh4#C!!AFL(ZPkGD zOUJ{c3hLc8djof@+97EE2NHED8)qa4(V2Q|)`_Wfl4GG#le~2vPZ+A-ikh zN!Xp00>>WxA(*3#haXwtflK!V_X0g&iRD~~Znnv^n^tG>uqbBZ||{SGP4| zn1W}^>fyA8iR#3s4igO+d+Oc8Yv&Wevo{&Ubh zNQucve~6ps}N7wtLQ>^-=Xsj*rC%y@X@;(mZL1E))RyG zoI-H^lTgOcW;GnCb%YS=i|D+57)1#|*mWk0qnG{^ z#$fxhxp?7Ds&)RSEBJjGWg8xdWGj`{;B!fu%hRYW(lzYBePvbnhx&mdTJzyR=>t$4 zlH|7X0&z{uQ7k_&n^9NqBWWShoNsap`Pugpd>lGpluHfKyr_;#X*ZUSstq%A?LVlZ zeA-QQt>o^&ARg?h!ZNi|!G+K5*m{Cy4Rq^SxnDg{EZYW3KP9;8vH)DQ>)(71tQn8m>6BMLqk=@uyNd(*R1dFKW))@D!qS*%m@~PDENC9WX_?iy*I13+ z#00@p-e#CdeW8Kc3V3>rH177PC^Sy0z(*(P4$Iw}4X-={lY$aKah@2bJ4Fk#kD6mu z(Rslk=hK|;yZisrsV7yJ84$+^EJeQkHDj*$a@b6#b{QG20T-gT zyCLdciYQ`@nlO4-6%JT$V{e|%gF(FlxbGvu`QbkFWWzAfrbJ-7Mv-f;)#ir0E|5<` zfW0(Juz*)eR)nhHy<%&0e!rOM*_jB=ilNZvHi9cm7zST;aV%nGxZpZp9AzGgN1joLOI@JoVF`(!S_ zvyR*QNP^R5FVHi75Z)2+xS_5#Y<*6@v$m^-ZH{)AN!{}16mr&Xcmk1!cQBCTV+l0*+w3-@wFxtoLUa~q8_s0>@b=wtU-s| zP$qn9KldoEnRB4e#zzB1taOz@Hn*IlQx=f}-9PGtsIZCdi{MQu&BQJnCZoOX;y4f5 z>9EX@wHR|8PLnDo@c+md#o zYBh{Sf2*JA(hth^sZ@&>cUS&XViwVub~jcku%NT)km`Nr`O<>DaI)1 zt0~&p{vDsyQ7^~&t?bfg1(3Gk0SwSS+(n~~BJl}AsLeTe7>uFTz#H2srUlniGq$Men4! zIQqv{LF}F!*zuwm=6v`|MtDBL38g|@vibs(5Tyfu!xjSndmmY3riO->1k^{8MchY* zLf=SNn)jFC#%eoZgV9_ZH*}^5i<_}+cNJ!i-_FiWehdzs`LLAEw4H;LS9akTl5eE~ z|6~Pj{|7DZlxzaYeSu(jy#uz*DkbK_Dwr#2jkm5XW@5E2Lv(fssGc9e{jIY{$38=J zZJIB5L7y4f{bKZ4k>Rw=ebM4~FvcXBGyWcvVXB-ZJi5_OrVpv&^yNl)KlCw~w*MNM zP!`SULn^G0vJeb+cEV6VBWXJH1I1QX<0*YLHub(Nx=|*@$NTaHmeZc#=U@@8nr^}- zO^$}=+zsfVZ29aS4KxtVMWq+l1z+AJbE1p2|8{&G8!uuueSUtv<#9_(+wtd5Auc>; z&Q1=BhbhydVY*0?v#a3Y_F`G|$g~usPI&#d-Qur`AI4Ko>kEVO54>ZeQ6Aq$9=}^^38H2mUinFt-QEo*o)A-B{zLNPsLZvu~ zWt2PJD2)>HT}cA%46(l?!s!o9*$*~*U`cZjypR^-)D3e{7KFI2S3+Q>OmiGG2Qm3n z7(4CRZFu2Q4<*w&h^@U?vAHMJ&}MnDr<*vim~of>yE0rPWkl?)m&Q1$EI~PCKR!(v z2d^fJa|XK`K{=ouTsl9J=jOTiB%696oSPVrZtBbO*#XK4f5@)!3V3X{2_8N0smN3y zR?Jvd235 zPWS8qEoS8c~F9LJ5YRjXpP%dB8VfL*T&F*N5p!Z=nxn!$~wIi)iV}UAjanuta($}HJQI`84 z6-&m%FJLsM&w`ybl$9~#J1 zn$r-b{nMFMMUS8-vEv^TLzE*{T=cLS^RHO3Dhn=w1e^d#MH#NGzy^Ennd9e?n+5x+ z5AgAcV!)YV+@h3RoLfhk#x)n1y$+M1Pjw+ISNu&*Qa<@&Pa`~j_zoHWpCfJ&8sXrJ z$fCs?TWMEY6`H8+V9(vlhr5sSq3f>%_jk))oKr|M=0zxYJ5!OX+4;ZOd-8KJ_55_e zl8{ou%^r!GrvzvrTFTrww+NdZjj;K*jUd2i7``nWhWC@CIgML;v9T!_^{5E#GI9#g zKR&oT=_hVuM&o^TGgSIjM69kPVGZTUeEzJ$)>(C;z`q*hYt`5x!lOSU-67e^71YI+ z;MME28>PmC6(5L(&xtpH=STTD=@V$zl>lv(ZV4I^ZgMC2|C_ObW3u2d?>+ZZXK&HN znD3Z5QG|}(7Hr;{1mMJ?p=`1g=ie=dw}$0#kAy%F>{^2E)O#jdv7c?4mIcLeWpJmv zpM2>WhYo#~c-e!`IG&sYN|nq0&D$5d#f!tfRbxSC7*n)ZK3oi+7rDYf(J%?!n1FihROB&7yttjdA7?Fk%C7AB3(IG;K+1j|CwKlG-Z@f**Vs4A z)P5&;+d%v69K<>O*vaVRulH}>BJ~F4~#P30?%T? z_#k|`jP@+}zr#T4xxMLT!A@i2Ad-!Rq`MNFW^5kjdeI&+<_O#5b{~SC3tq)K!wGi2rUc)_Ru}uBh0frabeB_{Y}}+Yh`V_$v+N7YV7KN0mK(+8x-6)3Bd1-0C}d zz}qUyD#EksyIGy~v+(-FB~Z;0 z<0386F*~;eN59cx9+;frRD;w0`QO@}Xi%mX2o!1qZs#7`7!#?-R|*C7a6;8Q^4(}Etpx-&Mf+l zR>`B?ixnAUlsFFtrZsbwfhWnu0DIIi(MQu05k-kA@A1#=D)iv*WSQgwaNd{?yUZoI zEr<4F%K4U;MzS8%p zzqorkrCf@dBv+}%$J8gi&}<8p-kj>Or|5c6Mb36c~Ci#K-DhY1En0yqwLGQV& z30o3>3eu*g008w&(%iub<@vaKU$!8=eFUibHgbh!SBZffAN#U;LEUZ}S#S3NZ!M-> z>Q-~u!n!!RUpo&ZkFxTl@-ZNa_M(~`WmV{&_SIb>l*a!er_#q@Qsg{bvwSpTVaS89 z_l;b@4J#t=eGYew2*N+_r!v+7;*gj5gY$dzk*su+!zqV(sA<3vezXH{y&Hf{9wIY0 zPQ)ftD?GGzEWxrHn2=S8l533E3RU_HXEbtu^i+w|?q67COXsu18)jpYEBLxQ{L?G^ z)=>V&LE4FF%n~j2XZUQD2(3C)*`vF5g8YFn*eo+hwCg8eUyLQbewl9VcjpFPJ6?%V z8mHKM#ykl6+{h*GK32GH@-NhsuErxF+u6a(1h%+k!iQEV?m{TNr(WmbMvEfB?x5d9 z>xu-Ip>>C>6IMa8a|ew4OEX`q)A7H9LS)6>F)g&K{nTk+7!K_tC%4e|i+K~5ZB=dc zx~m(t-c;emuMKR)?m&|E^5S(M=g$l9QE5&Wl=0o5 zG`9!f)X5FH;Hj9IKw^vocd2&E*yRg z&*puHaLIfUHC7g+-J3b@Dm%f8p+x9kbpjl7WVmt9ZE=K{Ikxp~792T{2kw0czbHdn z%{w2ZCFrj0>qSOiek!=FvjxeEv}Yt*4b7!2u{tJ`9Iqb%l9XM1X+NSll3brgmUwIFo}`mem7C3ep?uRsD37Jtx)8af1Jn_AB!h>_ex>? ziSO_#`8hdbr;cyw`+e{*Jxh<`!TFpZ-Pg3)ui1#`Q8D)e;EftP**Wd2FYh~8<2(K|SzB$JFS)D!*~R9W?JBjD<;MlLJs zWl^>P9}|A}g0tBy=HV$>bj}!oDOz#`NnXz|CQXDIYE(BKiUI%gH=y>Y7{~q@jT=sx z;GBn71WNzi<{XEs|Lp{ANAMu(awFHHwX5i=H6LY^`XH@jEo0bv0cP$x4Y8N#d|uAO z*n?Dm7&Aw3eDgD0d{;yj2tPJz1LcQUm4T(&Aery0fh9}LD04uLb`G(=kh>xEhV?V0h zgCFl+!_0*5L^q8`IWUc!E3;qVcc~ao{ka3S5hFN z=dO)^2bXEbjhX2e;yJGX?P{q1FtUZYerf^i;4`dBjk`S3sIMt^Ln~scR zz3UD^+k*oT93#QC`V`js&%H?b*AKYYON3i==dez9;vqcxJg@^2oco3XynRuKZL&e^rJWhj zu|Npd>ghiB!YGsrwZ`jlBbkqOJlL|Yfs41WBF^jRd*oOTT)THouoJ{#;fe3u;)5TF z%UF5To6keb)0EkGaS>>q+yJFLLxer3iMys-Vfd4=L@0d|6DZGT^?M`sRPhMNPJGMh z?N%ZBj(ikt>w(EiLxS4NYvEmkJwz>$j2?*Fd4jq6 zlmi`uOo(HpIcAgsc3Q~d?K~p*eyo=?QYQ3Ny<6n@wHgr5?0}r%*W|=34Se;$1ZQ8i zVJ2t`;P8t*AllYP^bhl3_*nxtv9!v{CbtKh-_!H+>qgdN-7st_{|d8cwy5=L9cG$W zVPS0}(>`S~gs+_e#r?yi&Oj5rv}djEqnurMmCy%1X5N4v7|$_W0euzW@2_ymZd} zT+el1*XQ&87_{%^e{Q-6UiDYuIP=G;85v;A7;~Ima!!2s!a2JA$>aVU*scUt7Y{W8 zUzbSYf&`%VrHrQSnJMK%%{xX z`W;(8fws;cYhK(@Gq`#s+WPy*E`{Y@x#RF+*s9^JVhn(g%oWY6L-I z8hIa}g`3#1q}1W&W4OqXO}qt$ko%-U)rIFP&z17?rR3 zVc>c@F8$>QkiW)Q;b~pu)dqb$V`zo$(Ue44-NieS*_b^>gKw{uhw#EuDxuGG?CVw7 z{NNu9ZWznWd#QjEs^xJ-mO_$BAk#LZ1`f^h=5ijM2NTms*273p7biVjT5gHAcHaL zEUx;Rh6TXpB(a{n&b607#->BXhi;;_Qy0B6CSvAxA?LZ%7%C(efZ4n@vRIkTSRR#8 z?p&Z~PFWYNGcBS6H#C#vJ8BrSTn0-TKa(3Pimk#y_KfFmWXaErJq>>%pTL>OHj?sL0I8;B^i)i>sCUeIfJr=*|72Xj z#mrOwY6@PNaGjV>EkgTDrdK>K88oy#W2;2aj3Ec@YbM=p3m4Tj=c5;+V4bxagIEFbMXw$bnwHwVsq|%_FyPZ z(}UfcC23z&GVZC%#RaCLDv6b&sR$+Q-;16U4@ zkrrR}@i6c|_QB)!9AK1Kn{>*Ua9 zDIu}f=730T1H829B^Q3g;CVJ1fAaScah-e*AE#yE$gLCk=ehzAUn-%&8`MdnW;?#w zo`y?a@~#V8MF zUh*;UeQzJx6fqR-R+_T;<7aZHAO`LCGtYP+yN4QXfJCVfcmSniamUg$0aCjyb7ldv-;c{i=FruPj52f zLdKn^>SO<_&!*u?FzcF4Sr*%^ha}lr0C68m zXw%74B=P-RTy0^B9u|Qqdg?!LR5s&dG`aCR@(6snng~k<$k0#Qk6_*kKfIdpUOePy z8obSFgmpF_NrajP(wEkZYv#ypnIwSLHzm~l&1MoaSpr8L>Hxb#GW6HX!x)t6i*GZg zaJL?e1QxCZ7bbU;vQ&L^oHYq`R#K97;2s{=%EraFHF!T40c=(-r8~LLDNax9vB6n{ zK_l&x!cQsV!-N4iYo#}LE$jkhYDB{LpAz)G%|MjTn}qhMH^q79qUgMY-2T}`${YdY z|0to)dAF3qF4w>{FBmM9W$72DG2WCVk5}i|i47gn@x<#K{Oo;@H+UWon_54Dwo?z; zFLBKL+_&P;`uGKKXz#~@uoT3rxvAFtmHcG#?qKK!F`i(%+VxXxd5wbo zF#O9g2x^d^!aq!t)?kjyc5M(9{EI;|HfxQ)e}Z488x5PbFb%W(Z_*tnfU7_k^N~?3??Il9{XGkLCu@{G)+v5eHW=E^=)va2l5}slG;VSi;Kg7$s&gO(J9n|% zZOt!?TRs!!dTxUN#uazIZ~*6eT|@0pGs%_@0`PcRN`rec#hnMFah`EC#OEo{3tP|P z<4ix?{p1uk@6IwvdgBDC+APc1LkWdp|JB~Ft5eWuG0S3Z(cm|{+zhMsodlh;EC(l3 z4eP2caoDm-(Kop^dg|Ys{yw?hLkoq&dLeu;n?JAqiI>@TULT{y%UB$R&ftBZ_nl=W z98$)2chxbe!IbPAPw+C$MhAAcN>e=xUk*h6_ z2FG5;LSH`sUj$A<>oKZa>~{gcyb^j(#*U~rcc8y-9!5+I;yjl~L%@J0Iw9>lQDhm- z&ot!lZ(a&{^Gq3i%UDLn%YoeP`E#L#V>viOdP(@+q4@EzEnYmV$2`UNaYs%TzWy_j zZ$2Sln)BlR{yD0)10S*7&AzW?oOL4Gk+nI1W}-CRKSl{hY?eorRGv7n=cw$tIu?h| zWpiM6ux<7Oubn;Q{zM}j|H2Lz?ur#f&cBa;?y#(ol_7j_6#GsZis?4=Pqqr`z=kn- zs1&l3FHc5z>GKTEqbzM{SHh@q0=#{Th$WV{k@_3Gq&?s+xg1#p*-siFXH^L~9HEbI z@+M+@!89&sEzfofyFuQtow%q7K{=#^s(R+yiRO0ThSppxORD4zRVDF9^G`5aAxF=o zmmp#Lh0hl%xhuKD!8&d<#3Zu%ywd>FrA+(#=a%kR%wEjA>fbc@K?_}AL2@wYMzs=0 z)(@ONP(th2@b#^;KUk}*hjVIjbXDF=6c4e)t}wNfPmU$Hsv?Im^gZ~KnxSy)*i|rN zcemMdhvC@K7I^K-1#x`rc{=&rBYK$akpnQ9Jv$BH==hp^ixEXsJbjepfS=jCeVODY@g0B07*t2LcbBAxy$A|58FORTb*}d8NZ4;Y9Xh9Xkfog} z_KNd+MvO;PsNs@9)bwa5Q5&2Ne*zn!`pQRQC}#ZsQak*czkqvRD1i1!B@|4z zknNoks57Ahls?N)*OQDh&w8P2TDfAM`=h|w$QHC2*R(Wz5azP{V$U)lA0OSva;8-X zRMzCzz7oI}_P1M)`<#;O*oi+s=b=bThu_9>Hg_2dv3`(plIu-2pGjB8@qdqT506}g z$#u6u(oB-Ri!sE(1MP6a`+MSN8y-;8$+`VAjnA4wn0cjy&Tnx`*}l9JPZ#GQc_8NP zB(6j9#$XVz-LAky87DdmFg;Nu_Q?8#)rIUn=;g(`q`!j1l#j50WpD%)4Mg?-Gy7I3 zavmd0Ak<<$?0(foJ?p?I`Qyz5+{7w8N)mb*E6vD92#Op*UE@k`; z+dW!*#-T-^!g}VsPziePgfV`7YJuyQO(LdypR@jjaaZar`Rgx(;KYL`5Tw#URK^J5 zYGg6B5>|`U+3sk*A=h8SpBc_ag=|}#{P`LYd6Z%o^IRPIYs)`Q_k_0W7e09cY?1&WyML207lp8r{dWKFnT?#@!J}9AVYjJ( zP6?lj@*5aW^=^+??b8rgeMPswhW8AX#*@?Ku+@Ui^xP?qkYhfbnlGHvM+aCRx)r`C zFm7#tDu&3L#tXa#A=#xek1rg|)wm z`?B4H-2wlr=b5}A9(g)}X*)BB#=aN0<7_tCdTa7uLN`K(UobpkEV5;XgwXr2m`YR* z6es=khxToZmpDa^-tL`+WuGiruCscIouCZ!)Y)AR_VUi}LP6H(Dul*L(w-T^@Xr@B zl$5?89;tGHI=p+>ulJa3OJLjE1`ss7CTV+wuqV8@zu%sgaRb5_YkuJ|c{)FN7OJ1O zM5CRX#JN7nuq+Ya1bavHHc~V(%RwpGaPIHJQSd=99p-)MAimvdIM1K?r`#Wrfeu2b zbS|dN`KQRY_e)t`swMX9Jex9hPd!d$npNd5?tF1NfJ|)yIJ4QZiBKN36&0{$%OY`$ zoiZI)tw-CgUL-xQKfxPl1fLD*BzV3i3T|8B?hr?=l;y&A{bqOnlFh_wybQj(+yhhZ z$kV`sqhVE|4J_~LCerdl(9GWotr&t;;YSqO8L_*}F-^XHju4KmXXn}LbINv;Zgi;3 z!v&zjPu!t~Hm4Qvwz_Ikty2a%)UiyfH#Ypo*_Ytx{o4@jDoIEDX1Oiac38XazIdGC zL;CV`PJi#cauBP5n#ELZIqSVgcVqk)*7F?Z_^F?-!!Uzj7`siD9=fH33bk^0WTTyU z-Rum!{xt_}T@LYnj}zeFtdCHl)k^|1Uf{y^Y;=;j#l09j0#fScfxiahGh7jZc0mzc z_V2W4_sniKKgy#ew|^52Q*|uWkiruBiByd)M=$eSj8oO-yA~~m&H>Be;T<-YI6fR( zec3ymOd@S2ad?912U@;O;vXIg28T5)Ka6E$*dAk<&S6FUeYn($jX-n7EQ?o`o={(a zHqN$aBy*h@3@b-d-CW#?lX+tA1q&}9g~+|kHy1M;Pu#XZ*SW5u3EFXJHI?<@#{+of z&rjjYr6NfD{hQE{3Q&KRai2!*6PG!@hq){7gDlf&+?YNOU$Y#I=?{9uIUz$~!c<+5 z@Ry_u+oW+7t0yl*WvOQc!;uVRJk|KGoL9*#2pGE+eyr#wf#cNCIo%xBpRP^Or$U%e zR78gsW{SV&%VJ7w6?BeLqCJ*pu|thz$;~{;)n+?`^N0CRGe(L!-(mjx9#xE*|C(jN z0NXz@{ZfY}KYsCccu^Su$rn4wR(ows>#@eUf4_;Icem5GF{yM7(|i4H)<&xVJzy$X zN}5)l#iKGl7_RV&lb!4hW9ROLtK-@Jr5$ix3G+KIv*s7no`avFDBwo*lKEabc*NQk zO&&ZIcV7~M!;GT-8OV6ILAc3K8W#>ZLMB99g#)uLKpK&z)wu$!{H}m*lb_ffuLsOc zXYA-tK73W&3us=S1t*eP$?tud*ycM4&;3>9-o^=m^DJU|VLQ?r-h)fR^007cFn6&; z5>5~NK@Y+gVi2Z;7n}aCb)>{aaRDS~tcMN3ePs0dRbPwLUmxp71RB$7G*1{n=6WsnvQ^{^sTrpCJl`p1~Yi^l%_}AS6F+AdwIBx7~6FbNsl|kGrtsS@>sTAZ7Eq* z6o)^bvG4p=4QCc>4>1?rVOw)MX-O4AU`SDaeJ&g+jk3GzK>DdXoh@B~L5G>P$+?o29b<6wd;L6TI9aN zbw$QpdgcXcw&!8L#^WYy#fJMf!GeNh(z{au^23Vhik-Zd1OBn)s`W=0Xn3!9Myl3V(!;NS~4uB-+MBvPzX(ri~4(JckNze`#}uZ!1J;v!@=rf z5M+nT(&kjh|suE$%xR3BNwU=zI7>ufllQ2hCiF+m- z36>Y`9 z&}Abr(&uAat{mpcZFxp_2If#d1#>@!ZqBJgNVK+8nL;KOk=#M2c>e%x58NH+D;&M zYaRTk=p%WdEbU|9RW$87M&4RH!V?`#=NvJKcVDdlCBF;%wH$)8eK;_l%{qQma)u+; zL1g0$uy0`AlT2lNKb++(YfdGz+ZhY|K@Rqe)8=DO?S%;|{lF!;m#mu+kAKiYcYf8axA4d1DMTKWql>Rq;>zPp z-*O<7JNB%dG(PVnt`F~!o&)8O+}H@xab?8HJRZwaSw78{@7(dyX|T}I9rRarkiOjt z@LR2jel5whlh>6&n|*aqW+R}L5zPB@G8cDF{=)fJjsTCzqacRm;<+pyhOGxCV95DQ z5;-&;FEb9q<-=Nh?nK7C9T*H9_u9xscLhjPDWaqG28o@@kAq*~8hE%xj$+G9T(;K? zO_r&qz<^2|&3vHKj_&9GF&<`D9McC(VVaz|2hpzXIJUp55RYDTkq#|*(68Uf4?&=8 zKNx%_nM{dOfXahK^it+bvE-6laNOYpIP}WX?&pr^_RRtVn&c$ z#b4+!JP(5uJ^13PR0woTV2l`9I>k#7ofv0-ZO(GBtceP}@=})ycU>f_muErJnI>qS z|Ct0H)WyKTwn+BR;}(2SfV-EAsB_>}vZ|~ZuNi;D;+-{OojtNR=Rh}b0s;N2J{EFH zts!uC4;kV=7#FRY$TGVrN!a%Y<(W=q&t5HlC}YD+Jyb-qJu*_hw)CO0Vm?L>*W)9n zD`Cnr8MG5BB+X`iEK}y&Iyh=FUmq6=n||Jc23D68#u{RGpf$^(ydz#*`-sNoWz%yt zQdIx30^HbMM5iS0O5yAJ&_XI7-7Kf_XQo7ev|A9&{lq*zZpx^gCW{FZ?Zkacvav!w z7fT(F@Hc-jo?c}d+e!5iSKoMi%=n+ZgKl#jRU_dT<179RYA1A{BFxt=qBgGrMep^y zX;DQMeLCP5@o?0@upv@d>Xt!PZDx5Z^O>HO)8X^7mxAKOWl%MR@n*~8(d0bS2#v7j z^|a1_O;I$QmF^_&R}~=CrjYIns1~VsZtCZwMlcP$@vDUxplypc^V}VDmBo?oWYJq&j=p>F z26v2QnwDub+@YG;kUnJ#Ot0!D5_<f9%&z$lMzM z8<%tv`{{Z(m)+l|1=WhUJ)Lx-Jofv$hiuYDO~%3eKU+gQ<2OEI@5Dh?x_p#}5A*AJ zz|1qu2ihpapG=pzO?fntZc;|uZ914yd7L}{@dCsPqhR5tK2rZsA9eRmMxTNhagC!Q z^yL;(&ucfyhlk4;%fcKj4n~t@KbmmyDRytVFXA0+u7fl^4{z;csN?`4_E`yWoKv)& zGrYmz+H6#P>C3yfz65poEC|VIBV~;`xRYhF`>GA#GCUQ*a9|M?9T1Tnc@n7(fATP+ zID~5nm4}QD#+#mBPd*r_ptZj&4lJZZ+h`$-9=8sxblLmeW;ISYc?dgCJCTU}kMW3X zHbzXa;s={6LRfSmz4>4OIg~7sx;i}%Z~v;|!u;05o7XeoCSw8|9jA(LR1W3l*^_}x zH@c7QzGdHP^Cye;!Q5ef5IMY$+&=RPorBCI%&6SVw9h;N<9C4QKGEfAS3x%}& z$?@dH!4j!&4&~v_@4I=Gd+(q{YO7Pcl{!?%XY;cCLALM) z$7+1QJOC17+5Kz(NEmZ>WPhzTo@$J1rcA(f9hv0*E*0!L5<} z;g2_R%EgYFm*`dR2mSNs%IILIIV+AiZ08+A&m21Q8JldJL58VZuqYz7ct+Z98SW!#*tz# zr^nQ*D64@Ky;BSf4!3O#0XJpTt_e8*lfk7}xR*rTTOvCZDEVFou zpZHic%PSk0i)7kSK8rE=RKn9h`(+=IEqjGyCgh-T)NSr<{U~_ydoHY(>mWytDS>-* zQNPaFV|O=Q`Y4kIyl5gdgEjGBlO&F4VfuNcFIcfIm+^pf_%(&g0CktKjB-i(%p?Jg zLbCDo3u``U@L8}eiv~kvc|%JS!SizgP0{}%T4}@dE_mbV%seO@R?Rch2w2VeCc_-k>rhZpk!nKsDv;N>0_po>9)ejk84CO4V|>Jk5c(CXIE?BWfh%zdu7TSt#F_L=V9e3ma(;35tjxkVCL1Q zb{6LE@Le0rxgPJwcXq`?>#I!Yv2G_n{RZJ-=P77fsKu4BY<4+W)(6xoQs<3An0&aJ zF8y&?L|o+HpLso9?)QVl)v4g-1+ut(8jw8gMX;M?p>DL0pf^H?V&=GsxcjU&@r;kg z7fRXqBAMN@UP-3@tzmsK(-k+iZ-5iwGhk7w46SULhVltk_~hGhVxpLbrRhwcut~@5WaG;n4q|#I8ppLV_G83ZzV!HeaJljXhOt@hftD|L^F=P+ zdUctT*wsmD|F!q`!>tKb&@`Y4VjU~U$npfVVKw||T`jk=a|YDy*##=~%-7!|iy_{1 zP_;xz9U8x21LGWqXnf*D6#-r)FEb@tYX`{Xx;ODGOoN@V9 z(2fs+H7@OB;dezyw=AUe+aR$-yF5%csidAs0YqwuBV*W`A}67iV&eM+yJs;*<$X^+ zv@Z-|b;7`d>9F^$_QXcUiyk$*Osvv(iEej(KpS>CWAx{ZR~At^dYe;@A2^T7!;Ymby+> zKrzd}3UgT^wu)1wb40o{r}-lBmdIuL{U%sAD}w~DxeHw`M`6iE1v;C}#=qXGrbi7W zMdq{RQGQD|q)0Qi)v-KW$~ZQHXV*B%f^jfmlr{7j_mbV?hM;_?IcC%na=nY4nKev< zu}+(hj~@ddEfx#*?b)6^;4g{V_M-TXG;=v5=#Ev!~-+1#2`P|!j4{9%#Y693Wc{Lh5~rZaR4>!wvRGimqr zCX)Ji0G@M}=x1NZTYkmj-?uU{<0xTI*SG zM}rOFcC0oGPG+-QJ2^D^4F&7w!Jj-S`pQfJZ>|@j%*z+#`k!|g z!W7;eBXoGZ%3UD6H2~tqc9HN-eKhyB#YN3OL~XOXsGx@QYuGwQ3BdYGIrW*9no?B8 zKEH4F!F;xmzHn|RLbsy9OKc= zRbGOp&L73u_03|kay!gRumJi`j;?0@3-Y?0y4`b5Sz8j$SYPMiBbA|{n-tLSmH=DR zqU~D4-XrbG#{zT4&3xibgcRbu4Xl} zK;axeNKOd99V)5i1aI+;?H^!_$rDgFkf(0LzM&=aH$9cP!nxjK+^)T?#O+cfv2Ln{ z%S<~l=0OG7Ip#IvGiT$jTR%8n&jC2yT@W>+lN=EWVfVaBs`%=UcwD_49y?G67s`e7 zj>}k}SpYe#se(s-w!*oBwB#l1|2dfbKX>0c$j`#7Fy;LfxST0PW0bux zl6mK2JIchNZCD^o!Y5?shW_L=VNGsk`!Dz3SO zFwvNTCrHsFC->nW6CZ3coW?z#Hy-r1+rz{AOxw9wA0KbF#wYh;$y4>yFut7e0zg2w zf0BpPS>-fcYGU&4`DZac%?l&etMhMS-$AGHE2w@TOQkhcXz>9pnjC+gTq?-}liN)o z>A>dL)1IQ|j%<`!UdR2*WNfi1NBZmM+S>xydar_7{qD0X+abWl&De)oIX9&HHzGciZP@Pxd#0wpmw;q-4w8hd#t%Q-d2Q*k%N zx+T%{*6Ymv8Lt96Ke_Du6px=LwmEu}v42{EN&|^g6%`K;Un`DulXX6uaC&0 zp@lq^8*u>7tntBa?-1^Y!F;G4uo)!kd&svp@~}p=jM|S=B2Sr5p+L74{&~xA-S62B zoqZ1znZG`|P65ZW-&pbN3u4^B?jR?T+1x_$|ES@)HCwS*tfXhvJn!8j07EITj zdBi#89@Cp3uPV*b#n3g{FnkGB+~?ZSIMU^456*J=6lR_hW$ z>r5sDGiG~kt{$E_KMAEZ25_?sGU2vnIMggqqC*cb9b;t~-JldIT3RCuca3WMxf6-b zYPcv@2E#gmh){oPA-pk^~JIVvL1vC!yN)r=mH7pWy_SC$-_oIi7?Gz)z=~CVf3BmRgkt z_36>z#WGt9Z=ON(QT})|SH$rLI?0%u|N86ai7Ek(R#e5novc4UmxRkDaxmTdC+9hJ z7Kkg{U{?~m3rh>30n6!H`9I=mjLoHar4A-~Do{o4d;bi4Qfm$8E;$DFJ|6+E8K^%( zX#|QcjK_V}+2ogZ62`M0V79jo@5q>f?t_9rHmRK)F%&@M;xf8tcmO##o3VLWA2sW2 zTJo|-HK?;B7ZXo;@#NGsa5#Adf)%8xQ?nP&Fz~}Cy=7vf@1c|`{Z~J$H+%w{i_P$} zG?h3_6M!hVj7ko7A;s1zXz2S7o*Wx0mP$_rS1AfE0~u4a;2{1A^u@fY8Qey00$dtn z4|-bN2badd~jvJ;?Jv3`edi zQ1uW2T$d@Qy83-~x4Z>tZ`lQR*9fWY^9gV>+zK`c`v?~>6kDRq@a6zYGLJpOfrr@L zc7YDBx!DlyGFt$iHIg%5n13X=oGxiK6!-j6!_d{TSo&Eh>3%>VZd%P|t!g6P{BjuU z6>q`?3n^+b$N=-_nd8FSH^rjoPpH@OOln@h=6Je7IR1_KNt5P^hdA8=%PE0i`9_Yq zn>pYEOKZ$F_ZP=|7vhzrEEn&pH!n4x!oT(pkjVJGCt3E*@s*4vJL?X2E^{nw*PjdT zOghQllWZ1Y>x;KM$8d_{dg;iNPjvOtCi3kx%XK=@11e6RNJ;B={LZvYXJYjD=YcCg zWyKOW%Je6p;$(FF#QY{VZTY*0FTga>6R1AiL(be)PCX0x_)hg3ca-Vj6N5|X*6i!d zf5DgxbN<0;$A!c&^BcbQ&Bi0AMEuwsZ*X=y1g}p^QSEJ>xP6Qd>KjLi1{x(})s<{K z!=L7*qF#bqd?73_ZXvU_siXYrQnrsf!trMWz!jBJqe3fkl(Mrll%3D@kHyy>4ub`m zTJU4G6#e8Vz|4O#Y;G=3r*8O&n_Y7-^5hTBS$_c(o!SH|40=gO;ZS_@VhXz4XixD~ zW**zWB~(g7iA;Kjf!QG$PG$32h}$*?hWwGD@kFL>YG|%hVyzZ*7^qQI(!bctIJaT zBzw#W7h%ot7Q5YtK4Op|W0hR==VP|NhDr9BEdQm0gt7TUZG#2kdNs~3HxoX2UWYZ? zm1r;XSPgS8r5j&e5^WnL582VRwCHUu@!6w>{@v23djv?y^&-q<^)~fHEtl`U6fT`! z18xNpv{7h+%`Dq8v{aw`35>xvQ&?7%w+(MSOc6Q1Z1|w2PD^qHApND3j&*GijlS&) zvofZ^aRXVp^hOa*W_#q7LOnjJ#0#d6_63tU%-iX!e#E!~xmJwVdO9 z!w%r5ZMKXhTc5HkO#sugOR4JdqvB)yM+jLK4O`C2Q>!PlanK-Jd|WBVHTQIoeS80s z()inC1*^9*tPk+{ElaomOhykGrpe^%xWN66@IA~8EX})!mdzm?Gu)18DDA|;GBz{$ zRZ910{uWQkU|Af;>L9d3fj(@i#k&o;nD+fU=NdQ${;x%lyeGlV0Aq`uQ%6^Yr=*pM zk3XID3frIs=(pcV(P=W!Gs z;`i*j4kE^&8RyJAHBtvKYz%XBB^QYu=U<^VyQ1jx%Tn}sPX^Fmf8o@rx8$~-O6s(Z ze3X-Pwm}kVI}5yc^ht#Tq)6xaY1Z8v)+@hTmAudsKtX?YH19Lu4dz{Z}ptg`1_!ndQM!%T#*%{vzVBO0O_%=XD^WU3-%RVbO{kV@jTV;S{OU=+{F(o7?1}8DC z-SHe99=8~y^0_wn>-C2eFfHrmU1d~UWGK$4o`(`bJCs@GkmNR?7@b^mnV(I>tJz(J zn`$>9aR$31FMCQcGNV7&W3JAAlyk7bdkxtnIiLN#HKp|Nn>k{~hFh@Z-Dwb1$k9Ef zvv5_u6`pYO7i;JiW9BxdxgF%g6DMF9svqD*tpr`l@@Rgq&cW`?JKU_Sad3+9VCBwr z64`4isd`BT*nB0JYZ}x?Tf08d;ayE+#$-+Wso4vh%4bqH@&{HL=Ap8aKEL|W3JCeT zxPK<#@=6Jgu{<@4$$UxM1sJma2^2T?kfcK@sXajj=wMsJS-J{f zqG>73#p|Sd^#a^@k#S8O!ib6f4_vRAheo=nT5S*0}OycOyFIt;?87BsJs zq908KIPjJX?r4;w5pE0M%CSwb%AuFcF;+=kBrL#{e{=Z7GX-EOQA%BGmB`!rwea}r z9Pk{)W}b}ob;na4$$%H+xOqCBs?5QPL|uLZdcfunCt$^*ZZdU)A)Yp6p7-!yqPrzs zR9Bot=Q4K8de&=g`&&$JI%3K}Wq(Mzy$dWgWvEP*J^tKbhlh9UBuSr@G1F)Oo>}3? zE!=elq+IWVKht$zm^K6@CfeY->9OMB)7)T?jyVLMlc$5P31EC{F?|xdJY|^bO+edo z(6&sLdetf6of!g@9QV{Ny(Jyn+5Egg^*BExG6{T4GU3t<*3%_2fBIME@B5&}UHO*< zE)%XpVU`jNe=Puo(IwQ?`;y3bkvwQG`cBWUswE1ZYUr-T{3o@PyqjKvm0B#j!S@H} zacCL5Q(FUOeJp3{sWGY)PsA`uJ#zn8EFP=MLc=5*-h%CR4WDJh#Bz1&$aIXenWst9 zra|PjZ4-Rang*rgW$8PO`DpfSGA8$(ChKfUuv*A6kM8R6ffElyV2cl^pOBz+A|sX& zW{wKeAB)=>-=Oe@i@x&aaAza;%@^pw01~DJj#+^sS4b#&hqWduz7s}Jm zN@vmNg)gojBjUW-?8d&fnTUVgCWqPu2qTmkM?;pXEFsv%bbvGT>$%O|v*Ch~8{F~e zB8xiqVN0bjblt*;SY7Ze)fR) zT+J0)_Wgc;y?vyg4grrE!B7a~ANx&1*>9?FZv&a=)qvYXX?P`5ntL_)9VA>Pa4c1t z&N`xu-!qw~;C7{0J=hGeV=Blp4~sX;|FzMw#v$LI6XE7SklDDPzusCr5kRD73BC5j zB6;1r4sS?|?j-EL|ejo1sb{-qWDfYtNH42a7>H zy9sL6W|M81v6yd{jXI_coZ_eZu)M$vf?E}+KAUq+Z7!jHb-i}2GBHChG9ZX3q1Y! zi)`YVF1N3Qb{#PkC;QCASF)BEcZo}KzFmT@jHR4^RLuJiyatg)H{i`FDY~@lDGg}) z+&?Smn6n=b>RRL5;B2D1MhLUUmC}-)Ibxl*+hFtbG-NN9r-o4un5Q-gk3H}cU%yp? zPZ?+6`6VCTWCeny;|JJpAV~!*rzXQA2jw>3t{L(}^;2A;awSmoFYBO)@$ZPz-MmB%uyd-VB0*Hz#@b}qjee z$Q>cYyav_}H%{iQtuMi~tY}DC+e_AztES#zvy5juzH_0*LYSMt^xjq1Nu0eCMou)t zt)s)pfUR}7?H-%cw()xvyj~sC-WYO*;}=5W6<1Js&iqcns;LRi`M6#wk3X6!04Jug|01hI z_GonBfc<%>d99XHEng4TA7_JR5aaesE3v$6Ieb0*1$kbijA5(QaY*SRPD^<|{8@Ga zq?)_Q6_bHze{v!oeEdz6=iNomM*o8JEpc$2x%@$IKdVz2zQ^o+e4B=nO^0Qfpl387o#{ znbA&5%=+gK25hb<)Gnqy@0O>`dVdq*%Fe>VyHvojb9LP+H2Ev^E<&77w7k?n1bjSj;kV8$>CWHp9nf_7JpRma5HIgy}0qxO+`7d7fX2 z$%C1XY^pwgOLPQAU-E(7%)h_yTmz2imPl>1@e;4XSiByWiIElOcm*X-R8V1=V&Qcu zyF8dLAf=clE;%Z`vfvXux%(IdMgnT^>MWkz=!kK3EVn-Y2PZRn9DJW`0^%MC8t_*chfZf_rt&G_Z!=7^Y7Wj-)Z_i{ zy0Z-BK$x_nlLR)YrtS&L#~llY@&>ldSK?Ak%X9hqdIVYGGifAx9f*(^|HS>}_rza`nNjOWJmt7kTCAfZ-G=rubH*Sg4X zZR_8|{euLCkCLI2nYMAvVwU%IuTq>*YXPgqPlLFOK5|ZdDDKU(#=B$U$k72oFuZa; zjF~T_D(o&0nNdWiZnsFzdDMkf5AyKZ883dk(nm;8dE@eKK z=5$@&&D9u(w*Lj^iNA^QS0QZKRYEP&48`$dXQKK(i+=4c$CaU)e=f^4;P{3g*FZId z-62z?=&*r+TQB5bwx5`rAMuQSw*K6&Js5mt0#2AMh2y0z5%YUOC{rn+uM6jhO=2QJ zXW?l$a8jOTE}V_B=2n>1<1apFSB9=k`yHz1%MU-63RdbLz<7rwJtG7Zd9yuN`&~{o zb^^>cnFHNcU8LitYHGPv9@BjWbAQ%LfQipXs`jagIK9+H*_%Dk@+E_WXr4un={_ja zk<2}r!Z^d{7eQFBBrWqeitKswpXfQdy^THoIx#T6^t^J zq!Dk2WA!r|yna7P^eb?ql#&VRm%*9`2`h3Kcqwvet2eP9iXtL{Ylw&^J@lO9E=`0+g z`kppUv%8d(ohYbZi&j*2@3lciFtEE7J3ujL1Orr5OhT}*6%+TInFR!!20;lEr3?@Q zc<0Ca53K8Q@0>X^&+~b%%GEuR@$2X;ys-GN*tTRR=C>J!vXEM(d!-b*G?6Bs<`rQ> zpTj}%GK`xe;c-7F;>2k~@NO4fVS&{@X0@-5ZS{+1gS07!XuKXSPa?gX5u!TX0T*7c z5{}=R2(r~{py#USs|e#QK4x89LrU9I$f(oSd^4^gaKuNU01; z1{Luh;i1eut_ly*-ns1SF0oC@85q9y7_4s4g`VOJJR#~>q8Cx zz2p@PF#guMUvnL4tU6>5(Y%Oe-DjH+5pU66^EzqEuyb{R0XNeN!# zwD^i|_E4)vHFy(8WO+PMnW31=L*r=0knLF zQ1+xcZ}-^(Cwg0>jSa9dH!g(?RsQWr@e^f5L&FZ*1Nz8R!ms%}=;nDB9f| zgB5u;*c>ZQ8JG43zYt^D;Ey2YJUvAW#TYQq)8uP2Z*U#E=X?_ROz#AHMCG8x@c_{(E)|x4cnl{V zl81LCqJDHXX6`#D>{)38p2T_Ibn73xnrEz20$SMYTw~SBulcw;>$9L^EQ902in#0I(`<6)akMh?$F}3kSV2%VIvgQCQR+z1 z;Z^_)rK~p-bxockm*9W^8IGLbC{G=PxN~MUPO;r5y4-&N@qq=fa(n|TeA))1mgd25 z)pkLRJjn017PihS7F#vrM2|dlQHvH-k(Tg#pc(j)24swp|LmOAB+E8;t9#kK+tJffbYI&UShsKRZ>QjqTfv52xhej|-K;(%y@~ z)9wFja`Rw)9G&|AH90itB|hq!gT|XWirY_kgMBBe$!nWf^Onx|@`ycV@A)8KRR5P> zo^+2pr&C7x8_FpnJ)7JgmA915IKqweE2p}M39=9{9Tj-SOZ?vK?W@k3i#smBk~4wDg4^?o)4S(nR!@J z-fV?BUYr4}t!^pq7?*>66kmm;F2qT-odbIv)Ool0y)fXVH9pd8#}237A@2ftxT=PU zsfI>qIUx(C$D8uM-DS`-y?{6ASILV@R=|1V5wLKbHeaP)id{zLV6SbRM2#!EA=%I$ z+-uZ$t#faz`9M6G>MG*}v?<;u`jj;1TCLOVNL|412q3@uA)-RHyreeL%I~ zo$Utsk~Oe7e&|eg)4818&X97h|1^z2J*r zc5xsCY_$Zvk?MQ`&GttT*R1ZRELeQuhU+Lp&W`hKNHn7&wR9- z-9vQ9lEIpyLjI~Il%k+_5wZ0z&IxddD;tBgi1~R{@_oX)#-L?;Cn;%B1sBTljS(6IM4WA%?OBJ}Z6k zp5-p=Uph*-P~ZRoCq_c%R5fm+?2kSEjK(AODrP`_yVM9bC{C90{#G&&UKDWeUiOdj z=C$CRoLo$PxiSmVsTkEse z2baEbz{=t*_IO7kXnhTXq0SOMxT7l$JY$Ciivty}7MJ4G*c^1}6ey~E)4*`vV`!JJ z&h4{R_~vXjj_iJ32mm`s)^vl_nk~$*zp1MG_`O)21q zWJ8!RSxx26b8+yUXrU<33OYENf=;joZevz4bxoalIFbsJ+wbg`{;X@1gr2| zX!JY*A0Hd=O@C!@WM2VaF!`wb?Nwd4d7zA2yM17nbWQOlsN;$+z-;%H;pO2uXk=U^ z^p($s#ZPC$`_(iLx3fa|9vigi-ky1Ny@%)aP!4RwaB=WEBeePb3R*gw@#uOP_yrd5 z6**P%@ii-9N|Xo>E@<=d4<-{Q)(L;#*~`MNkVjxn4qorpS^T}hkM6sEP~4X88q53O z-3s#8^tmoyPmXLdYpYJ}S5l!$;<#O7&GpRStrP zsg|HY-Y5^+;VzkI)H-KwQ$o-A*lZLpcNCpEZU+62;V@hGFN2$UP}i|^r(f-LNIr&b8Q zc?l$y-jGzQ$D_vRK}Whj{!fS2GfaxB;X9<#USPUoIbL~_gIzDi3Zp6x1)_|Aao0pDb{T9(-^izbEy^%}FkJ{*Mht zxdLs`s3aG%t|UVECU4zJ9|uz?2!v8_6E9`(4jH+~V;7WXy(f(x&o zvFFpj5nCV^&&PKWza=h!6$>WAj+?}vIg^GJw2S|bbP+Q~ABWp%-@n;yq-bXt1YhOeu)!n!CI(Ce+mL#&N38$v0nX*}9JJFHi3wNdl z!@tqZ?D?Sk_=$G76Q_nK)Ykmt77fXK?`(Cx@>w?=YR~{vhLy2dL7|WyxCU2WL?h(gyp@c?ElynDH6!^~M@zuAwv>m+By5hycRVsP7neM%5^}d#LqK6K7)W|@ z9XCCcUL#MI!zE@qp7Ix_W#g?Ooy0M_w!p{aa2T-lFN=F^rdo3%AJw|{6m5$3!jx&# zL1HiA9f)_g^=cVkiH}momwiLO2KxJ%`-`;=v2b_ZQBe2O;&;c$@Z$w3E;+VFu`vB4 zw;G<~LDCX1CY&{LZ~ z{7rLr-5ivkP7p>Y21AbpBjCgwHQueZJGv1&_wVZ4tnK~-FfeE$xOvh}Em~cbTc3+> z+wT^K8qjle@HR|#(B(E;TrkOYIEH>cs%XE`h_6mFxEbrv9Q_A~T z_>nkK!F59Ov?Tbc=?zUC_4%LCQhar+4h;M0@)I=`SlCRNt+V5VPqzkxoa*T)V-2n} zv7)oo8W}@oeu8FnmOaoUWsR__?ms-Up#esX_{BmmxnRb9YjnS%NZEg<0)3z4;1JJ| z;tQu3Fb_HduditGgT9+^lZ8L(R#hvaqi^x9KcBSfBAT=)XTw1g#mZ=!V@Tj+Tp2G- zpUD87ep9^7sBY%x97?cbEgr zd_Dn=n~+!3!(6p;OaZ!T9ug*Ls1xTVom*s9vj8Jv_fbx$_pf`(?uWnQU}8yGjqWN= zZnqGQjF}95UTE+Ek?GhsCL3jT3NfVOIB0&n0-;rEJV-ECO&(ByJAA5yC9?If`}q*K zcw3jBBd&O2Kq=2SKT5eV;5!}<%EfRg-E+qV!P#EkU^-5duiro(gk9Mfo3vlNyGse3 zM;AcXagA*B#vCZijE6B*dfdcV3X7b}xzC<>`ADHRbU0`NM$sDF;W24)_qRYzkrt0x zo=Z76Ik@j(jj%D#lXBcBo3e)*pP~N%ugkOXX4n1f^%o-?e*6uLxNgkbSrZ#=eK~hE z`Xg5cE`tl|u5f{TSb>g4xSagd&sj1{vCqZ5BghNiud`U4>-_iYi5UvA7Eel{FK5ZLCq&0x_cjooih!&{JRc>4J>J8-Q2!og7c=e zK!68lLtekb&+~|x`L9}7yJ;>M)XajXS?YYvl1!Xyk&8vY@30_zfcoSIk4I-wUofT| zv6oP%GULbIUP6--0VvIh6sF9Oz|*a7TWjpM`z{z2HV8dyf>_0$cj&M)2e&WoB7VQ` z59JC!aNnlRwTF3=-#q~5&Qeq8#ymi$RarP~(h>35aC;1CRKu^+FDNY&jPPVsFNv*#lcL&5UF`EqgLlY$j2$*) zqrP#SaJAY4&K_J1+?6~vPqyKSN4A(f#!0czSOQYbx7=WpF01VJ6F02Q#Xb4e!omJF zaC>$ym{p+8A8P7h^jay_kG#m%@yFOm^Z)S7PGX?}&Hqn_!(`)sZ25j-s}y@eL9m2h zF_l1u&Rf3KBPFG4+z;%mM!iamzi8wg2kkPCKs#dL27nB^5BUFD`uKnyKV;#|YkwbM zh0pWg@0VKm=atUlreA_DwgF)MS;k{YtErRqmS@M9%b%A#14lh2BoK$n)h`cCO^DO$ zlqkGeJ_L%LN5B!%tRC_0foSi52~%#f$+ZWl|D6E$=g4@*O?}l*vjXC-JFrf~mh4vX zmVYt|QDn$o0_%GliZ-^m3FUHqwX>tuf&0aS^QOfdmV++aNwraFqa*i>fS@gc7HnT1|6JBb4_`=jRAU+`q&Zzd@D8)w?6boa`9TQ$Iu6R!u&yavN5j2}E_bABv=jxB28L|6gNEHag(a ze06-HAI&TaNIN>ZlpmfypB26~z|&<7P{AD)9a`RDH`=46`UQ!n&SgO1+;q6NSA+L@ z?1P3nfoR_7AuwG>SUPe7G+4K=x$F@R=^lz79}f{~Ox3|@Nh*It{*H`U64N z1*FT>`Q?jkRWtna(dS0B5JuSoy~_rJuc?GjA1Z-^|GnX6nxm9o$qO*`FlC+0SS~n^ z3WkMxTcK~5CJ$*bi|5dHu^{beSVFDv?9dFjT(bzO zJk|KY<=yd(z8!{L{-!+N&lnrxOCUio;RAk1z-ZuGK5=HFJhgE-?7BA&auc=q%Y3T6 z#LC#>o6Pzg%12MqxO&ud7Bz0{gy(O9pwYO6?dZ`9Z7m1mIH5{DrtloUthI*Eu)4(h zEbM`&zx<@dW;vTc=LIu(%h~1LiaAAl;KNQYI6{o6-;opX%3Nm*3*E#fUdhL^KshyS zMu=-|&cGs{L@1Bb;Er}FI59bkcDinY;k+#nK5if!>nr76*Dj)pi2eyQ(=dE2fo(_L z@QrDc6(61_Lhi^2%B0rirL`{jOnWHKnOX1rXn#JQi_gX%$M=W@CTWn=^94-o+`_I5 zO~IH)S=h4nvXGon07K~>Qt-x*`!pn>&CURv=s!d#7^@5C`V{k3mn+!pL8OztLpc;# z_gR-)AFw)_^5}cj3SIZigNNR;V1~K|uh~Ue0IF;ZSw?l(Dh2z{4*KRAxtMBeg59sb zgb{PidB#V5Rb+l1esZi4&bUZGd{V-*R-9mYKEg54FSIw`0@dj3O&N5uRBd%V9%4TYT-l+VsnhMLxED9H#A zEM*c{x448?+t{+IsfOtFs~*OFzN@Gj-o##ytz=dEW7(g6QcSv}gTrX<)Mr>Ge%nEN zgs*kN#D>Yl5nl}h_tA_caXUVj*rMwuCx!24UHH(ygxh`AVd={aQJs7`@g6dvxxxl4 z-u8shZ|eM-njXH|N;;OL3#`S8zBAQfH@D7W%orc|Z%R14A{}GLMf>6IK~L!POTr(G zlt2nE;nsR7DaYs3;|F!p5?BR@Zw|%7H#`Eh^;&#*`_o*QoX|R_z1y|`e3NRSM?pGM ze!m1A@A*TGt{$%?pD+9_;W;|y^29bTz$NDqM1H3}mg?vL(x~hyOBC`KJAuhp5hhlu zaaBzZoU`5@tGeB0`_4yzrs)JYd`HG-XB()@h8LjXrz2Z;LjoHpGs`zESh3#l75quN z1uJjr@+IHK;rvccXt4i?!gW|1{yW-$*FB411BxYBY-NNIOTo)gRu3gS3#6H{FO%iYvD2J+n>8SLGWh>nCGg& zuTAKSYunmjt!WxF+mM3tKg8pD-APo}AAr`m^)S$5*yt|5NCy<8LvxFzj zxu+cGLwPr5^>E2+i10CfF|1O$Lx(<^JTp@dd!ClyK^GGiRGo=iX}|FHfFK4>KLviP zu7FOwI`?|Fk?mTG;s%(y@d&qOX0G+@LyeK z1NWTOP~L-b!$%h4GpZZTxg*3yug*YNLju^-+3_*q5$5J+;pav-8qscr?;i(%G+fFz z%aX9X$Pd4!QBGwL@!^ja^Dd7)6nfF;UvJFBB*;s2v07A7f+%=ySov0d7Ok6EBw(Td$5ouNFcRu zF*m>Xjx9cCir3~e!R>{dsr8u;D-XOAZ56U4Y|bkg=v#4dbxnVm`aphRJlA*tyN0*rQJ|%x(gm#RMNHwb9`2eYRoaGJo_r871s9n+jbn zt%8hCO)R{52bwM*w%+}ribPiloOdd2t)<)V|3c%vxtRIBR(LwY4y=rNfeZN>EJO5& z?I*$O_b;#?Nl)-q5bZ3!bQYh}?cjRVD@-_*gIH{m+X*$S9mdBc*{&4WBU@E!X5z#I{ZXpA?A|y<4xc>A-~N~=s5cS z>#F-o3oN{Chg0isu{`4TKk79eR;py&{jN7Qof?XNXU8Z%(b?UDav6+#gB4=?EO1$N z3p9S|a@VEfaEkk2jK376*wJFh3s>mz1oH!|%2bN6iwtpiS2f=F`Vn3*$;KgnzYCG1 zX=+K^40GS<^DDiHp?bQ6hp#sghOX4Z^-i^|+%TnW1b%G_z#CUwgoI8*!C<`uw5-zL z$xHRoo!-ypeA1R=Kf*dmHlAD5S)6%gAmx=efKw*^}zjX47^37OPa zhHM!R%8VA~5y()Y8;WnroP_c5YS8f|VYeK=vcwSb=A0OpfV9S9ku#cYqg|FMIMur#Q*ZFnA;c1(Q%{Ca0 zZM_J!d?j6tM3;P(az zPK^2k4y0)`>sW+~&gWpI|2Ls}(k#eUEdrMenjswRi8bmD_-RbN(k##fUnon!pr|b)n&nqAxcPxCprN!smZ-es1TA21BnO*u-hjpe{8hycw?v+>U^y@3=h>;VJ@K^aCwSStV>wi}b#A@ppQ5Z3X&T|M zxc6%4KS784CAy)`onhEl*u-`}E5a6<6-VzIDXuvc1G;AuAg@S+-}$A)2cY2br z;-EK-88HC%kw5+AiLKa^Jf30}T!~{Jl9&9pLY(%}6ol<3ag_R3&Bb(SGgC zQ86Xg9%puHf+Oe7E03la;qB&pXwyGHupl2wfASanuioy+ZDNBCeQd3_FFon5PoBp% zPu2OAAj&WJZA^KfeT2*7rop2bs~~c2GfR26leB_1nD}z2;&_Y%+-zR+!^Jx6O89TI zkIu#FnmXa;SO*x9)C*jrGoCvV!+%Bte@dC)b-8AU8}l?Vn<(a{1FDB)I0YY zcL2_0O>M2WDl$L}R4?XJ2BxGW{A)zpZn@YnE>JZ7coycAN5MyH(vVEn$K}MZ8=kX9 z(a!h`m+Sq1y=|Ud1nqNb;KGu}EO*gm@Tu|x9dAAENf`|&h;BZNRF5lF6VzdR0K5vW1eQvQAF_FO5xB`&JVe}UX9JuhB z>pKT49@uAtqxmhkGgiWVzl_7R{*E{}DoRn{YsB+uZt=ewd(%ovtX2aoqO7qEgBiwl zp!rG0520%ERe0F431;;&;0@ke(R3>DY<=b{8cDx>d3P}{nr0#>N$VTwRtp*N65h@r z5`Ps1pyO~?;cLfX@TI2%h?h0^oI3KVEHK8hvUo_SE98(aqlC>h}kRRVeYWg#JkiY{iXr__stkb z3wsm}eedv1RvE23ukqmyxUEAol&c+MpQjtCx~|B_CokN^5IQ3k$%^>`wRyz+{DXB? zd8m1>o8Y5UiT0OsP|+hqZ0Yh0dY?*z@Qs@Mk(U7~%ZzcHMU}#g=BdU8<6*K)jTaB* zxVmr zIJRl6&&Os;aj9D)n6A|1;|3Jte!5S+U-ez^(wGC`xeFnl^zA#fd*L`wJFK7bQ)#4b zhC2OApiR9g9}p%5{cWU?ruyveu?jXF90ToMY4MEx#+V+giF2!y*%#AdbpDr()^T0M zw@3WoPhB9yWVbN)6boGP)&@o?{2BdSj|WsP@Cy4ESLJg zn7RES`Mi|(Y1xX}n+9VADw)AnDIAr(=JU)aD{}NNz*&a_@P%^j#!noFLm%1W>9*gT zKMyZPk$5tfY{Es|k_=e*>N$kO((f>hV>WqY#@SyLibG$6eaSJHpJ2pq-1fz#--n`h zv$oKuUIQN7f5|;#i`e5m=J?sH3DT2+X~%xSjN}}g+w@Ji_;4Z2YBv)!A~m=L&DL7x z8KYf~W@Y;c91ju)#(#|;{)@1>ulk7*lQ>YseyR*n0*~`1q#ml!KJ5qTy2^Z{>v}oHZRTOZgaALRi?m- zEFHdPxFN24LU~&bMGCjJ!$JLl0P~iq^CH`xsMg&U&-#+DZS6r=(#;jduF~V{I{9Fq zF+=d}vop%`WfIE5D&kp1L5f3;IWRuuCb;dB@QasSaO@ukoO2^eamcj|UzaN5erpb} zUejp~{Xie>YMR-?6C5>%(C*{nPvJi) zcO{lc_;v$4yRjB#2vTl;I}(Q;3cxSnu7aL891Qdwpr@fGFOwKzT9`4)j-F+WhdF9d zM#k!GUBm-MHh93i0U9ZjB4tS%)tepp_;Zb=xU%zC)Ul%MiA7_@<-TXZ+UYdS9JToU z5yU`9Gsc9_J&N5c@ABF~8LfKVw!;VG&`Zq_WfaZ2tZ$=ArP*9dxrZ3&Ern0|ulc>N zbJ?qgzqouz9`;?@UD!PFb1S>Pr+cudKk+&ITb~ApGBx>KTSH8^ZH$els}%jOJHf{! zR~Tij#=FW8msp3Oey?G|6nk};qs4gUg)ht_NDAxecm7{*+%)7LdT+_ay6hg}G0WvJ zEM^iss?+47Vks}!Pl|J1nK3__#WnXb#=sFFLi~<1FwFKc^r=yPFPhtX{%T zl3yT~`0f9z!=tsgjlXn0_Hp{O(-@HSw{aBCkxh`;T=IXaareI(A`CoE1s8Ncjp{@vGj*9zs+1?+%AL!OVW2d zGhFkf7*6<_as5@K*S%NB9k(>d`%hdASDQz}tUp@hSvJAo{+j4vb%&k2UV?>&IcPVs zo4CP({Lx1O;b%(=d*^A1b(`$4>xwV(jV`_M!?gymZU2c~_$!5v6N~tu?^X)?4SS(t z+A0`bsl$^iOYjS2n07K4Eq2@)2PTsfV7`wgAJBd)b|ek)iwrHnV1W-X(;sIIj1rC(FM{dkXTY3v4W4jo7ls}2#}v24Z21+y zg~Y?xGZn=nbItKN%{rD^wByoA#;WEq`DkeQLzwwp3d0rT^*elmHPlbX=&cSo+G!tq zSsw%k>vux!P7Q89oHPar#4G-_SN=Q*aK4iC$)ApivoGz$alZy)H{&l#t7;?c<(vyI zuK5ewX-+sGy|A_3Zu9A}0 zN(icMX5N8PI2l>UH>&G0OV=hGo106#^&i5~FOCrXp(l*^smUX5>XYA22d8emz_v?X z;^&K$<$a>7I9PKRM4u0XonxBW@G}vRo-qa9-IDSQ+N(aX{GF9yYF!JNF7!*m~tc(9WA+MS8i1rfvAmX!^d7_OoC6r0CN?xzsD0*}W#f zwIc0wcGe3u#n-^-_(nK%$ACX@_Qr$b9nncPU-8sJ27C4vasP29!j=Puc>Q24{CX$l z-X9{+qSg<8Jsu|*_jQJk=j_2up~)x3*kE#sJ^B?sWlkE1?qjl1ORuY#>}Zc4Pc%Zi z4Qkwbud%9AY(DyVSczWks&O_k8UL&uCw_5EAYSw-_+zHcr;YbT?_0aEw|kx9ecfID zVb0@L4tcxLgV84Y9~hIV`rsjB)!|F|IP2eJv7)^Us(g#M#*}$1_iYn8lD6N;qKD8= z>kBr}ez|{Hu()~C3mEiY8VKfEyt;WC4qLbjL&ZtLythNaKFk$Zpc;SkiTvqvgHWs< zBJ`WA4gt56t@ShinH2hJ74gwS?#zkc2fF+fRQUEJqw z!d@(Vi7&KrFm}yIasK%;5c4w$%s-M2|Hf7r{N4e&PLy)z{ZdeiEo_}F$oDsq=Q0n& zmW~&vUoTAn~R$<-`+JX_hchcn2RZ{d58sOtk4L;%Z8@x&y zMVnbag^Z_jVdu4laA}J=@9xkOyS}%^3k~0tgLawY{*5JY_^%oNcb0f=szN^RL4!Q4 zY&BHbjsfPR%}s)hF=Vj@y4xkQo=I;o;U=*GOS*|~ef*)5G7#M4YW(|FOI$>~@&D>) zv@DVP{aMIYjz7mzE&Af7=wDExU&*WkWw7*cAPAZl+f%`vH_u?IRVFH5(%WmcJt?dvkAqeXan6UoXUE^SCC$cP zxHJV>LTxqH-y+X@=?}r;8R_PvGhk1-2G0zX;)fr^Sd03ptTj^+YcUHuDMj(YFH5jd zyyK;zz1hjtCaQbW^D%nCPhrMk8C;-qHmLXn>$lnytKZvV<*RV!Ft7$=zvkdn(){Q9 z1cP&5V%JAdUEL%>?=mS$u7t}!RwC+Uknh+lT2%R2!o*V*{LIYgM+5z-CsoUXPiX-{ z=olI7voGXp&e^ie!IV!?n~TA|@xpPd7ADnx$0EfT_H>;T`%TwCn^S6B@9Znwo0W|N z7uO3PU1vbhlNFF=*1}e}TEVjG?|4$TAI|e^WU$q=kPn)u%L=Spa8hM1){8#{)sDeX zF8+VL9WFJ*tXs5q^Sj8-?tg_}9%iGSeK*l&*KSDM83sO2o0(8y37I|K@xt4-irrq3 z5V(2@yzMIEI%+bQM7|H-{D&#~)->Y+x&wwa2Z^%ab70&z3TjPs_r6H&`6@8J8$3tr^XF};hEx``_P3qR=fFsh6u3zm zgXK~q#B;i+{VFU49}fMU7#JsuvG-l_-l3bur+@fCdA ztvyQRZ4(u3eKE*zvAu3bRXOrB1SJE?$kBP zg_3J=;g~Nz9I^`+7EBU`UK|Gew+mDsQsZjYR$#TEf{zP~k=L(Khdtpbyf(LzE&U^d z?yiNc+OQc~YO2JzT*{j2DK0y^0uuGy;KDCWu6D=>g>YTGoMy@nP0d0T>F}MqjuJ1P ziGgO#q}F-wya85_H@$+two_NEx#SJoXWGLaxs;!XmVv>U0)DmkDCLdD7S!|4#mLDM z#NOFq&|7~qbnw&W5pDGFh%;rIt+JE5jLpL6b=kOh`av3o>6e*vf;Q|IjiXs2dpg9WM|O3AIZ*xsWUa(9_?Gs@;T8bvz!|IL0Q z)<6%l(a>v~Hov*Y6g%zFK#gm6*yfL=sG@mAeL#27{$K!{whe@d0mMZN?Tz;)*rES} zuX6KO3H)RUON4gFy~DM2!(czQ=>N z|5-Rktlc~9eDKNPARJesC9J9I1>CBPi^M#?v-J}69K0V^9Fp+z?k?Eo7S-F_TIcin zW!PJdG;%q6#TgOLAalfX`dx_IImR1@_6kCyO>>2S-j;A`LmAIGFr5`0HC5fASxwiP zlfu}`dhk5EkUw?!$a?%}iz_<(p?fJ^M|JA36XiA*i1osWUrQh(ZaQ4)s>zveDmFKh zCuR8vv23;_q~9y!bwO4vD9lvlxhx+8PuC0QUg%MdQV|zlo@8y^r(?)GTfE&A&T`6Y z(UbVhW$G4Uqhkp0r#s-pYYooU5{L7%jI#Rn$wTL+;?1|DFZvfPK3i=GD_@lHGnL04 zvDtd?WLhEjim+oPd(~9Ue{wO=?yR66-NJOT%h`Xj81{zh>VviFm_3Mi4n2wWSe%WM zTpEPyn`T1C6)Rxt&K4GwN#A*5IluJso3p--9`IKMJX5L5?EKYKQ>m_+({nPe5uH?fnq9~4XogZZP$!`NU6XTphbJ=a!omoiD4 zq9?;txs0nG%b?Br0xnsclHx6>sZ4i~-|%{{_-@{LfYQV8aJmj(-pznA+_dO9@KQXQ z5X)y3#kTge)q$nZ{#^|ev}Cf=ZRjkxTF$pR5Hc?~{j?S{_b`aJxr3{IRc;PWS# z%QZ@JVQ!lgIP+AO>nD`qL(+SE&%P)u`Qi*sk#guTmi)6FhGEBFV~M~2lzsfx3!qOK zA4NX>?eliyt9?#rY8$US*dT*@_vkDjeS&IPJ`6v71MHVcx$%XmxUFIs#!Nk_u-k0J zXLZo!t8Di%@1s)eVZv11z^|sPk7l_{jPY6z0mT+Dqo#gZ&7OJxiOX}=#p#OZu zjh=dt)?C1c?KKg;-)(~%(rdx7ANA^^58>xw{x~iELc4Wt`a4@f`dO zJq7n)YV(!|8Sa(pq4(iHMW>|u{QJ6eZqQScccAaNlfLKe`cUQ33{zDT3ptTdPRP4k9 zF7ATXk>SvLzYCP!Q{$IgEaBVEGCuF;8F}qBb!Zd$kS}>u$?Qqvt=w72eSY6pw*982 zI(aS^FKG1=BNJ9av+qRc-$RQBmyN-K4MP!iCa`WFNvA`1sMHUm#6f#w>AkoFCoPF# zn?%oZLn+trS5v&S_JOA>?BLrVDPOQ%4@Rvm;Md+#?WK&2Hlb8|9VUt)_rsyKY7?w) z(B`IwdT8vSf$^_w<)cX>FvKq#;r&6;_HG8;qT0LDyorUiw}L5~%eXRSui|=D2^c2C zK+so19$`$s&&Wc)u3NlZ?WhF4w=d^Y-@Ifyi=}wQ{X3+L)Zk~%mt)v6@~Vt)5E3^o zfX%W6pheky8|aR*rKB7Wmz-q3w_3sYw`IKje>IA+KJCyl=QWHeH>duLvL{Lkc;vH2 z`Gqg0SoA|3heqFFz6Z+DggjPr`}Ghb#|J{CMj%W`r<^S4gD+;;;g>^I@_@_)zGT!q zepyIl-3t0*iCR6#^FK4Sq53esD|u?h^-)A;OTejZIln$Mkj->*!5v}N_|bVKi@#rv znUv`{XU3fzmPMX~O^+ps*{ZKrlF3kGe3!2uv;msAioqA1OL_v4p9~Z~3xvOJ;i6 zOm)&bA3e$&gimcZLsI+Ua5qtxZ{H~e&p{P@MvJxb<%w^2o4f#_Nfx5j-w@dAy#ucG z)8xauOL6O23Fa;im#e3y5qFSSEB?nt_r;b_Xj;mRLXJJ!eXS4<{y7JcL-cr`E$XVB zjk%awaaKsWqsGSnA6wW6 zu!M+1rF^f=H|O0O)Kxy;DF=LRgRnGa2-Gz8XsyqU-HdQYkv2}bdXZ(e_lH%QVetJ> z3p<@=3G1RudHf?A#ej1MVMwRRu=c2o|018xx*L?ow@p-ZGgq}WR<`?kpn?e-b4@lrhVi~Uv8pwJsn}WBuI^n>&jNXt+M<4@LU6S%%s*YqpLuGq>aT||{DU7xbQ&+*mMLK5McdZ-gGj!Qbs19ZuXCEk z3hDS^1^F;}>q-s1+a znwrb}>nMY=s)GBu3{vP?tb$`JCW30D7GM2g6uzdMtmP^f_JH1r64IzdoEt4J#yCj5 zk_1y4NY8wjdibfOyxLPu;r_@6K2RNQStR9^6NnjATF&RppQRYBN7)yRn;^|nhi7<> z#p|nw;%k|oyx=9}gBj&uk9CK{E(0@RMo=C&E^cDe=@~YrXZYU2y$XH*H_)hxfkpO4 z{ONOD7_gF_?T{C&jY#*M+&Wkotu0V--F0S?XC9Hb80G=B!fZ62H-gejueV$mO zw%t#qwx=ajs+V%h^;HVLtai9fy%+{swdFrcb-^ICl;`!1W`kW!aq(bvTzNa09XnZp z9mxB9=v5E#-R?jbE(wIV3NDLj^+<T-?73fme5mycI(+!b zdM%K^PJGM7H31AGTrlL=Ak6u?f<0RHj=bSHxWIaxcy40?Sl^EaQA>-bKHZGxTKw=> zcMV~swI%H+-|(`5$!yiY-L%JX#J@+8J?kWa;>mA$NZ|~Yz0sBWYHPHpsdd(w`wkad z=3q?YKCzSAOE}i!IrP||!NWH_#x@S5bC_^L_#R;i$K&7d@ut(++FWy$8SM+A{7wsv z!FsT5M;?Fv;5}pSCD4xiX#DY2<@&Kd(6KfLzZv}!eB72p-V0BtkEZ?670L;6B2Ts1 zPvx1pkMU=hY;5~{q#S;jChlSz0Daao;G zOZkA;gOtu|eqgUQx%hBtPtpHMD4413fF-LnxoeaZe_H$>NoV0!)%SF9noCOvVgU*l zP{2S%1@5`WAjB>#u)DAW3k=c#6BIB&QLqbxyZ6l1uZ5y?W1*NR3Ml0}Ki+@fJUo|u z=FFa1>$4>ICm>Q*)$bAN{Cb5y4dTUZ^sV3YsGK`3Kbl#c+Fr>?|MO-m&Ej5`z|Do{ zAaDTPyMIbx>6J=8r6OI%mH*g{>F8d-|fK6rh;#I`@^%L!5pvs`vBb%P59_B^xpZt=6C(ngqO1hLEttUu(#0Q zQ`3#`-7-zIeRQ6!Cw-3r@}86+QDhH3O;8+A0e)1EV2K`L9hF|d?h_+Iz4Cd z*nNWY*z=IE{UEG0(dL#>-ne$mAj$?y5vE@{#m6@%aS8d71_$flpeka+rPedaed@8x z%lXx;V$=ozlb#FFwN1)j6nA`$zt6s2x1^DCfPt>|}PAH{rhr zeR1}mK;gv~ZCFp47ln1I%)QqkjIjv8jKL%2l_0=Ev%WBY3~5Jq>EUSuT`Yf_z`kC3 zgek;YJSYfrX68zlPX##Rp`&<_nC+z&6}LK z*j%W~N2N$$oogj`+|X0Dxa=3UP=98U6(MeYp93d~m9W`Slix_n$H8;xojr3&UgRJH z^CdpuUZ}z=UfIF;_ho#CZldh=E>+Mzl)-UWHH&&~jUMlR!(P8UHZfHK9=$90;X)@t z5w{egM~?)r<-{P`=!KS>-Ozi)2)5>TKBn;;95T~Oyc2&0gp@S!KBvx=no`g=E9XT{ zR9A`bSS{@f%6&RK=^K3?qbqpRohibKrYMkIT}>G@THN!Z51v^w2z~qPkXgK@{Fk^K z+|n8=cC3C1mM`+)2zgP5nn|I?xSX4sLt19VJ(h0xgE#NP?ay-Z3i}=O1ZA}O?GeN z0Ni+46<20OvZ=qc;r*5}{^~8Jh&CS6^U-CX5c?nY*vfyZz z8kd`H#^SP2G~F5?|7{?Jy@_S~=m39~W@w?jak~Js=O@a4Wa-1lxA|?eh2#hcBnOrA z!n}(LFUs{;OL|BXX*;>LbP;@LKN+IVk~XHd9>PNj_P715`2ONCW;@ahbNevyNWLA- zfXn#9TsvlAWT70DLHo_4f90j2>*24vJ1ie6;rlL=&+$?@x370mWR5q)2ZQV3`4*YH za%wmf1P8Sh z9xi)C4aYJVGVmPqzOK*RbSN`jsNmk)(q%ASm3PjpWWP5iF?795>AYX&TDzYx0nsBq(%QW&RO&gJz#JU?~nfQQ?H@Grk6Ia{?7+5*bl;azGsDj?@sYi zrb+xLc{Ijd)IlGMcDTG#Ju{{`#;a{*T-|Gqu=UPW*q5{gh7L90Uk>QN=}whgC(l!! zA72D2Gw;FIuM*zpa258tM6&G&2ooY=wi>S z+GyU|$m*S+;PAaUSX1>^?wd{DS-&!VQEwM>=opNX*Z0Mz7iS9YIjLQhkaH?imNR0Aoqw8GPY>)@%;*M^ak<*Pq-|9B^N;9=mX)MRQXsvDJC%*Y^}Ahb)6ZXZ_$;xCURL zGXdA%6LI;X$!zoPLfk_;hz_>i;#ZYqxLtk$R&66))*>l+5=+}^?~GBw5O%2#{HxI6 zzLe2(!?=v!_3#%;u13SM0joj#G~G#VkHdmBa@-WLTV@|ri1{?H$lHHV9IBNCuq6+! zuWV(Gi>2_GwDi}sq69PPYdE_s5w3nU;t>zi@%GM8d^OukZbLfZFQ#SOxAZxio1%+< z;=aR%997;i@dMiJCr*y{U-_w-bK#B{2sh~N{K@JmE~2^d=(JcS*+aGHV<|s$eGQabNh|B8Wedr~&ZTko8NIn#U z&fUc*uiaqj9tyrQDbJ3$aK`^xXX9(%TlQg>0 z?t8_is#jq9DhqDX-8?jC3tGDDMCrpo`L--O2u>*BxpV0MD|ApUe@Sc&d6K;Tn*nI) z74Va*KC)xvYdF}xj92cwsK`TdWF3?{UlicBZ;kRNjvHVh)w2K9V}D#c?k$CvLMbos zKAM?r*g=U=1sGqqM_e3S4(e*>ptz?2A41&bh7|I7wWi6Q?fu7GLrd97iv*SpIv6{u z8JbdCn8EZS>_d#WI*UfR+&K_7RWE?P2`b!WtCUz`rF{9pAD)i_EOFI{j}Yfz#vSx@ z$h%+0t;VPdi>=*>=VuKu^uBlxG{v5;v~W;KI!hW@gvUr*7&5S%Xlk_++`YoVbfyZQ zo*|`UUdlJ@>?5T69)zryW8h#%Jw72|0}kCY7%z2_Dqd5cX}GnN58f0lnDPs7glc!o zd~NRJ;Egr22H=Gy$-=Zhr};FkBrdO|Of=#yEHXC23g?OUt{ShcTOpW`L%apb59-q;^qO&-L(sy8~x>v z@z3Sxj-DMwfjo> zg^|0M*PN}m3;I&d;%s52A8Ft>mGU=-R9RV|2uscSz}W+oGuWz!|O9FM2|;SlBRB98P|N=L$+&g1LmI2!w}slak*1IydR(h{Y=V4w$-OR zJ>q-Byc4o}%E9rDHw24x?|2}E*Y8UCs?~`yO+z(s-f^23uBm1YIo&WWx(?R#DPV^$ zk=DIK8MknA5+*-i2Kfv8pkhB|vu+rLyBs`l_^z?+&A}o}nMADq*WO}lk7P(lya0jg z)cJf-3Mbu4`IaC5WRJ6gVa*xh;Opx092?qic67%DhcB`pq}A8fBG2YVe_?q;H1Hm) zA?%?RufObv>S2SiEH*@Te;sAS49ul0&O>4{WWn+0dEjdDk4@Mwh1rRvZGCdrhSy+5 zT%c|<+HrYMI_7JI;+~4(@*MgW{EjQ-Jx@Pp>Xh$OKfMNC2N1)7e?;}cdANU6qujG` zE=*e&2pQwl_}lK!@TgTTW(+^b(&MC{mHz*=dTuLaQ(h?nGie9@YJ#EiRB{0>)oYSZ zrgQRVBYop09%Wq*o1v}z9}G&l$r{dlM5%Qiy1eWzemt`q(iet;4{@c|T|Yy8=wzOk za+)oy=|%JBdWg#Y&XSuY&`yJVBGnVe%$WpL}?2HEy9hQ83#lI*7S& z@UYe}oks+Vj5NIv@s@62D7T$jNgDg{w6v zPHXTnYG(N8s20`^y2yNsig69)dLMk-O*Fi@6CA&X!Q;&;eBMxd_*6;1;pINUe>Df8 zTkkROY^ENs{<vZ^^Uk7m7%bob@tiQbc&=5Eq?E%Ng)3@Bs0FNk) zar46?>|l-*d`Fh>6+cd}qnifcu>JpF#J72h??y(-k-ZD>VpW)^k{|);QtA^8GR+>Yx0ditX`dDBl%>+3Mu&_xBS8Ij}kG(Sa$|*|zOjPHmYNg<@zNBpj_w}-+vf8r{qbsI~TGy^X z)Ns-`9?|1V$%{Iye<>ewtcT2S&R>*X&m*=xWjahKfbJgezhZCbp_~NsPGOb!w81HhE2Tc9Q-hPl`($hciGr5GFAs<=em0}*f zr>77zeg(W-I0D=rY4E?BM`PyS!Dt#hmd!jvxf_3TaNQLj@tt1^w0nCVF2oTlte-s` zyE`ztRL-`w#XV{N-&drwc9cdi3O8hz@g?`5O)4!o5JkDftc`9CPxX5=5Jxl_5|p@ zxg9q3|Q6)2dysx^)D9u9yd}}>la}1f@b-% zA(SEFP2QjLN7*eCK)L|M&)B@*B;_%De*&|7Ps}!Q}<24(7~>_ z{pc#Dd*vK-U2+PRzS7`@*#_8Uo-x`a9TKi7?TLF`%uoB@Vm0~$Fr;S-+}|9*7|n%T zgNoaFX7z*PiC5egyCl_n7IgfK8#d1~*erb6Saw`k^X>0KCuLc+%VvN`C{Sgk` zwg<80( zP4b}MOF-LmB9yhN^QRVic>A3u8b;!jsOJw17cX9^gc`rI5LaTr z=f>(l%DNJ6t4Nb!4;8M~qnH(@o?usKXP6xK2NGU3vB_IXahg{yTI)5-*S($z4SVK8 z9@Y3L9S1l|HR{8?pPnY>ov`-E2WT*C&wC{6Kt)VRTisq$jcwZfeE-&U=PDTrU?&+YI7I10J5d9(&Jl!=!bgf(2zm$U2vB z%fIe&+xBI^*W86}A9c8u*8y~zKs%0qljIR|hr$Fi4=5X}#_O&b;0~|kuyP{wtyTWpP{G?l-v!dwPkV+aId&BcwRb_pFFo!>x^5>r zGykjG4nvx-Upeu|Mn}{At`J-{Abc4_{rMsCiO9%{qVhp7G#UcczrA1|>6eTjIly+O z5}ZdpeHtLjzl7~_qOQ8#?II-MP%vp1M@^8c&bHc|Uv{@_X&B^l1#l#S!oSI#uUa(4LfS*5p zhx;*9H|~6)7{*+@zr0xHBz(bX$+`I0*-ms`9|kWjP<`%A zd79*XpVY$`J5N^1Ze2;?e~(XUtIvCgLHMZk54c|c#pb?hr@TO!q(dxviuo6HKuTIf z&$1A9xqKq#wsS@QnXB2#)@%cdu8LIUSNVx4)&=!A!eTGq@0vr zfbP-=@%h`=F!E0dtdkk?M9OpdPqUbt1*XYH(V1RpRKi^A5}3?Q7f04Lz~Ao8?1X7K z8cd*_vSy2X;)hvq{m(pzdZogR#&<&5kSh3DWybv<>OlVi#r*wu72(oVPsoh5f{Bzv zH^99;O3O6S`p88V(^!UG-E(oM)K)y(ybCnvhr!BRVuCGjg#GhMxQnB!aLVy8#J?W} zXUp}t&AniBeLM(lnZ3ehvkshMMSSd@XyKCKMNmIP8PgI8clKUp%5 z{C9%CJg>&pKkMMY#roKy_ly0rc7!7GHqP2TPnfy-2IW$1f)V)5$+%%qk?Ib(U5zLG8HUjjKG?qCB{SZ46rRo*3fpQ8 zc-}zDvisN!iyqBWWM4E=`k0b_<5`&Kw3h1jts?%9J25+#7K|WGpi{^G^6;m|ychXw z9!`#8dLg>_d!7cCEcnBo8fUl7IVT)yk&AA(K>PC&$|N%4b7~ka*{}=uO*}8u29T$T zH1im)%J|NqAk6C3R#)x*8sOWT+Bl#kfqANB;}xKso!;F=nQmug?wmqgINL?E9!q&Z zr0M!!Ej`z%1sgxp-y@6_ullCLxyX2EOxEVx$rHElfi^C>u~T>;SMYt;pv}ux?$B9j zvA2+P;Q`{^#n(VLeJ2#U>+@lB&hOAUKj+g!)}u=c%D?8}_pj07vbZAn>5E`~lC;?| zTR*d;Zvn{$K5fB49J#yH@-6@S1sqm;erqzh*$$7;?| zCt=^?AgG8Q0ap_=xyy)hbPJ>U({F^BIPNTLo_HQ~AF1*s?BIws&YbzS%*!7#|LcI~%fL;k{gl?@77d z3C2pzngV>Dog#1fNgkpt|6c=l>@dW~tOnA0YVgIMzv6(Ml$93JB6o9M2=R?Gz`Rh6 z|30@3txgkvAbkK!9OnpOzSM6NeiyEsH&%XEAs$nGt30?t2ZmBT|KG0dYD@<#^H(7~ zTLxQu=PQn+`|sKkJ8|;kFlc%j0&$Cpg+ldeBh@QMySuWPzs_*lhVY=5r`QG+6J^Wy zeC(?4Bt|aMh27_hcwX;N)}d+=)}{7E%ly@BX5Kec6y)O8HKW8nVdo+H%Sre%Ta))E zf8KG04%+{>SMdFB2Lv!%P@SyD*RQgJ4j10?tn`hFPNa?BA}!*FW=>&$`8V9~Fc(jq zJ0OnmDuhW>vfvSD@cCDRanFWrxUqGbJb7;wlo!OpeRImtnM3vP$xiG$&RgEAry+D3 z_mYp=Sj7S->OyT;5np@bqT<`eR*c)5hvx5Fji zrMvc`Ls=9kq?=%Q4RJLC^wH5%6ZNJ?%KQypqW=`~eFP_nwt1bEx5^6eTzQ0O^7{?E ziA;gey@uS#MHd<=Q|5nj0}Wz~h6NV3^`9y8bul)o9)@3TVy@>Z(0^(!er{}$=c~;xlDey(#4Ko9^;m73I)j{2iFkUzZp3Jb*z!{=7{xUs3f{MTD!et_6%|LZLqN9f{#;p*7MwSk4~dWo-I z=Ai4ER`~#x+tABu3GC_Ej{l*(%>LGQe8+kdnd4MlShK%~6R(^7TQm&1*Sf&fMs=?F z!H|qNB6z1BL1YIhb*+A6(=?jmnL$rcY6iQPv`G&Ycb&{*ec5x(+(q>0+N^r9$^GY0|d8;lY=!*)T&>$wfr(>!xW zS7(9uPo|!JELYw<#r}-21OErF`F_s|MXsf(a@e1IRD5s}Z_m{OL-OJkK`7f2KN*Xf z`k>kO)olBO8cexJnb93bi;asfKsb5pgfp5vO9%l?b6cp1(BpIO*+Kt+H{5C0M#cGZ z(xPV<@_d!4tX^J&LP9S7=@KJOk12wx?pff`MU#uix1wd@HVk+>UB2|g2k?!Fh3!eE zT-#I%bMoHsvXnI0`Y!Dt=;SM|u363Y*HPZq??S#z^OB-9Z#hhyKEACszS3%k>Pl_Q zNor8UUnAaaIO(A)eZ(hUtuR^p8HE1Vh4-?fjNET;_>&RZ!rINjfK>y)_Kk!aIO@T> zVU)$@)=SacO+~3k+^tEW4&sSJ(O^q=`)~a;`B&3+7?`b%D$#po2VzJwyD$eYnIwvV zp|lTO`j#7O#|k|Lzk`S&DNx*E$S=?{3x^kR+30kcYrZP?onFW^$0V?#@w#Yv>%4j~+we6l>d(sT&u2aXcFVols;WY-%&c(%>?Zm|RJ)mM61{a9g>-EnT z76-iMm;T1Fu)e{#`sx7EOiLA4?vc+czK}cX>=l;0AZ|e80oZq3!fz&w#=(r{m_N@6 z4=E3);OB|9n%VV;F2+!9{hpn*tni~PM0>vG`F%pz*SVWeWp;l&^&wPHJ*^AsYYKUD zPY=0hSPAo5Ghk8_F>Iv=aQMG%_$p_Dyz_l8NSx>n)7{m%?Mg4aILI3(SHEQa4j+Rx zH%0h1+>kG`rX6VHYd+0&ROYo%Q{{^T1vuhHr1)lu9`s2g-{mkDHhYhX@)POdOrH;s zTkbaDAITe3*dvOC|IxuK25Oj?UB{A0L#_ITxF3uD$v0fQ4MTe^hD&4H@g6ViAang2 zzV(o?tlXP&5Y`s)-AQU}ON@$g(hzzV4qlY&<_#y7p$i1;rdeW+A?BadYSViCXPARd z!X|QURtlBtZbi;KODx3 z0}3yK1ml2d&^OvwA5}dyaQxs9fiP=)T_kV2n+J6{j*GqyL;uB%tb2(aXobDu|9&qP zR=m0niH}0zPl7)Gx>ygcpD*GnM|;YYt5uYNM)~OMx=)-;d77$g0G!Cy>0l)AQ9jB#&<&adEAl2aZzimO!rjk1>xyEb^cA)3zLAWC33VW34 zi+cO}U{a4QvIzAz__7^wdfOirC%4aqv7}4$EK}iY=8#78WF?bS!=Z(c6+D->cVjzrKs)JU7 z4i?Cjik}U(;MP>ZEpJ(|33Afj&o025IVxgTmkqG3K?awMwfRj`3yg633wd!jnN9u= zOnymqc(}dzB|8F&oI~J{@^wTyd%76JC}p zMh-Spz9r_B-4kbVt$r+g_n!^ZiFdTm{3qsQ=Hkbu(cZAJv|FjV3IjuWLF6;3%k#=CQw36RV-k>@_GBUgwDgaz$}{qaJF8;ua)S7>%?OIUqx?4iMguM?>K$OhdYWty!Jwq z!$vqwGaN;gE~crg;X}1>nUenh*(-7|B_&Zzff$q}y5XWCHHJmxf61%lb34We2bR4D z%g@Qgdoh&8OyMnT)x=F>N{$Zp)+ym9|80`1DaK_ul4uLai8^IEcJ@}O7;qpzuK_>XC+@+J%M#RIT6Px2IC9AbRlEx zIX*k#1V8vpou_H&;scu7uDkeyO+0T4L)|NQ#kC!5NIGdt!d>xIpHRVllpfT4FW?a4 zA-4{dz|>sIdN6lnfkO^p^Zc!tI&p&B6}{nd(_nbFNu4M6^da86H@d6juoLf(!K34H z2o(&u<7hj`u&m^&KSpM%kblG|y#QCOiW1HF8@T3h2@c)V=l>oN*U^jg`Awqi^L1n1 zrRE=-)DXeaeRMG;NEK`M*RjOoq~D<(%F6yKqI^*Xn2cEj7h>A+f(v$#ML7lGU5sTG zR-N(K+aGXT(}b_2`CieNH+<6h3|YV(FL)5{0;B2dy`%i@#t~XL%q)@3Sm%WY)EdG6 zxDNNHGptKz7;m@<&jVGJ&y4f&gk*xa4=<6HDh_6hlW>i_`dGPN9na~72-VX$AM=>C z<%>0KKY?oY!?CkPGwXfZ4mO^vfCNw=iWvzMwW2ioVOXZb#{op~8N z_5-Niqs^}_d5d?bAIo&RA=ftZ0^Kdc!I1Rl27^k_XKe%?J~UFkcWqCsjA;Nps|sdE z+MX*TUh|5)!^}Fz2Yb)zjjcL9Y}4Skcm#8C_N9^H=Bufo(>oQSMVgOkkk|ND1&^J6 zjrknjj(2ts#3a)zY*Yu@Yuml%nHk&Jr%FG3Y3PcB`!s`pq zpdgF-&(b{nok^L_!*9!(<0ojn8w0DBnDNFR2s9r)=cntdnBi<| zoRVHgee)x>;gJqlk9ot-cuRz}c|mYndpyi=)8v7dy)od#AY2yNgNgU@(2H2LQv*hb zH*VSBDLZ1*6n5q66?U-3xq^>hp(O;4+X{Q5h(SuezeU7m$*X+L)1JEuvcG$w!|4s+ ze?ybsrhLNtL)39fUW9B?9PLht%WWYfiJCuR(ea`iHYBLCt!M{FBo+Man*KOxw#62?-slyOdIk~mGc)}?z7Ww?TLq{hDU?a zSa9q+^b04wYk^ek+$|iwJlX?yb=0_rURD$ zx2~SR+>V~(qaGb^>oc__1~~ha9>$r~u^*OpkS!%mROSvgeAXtMk%*A2 zg>AalH4YM3n_5BlatAha(g8fff^qP(@$&a;eV~5AV7L)NdC>A9Xfa-niS5aYIyVkX z6ar{auGjA6^tT-;=dX^B%#`G}S0<2u|CMvJc&N`ic%XI(G6x&*(RWG5LiKIQG*Nbt zvg(7~|FNOnBU$io30{hCg|&-o+1`%%m_)iV^)wZ6?eIGw99szYzP00rPuW38SvjAn zXeT>0v3)RGviUgKF!JFp% ze<@2shfn%o2ge3h@Y^YFg0ry>NT_b;{R$Ma&RvGG-f_??PQqsx8sNY#>Ui2bM5r18 zeCkZrb|0^O8;h?_xZyPOuWSK%s0)oNxaxyN!uvHhAw@S74!IccLCRG8C5GVLV=n}( zmq6~{O0JJbguy+_q0d_m9*?wna@sq*ObpNYCvV6#TfLxBeK@F)Pk)YeG0rm$!=r^G zVV1hz7tiSS!pm9SENs|&G#^1T^R=VIjiu)ya>F_J zxI8L6s6WdtJvJu#Fw-*NP4wn7%evbjv zyG$Q*OsqJY4^v}vpfZ}W7^o(A)Ryr*zsIud4d%+={ROya%z62(PS)^V<2QF(_LX(_ zmjD!%^Hn?kDsFH1js5NO@Zu*G@m%UsnAbQJo=j5bcPHy&qn`vbJd_Hbk@UMclGbaK z6${#Fu6#tA#ye6q@wfISaJ%6N4l{|5kx#qAmjt;4_kEv_HkxB-=rWZyDd{RId1z9SiYOXSVf|S3YS& z4wUhi`#LD3F~9L(In6ZgjunUXx(NM0B|$r4f$sXCk6jMw;@HFk!kGJ^Fl}HrXrcM@ z4Dxpz-d)B&e_OBk_USrYE(xc-ogV+3C;^x1a=zFr!9xiDjpg~I18&4nbS!d zx*OF&WcFjWob*NC6DxSFtF{oBwu%@t;~>*dlV@-7L0zjsxb%7tw$_()Ni>H~b@mgl zrFO&eyeBX>$cpD!(;cd&jC)Pd5_TTn3WtLGL9>PquZxnvoG0b{v0-1KfM(aJ(>H*s zu@-+Y%?pdAZkVMCGBuL|tclFQZn;U~+gGs|jvcQ+fE@<9q`#C{)Mkp)cj5 zyN>zE9@1=TO5ZYmB4-E7Puq-V=JiFJ_)uZlcWnqIFO^G>Jqzn&h(R;zVTeh#uzGBpb@9W^Oniw|tTpYNh%D{y(iLArypp>}!r@cpJ#%Wk6!)pt0*zagD z(e*uK5rca&Y0P5JlJ@d{)&V z0t=2o>2nFMo$Z4jT7&T1t6RdaRN##p6m9+F#ehSY+F>Bt{r$$y(09aGteu#}DuTYeC9Sqs4&uW^gFlb&b-k3C6e0cu?hl`Bq}dLZ93mb2$ZPD> z*+J+Lq>j;@w=wA?36xJFzPfB1Ga~;^@3nQ%JFvIx)8{HIrr+&C^)a!=q7XLi%7MA$ z0ZAjzj*nj{58X1B*(6ygD^C<)WUmYIRp+|FyH54ID5{2iA#apoVi|v4{zvifs38KQ zzUX^D}NUuB1iaDlQD90Zz!22)NM0MBA zaK_CO;>g3kiuAg_^vn4Q=^4euJ%$(>RR`cUO#Xv*7GIX`0M9&iKIA9uEsMxEJvUP} zr(X(RKi`iV`<-IGU+iFhO9?lWlq-5%J_zRxW`aHOg-Yn#QF)-0x6JLJFpeNSpj#a* zIj~wjtm`G%cQy&qo@?=6G}G!^rHw7)_X(Z)?*ykv8~D0XpZgL&;pxCq?)z}PqHD?x z__8D%V$bVwGnBxq=rZ1~<%Gxl8TB}T*i-$J4~j|oc@iwO){`GO~Yt!8hHy5lPEdI&Un%9=>GP&K5S zkEqiU3eT*DyxU{p=5kH0Li^mR5AL|+t1}x^P>4~_bMRZOpLlUrcj_&l!0aq5-XN1g z;nGs>Xrm?EpRgVN1@wb3x?6p__dgv=89$iSM|inpKYYBm9=Z+J;wP1(N&D@I>!KdZ zLK5gcaU=)NFFz?x9~6r=+WpXExf-*aCWUkROWW$_YyJ^l-#P<%3)}HW^V862WeAow zkCPA8`p3?kdCpLIj6GYghXvnjfczS)yy64aU#5J$SXFTzTL>BcbHG%Sn8rnivB#Ey zc+`8Mkk?fT%fwRtzP&^~{a`nAx>^O>!Y#SSH3Q`mwE~RWt|n@}(*|=pIzO@ZSQBYZ zv`5xKP|0a#_UHrJ$LC^*wS)LMAOg7K9vJDb#wSoc33e~#t%u@R?d`4D(cKl_?3F6K zOo@L^9Q#zi@$B(kLu|LV4vfY5g8t7Te1W1b7c7r4!$f@yCYGYry;>HgCIyqurM!3f z4tDG2Rty{DO5cW^f-3n#8~TvG`j?bdecF!^M@WBMJ67(tYXk%lhxCY+1~(^`70=bi z56cd)^Mfe|{;encj5Xx_xE+K)DB)J^M`j-A)j>H?y%3jP-7A{zu7a2elz;lefU9Rp z;Owq4zHpRWwm#2xtTOm091QTa7{(B|$oRTtrrQ0pp#h*U#tJn!L{%LUko2Iyc82;&$ z9h~J-god`HC;uiDvmCuKo-$K5576P~NVjbGs+6A$a}x~BHlW^-!6@|)xWAq5Zf~cS z(R?XD_&((-Wb8c#8$0UoeH*>;K-B;ozwoB8atCtThD^S!uR3>)jz#O`{je z2Zu}f*TdIXOxXamcUHyBPMcX%wSm%dQUNYrF-^30mB2Xi5M?~t$_jkOV6V}AahcZ+ z88iEcfp5r%9v(;WPK8jHn*&Z`)VR5Y6#A3?zxMK2_V;K9W#N%R%cZ?Lt2mf62} ze2;I;cY*|LOG>ipa%eH?dE2RjbTlqIc6;VV0jXuHb?#?W_=^nT`Z%M~_<4}tlUK=`*; zhbzJ)(2x8||EsaH$?FuK_zTWAtdg63xpxAt=@D_}hkIb}8W;99pcwPWTX*T& zNHJdB7AvMbhHs|UJnxAVdK1@u@DMHGyT=YND0GE^!~z|?ZzJaT55}d-yu7(|cfuj@D_^gqK+dN9S1`~vXx1{hVu!I{8k;orLbVqSY74&Y` zkxzPQsC?M103W)ji&HcuuqdmT{~dgfEql`*t29*b=*0^xa&i8W=sJ{lxz~rkczKj* z{?)~xCt9d)R>Qi}-?M=Jp7hQkEU11P&VSSw-Fod3?v13LO;*xYV|xrbfH-qK8b2H> zFYoUMHd=#Vp`ixX4cEt@krE7F9mAfL#zSULPlzlwMCpWkkeW9S zw2vF}g?;Ry^j}HaoKy168jbvZf>y0r+kI*jmhgm%o3i1VzTiLB38s*yu6J;IT-8y6 zDoLl=eJsXg*Iev$&|Y+zGy?xRHh{CG9zSnx5BX&!Z8J|#*?O!!J`gvn&$!=0=jS_} zpVA*QgjvI`!H1#8p#4G}-oM%#9VvtM+`yZ{dq*YL@%{h0y64deT)s;{<=jRV>1PiX z-AZ|o?_%Ls#%-9Ky90Js8}Je2caUB!K!dN&^4F9HQA6LyvbBc=|A(((Nizd@KsvgP z2k>9Nop^Tp9QlWjpzY~3n zf4*jy;tiC4#^s{=d}lHDp#%b(i}|DQLoBfK1T5a_iq`YSuz2rJcy47b`qhsSFD*|8 z*UjYNF(E$iDtpLwAg!z}ynj?ejEJcDbC7+1sa!7yeOR%rNqv7;a-8 z?Z@JylHO?Cb%(6;@J~2*S}qQ@j~Az(FNQ^?Iq>_88vkf&51DbqR5u^T0t`DUj};N) z&LmyF&&vje?)bsGd66HVm>c6emhkc&e-s)me{nKpG!!PQiFrp>0Ct!Hw%66U?gRt; zGgX3jmpxQW?M{AyW5xVVgB8m$?WhF0dlbnv#Iv)vz|+niFqt?)M)OF|f4`)y#(pXK zi)&o-a7cX*af{1d*mZ6@cnsFyb~^fa!bltItM1B5lal$#J>I-Y_au8AY!9i#ySB5e zP%M*EMpKVKSpQOo5BMa3lGNh18XNk+5FL8f!sDH*-v=5>apC~G2ap2c1Hwuj%Kv&8{uG&bjVH`>F2YsBTIebf0Q z6Ueg6;tP&dvq}?tOuPCA{C+)WPjBmh*Uu7u>Xw#ZIC>q-(I4B!5nA|UI9|@}i@md? zEcG+Z*eN&R;QCRb(%ufI^n45v#n$}hS$mlDy_l~|(GvFI4yu8!5Yt(g^E%QcMi0cA zb8&3^FA03hDCVK&eT3xu2Vg|#I&iwK#ce9~VK=7`?0;29==H1w|J)(1)YVgBx^pa! z=}CLZJXJPzCHa`n7W28e2ZULpKSQbM83^$)=Fi?4DQ$Zd;NyVH@_6E*oFi^%K=d*8 z`G5f~wD|#}Oq*G;_h&qilZ$W8s)=E3=3V3%Aurt?M${Mc zJ@+K?*5@6CH(dIc$U3x01C}5(0}Gd+<74 z+_s}X*;oy4=3j)x6O6bQ<&*ZdF5%DK2(rNUrhIN0=^bd7G%A^TimE^09`l3wO)JIc z#70goA&@g&;{*R>daH#qJ{&>6YZI_~KZ6pm1>AvrqtVmLn zl`VUG?1T#0q*9@bY$CIa+}AnhW^e7%lAW|j_V4xW_YY9F_dV}3p3ldV-{q&;^`NS- zM*MWq47ST9c+r*nj9jy1pI`c6vqo>MU8>31#pd*=LYuyPPiK31#>XsPx1-$bMNW;N zs-&Mdw@@DrH``(0m{M>U;3=e-tfPq&2GFb6X*s#$CHQD!X&k|k&cCQkJv%Owp^9zQ9c`qFh5l2ss#L)P#>GIS9Ka@-y zggL>S9b}wHXH#A1mV-n-eP$-~ZJrLA{Mmah;d9uAA6Renj?Kw5P~KRXN7=*sh*{ne z95#UKIgcl@$UVU{d7~>`=|7rn8&ymF%lPfmI#4X;d%_KtC(+WIb6|ot;`4F`bnmJM zDTN;NlIJgMf4PROF*Z_eUR*%)y(Wp*R!Fe(rjoW@LEwNOqF@&~cqv+@)AEV7t+FhVKgQ|Dx8&d^+Q_Yy0I;z zIx6@7;=4i>P4VHoNPO$!jdDXBxHDUValR$sxFlV%KJ^z(^5wj;%wFP)Z@aMX#0}Vg zj|Su!>XP~ZP5P^PLk6`cAR=Wb=>0mvx(=~NZTk{Nq!u<{# zi=mfS2St^xAw5-Z#Et<=A0$K9jxVu}my8!Ck@OV(0gu@^NiJjgtZrDeU73o*^6BfH6Gp`(sJpFp$w>L2rhxV@iW8#*2_o072TmEor?5~nJxb8hqMvi?S;U8%XyvvP{W}{$QeXag9xjGI-R;Zw-gz*?)fyqRUBdH1s!wIj=rquhI-G*k}mfR!VS;K?!`hEy!T6 zDV$GlWobjVv3d(BeKBgq6(<|m?su=KGuPiP?yW8cUdh1&|E6Ov6MnOrVMWunG-AaH zbJ#PN=hyrwhV=StGK-}n@bC0qXd0mjhuqs!Kdy88wf-2Z{>1;Llk+IeM|T!`)8fU`a#W1Ce)S*EwuqW69C~mCkF7|?lDiUkb!HUJ;y2JSE;og3 zzPa$=-mSKss(o%UE#K=-$EG*3<-s>_VY?{oy2b#)??sZLpg$ETQh08c1b1@{zs{#b z;rWspyl{ZwDW2J2svbuxL!znA_o?z;Ye(ST3j^C~X3FR!TKm$C7F+Ae*ZZD;ydh)Z z;*mXUh=nU@?);9Dj5kcW!%*4ZIiGt!oW$v8B^W!U1lD{{WTD|>Y3@B&(kU9v0y^=$ zk44d3cl}RpfB!s=^*xCLw(`$p#zx$>+W|kd*8|u29+bN24^B5(!wj8_m0b_<>>Hdc z4!$8l?N$6a-@Klc_4`aEHu-dE?Lo2NF6UAYeu<|hs>8mUpD~T4;JF*7u*zB$F7yY`H$%ejn}^^T~ff=F1^JC z0lRV9kqx-}i3UIyeTvr5rZ@?o^LoZ|=spP;*druqWmD7W~ocDeE^-ioV?c61_=FNHbW4 z?@y0H%b{A}HY1R3-|kP|(M~M6T?Gx~+TF$N0>so=b`*X89yUzw0nKSPIIUj|ls~)3 zf=5Ntj&5GGEAAj$A0ox{s$w`_=PaamkHMh7 z#@}>t^toj6QSV2t_FC+38E0&6uYtbTN3vb6CQ7fJh1A9GlDzSg3aqz$*tR3x{@jps z_BUWu+F$08QO7mQc{DvoT|5`I0Pn<4#ec8(T^0Ay=9?}wVa6CCHp~XYDmYjFyd^ts zYoZ*srjRuIYl?$jbLNSCF(E2aO@a%dGlXd|DN--b^PQG!+l}7 zffLUWPG%4G>Cwr(oEf;Lo^@)vg+nhc!5>LRph7lSIJ*X>pX@2?)+)j7+#_Id*pBU1 z^T!c|?wlE|4iOrLE-l62woxuy`o@I2guXF}d@DmMDYeXM!O7q2S;3A9+PQ@16J@E3OFG;}tqarI zYF#t4ra8HdXcW{QX7K!lx5ta&&Z;cgQ}2;@wy-B&J)j9{TieqzYo13Fe2h7+ub>3Z zl2FHzIJYP=&#btXb)GUVXTFsEB{TPA!ABi~CT^%m2Po&&{z9jzE zkw-hEL+A8S@N~{j=5?R*;e)wmxZtJYfj>k`APBA{i3#7XKWinYSyll zw>6OY-T1<@E%G>HeT>-fo!>#$p1{;=nsELT-^*#+xAlh$mfGN=`_-_MO;MQdF;V{H z`taGW!$iuJa*t*)gb&=nHmv+YcqES+dZdcA3FY{1-3z|^R)>|RzF@cdWb_Sf2U326 zYxk1p7tFdYJJ6vAmhSxw`R8j{+Da+Td{+dw`~Oh%+VYRWQ~8WMLqqI>|Ka3GA-E$~ z1Fj!4q$1QN?aOx+D(mfO>#{<8;L;7|j@K6uLN{(gr$;cbD$L&kNS$>rR?*>YgE;EYhZ{8VZ?p#&LM|V<6O89%eal za!Sqmiu*GDusNJ9vufXKP@N)S9ryrGKi7sGPb;a0 z@BICIbL2+S2JG5#H`eYohvq$|c%be+_$~Ut3SQb%e*HHz-}aQf@5^%*`13!(KwJ1x zxeAX|`Qyc4E%2Dc@19GXNjl$-y~?Vj?Z$aD@Kb=;FUp?0WA0&)g%u3*vO&|IRq&)W zlMQZKN6TA1DbO*MUCN8cdGD5?`D$&D*$<~$YZuzl9%K>wE9u2IK5HL6CO&wuj|NR} zrtcmatTWdiF5$fHLpw*Xkbb7h=l>OwXmDBH%Ul&+e!AZ_U%$yQBI%+AoDltwX)mZJ zsZKtHjnEK_HZR009j0Qau{z94NTPqkT*%QfNT?akwYWyr5H`S)nG7*i_T_qvB_A}! zbB4O;wY0cR&uJN9L6e&PVmM|nA-JA?HF1C3nO@>jwOv>z;oKR{gO%kT#9vK=vBLrb zh~s+KM?4GQLRDdo^A{6kPu)VQ{j^v7cuI;lxtAe7EQsCnQc-%S6wt+1Kl$*tzHm3J zPg`v?{G~@NYMS(HLOq*Pl7pxIEJl|WBRE#WHI1*Up=fGP+55{#)(@8`4?{Wg+C2v}ne?_tF ztqmS|!@0zVQiR9*K4UMgll!pL2=wZtIM$o@y8Py@ZqyDcn!hm~0?)GgNvZ15S9A)k zXHkw-6cNp{a(pzzfe&w^d-hbk?Qa4@Z}(K{{4A!pY7@EMcspEIQ3D&6*vsvjZ0NM2 z5zBQtz`mDKv@t1$vd3AnF55<8e6<5A=W0UC(e{)vOpEltq%-60Tywr6k8C}9io2Tv zsms1r^sqLBa76?SJ?2j9l#_FkBCcV_TS*u?ND2;}M$v;U?v%Xax{wla7nTj=jQ#WK zVDvnNw0Qk&Cv9TGXV{>xYc*(?tYc?CM34cwldLF7&>pOdLvo9uVrr5=VejzlIEHDv zrLZ|9p7!mJrn62n)ifox)Ob@)jxVEi+ zjttes)~q5hxB98by`iG4xRg)l{%MGV>X)JMn{l{DMHBqm>(j{j8nk^2KL?z5pgtoD zG2?qT5LNj-H?sp2<3g;zG4A8~XgNxwHObbQ2pCPRc`HX!JFP2~0bp_A8O~at2IuJNrpC+!< zX!BrRiQJ6Yk2>KVOMO^UltAYe^{0_Hizd?ED2V5tk1No8FG+-e26&l`_i{%YyvT_%`x@!(G zNxhUirWRBD)bsKzO;fyi=`Muoyk{G=ds0&MH~hEu8FQ-C#gA6puQy&>=(Be?E#qFZ zeIM*t+{kKDH_M}QS4NB384fhT{~ofpR?yMf21j$h0IkYoTUTu0`QV;(^I9rXTgJ0X zB8y<#G#8=thz_bws0QzuYuSbee$;{QTVnK4c3r5ZpE}%gG4i;W&@+Yh=D5%asTR{4 zVuMbTDj`C91j}3BPI>fpA^m56MGofty}S1z`>_518*{^$XB0Hx2Du7Mb8DnKowygi zLPLCXeG$$%Jq5i-@*AH=3VnIxLaN_`g%n$^yK}AtD}@E~U(`-{`$Qp4Iiw{<7!BbJ zQVT3uqXlOQEXd{7A51!(!CrT3q$9fd)HuJl_%>-59y+xNr*hulf@!HJx(-Ioa|ZB% zGuubru7tROg*o3`+bJgp7EBU{q@P2XSF+Ysb_Py-Ns_I#n_>jF?3sOgO?L3VN{HRY=6T?w1KO5Z=623X{##V zJ9=|gV>mcQ#81)>4_m6=#)q`cluLF{S`&j z1{=&jQwgKrBnxwYenyA!=kRc#5$xHdhbyf3UMqZ{tdV?C2M- zr8jds@Ek8~yv@B2qhl|!SwlNe>_<&n(e)TBzg|siBl5_wyr)>(YaFHS{e_3G8$(sm zI;!J(q2l@}IUgx15J}q39CO&Je#4Cj_aMcbCI8ohzy1bvO7;Oee`HVJ} zXEV9Z&Xx^r?SWl0YTI^|e&0IM#(xcXL|sTsHl*eDwRmswV!7?cs~B=54O2h|MpPNl zz&Z^od9qvh**O-M4DE!fYxN=TP69c8@FZ=!V&=vDWfxaez=f`hh0)z_;=+{8*fc>O zx}R26b{>~cO9!WjefPda@0C1PX0#5(bg!X^(Rt+k;`(Lq1QO7JX;XX2=lW zqD4M#boiZ8wmR=MRchyv@5kd}^ot}~b=!&j_i3=f%lI>2%Q?Wgeys7RnR3?SLON)A zRUYfD3gV!<%;{Y+%Li?g@@#@~-!F>PKTXuyC!ZcJ)f6KqEye|x!tj8nI?S<2Chx9& zsahvU@SDcHQF&bRnPS1rlg*URatb+bO$DP2l31cuE}RL0djV z2wsi0SX;~UVtnl6vW@oq@7aj24qCvEiP~6^Q4ag}X0rYN+LQdI2KfY~vw#IPWSo>o z!;*W6RnZ|7+~pTu=i2_bf(tD%nwYcRP6vDctbpr-M=`t^PxHHRUO>E>e6ROi zxU%p%v^%W^OFyRZ91Tx8+x`bD=KVkRu7HJuB3a(14dgT1gR%=#1a+?6O-`?X5y?Fm z?r)~R?0ouHcT3)T|0wL`E=TEpb=axZM8QLLlK5`2JRBDe)0jtxW{nk_6E9)k zRmV|#x)vnw*o-?}Y;j2~&rRTUri(>6{I@ks(eaO&axw2$3#UyNDV}pzCWYg>VN!To zqk~SymGJz$jnB9{&E&+{M2Bn-iAOF}lDId< z3_QNt;K6a_T&0#J6E&=G-t`ZV;$6!c)^(;)0S&l+za9*-lAzJdO4wYjCv1#di61P+ z;h+Rfuszp{o~$XrJvKdHjMNrShm}L(COzRc_f|%SdSVZrEhyX3oy71KOrMj(d^rni zqD>{74e}HMlJ;Wf{7BqZt_l5(hfsmcgC-wT6`Zae=es-^l=VEsoO1?~TFf_GG(#1x zf3ZOyo?oCJ;UhFS?Z?_-6R>BHF4T3DpkGr3)clws1TDCRW&vrqO-lk3Vuq7O=cL3FZvr zSzXVL2oL+b#~I7-V|JMi3>f!@hJAfW;r$fyS2OwE^xRJT%=u1TLQOH&CKpZV(9J<+-255ua<Bjkep}+Ui~pA5%K3twW#d5}B;>5QZH0z~Re{;Gj!9z1q}| z<`iC3?C)%g$9Yb~|LR`M@On&$Jc~X48Ns9*XGkfJra8Mm3aKGxu(zV7NizY*&j`cu;ihnGNdnz8^dMdJNa4;^TYSymQ!~?SpytekBLMPJU)y1CJ0(>htM*r1IDTz9P_&t$v4>C=!tE%@3xnf1_qOIgWz6e#O0 zzG*+69yI(!-A<gC~u1ikUOdULSpKIXtMlsgcfa()lP|H73DBgGvl7gy^k7yVzp2K4*y!f1#-LX|H?`!C4kx`-#?F zHlY3#5id7r!)C5^zr6JoSoc*|)T9{D8@m?tEM6`Db?!2L4Lpt|oO`^XW;5Olwn6Qm zdhq8u@3pv&H&iD~amuB=awE?mwmCjSTqves{f*i9dz%!l<#X2k^m3jjY2(v*?>EY+ z%A@>(Lt=t%4R+6Yj#18<5NT~hqf$?_)xZryn=!#A317c6gUDUB_?zn_d;ZCi^;=_w z|DAddM@QANQCGUq%kTy~=dTZrTrY8MRXKDTtS5AGT7_p_#$w7&OzT^gIFDx48dz@$hYaGiRHmE{hlx0d|-zL?)b2ic-fwu(L%_NTcEq_TAG5p(NS4qY1$ z3m>+A!1#XmaUHMiZ@0ap*-?C_v5?7C6kkz)^iI4uqyxBynV|brgv8lznA-wJTEz9+ zCAu$J`v9)-<9P&g4ddCG3H+Jt_6>Kd*D6v%-%+n1?#Ue;B(5&*MQf#Zu-hMNo`+(K zPmYzrg1MP&ty(m#j^Hc{i!@exOjp^}mg^H-oyA*|bTG$`Yo~Kpvq$T=H(@gO5zLR3 zmC4@GZmth;9&=LsF)*2CE^(yR#Tx7f--l$6DT8q_eoSa-uZ(Ccq=wdO^0a3vFyJn+ zy!}bcxLO;{rj~IAcAa9~W`3)k{|z-#I?4w;S&GLCCgW#5|5{GA#m5&u-TB;J zY5b;;7L$%ReDW}~j%<&Anzf+PLI)q*DucbtlNEdS@VkHHH@v3pC-3%g50|2DLiKnJ z7@&O!mHfVm-iEN?6YpJJ%RtM!Ag31JPtK%)`z`YA_X%`cCU}%fqXO@B2cYE1{_%CQaSREQ33LFR*sJZfJ1NNcE&-miOQt>D}UBBXa?yKb?m6uW1^8f3hL(f>eGRy|e9QENk_dCqxZ2#gJ zVT#&z9h9#+6;arenPLss%b z{(X)Z!{<;Fo`)WC5?@%&l^?m#jOLa}$hh9G{WDveN-ZzwcOVIIjs`3jFCr;Q-n^SC8cv^rnQ*`M4&p z2ON*GMWdgbA)`d(ui%8Chp^yqJhntc z;ugLisNdj6J@0u@zklk&=3d8P^7a0(R5OhoYaU8R=X^!gp=z-BDfcg5D+QbVK0?v3 z16Y<8irGhX0hZ|C!Yr<%OPVIkw#dej{2sYn1Z4o+FP36HrNz^ZO5DK*EFf}$j{YZjbkcZd5g zP8}B3$A84?%zJosDc6U$|3ET+ul#2L@>Mo1xcui199rA~PI1q|CtkI>pNstu$<2K6UZb7I*yn4>hJv#%J~Fkij+oyVsS% zrb`y=QWp!Q$n{-4Hb_Lj4#Tmy-kg7zv|$MUK6)K41-H;-#o6Fis`t;QfW=Ot-JUpX zcX=a*C^W#m>=1Tx9Ee)yd7Zq+^K>#w!M3Cz$DjKOC#>Fq^HCSf_UNGAd(OV@I9ArY z-52(1+e6cpM5Z-DO4EM)!eY($te_Zh$&LB=XrT#AI&F)WH*!s29|u{#@_G~`SMkhr zL$14$U=jbD4xfdx;xmEhD7d!mly)bZQNd6huDeZQvx^R+&f|XQk48}A7EkxHT&TwU zqGI_UTl8(_pL0>N5c#PAv%8+*doW`-6OchY#zvD*MXg|U*bKH6)wA#Ow=&}edQ`)2 z0O>LO#y#@`Rc7VU&DUDu+3AP{O%w54yeV8An@G1t_apt~k-|}~!<1|;1Kl`VxmI*< z3U_HjE3-~eP-CDh-M~41XKu)Kxffflb7@Jkg5|bJNyG}xWWCuXB|bk z##~a}$oECQouO-IH`-PG8?DE5&at>|pmdcLQp?q;;d-#(9I=S?1fd!PTW zjp`XGwEegv*-Wcv`#tUOg`DREeTZb~HXFDn-IW$ZCJR5621=dLg(P%J5w*Ezzf|Nr z{8ioAt?JP@ZG;RH?y7?@B@^xr9t%^e_pw8h?eIR=XP$iXLSdS2p}cvfkcQNGh#F_3 zFvDApqi5@Yd4>)SHZFyLQZ>cT`v!DUvl$O%u9E-faTOaE9mC%|qi|ijLCT!8SF}LG zNUVMki-$|Ca95x{{4udZ+qWff;zgKZ?{*92s^x_gE}1Q^9ljs!8)l*plR_)koSX6I z;nzHCAJ+c|g=yxKo9u}Ay5TLlE`N^yIJ>^nKw~=Zb{t!e%#nZMIXPcHCt}|j<`A^i z4vXfLf|FOa?9Mc6d=c{&vXu3WmKm!=;${8uZ|1P8}*t@R58?`~$SfB~x zR7O#JW`9ao=(1>eA2L0Yhs|58AR*iipK_i2#mjm^)|(hSk?D@Jd2WcCiya->@&jkC zLN--Tg7+8kJc38=g8rTaTv#1}u`Bspmc5&rhewmaUr)jKGWYe=^>3T0P15~nH1}^t zDb%5Cj~#00aOSqAOfbE804)X~M5>+1RIN zDjHsqz)UkgihS-))^qO(($!lrF$+!D3}%ez>>@N_dYy-IDjZ_S>4$s+n2=8wr|HeBESvK`M+QjKRTx&+f|V>h~? z--o?V{YaC?@oej_!J_(!K2)!H2mh(rfk~~4GWmBg`MlQ?5188He^*MuaqC4UoN%Xk z+y3H?pvkOg9cP0V6_B1)Kk;84|4!X0fjM5Q*{MGP6dKo;)O3|H?_(dyd{Q3mx^hYk zS(Qv*DtnTDdkwZR-VWDrR{xK+BiN5AmdZ6&MKt_dw%lsGI_ENhVv-fF+<%h)oP0|5=_}UT@5P;g8*yKy1|$U^ z#@^l{u6t|&pNf*vH=-{cQlD4|~ zq}yP~2(fFctK)S!hd}uQFIK%}JPHz<3g=;2wh3&$V28C%+~-o@Ap37!Bld2*g57@^ zf_|g~*E}z6tE>J#V^DpK3%7@HM&h^tGTZA-9j`xQnLbCb%Uw6zlWzpwX)i6m)0c)g zW-6}jv%_@5QrIj>5hM$m@Lug{YOvJ#Cyg#hs9)a#Il(%$^aNgJ+8!wi^-IuoVmLf-T zAKZkpkDcH&87i}V3MqQjP5DjECHNg!0<*hjvYWFy)1ov@(la~BhV}bI?tI?VT*>dJ zPs2%$YIM%J6FeNYmix+`$i8_(j$xjm(w@()-M{I-sZ;x zljQLs4(sFV93VTd>&f=`gg=u^ zXR4zAGfU;D!`yQ*g*U$s_G7ljO#DzNg|hxUn_zSaln=1>d9447x*PL*bi)zxLFs$c zz5X1J-q3<^{~1$dyJKj(W{&)baSQevn~1rm%wb-tJx;VP1>twLOmWj1`}w_rjA^y( z+l(GGBeMb5uP}tii4q*~sHCm-R`id+CnJLJ>mN;c)N3debH8v}rWP|vbfPaQd3bW6 zHT;}nkNHpntDW_Q#ZDWsS57~is4j)w$#(S2zZL(@N7gY|g7y4o9&^TBc-%J;_c%si z=`k$`YTZp*X;EZ#+fxYPv;38hp3q}S8hbHsBpq(~hEEP_a9sue%v-s)=&wwe9DWcR zTE^k17S4i8Urq6~9yBp0mPvO>u+v1YC+|63@VasxGcph2Laq`ILaSHIc9lKO-&O+ZU6u$3#wgG#eIwqz!~Mu}*HVukUbOCp zu8ez)@FcHkVJU}&Or2U(>3kP2L`p!H=PB$z5KV`J7Rt@Pe#aR%w&T%B7O-*cJ~A$M zr4N>7a)+nwaF#8A$>DeGothg}sQlo5m15QyCBeT#OWW}RpwuhVYv!a-E;`Bwk=*_rrW^bJGp5L~(m)BYL7Z*5%v5QJW<;9En^i!>$ z_)3-Qx;GSq;?*j)Wz26nkeN@9Kh5Ww{94++kb7t5oEDqZ-IU!96qEm?6tVrGj>_W$ zi)i(q>++*&d~Xs0%;QB8Q}9fX$@~o*Kf6w`#pO30P2`%Zr8;8S^%ZzEXA;ijv+!lj zMmk*_%lB(1g(15;Dyer7?N-$l`|t8Y$~VIcleD34s086vS~uy!=0hY&{!#OrbJcr zEqS#Gf7c%(wmSU3`Q1G0H^r(KP=_6p<>3wwp~t~%ZCuS8BaTx! z_q`O3P=U{OfXZ&G@#9G&xcd4wvEYp~V0x7x|7WD!v9XY{Gxv-7z7o9mz8KC_cW1v} z{3dC~0=jGs@*jRdsPW7PyRXoIaR<+X>6_7@*POt*RdiH(94w-@f4s!wvp9cuv4Ha~ zbH>Op32v+}hQcN_MbaY!3cuNayR%oyk1MWW-k@XX$l3B1MO(1+KP!C4b-7+S9hE@~ zis*6D9MRqU0QP8^fk7&|V0nV)FK|DF<$i0Qp38sJH}37)%6)BLE`GqD+AnaenKrD_ zHKwT})A4$CxSYINa6ykmG{`WAxN2)uH+|FAe_onzMV@yWF?EO$EK1;c7PCs=%4uC8 z|7rxj854xxZM0xQzoGPvGvT!lYO%hqeW_F}AKy1v!vJf0>VvJwF}BR^DbKB-5dNZcbFCfsef+P7+)`VM=a=8X=KT^l zo*YlFl`*t##uB-b>y=LVZAXV<3$VIsiY9|^x9uknO?IQ!bj}J0DQ3%lNzgu`7^$STR@emWzC3y2o5hRRW&9Yto(oe{zlRp*+yF1p= zAFk7T-0h4Q(E5aPIcAdcXBReKY{4G)((rOoJE*cy0UN6vw!t%z)o^`&R;OZE$LbX4 zjQ-Nv{go12IjR^UZY3*9KL4SpSgr$q>MSmcjmMo=WAN25O&GEM2-YPDNIpi;Wqb~X z25iSCd-ULfg%p!HllFf%8a-`a7-0PWbnUqw(CtgdKoXGkUCUob^;rTlqg7MA^&j_nJzdH&p1 z9HQL=&+t81?>Bre+E4?F2dowr79PL?AI^I*(S_oNQrvrrXEC_g_@r0;rSF3{Z*6h9 zc>2L7)SLSpPjlA#h{r}`e(f;2Zl5ieR(!`1#tC@8YkSUuu*L}n)ouI6CBLlc)sF^@ zR56A!Cn?@JS_Eeg>Iz4tk?5Nri0Qqx!13`&QrzfAc1I=b=1ylidGIB+CfdLb9UENb zT@C3EGuW4hJ*nH2A1HLpWizF^`1m#dtm-_3CHwcGrpg-J*i9SM#-9MEfBhi$Q!2}H z3#2v5?|7!CHu%Td;DR{LHJzNu-Z-qG?tEuh9vsW$&!qUky%-GsOc&AHe#N zQt;^+Oy|CM)BW&gLeU)FH-&b<|5S|NQTHSo`^1^XPby|{?lwqP)u4NEB^&Z+4bLug zr|iyB*_(4xy!NjMzFs>lj0vs7X|g+bSz8KT)8onTY&6CAFP5JP`H55SZo_mROK|4e zMf2vHu%+-d+r;%Gr#@AK>D0T5X&-rR#gt+=`Xrv6l!emdYp#_1+KGMq_l2^r@Qk7S z5OJ8R3z2m$X3Tehkib|pdfXFlbmQK}Caxi|ehtS?3{_N?az9JQLbCkkA(qUQVo^#F zyqBzDiwsqi&x`X3O%@67pM4?cZQK{|{EXP8`%~KTdOG=MyRdG0-*J>l8ruBfzJND2 zXm7+l3j=dy*^^b_?m>PB^WVpAaE*P{p`tb&j+vT@GM(}%>WV~sDXu~%jfrjj*qDXR z6p&Vpr+W7QXEi&tOsav`vF(J+xg)Vk%?y1%XhYmCDXw~6)OLfGm;IxoNAjsT-9=QL zn}B)oF_@B}31>==VEZT;>ihD$#t2))wAb)x>ro-!@HWqh+lE>>dhqg|6g_$s!zh<= zGTT#wU`t95a2XlT@;DoiOuu0l&o^w~o?HxlFb9kNnSyGoJ zz$%ovd>xDbo;c%q{{MDb9Y|q2yokMh#wt^ea$k=#=D8Vz=2Ncm*5!Rt>_vs{Cu@wn zRRzs0zN~U;1keBF&%=Q;Lh3tnaM!D4o!V_>+ix3@MSKHZ`Q6N}uC1pj-Sa8VS0d)T z&c*U;q1fBh40hg3BA*x+%AU4f=xopH57*2e{%6WwEHYJoYAU3Xl-qKTcDm@EUJNcD zF0$qFZlvd^N$P2*So`VqbU~U=O(*+`)w+x6?QV7QGwTLZ$J!wHSHovb!&_r~OqFn! z=U6SBCH|D?;y|t;92-B1CHtxM*+?EO zzH!k?yg0xZ`X+Kt-LY!8ePf_(pJ=N5ezA~d4m&7j-jJe;Suw<2>%qcDs3IBQpZG^ z8tzT+OOz~s7-yBtt%kmArBEpz#IY{Z@K1YP=)Oi5Q|*euc#nq8OJ4h~6(_{Rqvz80Ak4DHMY$EQ)9WLv?r%$mT8%jQ zrZIT+(#00e=Wpk!C)5S3!-koG{3fjh!XkfKs`mf&t@wZot#EvaQZHLr=U{^`u2+J~ zrVRG%Eaw$JZ^e+*T;{Mp3BzkvV_~{B+`oSuR#m&gRI^m}_}m!s*z_Gk3$)?-dK=Uz ztc26Q6WE905wx^RKd#4%WhREVaO#8uD4)q0{;6YWSdBOBa(pga&e)Dx)7rPyu|D6E zspk$C+OVsXo$SL|({n4~p}|VFykIqbHgcoX0TNmJC|!JTvk1(*j|g8*e8DcCbJ1>w z6f`Cz(C~xNRAs$Ho_6LJexA4u{~-799%_%rM>A-i_mK_bx?gLogh}h}DDH+t<2KD< z=sHFRMxJk=1()(@%K1>S>4yugnW99$0tfh2H&A&%^DVXa=^%Ez9E&f%IiR<@9=up$ zgC5FCfVd$F-QT9lm%R(A*LzRVyo6^f_;OEELj-fuR8_|DoTiyQ7YijR4YZi^PP^?n zE2=JhO8(=fQS4C{=GnIuhwMwm3!!F^_mOiNXIDYkOQp;ORlqFtW?Mhjkfn}Y9y;0L#yeHu`Jbuq{>DiB zVABq#+|h=1w{_9Nq8QdRrzoaWt0-4;oqzCuuHt%wMAYsdgLTE45N>)DhYCJe-O~sH zAH~xLFE0|i_E${4XoC(GRbUr)L|PzVFiQ__GJ_Mt);yC{U|i&j4;-#k!Q=~lSPq4{7`iVnQADG<{r}5 z4k?s#*M<69MG2c6xvptWCEPn}%EGxGe%;4H3W`w3E8hiU$sudJE76AM&W-eodvaTs zIEz~Mm(bSv>XcXC4IWJ3yu=fgP=CeXmd&ho$}hS6HgS5kXflfLrKiN>2bmtIZhp+~ zC|BUaV$LqRe~hL);8`%E|FX2xd}nxg1&-Nc48f;tuu-pyvkeEz4)T9z|D8g5Yo03N zsb(BEI|n~U8GxBgRk_lyfMRcxy!-F5T(dj?Ti)aDW7~zZ%ewPqnzeXt{jwfa|zKFC9O6=|HO8He6}l z9p7#=fNME>Y1tbOGK&J1z~`f1+>7CRa)oet%RyY(VH&RY)`bESRi!zfk$=BCChmIn z87utwKFyV9#`QCzf%DT)M}L<5!Nnig7-5z|bG4>3N48)6>K5iN)~cw5PD>i#ARTt^$XwtRp5B4E#E2#*@I@hVk-W5O`D zYgRl}-q=8!1{lcI6x;Edi#cxMyKZ-lB+@MD!&#|C%$>7R?FUx0)vnc#*U;Q0uH>>n zBJ)_Qhmy=9NdA08xU!i)+t(_=vbr;)V@>pfvme)Xz9a8t{0BXMZN-G3ju671+w}=M zNl0HLfBUKfcA3TC&GS#}1=k@@wBYPzy*mmwml)jiW+)n$@;b(IZ}Y;cVEM}O+j-GV zH1260Ej>M6+{)*kSUxYAHuQuGYJ-%LUPkYfgVhc_=;()%{deHq4|J}K6`9Q!B z#muf|%K3aRJ*v!0Y#(`m>j)O&nf_AP`I7J03%P#^*8A8^YoaH-W_pi2C&tD-rGi6K zD0Z$3>&WwCcON~7RfEjHpxOrioU4FgW0bP>zN+vu>jrzXIFUsMbf)ypjrjJI7Ob$5 zV9CuYFwQg)g2LBeaQ=8)_CW&@FE`V>4;wj)|CC_0%a!7uRiW`LD^MS8iw*KhFm*Q- zQmp*(-b7RUd_^11R#_1o_=TEpE;Dsc35q3E5Evs9&Ye%hj%Cr9^-mMD_8-N>&;eLC z&Io)rCGdXGlk$%AS5)ofKWG06@Y6pce5_R9iB8+FPnbTKhx>xsr*3UE?b2@viIPUl zkiBMuBkrJU&)KMI)(#ZG@wD2*gI4d27t+t#;y(Uei?#}p*I#PEbNw#iQx9XZuXF5J;b;9CkW7zDSNIAK^DJ$TjB1qK+&urj2C>vkary`P`AMZ#1Ej%m0 z*!J*$G@W-mm;d+w3GuS`YG~Lb$*On_q`mjvrKzcsN~MLO&{Am-QR&?tysmT3l}dw# zy`#OOUGh60-`ns1;^lQ+*SXH~oX6w-_%;4@>)h-IKNmTVYhe7V2BoHI6NUQoY;cLT zLiX}DZXY=gYulQ`j`#yK{BaM8^Ny57Y_Y>xZZ(i`)I>OfQqOiXY<}|Crn!)E_q{TpRw@DC=vajJt&+qs&?yGQ;{fz3&_fE_Ylw~Du!D(Im zaON}#+#k+-fFHG-zqCLmMqWqfe#ddiS}n*e--#n`*`Q3R4`b8!(z6tAdf5!ZnfCT* zR9FovV^_&y`2Fnpa2m=Ib>JM&w2LlsJ#jcE(+>ZL9DIg8E11(2W=KcoCu5rnv*q7M z{lPs+d+^C1OL()fl6BELNKv;)zL+xrm%ifN%JJ92)DMo7Iq?ggpTJyVm;Y(DtKsd< zIHAXifi!?;5gQBI3hz|C=)sZ4XmQ&Cj&ohg(B}|Tu5~HryOFQaPwe|KPe>fVY-GN# zHe0L|&W;&M?R&DXAxKRYnsN&4o_Vy+&B7j!r}}fh@oaDA&6eBYgs)ZbCpkg*o1=;K zrByKHVn5-pMgomc-$<+H>&xex$Kat6W|&uR0QT|wXu2uyj5A7wTBRL^KCS{sgANjiUV&>tAYS@0UGPj}MR|;kZ z(eib12js4+F>4@LX*kMU zbmHtDi-z6`!73S#&tHTsA=>bcXT_fCwa_Om!avvUD`jxbj#b+;oC#Y%({!hj=`atW zkqpS&=M*|uEtThY{e=$Vq1Kw#*2x~LSc@LuAxcB9w}G(5Hw1Z3lF(;IN6Jk7f?vn- z41XYJI!vvF84HbN-+qVVh0F<Zl=VU1DTV;ri8S}U z4_&G6t$h8-4n#CE{y?W)=do}m_a_%l)1J|rXhPWn z`S1`;>@<}5?LxZHzebN_Cf_kMDn>ZRJGApA-Ld;+BUte=k=z|!NglLW1ALefb4I4Il>4wd4T9y_t-=BgExa*=+3X`5loOrwDJ!^oaUnq4x`w&J>zW~wG)nFUv2)n(TLT{egfXwF>e$QKhhs=z@(7+!1 z`c;GYRw4DiWG-HM$6m$jM-*MOzT>M+H?iEt0JNg{dAF;9>v0dHkFSrz4HkVc*o8Ag z{hP?BauXf8Hc@`f`y70n+MlUkdxfRB!6ZNZ4WG{aCUoUbdT-)8B6cX=2c=+=j1WA{jX-fLl})77B0^Nj5I(@!|yX93qlEihVS z$eDGAu-tRDym8lGOzpUb=dG47yR99TA7(b%y4S)kTW9Jzj65#Mmd;!D!I`l;ZN?go9g9umqsO{932->A!T@)@)3 zF;TS&{2)OXtDz_Q&Ml^KcC!_^*EKPfHAVIv`w2~~=^e%T+Zo9_WjP~a&~}6=POLP5 z4!`$NvO_nz@TgR9sJ6qqLn~qWgjGV*$906vSYtnqo867*x<3yGuc@%;NrnC+UURI%KGvD1Tbp`ir!&ey{1 z$yE?NqcV5tI(<@^_YJrEZjficsYAb|p?Jf$Nbu#JZEJch9h+{Ua38h8>ZXw2nme7>SJ_;{p5p2J*5Z|2O-S=eX-My%W8DSCr=6}CYVlne? z@1Ic^{VJd~<0jJyOAo>1D9;nB(oif|CQn%U8|O?ugfp(0!T5vrc(@;DCIZ3njjcCL-Cl=xwCo`M z7SF^YtKiiKW7)D1Lzx|IjFttO;F9Y^XPGk-JoK8dzmoatrd;zs`pM!)@52kLHeq;H zTbOk61WwuB8{1~{evLI7F|4`0m+Ye~4zkDE(n|1DIVQX71Gr3Y2R5YZ!Nxb4^k(=b z`WMkg9u^-2?QeC2^r3qM=WaR_difJ79@h)?|88T4-m@|Gs41MBl|Y-$dr@HXUfJNI zJOk(FtApuS`K;=nc+>7Y^Fxe4oRmdV(>Kwas73O!22IR};_tjRT^Kn=pC;IS!?;~B z!t#wL@sPe7Ruve*kZuR)-F7#!4ZfswbLi1@~{q0aJerun$ZXe=7Evw+S8cKEh8Yg~Jn2rJuJ zia$n{Qd2t0$#)#CFYSUE3pF8hn-&g>sRBFKUCISf`m`#HwZ8X;$x~j2(Zoe+)XB;g z{Mq}}Utn(eV*Q)-w*-7-xrfgMx?s4TJ#GZjFJ5cd4O^pDB}Tvyi{ zKkZ_#Yrz@#;2sR&tM>@=IA824uxI4YcOh<=J?g!zY^`ZdOQY~-cpo$?kiZX1397BB zhRKgYWDYz#dSiYZoed;#rZyTif^Bf{Vgoq#eGkQc>`5bH1mW{|dtBLA31`2ol%*vd z!FMLpFjHL@+69HtiP61D^I5!fHfwA~BvgU$CQG*I%x47d-`+Y)I9uG12JJkE;@w&D z(3EBjTe=5Z23vvp%|yCC&WD1GJIQUq7C#sBZvERUp}Cg}U7pp5XP>j5`=*}QnHfr1 ztT$NLj&-m#mEi3ZC%n7F&+@%*xNS_XQcLuv`^k^-NwXt#p1}HN{+#W?&ImJ2y=i`( z3KiED2+il2c{{&^4vp!haQdc+$B$J)&6(xGr7V5we1q??+Dp>=ZPQ?(mm3VXOBPH{ zOr$;6c|KXJ1HV|`zS5==_I^$fYM*%1(d8;+n;jtd=$YJ>Wruaqx>+{6PmS=z-^t~KPa2?Ztib8t5}k5L|ZSWVX*!R`K()iQ19nKl=Lu%dgdpu z;Ou}wGev3PX;ql-aYeYCpCDWb?o4m`H{#E)T9C$hNzrAMkT%&!Htcr<-WWL^I~>%2 zRgb;NF1Z$U2iZaLHV4$__m_2miEM1wVVJ+&2$!{C9sXfQN*mgY?uV`jHfdTI?#xW) zc7C#&j{9+OuT7};t1aj|p2X6_z0jnRuSMuyQg7Fj+zfq{24s)6Pby%#^)cBHuY|ERM^@t6*n#HhTr=b!%luz`jHF8Y`mZxs7G4vN-JRVVf~wW9jwIXcAQIbVxeNscEEv0s;=fWGn7y*BeXfC9ppyjOK3lrGf)+ZZS=e@(> z^D$^(+7UbQ+)3FrkS=|$!f z_ec|eGc(~_1!!ev$##m3*!^Sy9y=?6&`pN)E_FX{h?*r|+@=Np^^V8TqgHU^bvcdP z5k*JN%$FDB*`w9ja(MatjWC=27hVThf5|@IovsGr#Fk>po2suE$nWuktW|CZj1wL` zA4ZkW-O18hA~c`yr9F9%u)4D|Xk<8`s!#!rHfM$26MU%1N`*!&Dik6$3`EQSiYeZw zw*s$gp{Y#;^r%=a1l1?ejNcpRU0Z)ywM8oIFLr^KEeD03FL#g-ZB1$UZqV+i17=RH zfPb#6VW{w?n$9g~78D>fc^Qbp>0%N$%~iN9qa`_o5zcM%$ z&EFa0+6jh`vd01E4X%Kmx59)6tkDR0{Tow1iT>se2IAg?V)E*LLecP&p9_l$*csnm zfXZKVsTb$-CEb;G$m1N$g^RFFoCMrWK2zDI?VNwGQ2x%TBl>Y<_}`bGg+Hvbz3yEB zU(V(!Z60sI=F>r_+ED_v{JlkJRKV_+6}cWteL5P^h~2!_%YP<6!z1!VxTZsqpl=W; z&he4XKSG}i(9 zDH2@#v;tHu*7+Np_(d04w=i+sImNY0M)Y`HDjv#SE?=VEj1314;?6X47=6tFi#Ali zgbSkd>mW6_)8lIEUUgtd7y55VBTh_^Kw=;Ed>yHPNP8pM)2Iz-+I>7uWF7nW-#+x; z#9B0KV-GRbj(GcDMe9Cd-_c>1Q)<{+4;!XCk?*Cy`1aQo;prx3Lh4n*g8P25*H`!B zm+D9?vC)J+uTSC=&0a_{Bj_?{FLgM?bEGXk%C^0kiCs|+v7X0dZC)b!_1%uMy!Bz{ zYd+I0^`WNx8?uI)AUIdp9&Y8v3z?33bmczha9w#Wq}{)ZvNJQW|4cJ@X_7>X{&@2WhWSHyZr*lJZ~Mp5o+jx+?$5F1T61(%sKm`@ql&E$qRX_N7njm9zW(rp`%4^zON?qWI-qG@mgN+0zUa z*O_l0$=|1+sc_=&c&x1Mj2C(DHo-=Mzn4}(iux{PUa#L2zq5#XO!86;uwP4uSFmQd z#TH(lcR{)T#sq6oF}aj(O+BUvQT#%;&)2c2&H#p( zFgtWg1cq42kXn0b;p>JRi4?Ym0QWl(u*Pgs0qGst?`kt%TUH=EerO>68C*;)LT^P| zt`9nSWl$TkTo`>M6?(pN2AS6(;ZOcfD(YuV?up%DTW=?Hy;}jF0+NIunch_X`!C)* zpb%tMhN9WxV!AVCp2D6z9X-V|ppbsTrH6lL^;FJW)>$U+?H-HAb{nDQF9R4~Z`z?^M9OfICW~;ZZpBXCU4RmH>^FpjR(`e!2HEu{EHS|FBc;kJTQTv55v_1JiEgsx@+qGGI5*%R`e|4|OGhV6 z;(Iu*{+9Ic8qU%A?~-7xnkbCk*OgWeY{Ws#0;=J&b9Df7q3aE0e-~`TvIXPtH~Xo_ zt>{IPX|*`>k39??=!EfA>@Bi4mD#Qzju)pI;ue_}92w|D!*YM)u8=FjEA}SrT*Y1t zsh{j+;sHFF9f?{SG(j^y6@3DHF*wEu&Mir#Lw7ys-@{%?2j-R!zQ-D1jpMRIIfS)k z+t6*DKJ@r6f|@$B{%4sWvq%d9*_L+D;2JN~eblFCoO8GJ)k`6KWkK6LmY7&%PE^9s8 z+9cbM^l)4H+A&$EpO%JRmt8O-+Zfhdt)(s-!f8{knqcVQDK2R)BggkC3WF&`SNCnB zA0evpY5&Y&$;sN*ncnFg670I8ymhAMZ2y=2M@1ytuBXuO&d2Px!|~HhbIAAlLcO)O zQ{&aUvRmF0as9#0sO0Z(yOmA|Mo6D9pLxbY>8hcRz%o0#wT{gb@8HP8OY!Gg6Bv4+ zofsBTO7VSx`^c`x{=&EZ|%@ZOHOBqz7UW#wN{_5BE}`rQyS5jPI7fD}U`acyM@t+{KUxHdzAF$2q?*N8Zwuf|w<9O+55H+6-voICU+^%1Ta z>;g;KyZSGoI}WJSftDKfeg-t-*M0@Um8}Nip1nnsJ)pNjg=<1}XU?b4Tp@U$`9r<| zMdZ-+s7zg!21V_iTjz2QPDPXdZ!1a};|{TrC$Pi1;Rvb*aQU7$_pX1?Hc%n-nqwp` zyHiXWk3$ssi#Yf5VQFiPnw-*1>t+{GtjTiur_5MfUTBCjJPpCO<{@27nN1}vM&Nhm zHr}e=fUA!gLH&@8^nOiuN?M>T#j!@B>xE)+d2>>+xln@NLdqaCr@injrkPwvvk!E_ zJ^6shX1uv>GtPNo1-?lg(0N!6Txs)3$jOxwT>gqL%sGz+qp-6_Aby@9f$5JW_?)?m zF}{_#U)D6!Fs^}XHcV3-vhG8kM*wdJcZXe0fucoD8SNfvuIMa_#=4$%n0-eNvPQHQ zOX^DKhKgKKF#RZc)`Z~QC>@9h*2eo?%c1|2b^gm1HB%|~lZH*%ij6Og$WZeHmKiLU zk3Z6aW0=)7J=y|h7pX$e)fa>=@AnEfKG{;<=0=>Aj1XqAdf$GV=-|>JJdHb1ha!lRCb$LzH_*B zS!9PAUiGkh%pRdzw+KpD=1ap8_DXvNX``*A3?7$f$vVez_Uy`sIO32tRBSe+lZ6R* zV9-qY=hrIqBX~D9%(I5XLPwO2E`{BW?*!>Xc}x2tJ^V zTi2AqhlV(zy~{XKvS+H@EnUH;xDRKE6yhW!S6H%o2li2Q!>}JZFuIRDmUV4_KNoK( zPfRfue>N7Ar?tOAWwzYe2D))v{!DzC?jjweX;}Bu^SM2@T2g$R}c+*{EIU# zUkZji?>Yz#&?d)P7V5ecXU+(~k<1ww8mo=+Hf5l3w=#F@_!g=dSw!d7Pgkt|*N3*% z3Yd1kJDhO~6a#*jP=8%>g^(JJIK>txKi30;g}leqYk+C*2FcnRrQi|Q5L|yt2OfXb z#vW;`ujaW~Rqqz+(VNf6=g%t^_d7?Dx*oLQsHtH1%ZS?CVa@B+W%AIoDrCuQh~)}P z*wxOSRX;6syw}DBtVRFdUZBm(NKBbL7HJQAoO^1B*BiIf?2t>cO%{FV$V1Kr zCkKe!VTY$f;iC~@RN>g9_!I+k7ob{%I>20~^jP;lG@;-!@dPib_trkofmxiwG zy<6+jN@g0bwdzijJNPOyD{b-1`#PvMTPjRm8csoZ-ei3%M|R_PAdI|i2`^vn7M3I% zGB4#b`pRAl&M)tyQQ~wQT*zz+SrT3Rnp)Lvtrt#v&pQzl7+^DJP*w(8cpG+U|7S#M=<-{`q={a^mhEBWkJrmx63m5-kb zS>xhr4j&%&p-q;baB;OQ=nk^S?)CL>)cvvasoNyX{bqx~4(y}6qK$t8%UZP@W8b%s z_^^oNRXz%7z(yJt*oMT;j?j)-841n}(DGot?9wd}eQS5)K5czCRmaZ`*E)NnMN-GH zkKwoBxz_prm*x5R?a2}}u{MP#v37W><{8|*l_~pW_!oz^fm01`lPX;t(Un_yiqvTUrJ`w!{m^o5oWjYrRfx)f0T0{AgKj0mhOmX#U-S zH%E5EN8NRyZHgUsIa0?A^6SciZ6;zJ&su{!N)-oUbg(Di0}&3Z1aZ?Tcp2{4I_D1# zjitu9R&@Do577R4lJl^J;qz1jh!3^Hh_-d0G<8#6K4~HjeOF8qycQ}>?bG3%Q5m!> zA0T)zyLjThBAPaCrTlNNUAW|>KKcY2!rb5jS~_wDsj)V=WcFPQb6Stte#Q{MjK{t6 z>Oj5Zf?vrI6Y)WPF*%<|Q*<%aMd2y;PAfVJ+p<-}PCT=n?fpP*sM><#)Hb0`fHmZ~ znP9T@S%?^3Bm9dGqC=y8V$SOq!t-{VBmAij?j~Ew&hFfb$08KiVZ8*jlb8|By4H11 zs&YT4sfdG@6w!)ZGZe8N{~kr1-haSdqa{h?V(I# zUn(4zCEVtnxPjI)K-)pGO3q>aJ#rpueb9lDW*zMFUl~lYUhiKWt0KPOKFw^+e~J$C z&XLy|chU(n75rTc$!*;cT+?@n{Kg_x`rvZ_jh|Y=!)*@q2X>$;KHUGal7P`)eruF`eeSW_dy5E0*UYDlfR-Pwq zPuWM|_C4s=_(a)~7F$eRQVa98ONFZzrsC`b_Br;?mz%bqia9S`c(2hGK0NM1*B7@X zmzu-Eu*Oq(_q`)-9bf|W!wTr(Pv8v?bEpdE z{kT~j?6^BodiuSJXxhLzu&WIeSta?{(t9ut&^3nxrGB(!&qpi_vE%#R4z+yhAn<;n zbV=?cJlf;`YFEZQUDV`$i5~A(me;F@bx+u%o$jj`wkeXFG~3YNzmBl8jJ0+=$4(uy zCa3Q?JDfYI4!$(4lYKmU3zZSOvFA8_2nb^SaK~~Oe|NETQ;vEgiM-}P(AJyie1 zEYn4%pvRvf+Pe-8&B~PBo!5-RlCI*ZJDiJpK?kS%mx0>Qhf=psn%FzV* z*krqniY_mdZ~1Z-`m0L8`DVQEta=>HsBgyCQJg1!&lXSG*Mg#&r!M&T7f?|Rpxf<+6=ja*oVFqm|$7nYi&2I-izd7Qi z<;5`S%3EQipB-AV*8TZ$Jt02IRJ866+b_3!CstSa+kA@V_0GGukaaU^uLh% zV6i`?yeq&fox8zox*R&+Dp15&o9qO*J`_AWMnB7Zwv zX2u$r)!mf$@=QgKKgINL!6L;<9}zuO_TkzHUAWKrO*iZ7;C%ij={079x3tyA=hN9= z6IDQKu1%wfDMsKuGN1Wl5jcClG1RgTsPS73tW3V(*AYxbNmDURj5wtj_pBK+O+;+t zX#gtB8Spw<2N8G6q}}(l;QMZo_}?gNh?>(8ZxmdESn;FaKf5n!EdPOBr@jR zQ{k_@F^wK|6vtXDlTS=mrA(jw*zSfUjK23#SiJg}@ZMpYu$1?SHCuRpqpk;zXIYc5 zyatMkVuik^G(?5rHu^LDlI+<+f10aWjrZ)G;ND|badm1LU4Ln&7?f{|Pk6VUJEmBO zFLI?toUJfr%r(L5ohHsHtAV;hON8|oPvPGrPaHqg7&6_GXpg=d1$p*TYPPq-Hm|E; z%!p9Icu)j&S?WbYJ#%F@Rt7F1q}#Wx(#D$oS9 zcNWmAoN07_#uugdBS6#&Zy-p^Quq#4B`3=hcs9ixwu}63&98yesS~BoH9A7TfCj;4 zU9`|~c?bIV^$V`NtO8voNN|GtGgvauQl{SZ9u5-+;wn{hxNI+_@Tnj1p1VE#U}Ek0 zyc+P>UMN-0nT#zPJK{cO{+s$b(b%?aC^0ijxOZBD`z~=WbUH{D@+*?Er>Roo5GQ!G zBZ0gcnQzmyCg-9$`-VEz!t~m8vhG{*@UHf5T#=*?VDl6{7@q|(M-A-9pQCy8%*lMG z4i2O4qh0UCIHtxF&Uo#mugo-ldof)W!rBigt%0w-GG*U4|HGYHSCMpBSG*^az+ek? zZ&@pUzEcxRd~0Cu>XX8rgKfnp@@>>NWr^IzA)9sAelWK`pW{A`qcA>mUhcqrr0j0u z;^SqMP~Tq>WMGG%fwfYp8A6$v7A`lhfm>RE!Zo$sIJVIe!!{ej>b3{TDY^&Q9M2Q7 zXV_sLbAxB}jTgTB38!&;dXmoFcIYPhsh&w?f}SJFMDQ4X2~^gwW4s;*2#V)KFxs(AU|DM<)!zb!t2-`;YgD ztbsf*;=kM?9T}ZYe2AUY-C*z60CA{lJvp51sQB<{C;ljP!5J~EL*{#6-m+?Ns=lUd zQ*0)_@#B2Jj&cQ=9!2LJ%Wzc(Z3yH!r@+|4c#nJdHgX+myf)^Y1!rBc*72w31wW1VX5us5 z61qG+UGb>-A3lj9?77?kvRNn4$j|lnS9NavVHG8|rzlw2PmMS$mhrY9swgb!iR`33i7* zqXWhDC6DRpP%}k{e=Lq4-UZ*L>4Q$x9(t9 zQ`#{%b)f|F*uOCNM2@UhsY+j*_u=V8OYmLzLFhC7sPNTzs~{A`KejN(a~aD%%~h!&2rs zr>zMUmhaj?Pp*2=?}bX4*_zy}%+GwZyBcO)E>m{jSbz_iy=hr(0gJiM zPrOhC2~JW$EyP@WlUqWc=G~XixI7I{q&s6|Pfft9nt1e66(qOWtQ>hW9UpRz`?4?- zm~^dxdYMcmwEd#AQVSGKE!Kd2HNK90N8E#O159sc9bU$tbSwBPtHurB|V zaOKS|Vc4gR12Cr24ALWI6z2I6t5qGKriVQS zXIF#wfkNp`>nYf!v;!J2SKniY6ZhV#G=5u_(7lFpjSFgE_Rj#BGcz{6?N_1OVNT%Y zm_Unle8}nc>YQYAdwdhk_u;H{GTC^ZqweP(<*7dW41EfjR%cqZ5L-5$BY9Ley3cuk z|2!Y?o_rB@@iqftK_X=w_9eIK)3X2nbKE;-%2MK6uw>~Ko=F*jiR27z@Y_N&*RGRC z+|Wcr)}L4OJ}JE0e+G)?`NFj4yM;B)<4L9X7p~f%2E$&ti7Qu?(YVS1iphK(GYc!( z3zot9fpEHK=s`B^<_d>?8&K+r3LNlwiM;ZcCUzXd8pTloLXWY#F-^@9_4XLTS))Vr zX?PDhm~dMtcx;F7nQ`hfB3>v}tRq^=v&Y1E=|t}5{rLZOa<>p(WEqm?+ubPpK3%?S zof?%+jzz!0?P2w=FLb?o4E={2_d==)_ z9=oP2QnwHz#+T3nCxzno$D`O}x(xHzYlB%b^M^ZB13by_zhrv~Zi`)8^$*eBadar& zlH3<~LT-KznfCYOtPuoNjODt!G9`Y07T= zHA)vvv)DiWu7JvxOeVw0M)2D3J}zSZ#wlMDeirP}k2QYJr(f_(?rb62yO)sPundLS z>K3$Hi}-1@0rbdcEt5qx-18}wwsBOU!>JLi{&Afu8~m{2D$Hp4#Mi4I&-K6Kpy{uL zD~s&0?T9Mq_ta80`NVci>m|pfJU`sLO`xN?d+6_geZtaME$nx>3Z_n3EF1h=O5>$D zSUt7}T%Hmr9%Ax3l!fnTLlM@)K;K>?0^gM3@2_*$2 z9Y2}w6n$1kGu!a?&sutKozngE&FF z*@;%HYQo1C+Cbh(*4S56ft<```(E6`rsjUF=f1k$aylpffV=xSz<)e%JUfj2BXbI+ z{ne+U^{5W$xKj&k+dI?IA{FYNo+Zp7&NR`jhDU(`vK>=5)3r#>p@?>dm0IjiS>r`T znyYihthL9RGpbta)hg!sjqbAx8<=&} zpI1WNrWD9?x#q8%QVEOkgz$XbS@>J%3-&wX1f6H&iCTVQ@)$K}Zs#ucnp951Ee9zI zdG7JyMI|J=offWtUQ37C_n_FIIl{#ZLt5Rw5?!u`%B%TZ_NJr~ez^q*4exfNiNX@c zF_UD#%7Zk@&7JyY<_W`k+M||670ir{XC~V^+WwV!HFM*ovgew(IIR-azA+cRuQjA) zA-l0WZn`{jVI7*9gyQ;98u0%3XFA*^n!b2#kXxp^qNznObnpLBIM>-8FMOzkf_Zwv z(1@-0virc+UTbd`Ep*~*efdXrZr;l}oVza+)#p4A^zQ|T0ViwekYh(hm*{9z{&mLN z_c*(OeIhrwe!j7~u6$W%Au43dA#@He^P!ox1{?WR0E+ESb{sDu^=FIAX5 z$V0cQiP-F|2VYLGHmo0WaXliX9};(?^H3c;ebNx}Rz9UU)27j&zRX~Gb076DuSNeT z6Zm-7o@a-ZARl?b@3GWUJi&hLwp~suZqHSrNv4Q;mpD5hPYbVZU>)H85^2yv6-xaS z&R$k)aNcTz4Vjl)d#&>t1L%aycMLawBP44$pbhK&=4n{TF8|w(BZkY+@3=NBbX!Mb zEBr`1DM)y8Qw#0+-HsNn^eC#%d_HLX$3XnJ~?MD%k)LVSG+6nH&OhNXtB?W zxxQ+#Lg^3%jkK-8)rl_9-nWMsu2D`suUjhq&1XjOi3+&WSS(zQ@uVGpo6)fgAKkq5 z#hYctBr}yM!k1{_v&M?nnpUjHK)>7`m|tcLKiVFmmGiqZD^sdmJ=Gp}Fo*Mh{n&@I zx%6qlR`ThgC-*f7g3BQ$pk=sA*tSLsRn;mX)uc@6B`?67+6k>St!WfLn_DZOqQ6v_ zTxco&`cXpKCm+iH{hN+Mot>}?=Rm2A)xx9qE5NE|lk&lj418?HdnWdtbgOzyx3i~E z!HXv4Hs%LD?OsFGH!>ADhtz1f({T(PW(iN<*`sVoW$T$S?4mvF-~3isrm{!KD(*~M zCN|+BnHqfK_eD!aC3HSuE^AV|kLM-?>@V+ep_(IXykL(XRV%?Juu!@q zek!htZQokoPKCQr(gzh;|6scx?#F zd0^v!+xPIZd2gNUtwr8o_d^7o58_A2Zq+ za5!I=yR|0->Fu-Ne$u;jKL7CgL^|>82kL97!}7;H#N{{3Xy}x|3TJHxG+_PM@lB@% z4IgjP^WZ)&!e02xJPPBQQq2FjSgygk%@1oUTKh43&P%=UpE>q&HiB`%2k1zoEBzNK z3U}E1A3v<3bv|EkcOB)(+{xcPUiw2-PwXyvN+ui6D4McZW6AetjfsVD3k=C?S1fz$ zrpwd6*5TgXoNe4o15Pe*#k@a{A>QJH(8JmR=S-`BEob$F*!5OoWC73TeasXKuWiGq zT?4R3rUcG$-RR?10fTO5=f+&jR^oKt0Y$h6Dn<`DhHtNg;_a`j5#qDe`xO;1#Vf;Kv&$*?+|;SH zzV+1F!`-vQIQu&(uIH)XpmR${lMC6t)3OtCfQHhz;O z;?X&JP%V>S!>tOiSQ05+^L01Q+Nh0q*AUz}_rv+o6guH-3Ul)xpz`e+d{u4&k~I!E zCbR-9GcWkXMOukR7qRcGOQynIQ+$6Lea z2^!*+oESQFCQ@#=yd&!BUxd+L-wOx&4yGLge`4J9_rlnN4tVQOMe7_4X6-4XbE9g{CLHZy2tHGpr)pI~A)2O&3*18vNiT2h(`viP zsdKk-d>G)&XK4@7-Kw0mO;(B@atDlbsDQ_DB|>SwH!T^{fbU(!TFu+Zk9}>5iRsOrXeZKm9IqCLgcf${iydu)RMsPKPfQ7H`a@2@|8} z&JA6;acmG6lW}W(%jS1MPv+cuzbjSJ`~vhDJRXn!GKV3PKhbd6cA66MMz(9F0}dO- z>~T|>VD-aF^fWG|=a&oQ*L`N}i<_VW>KtdwdMz9$A9ZEeAZtJ_6(5Nz%PfyRgQ;30GZL zgCpk51Kd&pYD>&z4;1%t#=9WA`p68dcWQ`TKgLk=y9(I?qd+=h{QuS;1f`z`W@T$vR zx_Yb!U5;FtQ(EAFyXz{zJ2*l%I{z-_`Nd*7bNRlnG7!5le?YtKQuZK}Ktjo0`MJA4$B&@TOtAGi3v2IN)in6(#*LWm~_gQrynVc!#xWkFFYsQOtv# zy7G~{&tWa5sh7id&X%q7I14HpJb^=Ag|gexw5p{Y&GdGF@==a>eRTy?FUk~7dHB$o ztbZ8w+g@nTdzP%;WoWb_R6d8F_ft0Iu>Ge(@c$Nv_r988%|auHQ?H>FtJl&ye|<>( z=7615{`q~g$t%b+_mcg^c?A-rc0>$Qzl{7!OgCaOR2E)%eqQX)SUX6D| zS7`;j)xDt{lVmMwvTnT1;2_1-Z^v-*uO+y&n+_zf9(eHBa%eEi@E`R16r_yl)Oz+b z_`8Shp5?sWH{Q_9bC|-T12Bc>T{pZOvCmDu&y(Dg%B$Amizw#()-PAgkG+HVHUYhr zT;IYa*mrL^bQ#F?tydgg-zGuVM~2Wn=o}3<^rBT!O@e>yLri$K8mF6^Libol?CQc< z2_YB#ex+NBTI_Q)X~|UNKTsvVC4hZ)7(#3&?+dES;qcQEsfmFq`IN6lon6-8c1&H| z{9q^TU$;@d+S~@iMqGf?%RdO+UJRvOn||Sl*B^!2J&w4^gZ(vVC5wKw1I?fKqst3z zC>#+%m$mv(<(eR&K0$(2tO@MhW3jAdSrB;~&%vNgUSPL2P?T8Rr^RDT75STYV_}XB zsy;P<(6IgFn!yb7vTWggxFa5Ce)#`(l;&0^a1;NgkbgR`FzRP>P<5kjxWC==c zGZVOwYuyVq>ROtB=U9{0{H~JrCr6Qy={mW8#d~4zz=MKk+!kRnv!9Fe8nN)SA#Ch# zDE@g_OtbfyDx8b7a8+~}>@r!hDBYL(I`?!~qMs=Y)XzMJzf65Wv%(Y-3Gf8|dl(p8Ylx?T6@#(oR@XK!D!Pl-d)2InKzZ?$&E8OoUYeous+kh(&)T``I|GEJ z-QuysLo*y3&%XN;wN#ZEPSHIKVC1Y*7&UDi4rFco54H7_Kd(EbhsH~9R_lwd51&$J zw{wbKJ`(hGV6Jj!3&G={A+0Kl#@END$^UAq(+szrn4#Go%8EZz(64P2_9a3-{)Q7; zXFq`9cU}uO&a@NvmX*@GXXc8g{o7GbV*u`Irw#jtG4pmvIds!HpKDPXM8~5ZVAJ~^ z@V7cZbX!zG4TC!=vDHN@CFtcKd1cO+^ zKXPS;f1}?icGPAHM9RvC}Q+BAb67Elx-Gk^NiytH+J)MB}3+1ie-&EJxnu zY`_F8eXj@O`F#|`tSWcwNa=;JINY&~{jOYd{9Mk_qlG=m{Y#^8e@p?E)r4WgI8$i& z*iOtmz--ljSql3ZZOE`*z}$z1pwB$a)0t(h=fv@yRVg@c6@Hj*4YAegVo>dl);eQ* zt|PNC&%+n)oi1bzrDJ`6;6J;M!h+d5afhite$>-}KCD$~^Vyq*nkt0%=@LvH$U40< zi)4qN_N93NIrwL-H>?V0|KqfLdShg&SY;oF*KBRDr@JAj+)SVg;7(2USwi9K6By<( z9gQdPEOEtZ(zNiVxD%Dq#C!>^XRh_|=o_+8N7PBNBmw^{v4)j5s;M|NipCy}kiY)- zUWo8MAQX<c;^NNbWWA`JB1Sq6?WNjSxs;iB8+wsRzZUfSNkV*qfvA%9lokmxMg1uW{_I}{ zrs<1?A#ta1@EJF(cQ=9L_YW!f<80DRjZj8ix{oi4Hlyxw_FPX7f>)ai;j(wEkn~)F z@0bVM6kDczmQ#Swe~!k!ndV?;_nGn|wo?0mH?j+1>h#q<6G!eahixJ4MMHThsr`QR z|42Fuzo@<@4y$x8-GY*eARwTqY!D_k2DYNujf#pvE7Bzv1`-Ac7#Og3X0Bp`BHfDJ zg4pq%AMZbaes=H9J!j^b=PTZyv;_Y;*<$ouMTiMf!nPlb|6%t;f6X)au&y6gdFj9q zXD?o{cLOy(J}t2+k)vL}k73zeLpa`L2CL1RIWLPC?vbMv9Wm{~&`w!cTg=X-bL!!_ zm!7CF`95~%d-kxSZ(e#6roTnW+X0|=o^cmhPeJGCZLaQvBUL;1p&OS9xw2KtIC@t@ z&$&qaAd39P^rE(bgMsUvLaNODqVhhdG?+0JG1ogFeA6m!qkwVT-FYDXDFa>NhbW3% zhPLPRVAg|F`l!fqVIuNG9_y@7?_39DJ$B~;{%G>+8RKo3S0#@A#&-X2)q`<%7T0uE zl{EAs@$Qo?qWjy=fkBaDPtNkj_*hb1V@w~4Z9#si8((77K!Fn{OTq^1$5SoLGwG!Y zTpw%npVI+~>3Y)Q5>1-Dz6R$UUMrqz!d#$#>p-r+liTH+gxhZG;1ZD*e6_5gJ52#J zI6(&9YUg6gmg#7IM+4sfX1nkn9niaMq{kr@E#8IoRO3e%N&1E><0!hOa1V9wJHs&c{fh>o?Q}Ux%uJo0SiV&NE-n zi+V1)pDFM8rIr*^MoCOUP9j&j2G^9UfW<6j9B0nnr&)O(!YkSEa;ypS4QFuc-=|QR zu0F*U3fkklG2V=6|F8ERd?5kf zMk@5wpWGP*^iSQHmPtFgKYc2(l=Ez2%($Fvl$0#Tpd+nd?_(g^dAE;r`5A zE{h8$y5vfqi^W{}bY(1K?#lnpGb?;Y(FU38sCL8+TtdD0LHW1H?Xk8*`ECN%$MnUe zaRQh;o8@3KU*E&N@m$G^?KG9mrk|U)3jL2NGw&v2U97H)=E=*^nsdp>9WjFEgWKr$ z<_Ov+-6>w)|0}1}c7)qvw3mBS#OAYp%!llu$oX8+;wQ|hr6k75?^w+0M|&N-c@oQ| zm#9+Mr3lHU#NliPzvGA!6b@lIws}vW z(>-6Ba6*eWWBYm$GG3D9i>&o#kxsWna>+X2S&HVY?=_JLg{0^d+pgEJ@&T(=d759#%X#m zEaWpK_KT#o#&1NS)^fD`>S?^d?sTpp*4VVX12SK=2-k)$#ca0kDojy?5zI6EGO-TE z3<;BVY&nB#cyru2PX}}-7tmPtTRv-XM>?4CBts_F(Tc>=63G~OTCwC9ZZ|W6md~cJ zPFmOFYi-N3CjFgVxa5u;jA76G>Xy2m-qh%V`#4Qef_qK$;C0X_GEaJo+>3#5b(|%> zSkVsi@@{dJ1<_>n?jJ6fbA)wcQmL|!BfZ_XrBuP+3eB3HFs6DXXREt|L@S5V$<+@< zKjZ2kyXG}7>OqR5Iok={p3Trutm_*D(#?98=!!>(Go z#kK`@)+^&@#sEJXd5SAhP@~)d5y_N2z(t>A`_3z)F+FF# zxHeUmR&I~N`Ol5vOweaKJu-rF-9yA`CkEk}!}s97ybqV>B6?uhg%{oXLFhtjta_OB1-;#5)WmrMtY^1838=JX@zI=7)L!QR5ae|E~e~F#;d{V zAZ0x5ikv#=dcH@f{wx7SE9G$pyAdz(gWzYWGNP~g5i)8-9U z*3u;Am)MdMg~NjVMx2Klw;qzUEP zygbV?vzPIfnvA6F{>@ov5nGF*GimtWeU#UtOrRIopk&{1WkSOMzl&(o}PrC z#uKOYp_Xxv(fis#Z(Or*uy!DBzQyJQ`xy@(pn}>Jb?~PhS$~ z)zPxHYVkDonY0=?UHg%56H!UZg=Z1)6Jc$}StAuIl0XC4i&Al=oA=(mpysJG|hO;0~`Q)cII zu@z43Y6ErO5gxV5I=t+OTH2;}L2_rKfKoq3VY|YbY#IOOx>*vhuy}|j;y;V`7;EbG2fkE z{~9vfW+FLuG!8{<-q3EM4#$@J(9}aeuqM5plUvKUHK%qk-7s0SWJVTVey|$#1gbFn zcrNrEY1~scqTi&EM~EJ2hYp9d#ysp0`=D}z0REn_!uxMpVa0*LU)Nr6%@n^Xd;UGT7v7T>+shCYU#47kL2G=#tMB2X1i?4khPh;r*1JnNVuA~ zYQ$L-KefZVjoQ$;w}PJiTtMGH?vUnBtiY1sP?j&K1;>i5P{26Y0}h*nA9Q@cqg9PP z%lo+wFr}8HPF#Aun|sGxAHI(x(X7!${H3@Ot3xK^qXaz|m)k`jOe4s4(pyn|o;>}P zIgPP024Ks)ni}qHAgjZA@=pVC4Vy`au{@f`Z_Z+*5&g5|2n*GWa(GgG)1RLw0}63qqvv!#0zx^VkX zd3cg>ANz0fz-tM*;1nXqfBX|kNgef~qN!u(i_9BTcwh(h8J75FTMO*dy~XAGyOL;s zpPriYiFuqZB}C%Zo!7X_UsB1Zj{}W5wWT!in-*S8$GwA>_4>c_ha?6wR-y zhs(t|J$2@zjex%Hjzq=CS=<7TDqQm~0B?x&fi2(gSDM)_XH~w$gS~ggGheZ7`%o?- zP?uL_8F`;S)rgmCF2kH0C)9bb0GD$Ee!FMrZbvCkRsar>SWs@%du752pZrdoiC%l7`{vE_AMT}k9Dqxkvxn|tKN$g7p8Jm>kHo{h=Zo($PrvfR2pldjfs9If^m}{<ZVZj67LYF8$vz( zUp;#sMrG|0eXhNSS96o_*jIHJcQO&1OJp&Mv9e0>=P9w!fx@i2xar#-VHCF!-_O&9 zxdo{twR5Lc5hlVS<{sQ$)B;+IE{Q(BkfqBX%5Wmfye`%5Ls?hW_T0H%jwy#y;dF>g zOy=TV%p&RRU)b33jpG^5IXJNevZv>8yWB!(=P(!g@=C%foY5e^$xS%YKS+FXF?*No zjKG@7vhb=V5f|~sC@mL2??DHtaE}u;^(y4*uGsT?=G4*7ENO3R3%umM?iNnBCzW|C%is!9C;--;6QsPuz%ypPi=of z>WNm8-HrbEAx{BEF*i{;J9|hyTOd93ob3Dlp&ml?r0MxX)*8TT7} zF#>0AP!rEJI)@`Ac6e%*4xD;aL6cU`C;7@9(&_4znD=oH_P?qHWk0RZDX#^JaIEXFvD$m>Eg)yYS$zZ=7}*t5=62@M(gJ_;7P2F07r1cUT@{K=c=K-5E~T zF1;0n?NFdo*IDk^5d+vSYmH+sF-G)ilkmvQ<(MhQa_EOD!RzdS)GY2p5xb6YL&DGD zUEjW_vPzfDi3+K$elSg|yDOEO%yz+s9L6aw+r*VO73k}Xqd4G+5v*c4x!+5NQSAgy zwS#>GXh^k=t5AVJn!ciMQ^V)iq^B=#mB?1 z@!8%%kgjKiq0Emr(Crp?f1oRym-S}(EEl-eG}d=L7lDO&*EsWAX>>2io;r4KEiIG` z;z#eTr6JL~B_Zq%?oid-Q^y)+?jn1sE1ASR5_K1|Uh=>km~Sf!{y73lyB>kNU(e$B ztyTDH)?&P6t`9dq+w;p#GXDQaf#l*uE8IlQF#h9EZb*h6AIrR{IVN@Dv~0Emn&O0` zcPfHmxq$rDA~1M;i0DDTe7NCj2We_?oZ8+5%8N9lHQxrp^zK;9IKxuBs#U?#nf-Q} z7(+f&SBl5<_^s>?u4ES^DbTo!nV|=9c!w(7kkzDSw+IZWy)PQ=kc@wm1o+NK3(`MS zkd1I24HwA3@4P$|y`J22kNd}*ne!Mgx@OJ@kM&3N_>g{VkM++*$?G^-I^lN*V|Wb+ z?G#XwUId=gnlGNBCP$;9!%;ii7%3XL! zm%kcI{LjbZ{;`%gDL@?x-;5^fb!=xup^^K@o;}Y6&2XY_k|?E`dC~^0#FgxvS*3l3 zW@(198R`Vlm(|%&7^nw|x(B$qEe8ni=~Ac9NVxv|G~Suug$HajA#iFEX{8OJ+jXhj zlrh$5%2?>i{5>Lr%l9#QND{sn%4SSmXX&|b7`qgk!l>^uSTbD`oL?5v?d>cZ z^k+BMtx<(Xw{5_IA-eEuZVELSxzW6PMnZMQS*<(N49)8K{RGc@M7K}L0S?y)H2}_zF z_j4@gF6;y1{SeEUK6n|j5a!NtWvp3@wch=379_(eFk&GV4hSwC^4y+Z z^o%h@7xqX-nlR6;Z8MxtUBNwJ9MJ6eY%m@z3;V8A;jgO;v0Gjr8caIry6t`nxS$~3 z_SK%h`h(4D#08Ss_pR`uv+^kP)zQ20^vjM=YD92&#dF@bs@e z6dq6DRPQFz=@mv~KYI|&92AGggBOD0C& z#dE<2S*E!fWJ!`S-RuAL=T=1por;@FGhX+B`O2qp|Fg;X)mQ+dW?JLtEzLdWD9bJS zd`)vLN!l+-`hJro{fIj_%|HOYN94%=ZaC_XFoBgF-E_<}oW@MrE&e*$p52#k!Q4A< zxG^n0q#gbR2kTnFbN1VbV85OJ>Q7Tj3_ef$fBmWXvYm$832FGKzMM?jcv7vrjeT|8 zV5YejztP|!O)W8&6ssg)9vj33-)4f<3y_OXvYj8E3FP$`dWNXoB!n5}kkH zOg3g|oG5{PkGf4zma#{qmG%IKOB2yyn+Bw8&S(CgFfy&{E8ZHMgk6d<_?__&tB+lz z_6$dwIOzu$EqIKV&aTHl&vhZ8JcR~2xzg`vM#AKe))M!qlc$5TpMYPR;L@GdCWO!zhDF2 zy||V(NybRdE1$xqhg)#+EETxBJ|Bmr3_!_m9oQ*)NLStGlK0^d>5Qs}xJqshE}Wqa z`m8q)>BaUYSS|Y9cWr_0&0rNzzr6`Vyh#Hbou6CeC}!t;aVva=;uO6LsBVy@K9R;vIdhac*cMlt$m;2Bf)? zYSBNe&no83?bZ2*Z))gqg16+be-lmWyPXn3FP5%wa^k;wHjqJcm?W3E5*Ju79_iW& z&I}u2Wzwl0rbxB5n9Te3qq_5QU_0qCZr!o~P3-hRv6W@@KHo<#$0>+Qhdc30CpNHb zsUk^d9COcVH$lYKVceMS27Eza9lc-OAPzac0`qY&PM@g=`?eH8N7x_;&`abNy-Xt2 zP3*j6Z4ZIjacFpN5MF()3R#>rdNa4`e|@Jr-x!lTx0bTGEt1c5j4wT&fj*1XAo4~s zzB{ar4;;0?YkC!Rn$Dw(S7o7B`)T}PH3@yk3!vJ?2B$Js(0=;}54C(bnr6)E#xMcQ z{v}5j&BHL#*#zoj9C1|0t)8>c`tH$mt+Wd-yI8||a~qtN+6X1;W}S?p||!~Y~CqB|5Q!LKb%azXFF4KL>eb_wZTu`jXk}opuh?Y7A9iNq04h%MbLSM(q_nGyU@SH=us^M3{kzT#Uzl+8ts_ z?GAk*dzuZ)p>2e;gE^eT5;q$5;V(XMQsJ`hX^{DyTAY-Qn*I~eq)Z78e)OfW&uj7Q4rjP9ZZ6LLCx?oAm6{f;M{TjgMHd32ACqb2Jd&#Kk=iFc!rabXxF%K` z_J!JDR9<6Ge_Lm*51jm=1R4=BT$-~5Ip65QrTczyCvzU5n%#I*{-_7fD#ziPfaj2V zb({FmB_%o(or?lC=L)^Z7~{8%&~I(CaK-BtxFgsCKbt9m&ud3gGG}*kl~bHkSw5at zHpb^SbRm=V*={X9fXCl%6}v|&QAo^TmXT}>-wo4fcYrHtYH*@}BM#)H{-vkp7zb$Z ze+RMOTC$v>8gt|Nh~BJ?+<% zHTZ|j*HM(|BiVT0Sy#AyjU`Vd8G5$ z9z>tM?p%qh5x+gAj$Y<8ikI$RiCT7pv4!pL4`x2Pf3CJLIy{auh+%GohXyn}-5$E8 z#p6w{L6|m94aT0a!G*UQ*bb|%^tP=L@41%!{{_L4qD}Yl_4fn#be$TU*Gj>tEVZ7Q z+KrI~^dr-i3U@Ve$_LJ1UBE;fmLUKUV-7nQD{I?5!XwGdi0?C@mVPyqNalygk@JFb zYp?xdeF=b8QyNz4QjK(GL|J99oHmWeKSNnmLvkBUj7# z+NL*Q;+S7aI76*BR&LjXz8M9yxX6ae2Yuq)WNL8px3!qS*o?-|6gsHvOdj2a!UZF2 zapuPcnBVWRC}Wi(nRu1q%LpAPRu}M+qs&bg)Fj?k)Q47UE$i{9tO>jc%RDB)lG;SB zd2B3QUSvv18fGxytS#Cy@2gdOF1It;jkb*YgIRx-IdO*u)y%EIS9Tl4y;F5bZA1hb zvR(DU0m)eUO~0q+{L37|M?a{i<@5X`ecf$w)w>2rl*DuGtajO}{K3gZnZo_D0^TLQ zhMJqD5|hbF0VdrO3*&IzYJ6dc#r8ji3yvM#Rv0QSS4Xz4qfOQoL+|qAG z{Fgtq6r*S&vCxmfem8tEhPhk&kD5r+x7MQP)FI%-+@62h8)^0mOG&}nx!9>7hlSIW zVaF0%%wRlT+SPpNxE3S6w1H(;7-Eu&90|8ogq93Nw^oeZC_p|LsF-mSu4t9SU&s zFGF1RRu}U9Szdr{Iv!lNRlHbNnYO$-gko_Hr3nThXqTlmg;k>rN;GMA?P4e_GiLqg-tK6te`wyN= zFXpr-2zdNaLta}(NwRKd(t`P_yWtP8!!`qj^=dHHB?V!z8vbOS`CEzwmjszejW?Ei9eQI4|bqcD`vQGCIB=*I$zK^r%DGdH!hQa8kQy%I%Ao zL^+dhVL|RNFmPu(xj*hw`9~wk<<>+Dj_i+9b2Y&5OgQud+jJ7p_fh-VIAB^}X~g}LCFtOcvz9N-@HK0?R#=+IpwG3@m_hb0`_ z3)9wuor(|f<%k4SVg30{7(%s*!^ti0xkx-a8QX1p;Y;Q-S$esE8YWs(?Z=Ot`qWyC z4ql57C+mYSJB9Qs94X|Mq433u0l190Va5M0i`2#`(O|VQd~T!*JEv>%{%mJKsk&MG zqofaw{Imp()QrGy?@f?BF&;*rOXMyX#!;_crnL5~8HB%x!?IOw7?Z6E@0a#K1R0E1vxRH(H zFFZOeQy6HV$*)dlXO(-LWKFjctr;4RGCxhh#^N&_vWcSnXHnv5i)5f;+EMOwWjtpx z%!HrQw~p4oF_Em?7=yA8#`n|>g{PBfmv1drEOCKJgS_~40~@Hw%2J}+dme6_CW{tJ zl_6-j4|&D@K~q`wkC~hBVXXcfOByd}6XmeH%OJdCrV4Y53Q&C<^FvM4g$?Tq=v>th z8oObtw9Dr)-uM@Sb!KcwY>*FRq5_nj*~f`rS<(jRMCIn+T)9#e4*5758!qZWQG+l3 z`p^NlL_5R}o+;D7X*sBS&j@yCu^iY*9kA~ZaGOfD(!6QxT@&$)d-kIMPq-W6`}um{ zJx4%~DpT>>zb)eaca-VO>O(jaP2kku6tZ-8q8D|gqGy?!d>}jjzqU1&WNTL7+f6R0 z>#hrl+f*sLBoeu|PlQQpCX>dSmpJx>Bkb$D0u}0Yduqk8P9d!gmLUT+^IElElP?q1 zl3Ctp$)=hIWUR21Yy$F1OF38m@u>zfT^K33l2wJ>OQKPPTCi^RMN|b9W@2eJ&^Vy5Y);&NNU#^hJq5fg%-OI*(4X^+4;C3G0Q{QMP=G zc+j-f`1+GQ`qwMMtS$L4*2WSX`^R#}I#a2r(10F47!1$Gd+~La^;E4kNAi>Hg)MkC z5S1&`K)Jw#Z@O4Z7hi3c+*n?L2ZkKLB6W4JUy_1$s~97~emnAm3+ToUXVT4T_)?_CXlpBj?c^8OOhG;#8HbKagQ1g^RK+) z_-!+Ns4q5Y*B`iV(|H zCSz0nUyw9ug3FdVoLIgFYai=_hJOk*s12rd)`r4z9hM*c_bJ4F9>RIA*5ZA?*O2U+ z7V(+3KGat!09*eV!bTZ28Ydr#cRV9S%YN|SGky%)!%N_d6ys@knF(E5VGg)99=}|0 z#f~ObaAfjX0;7ZcB5;sJm3Il%JHmau*8l^tNFo#=5x$UKUdYRIz+ zB$tl~$Z73f^!T()+;u{kgoSZfv!yRMnSN$j;gNJAGfHgT)CY7}k43LDjvIYZNaIG~k`o~ikx7=EEt~>^_?v2BL-<06l-^n!cPz}CRbcOfUtj999j(%5KNM0q+ zL%&QJOy8mminB&hqQV~xxO9(;WqtJlJ{>S){47zylN_vQ*@ULPY?iU-JXXeAp&zFU z(#^~lH_@4d`ctKbBdc+uWeB?L)B%TVmbaq$|GF{cfi<;rT_`g7$F;E8@j1Uy7-gBsEHSYxLI8{VA-oe}*Y{&WmCa!DE;t=6X$8AovWn1H`&l}MZ&Zihg(>L2K^cek*Mfwx1r(_6MBKtg&OGBBZhJKzmn_nR z9S*6aA~%w@<((3Sb~Eqmzo+p1`b|+#vjV-3xQSNUns8pAKsyb0qQ^=TczDDK7u+NG z^Xfe}!EPdr*v`J+PXl0wuNB%ezOE@ci@WczjiNPONx8;|yLEdC$pzoQUX|`JHJUwp zTgvHGppoR)y(G-9F~gX<8t`;kB)#2XN*<@#E{1{??s090P2n+I`N^%+&_0A#$Y_hc z`Q$)Uy*m62O6QIlXVRGm+GMZh3D?vM&~lFu>%MD&Mso^X@^+x1F=?D7V^J0}o~?ax z0H>3#&41LdrOcI)Vmpl#jLrWI=bmap>Xv%k_j)y+_Ar1AOVen!jw1zi8woE5Tj7{s z#^yCSbN(l^`O&tuq+{PEKHAcUPBtz?V=@HCHXh2ij)K0O@mzURJe`|uLdTW*!M(5X zSo6~bM{23T;V>(_7}*XDEf}bqOBJ7i;rB?$=OsHA-sZ1=QW2&8jyo6Hi&9LOvdG zn5k+89`E}=-lRiZ(X}}4(?Bt;_3pxltBjyOa=D?>@QH?5xj1F`lFxAqfrbsIfl-s71f zVR$Y!{M(4@gH=J}`gznIZHdxiT~`0uz3;Xo^}aqu`m|RKTBz|Eq^ zcq*msd4VJDIzgt}O0*W~;5A*wz0bA6$SLjc;M#HN**n_&&Be7;abc|Fz_<#EyS0eg zP4Y^ef~&D%M-+N3(1zaZecFd*A@*i9ZaXj&x7F*xUFK~I zy!)KkN`oYAzcN)VK97di^x<`;6&jsuhn%!m!fl4^4qZH`rzZT~cLt8FHiP|J_i>d* z>11qRK*ywx@RDT{9sDx@UpT0P^0s99u*#iAl!bEVnfK;lKjwDZ93gsCSBYVej-_$x z@a%31sti!ZumM_NYf(VGHagOGtw!#aLOxFYI3AbgX~H9SRv%7{Aftn)gvNteM%%h4 z;FNzu)CP*Au&5kQz0rhSM6Vi*&;M|+toaRh)qN7(8TkdXS(b_Ad z9YyJ0eaUve0M?dSqWktXFms9FI(7$Bu7?Z7ZPFHvRn39j{%SB@Ih~7R{?eI8BH3qG z$Q5Q3U}m}p+7HkMr(>3=aIFOd;fuM5lRCVGDRWpUM~S01q~KKfU*M>r1;plt)2~Eg zxw8*9C%+CSIj=;SmHM!Gbt zO0>fGzpc=E^+(yI!#eylZFVm{yj5c8r$_K{H!A2Vg84oHX>>*6o0wWrK|=~IP1QlG zbDGedQ9*t)7Sg_}uerhR&SH$pEZoi*{Xj#;z?QT@n{9%Ja*Ph&&hEH&R4f}U9`maY*t;I&Ca@mb--{ATU)6=frW*q> z9{VKY7!8(Li8PD%W6a30_|#b$Rvwy4i%vbpg!`^+XU~h@B~wkO$5=@EX)eIyoBLpV ztuo`nLurd&e`+z5g_0U8^kS~LxRMznAC)|;(AtPrsj3imwGf}*vS7|GJvjHcfPxAK z)6I%0(i>b2n#yg*{#`oYdnko!cDPffceUsUKMEY0lTfilmc1e?+U}Ct}CAc3Ap)huE3jBUVp3g<}sH!}hg)Lm%R(`Ve?_l3Cmh#qDy(1-gL0CIi0(d7r8t|f&7rjm2-D{!Q>BZ?h#nL|oI z4b4zFLsKMm^QTT}0hM;uDJu0-pz(-#LN`er5}wvgeQ=)CzICc+r<)B{H0O6ZNKOK|`nlt=X^*qt}|i zC33(eX{8YB{+e^hnoO9|iOpl}pd#7|mouJiXP+$Yo9-TJ-8Ga7rFSY0Qxz!U@hD-YNVL8hz zfAhb(bgEjHU(0q3x89Btw{t02Yw`m&SZP7f1OfdHi@<{~ytz#GdK^->99_fpVV`*# zl_=R$p}P^sG@HT z{OliP&DV7KL}SMHHU>++8tak2{!V;Upa3)2^E@pz0*$}ch+=h8SthJD{ye1#KW|h} zY~FlYz5O*eT-A%8F!d?@kSviDC7nYbhncu!2J;LLvqpy@tuXOJyvN8QUH-mWEt$OJ zCDXG6)bJ<*tr`Qx8t;`!Gccy7e^R>l3mrZkPSt$0SZ$gYX~cJ-lmmx#*q}e^v6;TI zUm;y&3{RxTG-)(ni|x+aaN2BLn6f;TQqi{Zx*@+)N z_5x2fV;!L4$v!JRI6QYU?pe?d%TDeTZ=J1139_d!(9;CgRNM0xpq>=BJrTc9VmTBn z_c`{al)H7-g`H1(Q~y5MT>g$CoOMhWA0N|)?W`_^vwg8Mt1P5T!UgpGYXY|J-z-)e zt46CVGq8JMUzpy`_F_s~;DldquHIFTUvrPusLg#Pi?S>6o$BD8yHe;T0lm+Tz>=yL z!bw$r^l8v@^!?`yKf=CHVN)FWJV_Q`y08jkyR^`P&D38oUZwCP^YX1aE*)#2$J;Xg ze`CXVN!@=e-^~b&_R|uN&1AgLuK8q4xupkRc=B1+Pic2+oTPtlE&g~MiBrTnuvLNO z__VyK=SOl3VCcOz<+TDV8_1Gikr-J`R1k2F?t<-V@&4l zDN5k5`ZNs9F@o2Bqd6bH49e@!qqbOQxU;~EuMj?Bz8-(c`Ikw!V5Kd(X|ug5*Cg_= zb|J4@ySZ2F9yfD3bLg>}_VddlT(>k0r)p||NnR>upHRT204?Z~SAbh0$Kn*`mVc#_ zLc^E2(eTA5h1Xa;lr3$BIw3Dgu~MevQ8&56l~mKihGtaF8W?H6~&v-pE;VKA7h1?T}`n0*FNt1rtOp=<4oVuwMDZh z=0I+ZGIUj^an+id^z=_SX1f$|y_TNG^6?`uV6-;OGjrhIuC1eF?Fh+$I4fLrvWaB{ zFXmiCQi_y|CgYNU;%V}!xXkJsjCRq2tf87T#ykQ?)%b8xdG)A2cNvP954oOs|DOJ~ zqh@s@;m$TIJf+bLIqJ^bOF4aBbABx~AA2g6YRZtfb~aW_GX%5!Hy}jM6TTG3b1nOm z$ZEAQ+Xb}%vxSM+b=(;vV%1>L48}R+H}{;cc0SYNvm9zkI$*oxyqrEAu@1q`iHe{U zmWs-`TFm{e2@AeeP->rf6y)`qv+SRb$6RNy8YlpnBi0B?Ej=|Vy-knLx2Yws?i-Sg zjQ76#A{-NCmWfp=l}Sr`AO1@+1^fJNT0SV8o?Gq}e|*&kd2vUwSRun8Qbd6MwabX?AL|P%w)1z?n)OvJre1^7!4l|%7T5@ zK5m48J)b3pOeI2 z*Q~}@o?3Wgw+fg)WarFZO%SPZT>8{opWjkaOL`xDCBl{p%6~DJWqRe7dc5-FJ7%_1 zSbCh~`}8`T;TDO<0(C%pk~J1&HN)WYNMUTyNf2cO_SBzBx=cRF1~liZJdD~&(2MojyN)#X)R`fR*Q4~%K<3j?0uRePsQG08 z>z_q&N+t(ssA6tJI18DZ>0J1_lk{`77QHnZ1z(*Du`*>i8W(88=^+mM?#3D# z-xw}gdxiBKnTuxm`o-L>BU0KlCWFuegc1;t{zS9IVn@YMgdk$?>e$DCj^Wx?2 zw$jga0TMgN#}eP^sBwX1$JAKk;nPiEcQ4-K)pvdVh*>R7d3jS})L(^WJMP8qGo~;! zMF!g4)45mUtgn?wcXu4h&Kr$cpOm4>UbsR2UhJG$)m#vJiUB8qK4cdTPjU#WQ#zX&sIm ztOmWe6=U@ibF|Rbhf=;C@9o@*cP;e5_jxk?Wjveo$s`3NnOB=Ap*4yeI^x8088<#5 zon@QKa-32bW7`ya(fI+{ob|L~j9IRYt6%6t+7SWS#>Js~Ymhin+K%&nt-*Q!esb$` zKGM$0y%esdFJ7O`7|WGSJ?9)g+JJxhs+PVQn@dJ&Kg6NE24RXnn-%8FB-h!`@Yn?x zDA?9T5r1Ro*4ZTSAC)z@dXFaRCaOUE7HiBM)YNkqE8b+lAGu#kzvU-Nf-gR#E&t}y z>Z-ibF4oV{ILy3P{&A9vq4ik%ECTy>=sC_=p>=l)8bFd|aSL@8a^&ZjT}Sy2=>!NR|uy=cRB% z^9Gb<3^w;&3GR2~!cdllJ7i`Qr@QVDP4H#smZdIWu+xiQ%yI#B9?z1PFm_H<$Yvz7 zG~nuqWUAF4Lfz?mxRcD)_QI_Rtj!`sIp-du$Ffu$7p(#Pa?;REP9CjaYQZY*JQ;i& zNOIE}xymQ!vFqGuEIY>-Z|hY0)XqGOEhmL5!fo&x^Yqr5-ViN|P$l>78>s231F?aM zwA48WmzJ17SCb>2(!bV|$FXIxADx!{jAc{oVRJ7Ve0755l26Uzyi;AN->Sc;-q9)z z)YYRiW1`UIsmy=QPiE-J)AXLo#_pbg`!dZi;r;h`FAAkHn0={6{n(+E%QJ9Amf4f&ART5{2T zE}rBgLzz!zU`t;^Sg@%Te5+={i0Z4&;v?u5HHsl#68bqw-n z9!SB>onKnhQZ?7tAoqw^@}HO@p7Pup7pc|3om9r=z4D~V_c;Hs>^O6MdjV7TYhi`IK1|d! zm70!7rkGnUtd%p;JvbLVXIH2=a7PO!+*;Yw!`$xujnY*UC`M!;_DQwDvF&x-w;{v! z-!_!)RIjFO@)i>Pv5zrovmH(us|S7i&m#XnFY)sM4;V1%3wi3s^9;@1;<){*@JWd# z4$tQKaa?1mcB~G5-922oi0cyTUp%A5{U=IR-1nA_%4s0wFUgYIOKQ=2Ni<$})`OSN zZ7^?6J+v&36|%KQLE9-9Y$h;P|KKtut`g9&X??(VO*P(>n~dVsT;I!U*QZAf)cK)Q zB5TR>)-BHAf4z(#qsRvP^{s~+<*mYVmFw}%!vWars0>=yPQiI8&kTPQ%S!zA)1V4H zI%MJjK7G>g{1GeMI#~mb`0XVl&cs-*7{P)$Be9L^dv}VWMcxOVVp2yMzO2xI>2(?S z^_x7_H*15%{quA&d;p#8RmUcq72+8GQK+4v4NLtq$h^g!mX+lR-`wYnL>>M){E>>L z`>D~s>|5w~P8aTnC{n7-dKAW+fDql#Y{xZN_OOk~Je)>F$G>2^xf8rqutis%WuN>l zkJ(-Dq#L?_QR5;{Yj~o^bE~59=z2Nm7m$u7myNKyNE616OrjCRCj3083w?gNNxcr& z&_R#c68=eIN<(eWjeBF52Q3`ajS7BGg%_rrfbDmC!&~p*E^at+C=$4RzGZ7?vY7F1jovO(tqnmbOwR`E9ZvGWI`CiLU zy$+S+gE8g|zY8eZ;*!_g+h#eCZQE@mO-y-4KZd>$D@>82|DI080pAUvW!x<&z+o`+ z;V!m*K|1+tF(S1URuHmcFTVTgf@*o{Ffzmzr*b}Oh28I)!O=!iiyhCXdfawN%L9FS z+G``aFXwEQ9lZXd2F~C)T<(*(4rhx81qDf&9M>)UomWp^uLVhB9u%PcP~HQ7<6M|j zo@>vw)BkdJ5C5>rNcwf&GrD4aPh#kzLLt>LIKj;nO7!I5wkVB#;S8$<-D7EmK?m9o z?+fA?JnP(-|Lkuo(WH?|FLT5c+ETyGXBvd1X>?SFhkTn?F{~_UWL8W)L@8zG1eb5LrwntP7ANY z4XZYw*$tkv%o%sq6WnO52*{D;<#5sdl(dU zT+h5B_6WYdUTkxE9@Q}o?Z zN&mhYbieB?_AWJo@ther{$CyEQoIwM2?)XY{P!7StqkhIQ*fDcIR4+Oh=v>>l_3IZ z((!~n{5HDqq7}|8(twhzbh6kxkSad!WQ*R~Vyi+uG;~Fa-g#7EMt2%+w5MrWdj`1Z*&Q4AM=_OZ=FtCK7GMYIZja6 zK2Ul)tdGAk9;-lsqpr%uWlsy`_hOz4{4E2k->75k zP;D5^Z_1*ST6!l5lH`s!kFu8j_(@3%1pAGpZHsxYGT^>MrA1Ym-Y1BrW-VqG+f_*O zOEemdHicGI1?m0i33MT7ulT#UEG+t!+S70R%NuD(wju3AWnL_sL4(+%2IoSz&JO^Yv>QT-tWn5KUg%T2k)qFxRD zye~%cv!*yEOCPMO>hVWgD2@u$hpyWhbc=uY=H@*WNw$rFJ zfIL{<;_t5wL$G~^0G6CmC4bde+%;NWlYfn~RT0uTzfS!ASsQ8wm`D%XSJR;D z{Unw681uqxFn^#PtnCb-5Y?AB#Lo+4)xT0VpQ8`Y+bv%AbTt+`XkgP76);IUnzU74Fb`2|3>b`EA#M3@sDzvhybqca3BFP&xFO zpacEit4XIUiY2#Y&M?US0*><@fqz^0Y%(E@ZXR`}%y)-{&isCHH|Qm7zUavMZd9c9 z&8vFY4v(!|(dYa{sIPp-#F0E_`N${y_{<3&nRrUKtJTu}23tvW;2y3k8;k-EHMoDs zlkN@rg&E0BrPizUsI7A+PA-v!c8v^N^Vk4Ijhb-jVloXaH6{5^<0V@{Yf*;tNUsjofy7Bx_*|Fg=O*tJRxHWD6yJ~VGDaKzVjVU< zpV#y3pYSTD+~#1q8t*Su->pIC{4e95IR;>@Z7RJ{{)}GKwu=3^UedXI68@H&r4Waq+><|xDR!7hlaF&9MSO(B z@Pq-0*R4mHGDV~+wAF{!Xq8R^5P4JgufP&lgC1OS!I0WilFa zreE4GRq348dDOCcF)INTisyUgRTE8Ndx(#;r1w2Kck-Dy=AJA>MyImCSxM~2;t4c* zN(bH<(GSWRZKYj#)pQW8Bp!D%1}t) z9MSh`_ed0EA#o`U!tc9&!9z#hOBlt_M}IR~V$d6w_p!p}!WLL}F^=^w7(j9?7Ki!v z6aQOTf<6aLI7@=>t3NiNzeOmzKh=j)jSPC_=Sp?X|A{&$je&t>|JeWMk$p~FOUBt~ z?xx>MKh@jQ_s#J*>fdCsxqcP?`7x-chFr>3C7<$W+@>He`Za>{C1y84+k;54_Ao8l z8-5twPMLw~eNUs`ITWogVUf^Lw7c^$x_{xj z`~F;q??0EqB3|G~lR=Q2^_6_K#*p{&-C|?AHE1DJ$Hm+O)pzVpI$>Z%diT26xDq}$ z{eB5art?IHM?3s~_kz-hT2{TNfL?ELqiogW8%p{<(z>*2vYeJIxnj_OpWj5{UOmqB z(me{hPR#|mh?{I}xjl*3#ADUBtt{YOHTrxQhYw`*VRJ|ysnwxG`rE7{4&yvP+q>0N zXH+U#!Ed9*$IsxmImV##cz|?fZ4Kqwych3zVu{&HTfkx1HMZaD6c{*b_0*Xw+YeGu zi!L>{d4W?7pXC?!$3O+Xx8xiNk$DT0n+7uH7CRbR7K@JhZ6X8pEVP{{i&nupaP+Ub zbh$Ur5ZvSfI>AMFPICm`Yw5tFd1-Wf5zi|;dsrAd&kE}`T0nf;ff-)se)b0|@U)c) z&t*}gbNq%|^EyQ|$!Ip2AN-812VLMqmX~zBeJwe@86Xk=+=Hu@492zm-gd;! zfim;^H|H1XQK`&M98f9?ncp+;L%0Eocko;)(-iX6Hlfr20eD6ipbyt{_Kwzo3+0?! zwY3G#L)jTK_#_YR+}|%{LKe^W2d> z9h_-7qXo|1+bev=GB7mp19Wp;?mwG)j0p|Ibw~6eXGuBr8XrWHX7~$F`e~B==Sz6G z$^dRCTI0Wv7MPIHDIA_5M{(c%aC)8rM7@xL)(S5uC{Jdu6SJu4i6NP**+OMv8df?w z;o@3#NN(RtqOn70`I%X4rq~*HvKBC`juSavG@@QJLhvQmsh;_eiDi@2aM4AcZMv#} zl)0wScMCDWEFWpH1HYR`ERYOKDMahllQ1Pp3$|TKqj}HzBY!u!Tn!-mH8Sp>0i~YAafw`DYq}4k+kd5yT+uz$tCveWj zkx(m1C(mSmzPuT7jvZq5xek;8ad=SLEPSOrm-hVREPn4{@F?9!x;gd^^>ee3Z14=m zVf>CCtpo_wzt`Gb9d;V;On2G~sYG4$`v_j}Iw9+d;-XJxQ<6 z_2_J|4x^g{(3z7-Gam3%`1Yrwu-4J=bNL@O(IlQ-`Cy5^zBEIYT~}$Vu^su`i$Uwm ziQ?KjRapMQ3$NS~z?bw{xR`TD)={LmI!}u<&mBVF3Nx@?vjI<}a?c=tmYa;Muovf~ zrTC^ir#U!as5{I*oEsnSNr0|?*hna>?0lUE`e_7 z=!#3ZM#ZP^GqQcaf$+VxXsgE=RD5O(^Uhe}{+wnAK6aH&9N1nXu z#JRJpc_?#TtVf{WhYqaB%^;7%eEyWn z6B-}4M8iGJVEfXZ6{aatXXkP}`OX*|?#-reji0ew&lTQ`<2=jI!5Df?4Q_n0MD5OI zIJErU&3nK3&6j79f9sTm+~7>KJZXSW>a^hH&s4hh&5YXp4dI0Ic{J4x#Phv0p@ZuR zl#IA$^#~h&(EKFa6Uf3)qYO66FQ3c=TIBO&0$fxq!6Z8m{53`oGWV3zfBWW>Y||sQ zU~D~Ben`Na|8$@@ncr(ncy_byUf~UkOw7Of4t7*)!|xgOXn1uF+Hco~^8H*Ve|$c@ zvGNxRo^tP)(qwb+QQ~HT)*e(h~010LEeSm%d7@-{?9BnmFp1n);B|pb(~1=gfT6hv>vOtuG^)5 z7Rn4$#UTaS;1F3rru&__=Y-gsIX=?UE1pujV1dNr^acE)ISD_SYeRTR4Ox$mCpCF5 z(ce@nH0{?6O^HuMItC6jqB91~Mkbd&P*bIG?K`p3$`p)G%fd0OlpY4cx?YoM%w z6JiOo6z!yWFRF-~tR-73Em6L26Rb)+#Gbp_ldg9RS{-T>I{9#JSRL1cP3vSbzk{** z#dm02t^)O%akR+EjAq64fxrJOu{f{^yfot2&)@+RUl)ZN(k;Z#M)SW*hGEZ+^w$*5 zMtdKFCl2J_98%VRIl61HzoR}(`8fu5ly|cq@$u{{=V+y0Zi0D&uF}HIc2rUnjqlk+ zv7Od4R15UP)l2{#+^5t2H3lCV^$}^s^PO$`3z#-OPQ1`lo05JV#Dx~-Aa`gZ%9tAC z1)kkdKZG+I3!30!@AT56uZ!@tSfxjo`-p2%YV>2VcKmwrue&@qq-ZaG*S3J~t2-%l zbqvXWFc5!kR|K1dhneWV1?*pe4?VZ;!gaNJ@ct^l;d0Gkzisv+PuEI(R@Dz{-|E8b z+<7!pp#{U|4+gzM-$?K_inCdEi!X()#mX{OoX$D1?xj0vk$ZnSm)XVlEmk;qb~7Bg zKS$J(YDYY{5aXrK*tE|7v!-3BLN5763TN~Q1D{gnk0i<2+(yj2y%US01YqfK44fr% z;fw}jrn~IPARz|Z-fUs>F4v$yZ)}fe&>&1f+BqSX=DBN$+s61vzfOBfzn0#Vyp7PJ z(k1ygnCAtkm0EIkXcJ5xdzGomJJG46Sp4@VO>}+tc{p-N7an>hvE!Vz_02d2$9&{$ zSjfPS-z@M{rY2mymQJpt9qIa$2&TBm3O`mf!e#ThEaiO`4o~WZ-uHE2xmc5C{)xr| z>s;BE)?(bZ#T%<9>B2_eEdH){pC$kl?U z{C6HL$^&p#rv_*S^4(8tBb*z^hF@(t0eQQ7_3S`=EzeTsP%TQnJ`r|Z(j-s*Zw_3n zFW!_~f?JH;aa4#Ne7Rmu1|I_H-LXgPqhA9$Y)`;?7hM>0*9te^Y=pKidxR6`W@6yk zxA4A68$KV^B*$OTxIR}Xo^q@n8;t@`ZH+#-)s$1J(mXo)XR>gvzZQiBUqtI+hVTol zP=)i;_Q`h$Uwx6IJ!8l9^fsXd*J0@{2Uxi|mi1bbP5U$qX!?3v$h^yQ=V~4B#0Cw> z{k?~-czV*&u`}4a$5t5dpb2V%bLStDKciEp~(HeD7bv)x2kG;w;Di*QGp1Rcd+8 zGu#zTVMvS|^se01Gb?%D^C!`Z4$O+Of)RiDJB~B-bf+I;e);yKAmSRTPmRJWzM7>SpMhw`q8r9tN;q3h}P<`-MPY?4m zf&YzGG{WbPou!XWooEf$uWorWMf@@D8NU1LjxDtUXj`sH1$UxR>uYaOv>+H4#lL_x zf8)e1N3`jI@j(pdcc|kHVK}qU2>lkSf@lNJ2cOso17D<-YF#bDHw8TF>$U){XKB*& z&(U~TalLpq&y?5aUKG(l3#h~n+QIk8t33?F(?==8=;Mc3QerSWH+dw5`gY+i{~!ysE+IrK5ZL9FbdZ zsZUc36_#p=(--(iJ^wJ@H~nBzcoUycY{gB_&4ZB}hZUBYH1yP~I0q$qa%vF{{$>p6#r*E3 z5sgo;?hzU9ss-JhGho7=6c%%5E^SNvh{?O%AiF=G6D2M5W8*-Hb#fYN_V(iYYwmsE zx`KaK8hYy08>xU6`-US5qM*<$yxgUS6Ku61O=}N*oMcRIviZ(r zVj&*LosF}4^Bj)bRy^Olp{HIw;PuLE@?Yk%C7s>xJWE-tHEGD=N$`JdSoyyw6fD;l z*XUftufKS{ZLS_X{9I1Ao#xVjb&r^JQX|gjpMX%nx%a)T@ihN8yB_TkdgfB@~w`H{itWvwG@Pj8+9b;j_A0`DEdDLv4zDUV_afhLAUzYkrD( zZmGCKsP$HkuF8%@+XV(7R!4BX=M42+n;{>%k2LZ*A0yBX1dB5;-Pi#afCe<|*h{AZ zJ*XmO25Zu=#uGfN)b>iO=x~z>_0d>^OP{Df`tL0C4^l?4ybkXzeWbe8kLj^^zC^54 zjIv@s?0;Mv?nkDPC*PNusQwVn4ztD|uNxrb+*8p5-f!%A&ApR*5=$#5s?y!49k}O% z2}lDu>u_0e&%U=dXDVHM-+|{ct-&~ib32pk!7lg^%gJ+~%2E^s|T&z&eHHq zJ6ipl|Nl>#D9-)$44q>J_V8O~Bz?BI8V>vOcoEFc4;uGO1Sc!`F-K~dAA1mD?3M&XvI1AUa@H9)X2TMMI;fs&=J>^8`l^6 zNSD<;rm*cvl9_?cXm~mTXLHR@7}t&X#Cwp7%UjW~w4>1f#tg_De}l#PIM7V*C>$)_ z%0%|HSbt+A{&*{Z0iiz9Tdj{tx8{ZInI8D8M7mVTFDHr^Gpa2f8eaqrb22$kjk6imS5Y`u@p-+`3 z{~4ZtUCZ;LbsJ!W!M&T2R|It9%2w2p<2}#0EUf>ahpGPBFlpc(8s%opGvN$itn3A} zwhX|t{06j;|7-yN+5h)Bar!60#HhQcZq%j}(D9{w22k{eic=R+OT!KS@*Y^#y@E!U z1dub=qK8X-r0B`BtaSEB{LVF@;*)rs!uNGb>-f%u=l{0X>=BxJW^q>eD;Vg7PvVz7R3n2NZ$wD58%(a&#_<;KamvSxK(71Xy>(C+087fb`BS-hlT=_2m zNY4q5N)uS{g8lS+yaDYrv4@w+nfNr;9*g)5?z~z$d42JqVT)(6)$!IiWpOwesmy`^tkl zgMSDM4Qz0MWdppCs}g-Yq)OV)w)ONggZV9OvvCr8xHXXtUof4bbvjXc+6JO|&9uMH zb564ku__x!5*&_1YoBIe$w&eJ?>MZS`j^#QT7_F;oAzs;3f=);Dutt^peIgrC=J|5GQz3wmA7ALojRf-hV=KPu zG6sIhbTO$}95XfGp5G^RJ@sK(nH?Rijp(TlJKLY3?|-g6%!EbWOYryE7jRcDQ5@R+ z9H;MIjpw(uvs~`AY5CMdONV_I2Orpklh6Q{dZ=26;!*U3R*H$xoJ}aR?1ub(yt68|zT&-C=NYL>3xH zn`6l^Ehx&d#*QUCv(j}gyP;Qt18RGtrBxW$oMfXH{eoSObs)?BBC_v7)Q{DLX=>T@ z=9vSHGCC%V?sAb%A5}wO{!lV9)f)Xd8*Rlud)C`SiTtN8zXq>dVNlS-pwY~ z*)@-3etkg4vjf52$VWQod?W3@?j|XEkdBUbJTNMs=MgkpqfAa6q$b_Fd2qBo`A^w| z>+R&gcV{-PSfz{o_%0%I&0bnJ*oZ2(7{ZdD7f^e~EbMhx6FlzooT+nms+Se6flmH63=kE04Mk>3PDv=g7!`A_MfaVSyI(oyCyE`3USS5% zc(Mq_mzu-Wvh6J9+kSG0)Tfwr_HZmD6O*}~xoMy#Bs|;b+W<249=!g zh!ee?)}Mw{g`l@5=htn?#_iJ;aRtwcmB#u=AElMih<)=Ud66YJtZ+O|;68#$1zB|S z%OJwPe}p;nY_Ptn4*Xl5inc9qCP`}~o_9$pZGWsvXDYYiyk10d0+|WHgi4X?|f0B?L~YZ ztlOi54gS!GY|65p`XJ8xN^5&1(08)|;;9G6K*j!!p8Bwc>n^Ll)b`9c{cbta3)d)I zt1(SHrt%rebUEXWMFQ|MYe6bpiQApqnWNukoZPM7(=%MS#lMFtbv=6(o>Y(dYh>|n zl{P5vx0U7@ClU@D%50vfQR%$|?(H&$34@d%B4ua(c(Gp;N44lJXUUlJwR^II@KbqAiU z)`!-^8Dz26lbk=j7p>-Z&!J(npzl4#p2s=T&Dfpj9um$98*4GH%p3cC6o8a#R;MSH z(V&4hBxO5viFlUJhb~jN@u86-eB)@FVwU*MLe3j(;Pp2C8k=lef-F%1XDl@kS?tTg z+-NgQ^3?*>4LNj0-;v7dqgZ@~o3!Id4UOqako1YRK@!L$ukvj`Gt+5 zK+PQ7BKs5G@|^TbcoENjAC5Dx>w?O;Z&XnpPnJcpA_@Oa{>iU}u(b~CL4Xpe&zgrj zwj0B`Rws;kbPAs9zhY_I7f^Bf2RyjP9r|;P_lx)SRJ6oRvSfA!{_W#|aePN!PtYvD}%_fr#! z6K(MIm0C#p!fV2p6L5ET7kko?#y%Qf#)io*=#{`(f?R_!?r=Tt1ydz@WzSLVXB_^= zIbFHuxfUR;7XBNtR~Rx&QL1G#mkdKZf!%39>#V7m$oGVIf9aCN;1ZMtW3c8L!edW3 zo9=msP!uT7b&@{VHpKv<4;4Za_avD`ZDl8$570q%eFA$2u(QiT4+T5Cox}Yy>(l96 z+CWNGoyB(ivB4`pYN2>;oX9uKiq-{%;+*%|(C1Y)PG8jr*LdU&6UuLwLQcwx>5RJQT%y%=@0 zzJPL!3M5n|(XCOYDo zP0oemciz!!3vgRyFWeNQ4Ol%uYIHM!p3WG?W`0s5%QNw~eTy+rh=NqTZxX#mOL6Wt zC6GI|ucszxJ{(7b;=8zB*$9p~+v5GfoEN9$Aj$LdbXYE;w&T2aoHh(N z83WsoDfQHWF+*bLo1F#8Mf_rqb#3vdfM=}pdyTBAD_K5_#Kj4X%#-gf+OI#P2uzez z<-Fh-#M=?(8bIX1G^$K!P^obKaG2GeH8{GG;!@>Xw&uJEb z%OWkQkxVk>KQ$5OM)G^jlZVvSd|k5NNsp#KIEhW%!)RO3NRRbmsVq5DjJLL8;`IJF zv{MB@P=aUv$YaB315t5z3EaKIKPR4Ty;mt4`$m}Y8C(m-pDD)41@d^(cB4qig6E0^ z{^)u3ui0HfyLZF6$3qw7jt-P+{GW4suuL-FTZtME2jbBw#*k9wimAiTKt;t{R#6{B z`y<-WINbxDba_j|$JA4fottDVW#ATmD@o=&*kOYV=-R7|7>si8(K!cOcIsfUk`8D* zO`{4EBMQ$k0yC3h)H^#9PfgW=Ekg#NEayUByobZncOHjfoZA|-V=q%Jxr|wyUNT2*^RN)ZTb+jSkf8 z<{kvg2UPGhP@+EPB5s@Pi{1-$;BitWC7ySuIf}o9HJsr#h%*mIMLZLQCaF=`!cCYl z#T48E6yR-j0!#Xr#1gIMP*`RsZnL!q)A#Pu5&dfEc#4yxQzac$jtKF>3^lmW=0?XZ zMdIM{*TPqCIYT#|XCK6OGjZc$e17Cp&$~Y0OEPs0HYJ;zJma9uT{`1m4P9CvBzalG z_k?2?ad;^BM&ZZ1;gcb7gmWBy1`SQEq& zzN^uXt#K&hZ44ng3ewVD3DoenzgS_cBD5=JvxlmI47W}oqeES|V}>!PDJo;)xv{XO z)0^qk+ev3QB#`u+f;f1>5{kUpfQ1i+L&dNSDE~mQ=b6>u+6`NG?o(L*i`86kp#yq5 zvH4m9E6TDXVOKnsXb%u;glbDwZzWMbxz-!Dt9_)qWgbxT&P2)i&o5DP^mhE&WdL?5 z8DzR+Acg+-PV~<|AJ$9?0PCGncE!j{dP-&qty#VZK1bG}%ym)E?7w9L_ra;e;uW#J zXu@6}=?Civ)S7i&(rPcDld&gJ%gh|gQ#_=f-qzARy)JR#x^V7O>xWC_RiRVYo_gzS z!UwZbMb5vkf-BFYeK>G0yS+Ob=Yk0?Iim#|K9$k-WeX{Ncp+;$=pj9Gr-tH7k|Yiv zny`eWVElKUF;{Iz>$Ac*H{+dX=A|6&Z|#82;kwZL=n^iwITS}I^7&f7oYrn%NIHg% z!c9B*EMEXmw;mm?tJJJ= zl?;u}#6gh*amXSK(0*t@D~E^RtyVc07M+7PgSBw$8*RuKkU^+nNIN$h!*Z_@)T^0} zCr@j^X3k4|b?0l(d)!Kq?{!bcV|PUv8{&2agDjlz)jI)fm{LH~c>O$aDxXDd;_pi5 z8k#3am83Vmz(~0`oN+<`$08c>^`glbVXF`OZWfScuYq)Vt+R0B2?5nkEXLp`CXinx zPm5bbJ-z)~<3psdTtMslI6;m@Hr^52qJV3;yFX^o=ukH*89kfDmk98`3$vhlg92OM z%a%MsWAJBayJ+mu94y$VfbAP~;JH9UYBVyAj?OlPaa{lKXy!c{u{ux^`T8O{JB&ry zI2~|*m`NF12h!lzzl6$P97tHP8F!yfD!pFB=UJDHJsJ#!0ctdCJ-<1g$QG&mk%tcc zzWu+}Ynf&sJaf)K~^?8rTG0y;7|5=Tw!W|x*N z!781#dubB5x!We2}=S8Q25DEG}P%UKIe83OFwJ$cw^7H zH)Hzog}9I39ikqNhVb%_ETtrdWe@YF#Rfm{-UM~<=JR5&{LScgVUk#TeKmSo+GDm0 z*Wp~yr|RJSc)qJ2%u)}>nKA;D`Kk)7QzFSO%$l<9yk=_c3V3Xr1cnWn&%z_^DQ$Q> zEje54JF?$NGs*Ck!5`t(Ho zBzjymhfY&3>Cui_x_$Dy*wtzqjz438nL4VFr;&q4-WwxuHrF|ia@t)TM6vw~*%G(s zxF{?IO}FZB_Mko4f7yW2;qOINZ8=z0_O0hxwqI!~omU-4FXKeey5KS@Umb$c!}TC~ zPB{&GA4K6@4Z@|T4JhR+VsB3qIBuy#xr1h+a+VQTM!WJG#R*WF@`lZ+UPNO)zQbF} zUSKqX@3b#Iqfd#hl9@(X*mll=!isS4o1>xm!F%UD#S4gEATsXyPP zZ|Y|PTYr||Po?Sj>j&qI4Lu3hKYe14j-{~?TO3I4U>ufcl(Ru}1ziP>IFjcO?c(~D z0exL**P48GCyMKAL!Z%;>fMs@`7d$#@>ulc`k&K@=fLONch>aXh8^QG*O|sx3{G6g zZ%K`4RyYwyDC>i4Q2|MpyOO7#vrv?%Prtqtq0&lIxU8W-V@!nD7|&<Ii}`*0exHTtnV|`H4ee>uhEN<6X(66D^&*z1 zspIiEJTJJk8OIL|Mti=e^7=O#{@J#%>8Ua7Tgyn!Zuy1YCpDp9qyx2EZ0yla^g3US z?U@5m-kRU(N)4!Q-~BvqvOn0qX{RO97&6e$5v#O@ukFJtbnR?>bOnT^!G}?k(EER#0_a1Nz<<*17r{yDpr~n#-r$!l)&M3kWH#kGGU6G~*&cF@+JlE{F zE3R010(2I?VUK?==9yFP@qUvRh!lLJm)})Uxt*(I?cyvfyyJ%6jT$gqXD?-P-H~sD zBQsLw`~Hd$+;mt0E?v*T^$MCeyHXp*{LQ4DGYzR*#S~<@4%Y2Y6}jjym1L=2#Ig6M z_0)=&nspTDmPpfNH;D%FJP1RdHWsobjTx@6qv>29c-Q|S6K}tYrEU)Rc8fl!Z!MrD zXPoJ*dp^4!?;{;t@|65Dc1zNhzCsPI1N^{u*UE+U)M}kb-`)-vXDOZIJI4<8c%%&* zd&r&~Q)94T&O$a#kI$`ke(0y64}}F>YuD^d_2eWRa)5J&?>{ArX%8fJytc8bB7E*+ z1|4_or41@IG-C1(@!Bv|oVIloe0|cF&AjPIik@+3JM)le*M`$Dn7?C3RIOo_B28M? z8iUH-x$J98HlFgc##$qu=XE}vW;i&}=d>B@Sb;WP_n8R4_sX!`FemzZCk`$9b&L8; z*oX7C$zi|KI>1)(EK41p8|!DrDw{9iwNIn44S2q=LMBbP=}b2=eh5=_)v3~YeUI17 zXr(4OX~&}fnf;=abG{(Zc*JfW{Ex*r1kpXkE`0Ua2_F3Pmf9_TMUTD=kz{eL+VUsE zaK&78m>(&iLEaJQ5!B5F=4g`2uviS5@?K=yXBi&JeGg@Js&L3;51p(trA|c+7}Ja2 zxmLZRxkc+Gedmr&`4jtcf3C)SXZlheh7X5K5w{rB;2Q^9bR5ci z!Z<_nPTPl}vn|0Yp`B`YzP#h!Y_ZwaZMZp17q8f;f!`FaYp}N>uc$Z7R;CZvJqcmL z>IH17g#!g~4O>LT@Y2PT)k$C$jeQ%9U`&&|RQXO!Pw&y)tO)g7JN%_&F8iA7Pi4ot zklCBTy#WqVoA??kjB%3ueXNLI{dqsLQ_KXB4s>1|i$|997VTBxIdoTIu+#kmvmO_Q zdVF`fRICP{&&1LFk7m@rvzxUpb|u}jTX4&*2KK|pn!YdGiADOBVyUMlQ{p2Kd@3!OP34QU@YE`f)aH0^E z4Y=ajUeV_%4A#HVfoJzK*xnJ$32A z>2kUsF^^uYYY?uUXhi>dBhGg>h2YUjbV`0|PhD!g>V|Ol7;LnB%g*L4CClPg+=;Y^v#EZZ0locb3f6xwV#|M1@R+MMj5~f3E=u0_^ewJed2Y=1C`?%PkXZ*`#h5rd zoMf#JsoLjh-3=#F4$o%=-mlTigX^;V^x?66J*i0JsaR#WxFGNx%#eIz+k$P_%nAH< z&zV$;oeNpPvL;-ZIliZFSrdDn^j)0EY`n8@Rtnd3t}DXWM(&xi=bSXt8v1bWr+9Uo zGP>-QfbTLhcHqC$FxFoK7W`Yoc1`0RE3W0+Wthu~#^j(eXLKs?Tf;iP4Eht{NDq`| zvLtUusqql*eN#`A47;p_vbp0xHMJMh`Ol69?u|l=gf5Z#jeU4ELl!61>wqk0xP5pO z%{9!XOx^A>3bIGyjEg#86`Vn8oFx*`=esbG_v(RP*I*sLW%uSRzVMD{oRG9%Brsn{ z75ZJ+-R%sKJfC_*<_l8ZJ4E7jC=)Y&4#k3Kb;vvALRGaJF%?>bct=2%+qR?ChHmDc zqDgChM59T|JCPO7E31%s4^?+n;hEwddcMJgrtpljO3qL7I{ktYeb!52|CM0Civ>8~ zi6)GD;>>e&H{hZaE3w?ei`Xi!inFH+U}mZ&P2f7Wwv9W)*RMZErwQ|MkFGw*RB~V2 zoOeBShLlEgR>TjS+Mo&7tZQ)7R%@)+6u_wAw$i}gyQsRivG~LkBf8#a9~yt)9P`l~ z)Iw1-jAe^sjkoh`NgbT+#q;A1M$u7kOOnLCVRuyf;PH#Y`24njeb}H*y;Y*{{VgNt zPEi8UqI7n0VIZqsK9%lQci~BqIrO>XD0OS%f1}&Z62U}e4E2#f*<5e7o%fub=b|x8 zvA5_8*Il1F8;y7RePAOh!|=cv1xy{onIy9k>E*4yq;{znXeT&I&G+&>fA<2({NJu* zSG)D376Qu%(-=Il(ExhK$8;LY08q&|8<5=lz z0ez+3(u^rD=)YI8l39C7r2FpgzH7+=InkH1_rcs-<7yZq1 zV!mtoQn&5~)I}wbUA+$%$*T4AIoG;!Xic^OEt_o)e*DHaE~b*&<}Z=>U$}&WzW8I_ z2L5{qGReeh2n{|tKs0gpDM)%PME!9$|1z&)FYiqx86k_fVfw4U!| zV#^aHXRn*0+?QEk|4*46ZYjno#!5K+$WD>7!hTHNC4(p4>A+2{=~`~hHK;4hSnl=9 zsE{%O&%V^*{JISC+2BBdueyZK{M6}O{VMeA=1i^Ca!{cd$&LfRK@49^fBg6k-`5qC zHGHIDbM(}$nA;_x_~B@a@b*xBdT=Kk`_^@{iFR6K?iY<) zx4jpo=&wNa>{ht`UKRFk4r?+VzG!_3_d{;dAcQDG#;JY!nWox|B>*6?(N zk5pZwlF~l6i$&MBbKQ$J{u!kPr!U3PWOZBm?D&z%olrp8(}N)VP#|;D5=-?K?Iqx>cCs@&H{sDXd30T-20FhJ>8uCmCMnCn>ux7$ zZeb0n2L(&geJXbFw-kE74vbf&S{| zC}>rMVOF=Gp5OeZkI7-;Y5Q>X1p}_z(1u6%xh{IpTr!V7&r)q(;d-B4c%R=jj%zqm zzm|3QTKSX6sMmgM9McAO59q=J;We}yF$l--8`kv~<#dZ{3;S3#2p5zaQ{894kE6|? zY@-rQ-ZdHbjWmMce_Zj{prdf@+G|!@vYZxqwxUY?VDRD@odZfA^Y?*^WZ|D|ydU6# zVl?eqXqKsS$XaIe!RBNZIfM+nc)o3YLbB{=<0AM8_NDT-K|4<;&VJ@sLhDsaYzBV7ud z1pg!Htiz)2o;I$OfOIS^jevBhpzz%l15~gT5$py5u~1REtVgj01+fcb2?g9UGi!Hu zD;6L~h+^=bAMbza^@z{4aORwux$nI()C}!HtL;i2b z6S{e5twe~ozyo>{z&=l%74#^@!l&Ij>%*JSd}JA2@Nb(wSQMPa1CN5Re3SwBrAsl) zzZFzOIx?>$EwZ^6jUSrL!SApllv$*9)`V%J=hFQ}KQN1HU*-J#em8hced_$UVr)Ae zT;`8U+O>c#OYz(GRxtCJ6 z>FN`bUYaR!j@QTO^FqMzPPy!;dMR$b)(u_TPYG9_yurtrvG|?quM!XLhmoN}AtAYv z6+}q!fkG>UI(B8D#m-zKkb)zs$BO-5J;&%KUrbvmf`SuoP%S(b?@g#>UpVj7@Z~G& zyHr6kyDsZlL3>a>#B;Gr7*ni7U= zyeat1@W90Zd$>;OJ#+4|fG++0h~usL!9PB$40FFl$yy$gM;mwI;9YK5yhaDg*KZ<+ z7oPNLMK5-Lo)rK6YXa*nQ^j*0+mf2c5}Y(j1LoM~<1zE@ojXwF`T3+amov~tS;6(9 z3cPw|B>pVcgO64(_)k*Pb#^=X9B$zHzyE0- z2JYmV`A0X&Z}SGpzsgTIAu%1xRgFQ%?gRw<_`+zj1IzpBLht!(u;R^3wrvQ1`#lN!Oq@6~E8Y?(ip^gIA#A)gFV1MhSm=Lal>W=)pi;lvJ*zV9UK8{s)FuKM6 zKX!H<34begq5fSPJb8ih{kCtX@~$p)Nh5+SOYoErpZkQmCa;rt%;|yMG{(b-pzf^8 zA1Tj^Q9+X_sX};hK05d6fTIQmP{`kJAGy9_X@>!fh}=Po-?~uClJ>v@)1;^}s|mK; z)t0q@7PV^3@6Px17vw?z~bu7^m~~Zxv$rO-o1k4 zBNxAW3^WOjS zVkk^=|H#i`7JGLtgr+F{K*#sG&<~{e@Iw>)m-twyAO8f~v#oJ?fgwyBs?D`DYw^E{ z#_*Z5cG=FGw7;WCy!3erihJwfw5eLK=tCyC549y*4riI9y@Fb3*M_iSF=r>vkSHE5p;WQ8y-)wffYTJam!o&InDEDCqKH; zpzUd>zM-2iutG$)KV;#_4K3{6oaK1OU$OIk4=-OwZ;n{fFSpSeuw=xqL})mQhaqp1!X#?g{FaTaiaEuP6pSvaNe)S2E*S==U9Te6ulb0L-f@y zEO)*Og;aB&&Z+U@yO}T0?Xpj2E=+^fTU^X@Nm^&uGS^?tw0iy;>e*$VSUoxwhd#8x zjA=aEk-uBdHa2pWmq^&R@)~Tl6+yo+^*`wc<9Ns2E|H^TKfi-b!f3s7?E6GU@Pbw}4~4B(kZMce~*VQYxoHSRraKJ`vw z@XnmPhsby)M-K=uk>ZllMkqH@67OqPqd}3wJKq2?-V@Mb0PE}{JR@T1qWB{!zv%}i z3cE1xq${=`(}C5xc@$^lNyTS-u{8d7;b$QC+6{NU#16~Zxv8!tVF4F~PeXqgCn4hG3}9B$C}i5n!u^OHlY({a}pWB8)EmE0$BUgeK}!bIH? zSef>@b1te|=RucFr(xWid2Gqa*Z6AeV9qlaLC|}1+Lm_;xAUBr*-898Fv_1hzk9H> zaw+nZHq>Ocg6Yp=;IX+oB<)|wivBVx^>?N%$47v(C?9L@S)=Y#T}bP~b2i6torGZ& zqmN$ly@@<`Abh=KlD8BOM>W8Q$lYwjdnp#bQ^G`>RAK0^d|d4Q7bbB2*qBk3ICtIv z?CNL;72!>kJ~fBF+!!oOnkdESjSXx1I%7)to? z12cSm!JVIL^TW@n{}4Y(SmO?ytL2BIS7`&wlA^}V1~@%_X5gCqBJ3Vg55-pV#hlek ziw-TtlfV8jNmw-3U%i9q@tk)*ehZafF{P9@I$-Y=ByT$ToEEK#msswtKv&Pnc;lol zyyicvt!)j^ck*FjIM+;;-BZTLeCPgo_B%Y^H=@&*s%JSIHdWOylQUWD?xNu|Zblnc zt>yUz2~uo4-2gY9JrX`wsp1yJp&)(TpA|E0`nP@!dh_pND%Uc=5MA6D&NX!oS>!mH zd#rwbX1!!*;lYI;Oc-mzF7n#)#AG#IDm8^|&sCw|<_324z$CV%Ya|UXXv5_Fws7RA z3J&Bo;rb-5p$c**mBduMb-0^g+=J^yO?gl1+swXoTYg zi<5hf^%YC;aco0pO<1zUh5Uc5#-iQh#THzHx!S|KbFX@Fzd1cl*oPLYZK2AsnKnJl zq3<@u;$9C@@uiUkF3Z-0t-P*=nl{40F(N^E(-m-XG5~Fx0@iD1KGyv*#1Uuopunz# zhL!o!s;-+^j_f1S&b1g(We8c(QapLM0UUZP63+IiMwsu*`JYB`cV38m?8$f368TQ@ zpPB_JD9JD*y9W$C&g)o51B}y962Ew$M#qYWaSyC1R6ch^)w5ecyYUI@pAbj$uYbgt z!~G#9DoAem>^j}caF^70?!vQcT=C!~9XOrDGn+UQ#(B6aoAdPy_WAP-8uv{RAKu)H z?yp*f7s~Zu?QduDy|f0~8@h^L<>lkSMm4N+(Febn-DFyAL=oCH&|B>s9v6?qka_y> z{KRJRI?Z>Nx9x=)R{juPwS+xwwP6AGUFhkKBy8AvgPqdrMYERVVsEj#c;>lt2>e}I zCKkcm${=~&>T9&kVT0s5*LTb2q!f(5c$I2dNWp5CB>WJim0{0R=6Sp zdRgvBbxTIT&V%_FrD}~G=A2_3ua2`X^#6g~*&UeE12eH&4YQv(< zy&>I~bE>~QrO_>YCHr!A;)#)ck%MbsK&cd^;(E9}d}g3Rk769(R0l~aG2-)QxmHDW z8BX8W!A4Gs#^(>-fF9q|Vb`rx=4eV6gLGj5|C(<6Yubt8B}R+SqF!7SE>h)LtET_+ zRn^0c9fyS#{MXuh6j9Qy4`1uv;qOb~SUSiErYsJF#-$&b=w~)tJ2i}C(1u>z3;jrm zYh#YpgVWH*!k7!{n0$9AoQM-xj#Qhb56(q}!N%|{I~B+5(7_@9X~C{FS@bI1n)W+= zVR6$dV5fN#OII;w+S%Il$TA6UpXGbKZ5s4-covS_YQg~%5#hsh47}CEI(DqUoqN0D?@gMVKd^y5 zW>}Ku0Y$jvsE;-w17Pf>cbA-O03H3Vx`cD1Ib*iN$;e>Bw`FcdJ{_sl;NOR$vP*H=1ZlMmG6v*(+8a zn1+w1nPZnS&Wc%5ip%5bI(vtE4OiiJjvh>XRlvGHFS0VpMeP7$D&Ykfw$cFS|I>qO zVI>qc&YPZ>=CN}|pYi;THE1g0`g5~Voc^#DUT<0?M5k%UZG5M49lj%Md|!pGkzSp> z!_hk-^4b4hQ>e~6$-%N7RJ8m&9z9?Q_s5swzK&Y(8>A!-cULF>vB5aP))Zv#y)d+E z0W9&YVclI8(y~V%aPQIpc*OM~YfY|_i;ug+>@uHMRP@3>_jTaNgw1s3p*w}Fc47AC zrT9y)7PNe(iXZ5R&^2x%q^fjbBlh*8nj1OjZKfbr?plC}zq@tTgj+rK(9kwR@)>Fa zT^rBg4(~7wF3^XPpl#$R_NH2WN8!)0zL44y&*rCCGpkE(bh#u6C+)q(G&yhNr(zCn z|K=u6Z$F1xH?8rgzX)uO2gwhYU7=UcIL|r07R$z^;jE1&oKLZxM#k`LAmy&&?35Gm z-?VpZZny*M>*`87rmVpH2{YMf?gQ5B8PwTdBu(o;XKFlHITe zQtj1~9DGN>?LYZ=tBVzGbJl~EX16HQb0$5F+RP3PQ|BC9AFlsuk}XGP+WLAaZpdj7 zejO-4YwurhdcFZHxl@H+2gTTWo4@g_ZqejEGwDFAqo5eBP0v(kVvdppEYMv@mV?_c zt)&lK1bGb6FRQku>jR8wUSp z2m@}G;=@n1u(JKJu=5A^jwlU=sb&4yh8k^p?4N_d{>Grn*&8okYonV?3l5CUrJDb2 zNk65Y1uUA@SoB zD)`Wb?jP*odVvyVb#sNET7FF3TtuUHq~U}`P0YPsgMQD?#BSY+g~xqXV)^4PxacU) z$B}I!y(nv1-c<#z^!$VlW(!bBV$64K2jI+(fk5-mu}f=RY1ro#7(H-;_{E18m@jq5 zNfSiiTV_FPF6_m13U)BBZwvkN%%-2d#o}GJ(@^6E=ks*Y0&(C~IJ}VWf%%>OBG-k6 zjmtr&7sNDmcH^;o`e?C0AL6ESp2-`o;YiD4L%7dQ$@ekEP1-DJ?)L@FUDseonh4@f zx=~7NE-Kz0#fEfLVJhcwPd+Y!C!a#(BFQT{S@~A7+rW}~&#%UyQrifZj!eRyKu-#XFR}t;;qR$X_RO!ayKR~{F<1{L9vB7j!M|jeAM_-xd0dAt`X~4uEWrDLd_T>(+!bMk zG^xsvd;@GjO~u!9EBzO`@%5YSf)G7nqB03$mZ9}v3<-f zcDai)WjxKqf5%+K8x1S*)I=+s$Lm|6lxNo}U8aJ<^^%gRIu!j%#UbXVFsIix+8^gh z2M2Zt&ljHns{^l@mW2cR#Am-oH&)=c*4b>$Hz(?OJrhTkM2L@_e}jQXB-{rif~=#K zw0!hQv~RS59=58eo9zxT&y*E81I28&C-K)XC|Os4Mc$T}8LI~eN8X~XYp2tIew*3H z4t0Ff#~UsLH_ODg3b6U>4~U2~0AXo0Za*a8F>Miyo^*>sw@;_kVUB`%yf%5gnuc>f znM2x;MYLmf8$KT42NHgkBRK>7?clzWP&NMfckPX8d$d8WVn(GFi*Z_77dVm|gH>O7 zp3W2vSiw0(;VP!I*GeBQ4d-+IMUUvnpg4)roJvd(BC-639>}>qIoeeMjWJOyxuO>} zcx7Ywhl}U+Lf_+X@i@G%Yy=aFM!_7nkL-VWMt3KSqAd|^_`+HQXCqYc#Ge5$ytp4b zS;=*h9ohJ9hlNn)qeJ(GX5)iUW7sZAL;WXO_+^h47}Vwxf1^>O@;5eWR0XI+)-j%8 z#9s7vrDC9nt6DDPJrYIf-f-8_^r`CKo^ zKj_E4AMvDt+N<&AKUKkUh=|^=PDRs6O}t0eq``MGu;=PxVdG^EPF3!L7kKYkC(0we z`BpScM+L&%xZcFp3D%$6D?2E6re&UsvHH4$xc8w?_Qx6|$GxD=zJARM z4UFC63*w3p+4)2lN-bWB+m4PC_cMQqJ4J5XgCK$~ftFO*xEFIr*hBlIW}01)NnOV7 z6{`#BSfX!+3wUm$vGG+HeMK97H|4Xgw*231$wZDTU>W;&qryjhtbC^rQ@u;*m4he6 z1?4gS-a+z35s!HN+AKMG=L@c|S%X@aMR32P1Re|RY)q;Ho1fQ-+%vaiO> z3=i}^D}vyIA##(Lm*hP1t>l>0lK!5l#?; ze}~ZLP66gyb;HtQ-1p~Gg(@3EaS(sU?j5>=QonnXsLn~4?%D^+Ce35T4=owo^rUS| zS7Pr|ciD=2uJn6xHl7;mDX!72#0NKebb6x0Z*pJN?2F`w=`Ai&7ju?~2&UBp$$KPUq|))1 zC0~|X(LpT1CyQ)hj)gidZ+7q83A#v~d4B9d90a?BL!}qMWvB_vkIQBH;Xu24+R^*# zVbIfSH-2By10Qjp$@b)1bpG{JdSI}bo$cA3do(>e&-hmb7fKkk2v1eC3Td{xaq^cI z=(gMdc6y%2k>>*uri$S8wp(QMYbrhD^)2{G1a-_>i;otU$okCFCgY4L*m2k#=H)J- z_BH$-m->Su=a}i0JfIK1`bg52?!u#5zUX^a8`kGWQFn{=*chlGGp+jb|sT8)FIir zrMR%G8B7|>IYMq(_#)6v=yqrZ>3?a%Q!0*d`l|}AeA5f=J?+PCcz9Aif0uV%sw#K~ z8_^i^RQ~pBW`jp*Q$j!{KJC9>=$V#;p?Uvc-Fr<4G|r<)V@uMxqYT+x12$~!2g*FL zT=IU5BK`{P*?IOIUU|`jwj^A?+D+WLQirU@WZ|shV6mCbXI#}fud@ye);kDBM+bD) zffF?v_-3^?>|7HfJ38+rI<9r;Jo_1(Im2SIu;1%!aYutCWd-iVLFes3-6BZ-VEF@b zH0df?P@j%r`%Q6B5!ZO!z6QIdX+dpk0Xx3VnN0Z(>!=9W+{8WTwO9|gaW6#cx)Rd- z<3<(MdF;ZCuh>?TgLglQK(oe$^yQhDZ#05stgc24OE)~Th37prgvcKkJ)?b}-bh-T ztmy5oDzy7#1ryD*uy@!H=vrsN?nUU(sE|ywl)h#0AM!Dv%n`@&o$sU{TPcI{i0-X$ zW676vFt}kT95VeOt4MIA?wVN`+o&Kmp0^vfgev3DhujOmzh7=XnfP+vW_I4B8V{`) zh6DM}`O_)eX-B9B=?!rd?tbLFZ?D;`alR!BO7odC&J342FsE_ubfwP{j2$zZ ztz6TK2843mi$kP%Q{o#Oa4rBpOyqigt_hsmozHWOHUz8+w5CTkC74%d3z-`u6 z^zgA_b{4J_VUd7+S%FZ#9$^WeZQs_&W)CueDk^L!>qHpz;d%g_(R?qg+#*yT+l}%q z7C4jNo1yYsG-lWoy6`uT&0nmI&)4~YcUHTs{zNajXcmuyzqbgJ6L({uk4;dz)c|&J zj!n(*Ow0+g7JpHbq2IRv?BK(J-ZySh(^&p>6di?wT_VXhVGX9apOjg7XjAN~NKE!I zhhbZnk>5f-zpC#C2S*3VGaK)b&A~nrbKv@rCT~1?S{qIzOr)caaxf%SP52kR0Cg*# z!H#$hc(Z#at>)T6RjC2IofITbYQIO)xLAqDmnw`(jlhxX^r8K^GFJBP2diI2u)9m% zn{7xdtdZ@UQ4TTdYgk;Sh~;q(&xn@As6N;X zMstQ3>F~FlshhBV)hv=fYQx{!PLR&`XiCNJD0itu;_yxd-Q`a3a7RBD-s;ZvS4%NH zyqoa)wGqvWO2Mn%Eo^oi=bLF|;w13_q4h%&n!_KM$r<1qc5J3~vn*-vHxH&;tKV++UI{KL5mu!mtSCGaO)~ zUXWbv*ge{Mzl+37m2*I|O|Y70xc9s>naWJpat-G>q3!Dxn7X1n_=e@P*Ou-yyk{1+ z{<^@N*6%@04_!1cHGuEOPSUo`ZnW@D9_x_R;;M-`*z9ctiLNJLIRA|A`q{C-qplR( zmce(FBbf1yYK+|DfE^tV%-LW?Y6s6@yt@?`r*_BmL4fNk|V=)aR5o%{XdCLg%}V=BA7 z#)3t(dD3Bvr5G~#E>k|^KEDM0Joadh@O>}9F%^9n;Ge~8 z3xJ09wx*iIFnE7ihhn+5r+;O$V5+?b4{tZeO}hGUtL+xK9Ezf)FY?%vzuI)m=pf3g zrizazYoOT)H?TBrl?fl*$%Wt7j}Np9``_=zAf@l{?y>>6-_@b7Zk$hLV=eA^Lx$f~ z0`RpZXVij`g z9m&pfeb=hbb)LGEp}7eAM3_OV>Kt0Jpba;@b%NDg+n?X^hWdI+B=^U4 z!!n5@*emyEU%5y7Lg->VQPEAP{bWS5Lsnzgnr3$4KR);M{mnhMnjq`Bg&rR5L1~=p z8?MP&9Dm(l$GFTw_uUgFg=ct7qp2lEaX!)nQ4cyBNO zW-O^z&u?8t49q0 z&aGuPIFChfks9vX=^^-WZE%#CE~r&SvbMVgn9$S{r5kvr{D0fY@4g$k*0?i0wH}zg zJ^~V~RG58@6yJubVbZp2;mX6^Xl4UV)b2cnZR9nim3u^w_<;J;C}v@0!M<=U z#Ma%d;IBW1DI}I+^Kex@H?I&>W>(_86{els$XP{i@Z-8zOyRz#*XGUik>|4{w+O(fI!=7bbkmA=Ht>Cn^R<{0_Gev()!Jv9iP;HDdW}!Q?IO*Nns4 zf8MjkifCoQ=Or1K|f5^;#zBu z+q6$Ll1fW^3V$9>CilBJSfq7Y=Ke~HzTKRF-{Z|dZm^P;<^8~mbpfz%Zjd}V^EQQc z?<3K>mXBc)FTA6#0~6kclc7^4hCEdj(ifND_}p*cWsxL)*x#OPb}UDw09A0ZjK$*< z9>c3S8c?i|PhI?tiLwoW2c^oV@C)g-DP%P(VtTX>+&SgL zd|o)wosbli+M5c8AL!8iUujtR+XyNH(z%DaJKnyj1-`4-)6p7hdex_iJwH+o4@2KD zd9;WPnkvOdL9LvbMCY@mx)hPV5WgPf{>oo->C5~!T=3VKb83R*Eq1R-_m)`VK3EZZ zavtPTx8Ce@KKJ8qZH1=0xq(w|8Iv${6<++^!t#PwhNCD>ovU&PLvqU(??YFg{uvvG6VBc+&l0G^wT}bxhr2#W%4W>m~0H8Nr$2T6)_wb zU&VVKb2NS=Ky}q**_B?UXcF-Qtb4o?w%>n=BXfJAf2$!xgAI86lGLr;d!ZncyP-J7}QeB!Z+D5+0|au_i766Y8uY; z`F$OE!wFwVL=d1kRQ`IzLu$D6n(LhH$-k-!XSLbFM+-Gv_|^|@-#232Ib*=rww^`L-(yy@eB<>k8YJaRi-vUQ;j4R_{x&;pCM zkL!FtC|Z=_5dO}ykIfb$qxRs+J_;CRXaKq*8UB|RjA9={7;V%{F)ln8Ff2>ZJk0yB zR}+e zrhy*Yk3}Vo6#Pcs%$jEB)+D#_`FRkr*M~HS;YV`_UKg zj1WP8*SDB%xd0Uoyk{d+m3bDAHMHxBm_o7??YZ{G_`9{R*Ai*<${xHY41>)sg*c(n z6ytX4!x*khzwl`v>LgDU?+n(**#%y3$fFBOTQ5afSrd$wBnwH4_n_+iI;g5OfS46B zY?q=>=35ZcIn`Ovx`PNFMO~CTRsNkklK;4 zMxFJB|MJ7x#$c|e{gZ~thpwD|I^qM?tRId6Ng^2Y*#{z0W$d~`G`rFeLGM=n#9y(T zhmgqMjJn=%+1;0Y&UfQ~o`zS29zu(jE?xSO+F1vbrlg}}f;z4%;kjlDH_-Z{)>Owc z8J|op2Un+;OkY{VcAH8u&a?^U2h;g~)_OGTaU3RmGJ|hQ(eyrv&n-E-rZ>O4O{c!3 zQ;Wos4{9oyw9W>;-SuN}>!diWl>gm=+`zsS#^iQj1*RsoFsN9KWsPl}b-=T3E6sXi zL6?WA!gTW>`RIi&$?oYgiEE8EE>Cd-{kT)IJ*iSWcAyDt2A2p!^uOZcCo?cQ&lpZC zo8xHT0J!WsS?2qg?|e;~Aur*j@VxCMD)Nl>InNCtC)SpR85ZIkPe+&)5+pA_aFfi% zT_hHpGf`!i5grhr9aosyj z?65L`g5n0W8pM63myMy%{t_tf^_6v3v1b>xJ?QtgG<go-pg0SwENa;Yw>|hU!ya`F^gy4_pxk_W(RWvOcA~`sBi4@r&)v#w%&1aaxl0+R z&&?JR%l6mfVy7wND1{2)#>+|^ci#v-<`}}gH*c}|X*4dJqYE)r-zZ>e7L7>^7T33* z0Il(NSV@jO+t*i$`YRfs=g6-zq0pJ!h9{xly@}$nC*R`is6Kd!=ML<&dWUPxV^GE8 z1N;3}4TqWA!=0&SOf^o5L=9ki##)fxz6bYSn8EZ>d2GfAq#fE8v}9};C_5ElVFrJP z@OjRQ@j4W?su*`POcCdK>f`1C9=!f`$ig$FnD?fE@BCK_aToBs0#7Qr!gzH4*dHji?>Yorc>O1nv$Up zPJQCgZ}bD`Q=kFk5_Z$vk4BUgWds^2JbTOf1{FPtk=%Q69?Po7VH@xD`ri3~$3(;M zHlIPI^4ZwL=qfhg{ah9{IFda1+&)m>96tT0f*Wso!`BCWnC$`&IuXyc+@~xB_dmL{ zCNCAIR~W+yNXHMG)H>h!yWI-te}1Q-J(Xe6t#Y{V=^2aeD`IcCmPVA>0Gs>J`GZUJ z=+@r_c&?i{4C%jsu9UT*%?ej2vJ8^H=GvzUJF(=CYBvm*T7!4jeypHUimYcNByP(M zOk8eEt@34f0GgT3=ww_v<_8Q3&;m29?UZuPg0%G2;FBBoL{~nijf<8^o;ny{$Xrht zw6shn-^lgA4GoZGRU(AaSF~9*9mB{Ngi})dXwnGYU0w?RWxYbhEW6J4e9c8W`p~uq z=Y=@Irhp*%%oo>b-_H)QNqZ)?-4o#s&JuA-;C|ID*;trTB}}`14PGa8>)ZqGs&S`8 z?rZqp9N;w3KDy7nQH9JZ2BhjkZU9?mPI6+o?Ziuej*Dvp6$#?6amXDDC(n zJ13W7`e!AyY|Rqxx9-8e4qfrdbOXp9bcTxkd(f5FK9Dq!;oR~e7;w`NR=o0ro;Pum2za9>`k7nOEvv70|B|LGzT=?u*g}v8`u-^hhI34{BM?GAMw%#W2GOGl( zjladp-r6%yevUpG)k9J2S6TWdSMvR|3a1T^635?vi=GF3G1o-|ZId17QowOE+1e8x zbXUXuDmJiWuqpGrF2(T0^wjmtes?8Bn~CVmr@>%0r3m%IP4Fbo zJO03QX~y|t+)y%2?0QHa>o&TuT^U{}?v2-iL~!AXvfM9q z4fUQmLFm_|6lYa(9nNw!@rGX76c;xN`#77ysFu|{+oc)n-w50bz*$)Hu2GV0Z;69! zH?Ft#z%R;NTRUJPH7`iP*N0SvS$EE04=4UkfE4kd9bR;iGf}^s(1WFZJ;^sM3$+rJ z#I?)fu=l!qAYY>aJ67%?mTN>lX2!61Q;@u4*)?LxF_PJ%WLTFn7Pq(Rb5?j2l&7|_ zi=oEs^0yCoi)YOz^UP`gCNC%&aE>M892T%@Dy1E6#~#oF0!}HT)kY6+ThN=0;rgj4 zuQVL~#Y!mqt4q3(DJV-ahO!^&cy^C!=Nta#w+$4#!;(@0npqZVN+Mt3=Y2Lfznbeb8g*&++O<4e!4SIgJ*v-JiAL9!rLRLmHT`iDU}I6y`MnEMNN3w^B@bccBi#jt8rUKhP^em+#$i;1mO}FXg(sysI=|&L+vV)8BFBpe($VY690HCsPs6&6)7o zK>Ts(3Aj7)J(I7oWu{H8boOWxnpKCf->T>FlAAqx6d1y+zMSoU_8gA)wTH~9>Uc!r z3#ZQ*v-aJkxXerujko?}HW&Nwj!r73%3?Bm0k|N9= zXWV(G7k|(tlVY9~n>0;qxr&wM2>gZE%wq&waa>q6@6$@J`HDmFrQp_cRKN3E)ZlL2Ysi#(_9Wkd>2 zNYI6~l|5;1VJ3QV-$(PEI2_x0r?V#X`%*|_b{SDmK1VI#HR0R+E0k{>BXN5q!{(SV z_(;S#fj_Hw)@UmW*=fuc^{7FweM7K*tO)L$&>-pLOw`&OAS`I~gpudU*;B3Ata#=$ zdQkQY^NcMakF)pA1iOOmb01b$$QiBolW@>c3!!SQ0d0*<#X;XpVfK8UOY@80(;C{a zqGthxcX6f9g-Y-xz8o5L9%WM@X`)0D$&@yRn0{2Lb}FWz>ARJ=OG z7kU3}IoJ?uj%dRy?@4r>v#|dBvPts#QWI)j;2eV*6UgCvs>429 zLpjY*Jnhp7I1%ucSzNSb+Lv6pZhbjA4hmzrKIic~*>c^0A=E25k_Y$YE;?Zk&RoMb zcAYy^tu$ncACAHdvu?2R-UL?lRYV5=rJ=$6FHG5{2$QDSqKz@nlNfM|ewoZ5=h7IK zzfv8iJ9xvzRbOPc9u@K$^9KTo4InI9N)dKuG<>ix#6=+P@fd_3xCYYXvImr28pfPj zjk&j17d@i-f%EPovZSI?96PQn>Q5;bcCM>JbFPul9%l$=t~cN<>&09{ZUTve8i{qu zpx}aF{*EnyVx_CBOSC*gs@;_7EyoBF{EMT>YY;pv|A z{@hUcG(`sXEz zjrEm0z&)56?}l1)IaAKnihzTJ7omp>_{l7Ge& ze9a8(|KmPlYajcKH~yYjHJLuP_*uIHz=~i6(__ z%)oc|0|bxPu3)Zonkmno%2WoU9%=}@h|qyrX2n?-(}K1hV0v}AX>xufDL`d z$hOAmlUL4M+!bRE(K;!(y0{TWjJ*nfZZD!!eShMK37%X>5G238C8#N;e)<&EVdR@H14Fy=gg_KSshILgXG=PA5oLhQc2+g z8}#ho4;sTS$&3!w;{91s=(F7z-hJK&&rN(_#OhM^@uL;qSnda6|CusTwHkT^4uS*f ze(b^p18Tdl7Ny4AZ!$kfzNPsR-GA~=T$r4V*6$23)k_EZrcL7d>Q%VGw@lcY`Up&- z)#3E^{j7>pS7Umt!WW(wSzx>?Exwq8S#7<=Wf?^nmBT&PD-0kpxCMXuWZ`^f3M!+f zka2km#!WO7FF$(%Y`yvXli%saEp8-VvjWSuk6_jBoXG!YCQckNRlIcQd6e+ny8oT) zfXR;3+Hn@u>g~a|O${BiydbcfG3)cwi4M$Jgk^IM2y@+!LEb+VDDDx?o^KYBeoHC_ z-u%ouT#7J5&lZ>Q-Ik5hE!vPZoibL$ut~qV>9lD=h`5D&d2&@QvCtMf)^4nU0}pyZuL-?n zw(%}x<-ZsMyH64iR(g*+Jv}@10Hbpp`OnBvocPKSE?)gX7nWvGPU|soq+AUjoHd8j zdrX=4p!@KZzk|#_Z({Xb&QaNH9cr64kl#UjabTzj3%RzzYFP<=7J1OyRg0OnhaSa* z7NVxXH1WQ29sF5j2aET%%f!Ae^nG3y=W_O8g$Ecei1ETVe5cc%Kb8S6s16+&mxUAVHF?!$FhrUK^X?+cz&KZbX=kl3e@LYP-<1fm_+Je(>-nVUb>b$Qx0vEx16DjK zicZskvs z->w0sLwN6h{Q+5=S|VAUBf{rGFPOKlLU!D(4)492gbpW-;gQb)_@m+j|MJRMOLtQ= z72LrxBtmwoNF9SF41{$G{;We$ha3#DFrY&ZjvM8mN2mdA;eN@j=9y$_QQ4-=K=&;Rf)N?=|p9AAM+V;rE{Z8e;4=LUZN8L&PNa(ue zIK0@a43ZHOSY;MA#_kKJN?U@ZZ>A)owb#0*QdQWB+?LFj~Kw;+7b#?cBhll#cXV_9xXQ9gQIRt z6@NY19lPE#hx(J>WzEmsNQZ0T4oCU3?0pR5uX$jvYlh(1IFFSwy_Sj>V@^O&dPVo}e>h+O?Tq(pp$6e6(nl31s zOr~igm*Y_T?m~pV7gf$*jm)hV$@3v>+6tSv!PfI)o|GM5;2WEtEJ)2b~I_2lG zk_5z$nxnA$07LLObq+3n`@-A)!@gE z6m0)q52v%V;Pk`-8pZwIxAtm47v6Wz*1S(*VTnYxg=Z~J^Mx<97i2@%yHV)lEbMks zxw;^-4i{@g;NJDdAT{0(mE$~NykaS9UTBI6Q(PgoI6`*OMjacLOZcwek7-SJrk8ut zF)iIwm=UByzYH@`Sy3O_&JUJXKD)%3V_hZ3Gjh-_hwJvMbRfHk_h^;NFgdhBsC@ny zy4R?{H@gGua~5aEJzk15?;>kAaUkcK)!4ejP26I%7rUf&L(>I3BcAik(kEu%F6iUoRQ%{$hz{ z#fC6)sSb7Jy;hB>Vc^fj&g5lNfzz#eLcG5k%0qiW5^@~{*ZVE6iO27K4htW1j>DTk zB`{H($YK(Vsm&|}e^-8G5mh?0e<#;h=l>Nhwin@EC9BT&|2@tUx#BvRHtWZ*XG)s5 zs@@&K+UsQ9IS2TuW<0+A*hOq6EkeJ(KVa>Bp1ySrCKg!ANZWXqR0foE;h)XIJ=Ru zLniu6^JAwkGHe~{j?sq z72(w9y>MT5J=nN>8jUDlju$L7g@~0FxY8^Fp04e}95wk4^neGm~c{6uu6+!V1gv*`vbAbUJGdigw1y zHa<3>;LS5IWv~S-TbYWQ<#lj9?;5Pb6|}1SCvJ=Lg*!`Bv8%OFr#ASfdN>V_<$JMU zJK+xB8`yHD?vuj*U`du-&&0HblAeoLDJSZm>q53EtqYI7{|myc)jn z4FuwQ4W-qFG~+-{XD?8(HCR59_W}WC3X*jRuY1mwXnY#lJ6bAAC871Z-}mqTNP3@p&pqe) zd_1ceS6`3imu_v_gncm=xea?BLiR8jnD(NGGj8Nj3#vsh@N1Otze3^jXs?|o^D&{` zLR_=;cSES>QO57ytHiwzGsHE!=fM2AgUDp2Uz(gIhfO!PaUqi7xb|&}mhTxFqITszUsnL$p_F7|nPr z0j>ObSiS8EIWbL(9G(zNM;^&Qlm4~*y+6!L9^DJBXVgSW7qn>JzYx6CWdPMSNhr9% ze0+hd|8R(>abNoIU%N9LNteT`BiLDf*^LZ|okO3nbH3@UDK{+GhGupo<6;#Bn6f7k z!>T{RHKGDFPma)RmZ`U8i!uz`y?8X7<(x>Tqy;TFl7Rb5?YLW01k~I$9eYpd zK;r(1joWRSX|9c=*Ivs^T+_t*&o-9(c`lUZ21R0LbS;Nf%^+kMZn2RE$laMN#}K}Q z>Q`Tqr!|6_tH$Cob6b(RS^;*QlE#{LEvSH3*q0fGV4@7|N6J8}>7MwVo*G((N6&tT z)5q`fvo4#{Z$B90j1Lx71CN(QhT=QgQ=<*nUkSsOCr?T7F$LUmb0p~Y>W~)mYUbtd zf$(WIoG9QS3^`;Bi&fHzs6t3b`NU%h)A3}P6yVBvMrcu_35Vit(SLgLsYUy0@}IFL zTB?i!^O{~>f$jLzP1yIjn#u*)9!GNfD;#grg7ZTus-<|~?g0U4+1bJ02Oi=(chLeZ zG-opq`^9JYnQGN|r|~;vR#kJiCfB3ycO?w`tOXn7zTv{>t5LB~2p`RU(xt9RbY$2h z(G>S`n0dQiJc|ej=)U7FpSzLW`=Ku2u|u8Q8&Zw0?#iHqygS#--a0k!a&U3o z2eSW|f1}~LD|FjZH?NmNkF#73bA0Qd0oy!NY5vX~s1{?!HL=VW-I#9>^JFJcT3?Nw zsn!{IvmdxHp6^vWsv%O8IPt+MQNc9kj`2-RoO<)d=-!l>@%bK@EhFJ@Nckv z{thkB1FxB~9HN73Xly_~Rt_Bwt7K%ct-}<4KX4|}VO3bi=G#AR=X-9mXL%5BH{tkk z`tW*48s4uSj58K7{aA7#oi@da>P(Y|AioRXwem7KeME~$&Rk4S4P@d2lSqE&NyZ9r z{SN!x)kNin0{Y!;A-b9w!k4xreDeGwSQy=a`3JYsWDcrSex%DvPDU8!PN^V(Y6 zt3S)yOxLbY!_!6;PwVk+~{sQXIlZu6_bYQAiCT0|< zVQQ5c*vF;P;m5b*N{6T1zRpI7RqP~ZSMMd3mQ{GLts9T zd{-!i+q<>k)0j5=&twe-*(pQb=`!%0(n|J)nUa^YtMF`JH$(;AhI`G|U@HHVaATRKCU7Vyeo-d@aaA}?_A9*FWX+9;eh8NY%*XR9 zjYO;J(Z5?_F~_l!ygX2V$DF_RoIu>4U^QWIkRhZcxt#JPMo6!u6MuT zvEo%YlcVdh1Cl-j2>CcQUH5XlXZORJU`+ z*>7-kpgDdHW_g;IS*?95LA4@F=6{#R#}^s<$5fAmo?J+aSg%#FyP4asatBz03rVRv z$kQ52S`xbjb#%^?@f!-UEl?ddvi#G6BJalMi8pBan7v*bf2raD9U<(n>Ek1(l*7FG zkBq=-LdH(Brd6vG@D;j{Nn-$&zFDw*ZUI!!Qo@5BZV+-@o77oUk1_awook^4^^!K<9tDJ829y+r}*< zk+|5W8EpHN!EAmdRn0S^!=%jNlf)I=H82IWnReYOp%#v9eZiPF078XY=aGa>3XJZ z^XZ1mZ&gL9GX=C@QV{yFJhfSym@oDA2l#mL1}s!bq=BpZvH8wuD30=Od=PMhmUw%3 zW&6pY!Ur{YuI)ztT@IvM2PNUG>BG3-UDfDv^($zvJt|5$Vo$3MC!>Uq5;#jFp~~p@ z@V!|D`fe7|qKQV-H;^%%7;o0q{|2=xi14ynql}N)=i*ZJX@1>b3mUpS9@j1yTz_cx zXN>&Lyoao=hv^i-(lkr3JXcB1W=7Fn2b1wuP8s2gWHCA42^6~=37lbB6CaXrt$_>o zG+03WnfCblI2{o3#hF3CGxYXQSF#CD%IC>6M_m*(LqXlr`yeCnX8Q5QBx&^fY>y;>(6#v z{K!G{!MzM7{kctE_nDB2sZ9UL^gmJ_clmWgtmsM2tvEd@RMaC!@N=d<`s@?Hjbt18 zbM*xb(XxP>&2m_(It-?QfN|ui@WS|R2oAC4oX$T0)ENSro6?B?N3|Z+;P# zF_wbwR^QS5?Ft<9R0w+m*nW*%U}x1ZQqNdngKl*}Uw%6mR{92;kBq=d#@LzpoXtOz zOR#Ib6}&tuk5_zH*3e!dIUTluPD@R~#<*Ymb-l3ss!estuX=lfT#-Opi;aV8dPm zQ52Me)8P&hJ-~Kn_SW>tp=|V$@(>kH1U$6V9Gy)B(6*1wC6>6sw;MX7V<^i;R*=F^ zxo%utw+=nXcmk@M+K82q^%4>zF=4v~tWC|Glq& zOQL&s4i{fsN#}}?>zXFxtZQsvD5wQF+oz=WhZgz9dY*%Sx?sP)f5VIY z@3Hyp7|d|c237eDbjF>26y%S9?m5!9;DaGNws$11SE^9!a~CKz=6hx>)TZUD!?Bj- zgZwE;!|ES{@XBUYD2*wk$?ME1T$cl*K^GW1h9^@EwaAU$MRf3zG|b{6__*&?_{aP+ zTs2h_?bZ;`bKB;j`*{P1t4YR5njO&g-wjBbo3-=1pROT-M8xx6ZX@%i%J!tM@M z`yUHw&u;^|l=VWE?0ZgO-?PU#!mG7k1^=`Q;LzH$EF1kZ!qfn4eXR>?tO{YRkvR-n zc#iM`LaMQb&FOjqNxGyg?yYcum{+5SPo6F9Vsrl?SDd(Na{(Q*JQ>H|WsoJAEOb;+ z#Z~{*ApCVQ9r>H(#aln(vY8g{ZTk%(*PKFPSpU58cqfdt9#1lyEa>`cQMjSeUbN;@ z0m?@WMmHq^I173)s32Zk<5xmbsMgX<{M%$J`sG^=rRV=6Ur(5l87xy~%*aj_r+$~$ zzi&+oy5g|KX|X7IIl&SKp?KF8EwZH{+t_@{#{$+fEsfzM6G&iw=St?SySaifz0sPx zSaA<} zPh{Hca;3)isUh^_fFwk`_>N7xks)J) zsm>?HU)#BZd=XY-#O_b9;cYv&?Su;2zn%io9&V)OKN}kRu^6`rtUUIU!#HWG270Qfo~o&3@Ww>WR$HBZQ42JZkpvo**c zV;vgamW=VAUXr>61z7vg41c6+z*+T7dc1`3*sob|bM6b!^tU%C*nQ^%X0eQ?&zo_5 zt&C`RXe&+M<3dfq7Zk5G;S|mv-M?wWJkcfi*zlOlBm&}?U5$rFbc)~UyKlV5pr5Yz z%19eJ$~I81d42e&X#~`FNF(MLK!1}XITcln$|{{O-Ql=rT$v8_*9b?s5eBfKHw~MF zgK+dtRXDo2kZ%4xf`6kmH?QG!p9)-1E}}~> z=u>^hw?7!~-I(9rLPPI_d)m-xJUrK1qD< zA4t!_(eqTWhVjb$G}CF`ge*Kf>N(dns2mDjTqDKGsifHbf5FA&dgHoXaP?WQ$x_7Iw>YODUsA5c~-9s5)MTeO68PJf!(HMQ=3yG2{ zVtFQd*cPk>B}-Ir8qa!w8(n-zk0re=%s_*L)8y&{ik}X;AeSis!DXq&)mzf(Y1-iq@O3OtgoP|ma}>)xd7vQLo?V1O zR~7sf$#&`$h0H4~q^VODk+AdLjb|4%)1{mDc=`WU$7Saj_xk$)f5UST9hb>wYq>_E zz_4=YhjwvYyBb+j1IC1DdF)I=w5{mwF6LwMa}#y!1&od~Lw~k^oP1uF&dAcoJB!!x z2Imye!)Fw{nx{q5517-U2@&|otb&_4Ooy&3V7~MNFUiER0z6kgTztRhDC^RVFZFQ$ z#0JlI%8F>+Fbe)#*T&zJF9Wq`mZz)kM_$_8r4i}Q)Yxe}_!?e8odVe|=^w{sO^A2}JjdzH(|qt7lyv0uI^W+A1FL#@_6l1mae z(8i5haj%{dD9tvfo|wwArW&}!=Sg_ar5%FQRpHy1B04EXk5>Lshb1hNw~WolR;>v4 zvZ&BPy>K1iIjI- zJ4Xbb+PG9!2pUso@Okg#a9@ud9PW1_{8T&o@M9cam3QXU^|a}vdNz}prUUNhvT)oa zW$dw1hwXRt=z$96GmnhtUhXM_(~(z6e0d5vd{PN#-*EyRpTqpW?X2I9Te+wDB+=TGuB5J6%89SU8 z5hqJq#=?!o?mbIHRj~wjb2{iVRRF*^fny}jv%Q!VjJ=_NpUj7X))pO7Klv6YR%pTU znTaH0q9OH*jYe6uZnA%45pF!Ehda+}!Spd@RFq&(<9CfCERz`D$c}_yvg)NE-Sl872Qy5dGItgi)5tID%;sUJ~XxJ>Nt%J@!ef$KBxULOXmes;@)4SptZ>#RW(O;ZU&!2hOJfi5k3;itn%@TasZhC!y zJ^*nc^+x)1%r?di5Dfu^!gSPr`Wx_;DunGSqz9aa(>257Ksx_Cl=)vEhgWJ6$y=dR zYfl2M_1(Zf$QIyC%b6f^#DI88ThN!CDR}GgcrNW_Dt3%|3vV57!E5FrGRb0nK*UY5 z?2;^&jgb?xu+FNmd9_&rHoiCKp6qa-PiDoV?i3}6@-nBlSgy_T$MxI;)nu$+{7PKo zLnf%v;J7qgt&~9Ce9*;JF+v#gr-rxlvZX~u(dhFZpF3n%9#5VvF&!Cayx z&IEtf~#5|@`E!$H@dB!gPv0xlIsi=ve<-=i^)(`$jz&VJS+fRbGn~-Zt zwsd@5IxaLQBjxPg&+&7_ee69_J6XChvO1M67`ub}*k=vz<*dl|e_F(KoDlcAS;3yc z=lFeJWpK(Y4`_QbgKPk%b!U5xL~m0vsGx^=8A7qVQ3yYkr5hzir&8CZxuT>QWe~sU z40&HrqVYc~(3t4U-*;9-yBXe~r|3++ezc%1q7*c{T<9^*RgEriOvUMXjJr5T z2~(RD#F|*$GeLB#-e&ar?=pA$(`|6LB?<42Y$qoR?CB!6&3M@C66v!wr&1r2(CLGM z$ar!wP9LU(Ln@gLfpM1nSpILNUNf)KqJ(Fi72(vLuY9>`1+=OGt$Om}yIW$!=oBX?QR=|jWObA^n^UT_*>LZv{$ z(1)B2x=a7rkD`BDe4#O4jlSBGiiZT2qNEL1SU>2Cr;4Gv9~tZ4V95Lv;ZhRvt$7%uU1O|6aqzf?FWxrA8y&S)Sv+{|Kk4fcrA# zV11=KNqrVf53G;D7g{4Z^#u+zg^NK^zakt}A4$WRPtD7xjvL12igoW_z@~|+&^=X+ zj+w}QxAj|z(r;aSHC_j#KGyJMyd^#MCIxL@FBc`>_=0_t{KfmbkVR@#G(Q#F9cOVH z#}q>c<0N#?tRy2IY0;~;n)s}L8nN`3L&*V4sBLs4ei61b$6^!4R5@}~LYwJ~SkBsI zZ7^jFD4!*%c(bjBTho(;A;ya6(X9qiqx6~PR~M%y#&fzO%Hg7Cqj)~Bqf{Rw2gX9% zjMIF3Wi?*8_Y0<8uj3Yl6`@w!Z%AcK?}HcB=#ws%-4+@k5=Qmm{+KA#WNb+z6J46n zuZ8uKuX5M6mch|QEJoAMgcx_tr(Gv95iceXm(v8dP1VG*k6JLhTa8ZCV1E8ld7|wK zjx>p@!p-NI#;ANZjZ4bKLH&0{;~4|{^EM&ajL;^l*&Z)PB@;i-Y~_Lv{Rh|dRl%!# zEBV%8L%9WM*!)`xOr%SYo3G1qx&;t5znq$}okwrSIC7m=5a*mX$iC-K-K+qEzdywN z#yLML`puW=K!%+rUrZV??yrOR%$eaV)2NV`O2_=$!ChZr1<7h7$&f5f^6-rjzL;PK z9kVa;Ko;@&MwAZx^ z^6s4^so|!?qg04ln=PQd&W9h=#`5Eixx>HB_GI60=Czkd#_VH-9!V^V6PGYP&sY`M zqN9i-_sNPidv>)!H2=>=9DC|ACrr2l$|ZxvZxCZg2YN0f3Y*d|k(k9y&)l4d8t)WD zk>`ssz+MsCp9mm%J3A}pvHZ37S9ph375vXt5stL=@KPz|F!;k0QuEZ9ly}xUfi)76lJ^HmM5r5BkO(vdHqmB_Q^DbXf z~MKy7@GL_C+DQO7+MPLRL!6MrM~H28%{ihGsG%1AZMP3XBP zPLRR0SRKhJxaFIL=w8?rTqy5@RxGQl=xq&nn*2xBXlju~MvEyHY{N{0e+@-*Kj7~c z2eIC-t2&mw3;OY13Og%D%Apg>hK<%{dxwfSV*g;xEsis=HKP9(hvUvZV+eN2z&ES= z;X$t|$R01G+Oa0|YppCy-EkiN{;D7c3^d6vZ&f_;$`^K?6_DC@=G4)OkCQw6K_(P1R=g%^>&JQdV z4YKIQ=XHL#;FK;LXMbLW{dxEFS=_a+MG$w@RNS{@S7}k_9yR=RXd3CdAdmAKEg^TK zGimX&ql0TA@x(kQ?ys#joi{ZOch|GtPgH)OkFHsKUuNdtQs4%)a~#M99Xt9h zF%_F9lzQBFC7|)W>G;=06FgiL@Nk6`RD=tO#H%2>>TWoW&AZICX}3c53JGvC*g;|( zN73q^8_{oG9Z~nH#+N4gj|j0h zAxc9>P`}mjX#2@gDZc&Upjc>A_3y!xv{Ze&=~QMPL_ zc3~Aa;GsvsKLIa2ZYS1G#rP}F1PyO#!X{?}TJTeV4{xI9`al_+lsFv1o<8EuR-T4+ zKO{hZU>vy-g4FHtP&#w26YMR&g4c7sF=x6q)Q%NW0~1X=s;?xPv$qEPC9jc&GEEYH zVF9iGo{sN}e>VJn@Bvp$v={q!6SPL5QDgzMSS*5PcjD>F`~8@F#s)4c$l;9F|6?sU zlZR91Pz~n&FBr#h@6?QFY1um5USJHD@|l*c{U>a$gGKk?p5$ zNWknUSJD@qM)z6n#>~ix+)(!_95uKXM$XJ3rzO~&e6t*0QJTQ@KTpQ}!B62R%Yu!F zAC9MA8Ud+n=6SXsf5Z4W)}`rn^QKwQtf7fGb^cP(OxJGQb89@t#4ydCQ87$TGZD`p zzJMkzf254hgj0#>X<6K6G6EiL8%4sSm?npL|8Fd-@sygYP5&Ci;QF)LU=*2+QQpiS z@>2~e=IYYXH`GvVZ8Z1i#VHsxr!WMFyU!Vd)_dKCcU8(T!zPg& znr2JOUL>RWS1H&q`2>Erpp7$!X+sOsy@!nwK%drI{;8TReU-;_%Nx#;49&~T(_n|6 z*lc`Zq!n~XnvyFsHOaxHrZ_sp4nA7d^D%8QI84?B=1a_Ab45$$k4wOctRX}Jf1u;b z1t?8~P_eiS3?CJdhcit{_8@7@h;f87ldVbOAJ&8TCNo|136E=yOha-o4IN%-fZ<|A z{D+ca-%XG7BC0+RfoFAFxG?)x&|;xmRhkiFU(@>kkKY^@QE^+a=r?eFu!?j#%NB{~s?4c5S^lHj>TTNAr_96-gYiSqRl^TTn(y5&5LxG12(V=SOlrWu!6j}_PT(|@{jP`(=0fuhJfUAGQLSFE^H2ky zhC(WUA=Gf5EOgq}!N+eEB$myt@7bi$r4Ms)|K06;6?+55toMXpJ{rXFrv;T``RU&8 z$8*Qo+&abf75rLv2c8|vrWgAM@O*?X+iy~ETy>G$_mU#>XQnV-#CCL57|-4At;Bba zzJdMsY;xfV(>Zs^pyko=+>GHYJNnFH&{?etFT=H1_MH+;_+81r@nxDZpYLEdJH0M! zrv(lAv=#R+T`CGM@5Vc0e8sx``V>~<8x%4A;1uG0TNdYe3>Vk9<&G*WJn+ExTWz&m&6r{wJF1s?O$2c1SwAK$49C$ndLX$_NPjO;Ma6a3xJ=J-_&K9a zJZH#MG{AH_cgWFj=A&8e$=7M$;N9d8+=DWLTkBL1XKTS#4;Q-i^f@eiZ3|eTi1%Gs zUFPeM6(`xOes?O~)w{>7u(<^W3l!nqf&{Wx)rRiNO2mRYk|4-DfikHAJZY#6OQ<4# zv=soS(!sxyu%wTcZNa^xPLh31jp$iugI!E}pRmgs9wi$S3kxms$Uqs-J88qn1qJ-7 z?J`)u#SsRH0?6zZOFDb-R&+lxglK>Hf%^UPF!ZPplGr{pS6C>%uX7sGsAt#??0S2K ze6y87=|PSVSY$(vZL^?ew()o_x4@$g3Psm4i%3E1BLql$=;sg-Mm&aK*fyk3PuuMC^_KE7@Jdr2RNgWF)@3?~V{s zj}#Rg*0z>6(wD={sixpjqDC$+WE`_2Ot01F%Eg}90|C{~$cnd`a9OBN{d(eX=Em1# ze|8BfC>vwTRxNlrSV*6QvRNmaF^*=vz_KzsnEtAhuWVuYjOJg#Hz=Fy_dX4eJpPhn z{^N+d{{`A!qD2cgSwN>$Gt>5qP?hojJ@4t#P0lLpu2d8ao?HvYToYj#I%L7!Ao^95 zilM=M4Z8xXFlTo+e0iiJDq8XpwFa#5^kQwuwsFAU#Yf@8j1Y(mN~ACC2e35U9>%W} z(&4Cr3tl;hMv7$7r%x4h=Q$B0zaaXKy@VzFTl>-SkUXh$L4m|#RFdCS6~+XOP>E6Hg&eNwd}h4qTt@Y~NEKCe_6%cMQw zM6@Qk5MoDXu$j-U-pQQNp$vT6@&Z~q?m)w}96IRY0Pedn9yV(t44kYYFSkgN$!F7P z#F|_TX!qxqKhVUKslG7m+dKXcWA*4PXDk|5)<0yWps)EOurFf#D{r7PnXdiWM03c< zG(s+oy_x>GR`rj>U?%*6D%rg#f_L?<5c?-EgYYd2bkjzfbry09WogF1!DF=onS z^43%irE*Q7_4+8XmE9MCUs=}PkQ&dEQ&YA&D^Q5=Hdb}soa2w<_qxU`cV+~Um-6SRK+}T-B5V4mYe=a2LD=3fW^}yN!pA7 zT&^CDCLwz8Kth+E30KDay)E3yPUd4Bb%~s`G9fBV|5Jay8=PW0xU;cLKY4f}d>%Q2 zd>ZFU%j_!A`>GvGn5T%k?40qYdBnF zB<|tg)GMP3)q5o3ZC^eK*)ENDwd`T?QEPHi+mcp!$Kv+q1s=!e3FzgzWUQ3ZfQ{?r z@N-8$Dc55x!IWfrKsF1PhIMcYmbAk7UChJH_KdKn3J2?dhA4p>IV4++#Y~sA{>d(G zN=peA7t4ry_$Di5teeR4nOQ&ZV0RjI_S}Z5i`+y@?8;zO{!QZ1GlaBmtHL|#OuM39 z&);Lr|812qsIK8EIzN@7`AY-rWj+gKWy8kW)GS)CY9lvyrVdTmuYmI&uIA@7%j1D{ zrs6mL3C0WhZ}DeHv>VMC?KFj(F6+srgaQ(AL67?0+>9|h+ezSu67=mGf-843eKp%< ztJf*wpnLV6SIji=$u=8MZ|>v|3###H(`T5zE}Kh=I}JXMe~HfuX~8ABc#JmPK&?S@ zL^IaE@I;>u0ffyL(%0ciX!Ar-v~QpWWQI|)bFU^@5gtkt+>XWF}LDnb8j)H0SLOOkt5{{2?5H;?SL4k)d z3?A=D3=hqt=T9UuP_`FWaHbmdwts=Q5;sIv?ncyk@e1^@HikqGmeVEt1`Wg2;K;8+ zT4QcVt951J&H(~`(Ja%xPLGUqO`*pxXW^;MIs9!oMVuPw3U<5HNT5$9))qa7xWZO= zw?vQLvd+MbjZcVK9>BGw6(mjQ<b?Ytv;svW0Eh)@2 z8qcXRk8I%l2Qc@HDomIGbWedfHP7iIfyfQzAtNzTGuvT-3s)+#^ ztfhtS_BIeVq=29CiRp-Vrp;izL?b(6tXBDe4v8e8X9n=mAM+b^_VO8Htf)GTL7D!OtR63;i_an`*brn zdbEZ={X-hRXW7E$`_l-FV_r+^c-)y|OqNdQMNR8DC=3$9q}@t%R9Y%tri;0>wdL?u z`>1$d$p=T%@39H^RP`8<_$`MeiHr~V!k%O-5m42%Bph~M9rEWXVBx%e5~(L7T}-?5 zT_*?Y1z)(FwmSgLKS*8hcG5k$8r6L}!Qhx1S@@y^je?|6=N{{Fy^I=-#%0luDv!vq zekJ^=`Ij8I)XhuINTIdwGf-B`RkUk>&09KdkfX^%i8A96DSC9m)x-7th&h(juQM9E zQe8!J(kP}!>0@Y_7X1Eg*tkzFi{47u#CdJeqbaV6cwx_a-g>11J{Ook#B~i)o>Pqz z53n3J7|ks%HvzY~Ysl8s$BBda39PxoW~@0{P*$r;%kt&%_49hqK6wQUDKUng_UHVs z6HJ?0-w9hTW^?4>J$P_f4>V>(kmQRs^kKdx9qnlatCO2CDbWLOcL`vGo*td@LIDr1 zRub{2F2ZIRo}?_-AeLX2(EEyMIQquFhWTOD=)rR3+E?g`w%=93$gNXB`<64gE^@@! zxFhh!eG#1al1v8*2Jm9ABkZ@6#mX0o;NR^?3bqDOpL2;wyS+KPqt!UNyc2TIUl(1f zH9)Lb413oNA-|Ybs=6){AN$)5>r>h%19C3_%>O$}Dhu?< z^Ns9X)?|czZ%p{$eG0hruoE1!DyrgM1f=@71tV-I-3jPiDVh|WlwIw}$uJ*?$qhOilY z%RQL*Tor65FeX)@0mTqQm{enms+pQ%kMP0=*7R#m98P$%LUeriR}8%*Vmd!v@S9x> zV-yV`yQG5LFIA_-V&s{t#fk+sg$Dyg8Anfx8ZrUk% zbl>L--Q#AGXbU&mU0;EHO%9MHqky}Elwsd0HmB7Np^K!GFzU*EuEIweSB|oVD|?E_ zo)PwR&C0E4QYsBv<44kD=BXd#s3r<`Dn)Om-T7Z%5nrZ-ZkD?6&as!@m0(NdMrEVm z%Q(@2ip%JJ%mNQQW**qPN=)CIf=PS!dj6GQeTWqMx{6X>=pc*ttZgAFBY@~HwxNA> zF*qWMX(9Z2vB7;74j(RrwWpNm_ox)SpR<^I-(3cSoDYlV3=;m@*cZ$+O|wP($;)y~ zcViC^mfDkv%qLPYCJvqVmUu`qZP@RcM3hw00Qn1Y?49wA%(BuU7Q-^=m#!>4Z{5vh zy{UxXA8!)*sBp56T2bNBX!PB!BvNuZfk)>`q4yU7c;y;34)@EXLQ9r0uviuUto=)b zr+fIZv>c@UuamzT#$*g*G`Zg0j1KR{h}<4hR3EJ;?j?S(tU^^4X*|1NB|ocQ0Uz^2 z;X9{E0@_R<$!?Xn_6x^ZQy89!p~`>A6ZVday<&(8C$!*5mXPikEr*`<4W36eH5pUi z0uI=A@*2YX;N!rwG_3ZocUx1bvP{(cb)1xxH6tjxqd}_x&K3&k^{Fhy=dGeh!2Cpy zE;WdE0Vl|OdcO(&e&oCkluE`ocG zsdVh?0d#3~g8CRa^z~JQz$9lfEhdzvE=$6aapSq#I|9^PIR{uyAJN-0lE$w~Wm=79 zPV;;wzKHxRen$kj710SN^=Qa*8R(|~+oeyF`Rnvabh?l(KVyI<_e}VZg^U;HKMJ~c zsFL5wc690Wcr2bfncI<^g%5n6Lif+RF#nbwwUwUGqqiGJ!r3gw zmCThEbG#otvZXWc$Klk;t3~R}i+X={SDQ zI9asYXaK*24&<@E9(~&zfrjjJIoe_yPVSaM8OCSO=+L8w*2&|}OR?OR_(^c+>@;F; zphvV?**O#E0UAT9c>PEl`a_U~nX8q^pv}K9?#>!a3(y0J>AEz)R2HA4ws5m#%Axmg zB{8{gOxo*ZQP#p6I$Wlc+3{|4R&E7u`Rf3A7nN|~K~-q=*CiQ;7Ewp#WISo~h`Sst zjefVS;MR#El6&8do)c}s^o7#UHE#qx$m;9M0##AT;!^x~OVSAxcrH&HH!z(@)@~8+&-OB+>2}bz+JU@}v8BxG#rSk39v_(JI?W*g|0OUs<}?LV z2>nW)-_<2K3({zZVLDE{*U6Pns{)tG8)WSDaAKZjMK7@|@`+ALqGe;*j8s7q6Rt3? zbcq@b|C5H^x8{icvr|Aji?3wr(NDZge+pe(lZuZ@T}3r272q_`LQdHl6NR0&boQyu zcq`9c*F zW7j#6(gO?WCC{ylf$PJq8E$}Ul!9U5MkAtPXHCDAr{lj%H@G*BSr{YN1)0f=uf7sM z_3a7qtf1tNkdA$-hv`-aU{g zHlVL(q+#2SXJp!0gwy{@#j^r#l`h@qBg9>&KwSx8eyUWPbZ^q;x^BP_^^?+9vQ^*{FB^|BF&Q%X9 z&o@D8^akVh?A##FyoSnXl&&OZb*4@UrFVhiqFf~ea3wHhLLKtracw?Rr7h%03~eLpa_F{-t)s2RX|JW zOA;tElnnptN~bPN!lt+9N#<}fDyf&qa$iP^#{9U9cMgm|@55RUAE8F0T2s;Y^8wF- zKK6gbcq*5IEBIHgGN^FXTzn4f)3u==9z^1^>qALdhb7%MITfQ`hKaaqy*RLcIzIZR z3t4;AXkcY3+74OC{hP^j8e#jyXM!x_*IqEy#*BSl3flDRlPwr~hvkm!QlqjJsR$jE>y2R=!ed<|`K>Pb^+=CCT`k0mb2B)8Xcg2q zUnO0W!bvJ8!1inI5OeJiZ^3w#R(m$$yLx5O*02-!_pStftP#K)_Bq*Fn#%Yib3|$L z6>$E_E|OdOiT}7?m+IT;;QN}pT&AcTR8}>SaTAAZ1sJtuRLPis`$e1Uh(O zI%Bi5eKh}x>2IH&6iHNS(KNGvFjICp@Ag3nrRt1eiiCi;T@0olpXH!-$Qy3Xhv6`8 z=1SrsRYZ#K+0bm3>7Z8lms}lFijQ*j5!wFtP=hwzGE)MJ|I~WQ%uvDY0YhPf@D2Yi z=N`+D7Qi53II#$^ptj5d;4|hZdAy(n&x{|9B@YFVuBuOG$xCBszmkZW)PnQci=^F7 zll;BG@(mA!aLsA)2fNANTuse#)pZ+&vZ2dl;hF^}t zjDKF-Iynv8vT!nRl3GM}uqA~DgmD|O%`aP3A!G8tpEx@>EKbS`7*w5AEy)6L) zxgs+DvyeCp(xd8ob@7RUDgXJkJa(+H0YhGe+-`TED|W|X_Wr4yc^RAGAA1DhmiOV# zP(!N6bY)u8o|COvY}bD>6_1w4iAL;^!Bt)FNYf!_5*(^W1Apk^^4@oz1uvBFoV^2t z-hIOFj3BOdIq;EFFSC4E#tL`-aN8XB_PGtA*fIK-f?>7qjmSZFPJKpKCSp@sq z6Q)-=&GqHbIOvSHf4E#D#Fbf=P&mPXe_t+xLEUcP+A)Rrp0T8_MzFj1pp|FMcr_Zq z*pE+4*lzi6E@euz{MGsF4F3XoKMPAoqTA?i-9 zv}a)ghP~s+CbeC4bs}9 zNiI&%$M4&8ps3~?FTYO~ZPuDY;Q9dK*kMis7AIlw)m5TL5l)Bafx39lV?41vD~E%xTR>Qa9g$!f^_aLg^f;*wZ<)p~ zBZd78XDBz#hxHy~J`mq+y5y3LKHVFsgHGugT=kkNXj<7UeqZcO(Z}Vp$HEK4<9u*{ z4SlmF976+?MZH5yv6t!9|F_pz+{Czp#q7Pq&X(LJImF6$r08)6uimdqlO_pJTm2rF zbgdk|FKi?e^M{iBk@M;P&l&jHcM0kHV@*?kZoti(#)uRyQXCW}z%?>jF!h5PZDY*7 zl!}w0k-N0$g@Xg|@8mN6-Id+ce@reuFL)+8?5&6a&1}wNq)GCg%wrx*)>l~mA4%uo zSL6Tw@uIyut+g5nWZR1y07bc+hj&I4KhbQ8e!6``4EtCmHI<>`ch$nrB&s82T%rnRT5aa zZaf<_aw(M@|6cjaNR#&L<+sH=PnfOd#=gsvsE_^xVLaz+)p&BPVA}=QT+W$TOH^=? zsy|3ACb9ATR#NxCzJe`DXszi0{Fi0Sxe(4wJCSD`v|ScHR%FoZ=y!@bvu8ACl!bD3 z;fLAKYZ=!VpEsk&i#myOXY0_yWnP%?X9%wc`>}W9m($>yNI@ldJ-rTkh~3XUKo7YE z+fslVcyqgAWWKl95DAJJUTJsz0n+BNS+a0QHEtvOzrgSQ%QD*!_m8QiwVZy`P z;z=c9vSB<^@;_%3u5!lOVXi^?>?J>#sYByTn&AG1!{U`Fz!tFLW_7 zkcLf{V$Y`saZ0@ulk87`!z+E(#xqJ<=Y&JfWepnKQL4CaD&H8*d={nAqw`V1%p10B zXwSv;VxkRpw9cgLZXIZNl_7?2;5}HpGOhZyOz5CI2&d>pK;k0{_-~;T->U~=pY^B3 z_1E3l@&`$D@w6svpYeyTg-uuVCqEWju=w5`=wkhK;h0r1{(W;4wy(B_tUDHTN#7kS zq>xE&vcXX%Eb&P??QPUWKb|4-c#%3Tx@!Vs21hf) zAB(AF!95}CwH1x>8H;~!@a(NTCzi}L2A;q5&Ef}2JBW^GA;YETWs5_ zPY*nG@U~}@Sd&tW?IWJTMGafnUe%Lrq*T)GD?*0_U0B?bI9l1(Lw@7=MY7w}S&>Ja z&Of`k{ImO_yj3>-syiO`(}(kA67VyXFmL`nK;1(Sw?mz-PjXV+K&7jDG3V*2^u@X> zyiRaoQF>sFLED@5eEuV-9qB;Q(*vo3M-meJanBK|+)|-86E- zLsgz|qt%3syu6&Q4m3n2s?or)FQIaSF-+yY<4|o0UCBxj)_*JIndp~bLfZlulkPwZ zc823-zr$jeY<24YdLWLyH6Ob0o1V(vk03t%B7RMkvY(tQ4Vm~SiIjdFkuO#@W+O+m;k;c_ z#oJ}tROx1pb@O>Gy&cVjSLyViwO)8<=!`oprb9Foz&sBR);%eSnl}7~X{JZ$SiCt^ z=$l{*_bPsx^BY@g&&eL}z2){%X4v!QGjXoveYC#M`NYce;Ro02ZVgGHn+f~i=b@_< z<kE-w*Jk;E z`$<1C&YHz~|*`bM|gO*NPV}6SN=p zNBY?l&M2G1n>0N-TWf(O4%Rv@M> zaAC@a*N}etO!<>(-^opF07t`1v9fzHZakI=cYZrSd8RS@wpEAr4h#YN5dOV0?t&Sj z7X4UyThs6S}i@Sd6EAGzC5uQ9eOdH@Y64&~kJE}{nWsUIiL5n!MRLY*D z7|_WP)q-YR393I66}pJcn`4+PZY|X5(tmLrk#GIPR&m`hnFOD`d*=xKgZ}DR%wyTnw$NMqgC}3|-=1)D4N$Shfe^ zDzDP3^iHF4!)@7q?hC(BcOSC`KSYz=wru`BuC03b5(?VYsdd?ND6tCwhfY!!@=u?FH5+7a zej1W?E5D(u){7Y%c@B}yS4=Sr6U>Jm!|~^p6g6SxTw=YFZCTwQXB@%r7r|Kulo4eh zKRY^#{TRrzfD1dF59I8%tHoc@I;L58^pN}agSsoU&AlBDV*VV?&%0d=TNm1s-ja^E zF?*tTG+2W^4mHBQ3BGXLXbig=nM@`dqJ&w$OKE7)SG@AuUjC}LBU7EQm~Kq5$9Wes zDSn0$EmD@?rLqbR>m1xxI2GxL{v#5Sf1;jb;J_t79+@pq3nyRekTEcuKzjyXaO*GA?0^uyG5^T9k> zmqJF@!=o83BK>E^wwUPBp{aKT|47bEXgvq7&e_6kVFDX4A(d`lpAPeOl=7bOGyb>% z!X3K{bX;OcAJGV%OpTaz&ky+Di^*cl4{g%u%^51ZH(2^?0^3rVN;cWAgj~1ISn?xU zp?}D4_GEGTi8N#WUl?%y2t5tq`w$lsoZf83jw$~}i4n;>IIAN(Q;MEbUx_EHI#R2x z4;oJ23^Dw!di?SlS`@wubV9Gu*x`P(E6W5|e?=U4r4*`ON#V0hg;t*R!J#!y(Aez3 zrVL4-f!|_;1P49*U^xT++vE*_aa-67b2avSaew@`3^8PQDQwYHf{LeUYSYMtP11uneoycGRF%AD4-=$3t0%Lz0aG3u;Ei6TEVIIv-MndtJ#EjR(t?ff zp@R|Fshe@{rw;udXDc4$J?${w%APLZ+OzKsvZZlcvp?1wP4nu-*2GfUE&Gh0ulE*mpA=%ZBqf|>&;yR1 zAlA*vhHdHZjJG$LPclm$u>SP&j zfcg`CV1W?Ds`>06xpsokxnC)Te`&$BZuauZU!B;G!Hdc3r30#{W>Gr#U217^M*3cJ z_Pe|d|F{1P%;(=h77VgC{MM$SM=zF`;p(Z|#J{O-Y?*Ex9coCruh-*%=Fa90pHkuK&E)f@+;p;Y`OevaC_% z9Ls!R()A<6!T5^3M3tQ`?O)vyLzli4J-+iBM0GXff3)GuQvUb!{)}O{ULb4qVBPv9 zka0>+`3#p!Wbnt1c04iSOjkEN`d1Cwj~K$jO$M}YlL~J9a6rsIhIm`)HH6k1gX0#S zt(M94OLYgt`G4G5kn zohqz+ZbH57eDU?xZDP-gQgY_poLh|~eqrrUW*;7JF$6v#ph##U-z8N#> zs7+o=?h0k!iZMv_EaZ9E!2_OEWIjEaHW^KaRL+;%zvmMU-UdP>f8QAxgk#qe1L5oq z3Fjm<;)~G9;*@1N)U(tG&p$8%>o?Kt;>#pDJFH$f)q{KAmrj7(!38jiv&6>~CC~-4 zcG%H=gnH?jDr&`n!)9y+?`eY%{oxZv48JXd&6)HC@1no^BitUTM)HsM;QkhWXrIfUsgpccJMWcj z*l7thPV`i07;?%>Y0LRfids=tQ;3s8|AF)E09YY8$F=CDY{z`A%lczPCez+RW?PBq z^T?bnFw&*zZie#fp%YnZA3lExPUoBc@XTDZW<{;g9q^S3OZ*f%>eUYppe)W1mo#t| z!FWBs1AmG0APf$9a?PZVzT(!It~Z(0H>c9euG54=ToYxi-HeAf*~|0#aUGHQ5^8Sg zgbiohnbq!fv@h|IkT@=jRv7=qX-*P+pybV3kMdb1AXBJvh`>e1cn zDvj{>MsJ4!&~VO`MNQ***1T3MmYcBP=0y5(Q3oS)wP@6!-@FExfbscM=HF{Q6laRQF?!0gGLQ7#eANtd}E|C zYE-`$_iZS~i-&K)x?VO=#Q&ZT+dpE+IWIWL8OtfZ*U)d3Q2D!}OH`R}Lw#$FaO!F6 z3(zBj1N|H(h>{6UHOeHA^%n9^dTj5Jtd?g&OT5>~TSg#wQTLTnhfBaXuYiZiqJ{HL2!FHB9+#3PD4-W_Z#6GB8pF3-3Z4x8o#K zZl4Yr{JRv%b%<+{@$a>R@c zZ_`lp8xOXZ;2_^Kie2UR4N+_zpWjW=r$Du38F_B|h*hsZ$aT>m<-fJfm6g@Bfu9KlUMvmg2Y92eGi-P%*Rk%`&4NJKw=W_n~6=Dh=Ac zNf*Cy-=F@rD0YDFa{rq@LD>0*fAxJ``=#(Uw55d%Sq-~D%&tfq!8Ub3#;P1uej2^5v0 zgU&rQX>sjWh*@p~hb_|Bntd5`Jhxp)TUv$#AKeAbiYOQoq)Yc+b;mh1_r&a#9_%vD zY?8c}$X(TsQAndYm2Bo2i0L*LYEG3A4VPYEYac`0!OGaN-Bzsk zI0**v8d6u40m3^8yk2a|nmM<8|708S1!sWl9AmGTWd_KmqfzQX@O*Y0KF0Vk$Gr8F z8T}oyv$SaCrMvJy9_%4oGbZ*_qn@{FWd$~7q}0U==c>OG-Ff3X-SIm_sdWc6&iV0u zw3cT8ZGp@2TFkWgE`FL;0D4^KxokN9{c{cEJ->`)32Zf;Z*w@`Z`)UT)yZ2?A3}Jp z!LpcCI=N<%pxvzicXiRnGZ%{>_NFd-QdEPfrM)3!xh835>Y(>>KRER|hAn)XNG%(u z2u7f^nohiE~g-7o)kw4(Qp-9u7`7 zrGm>`^Yx#HICYmQc`o(9mK~$oH|jKzGspbG^eFD? zA4siwC&t8=;M?pf#hlV7{}Rb|SW#=X5gzE^jw@r^#sBR#4@pg^Hmn0qC_W-)bw>2Q z@f0dGjN!=$p3k|x7uE4B%gbDMeKj-@uJ3aI^>iJw&uxR$3BKaqCF(Tps|8+u;sH9d zEZCR63uwqhW1JhOMO_MS!vFG693>WP^DZ^Q>#4%0q+=L=yAYoAn+ApMo^1VrbSjs; z7w5L{9pJEAaC76Sa~DK(B=!%*-gA z=KH3|Cb=3il}!&(>_1WbIa-JM&Cpe7s1m%!v#m~R=x}qL(9zx*Ulxv1Jl8i?`LLPy zdB*6Ic8Dx=V)rwWsJMfP+}gL0zF+44qFJVR;kGxc4ev&zz@bUzuw{@r`?|z}n$wO{I``C~z_C8K@0cg}Yx=VupX2F)@+@I$jXtg~ zj#11Vy#`ye7|y?fsnt+0)t|+esL{UEA@X$+!X+mUD|Q#dOE_cXp*fu_QWYvWV8dvEdu@wVar!XQH=BZH+{BEVkMW=z|9#_mmecQ#u*q1198In(b{8Y& zn=-A19qIk9m$KG=652S*3BQf26YHuy*;%KxWMh~IbzO`pvcofQyj>!OZ8B#SUTTVG zTu*%>i?@#_%}rg-53AQ9p(Gq-1H7O*%#}6g{*Q&SSWp>qfP0X2v0qLh9Lv>ZK6360 z>D3#wereFd4qBLh)E9EjPGC{*<4C#7Bq3K-LbsI%W8^%2ka6GrddGBX-v3Crr=Cp_ z-M-^rPYKpc^JkfVRS5fS6#DGzixbn`LBF#JEO}u@9k@;)e8vHB@c|#^6TFgcsp!Ie zgMT!;a5ViGZH|){`?FJxD)dp>Bp81##)D0His#*zdx9bxP01qA6O5wNsN}6HK8qg! zzw^D=hOW!V20UfM^Gw(+wKzJtPzTRW)8hHjpJ2lZV<=8eW|7*-6e9c*)K-^baQF@I zl8%GdYmBM%axi*(Jr}Fv+}VYag>>Y+#Jq}dp!3FoS9$){S5SI z)#|R88I&P@JmP_hy{fg8DVOS8}7;cDQ>@S!1H7sXvkx2)VDb+ zW|<+{KX?Sw9~r@_vY(XQ(33KrNbv;Uy(}?_SM&gLrx>#J_kQA_=>ZTtM3btNEYVHh z8=UWrW8(&{BP0D=A#)a6GMCx&$;-n8dvU&;+rR7J@?8o=AZ0;89qDR%is1ID5HIaL z25rsLAuG;`)*tf5*HwGO^Bvq-MOF%(ecUK|zSrToZ8u@{)=#4LZ@%}Q%b(4PdqS{T z3BJ5_T(PTs^j($0D}u3nR|M?jeCZ`hX_Px6MRu%>XX=?$W6FaGqT3=pN}r{Ru2W6m z!ou-vti?(?`nyiZT6|78F={GPQ`swA%BAuz1i0YK(n~*@cGKhn-?C zS6Z;#vl3KWaRzT~PJ!Ip5{TYo!jji3(abPwaq!hmtg>t)?aqB8*RIs2dFQQhVx&Io z7qjX1yBio8^#uDraAOPpOQGXGK7rW)P10$)0{b~LC(4y)hIUk@9$GJDqw5WMZf7T~ zN~jfg=0>wSeBL>-?z51q>%l&aPo;&!H$y|dCaaCQifNVy;3;QRj^O;&y-Hoq|KqIw zo26kmeVQkPJ?7ffI?kRAT_hyR1U$Qr_gU-1;R-V$PopOQ%Ob_~XEiAAoH`bG`oge& zDV#^Ng|2K(74Gbo(DAH682VTroDMj%Z=Vw>R=6h&;eN6zp$&7p@x1c)!EE4Vb&Bqp zFT}3xi(k@R;5X-WS5(_liLEuRcv&be{oul!xQ;q(ORQYQ{~tM)j-+EcU;0DCWZtX0ET+U^o-(h&rcC+jYP$VF2ZK0w zWXq8EP|W!}vBgrhu-1fPwX%hlj8a^%|0-C084HH>Bei+Thmc0#P;q&_eG4=$aY9$4Ng) zOh!}Qh{e+kXq@FO7(V8!IP$zXd-_0`M(?Z^Hl8oRru&78{p8hRbK2nQ zhLJmL#GF=DI<-9z1I9#vdVhDOJdJA|Ta#qo_J%C8^KIPwb%MBa4F7J2Y2f*e5;&C< z&7w{%p~bgrg@b*aao5SApuF$^s9XB7tv1VOg`N`PQx~S4mPqn-rt%WK<1{BhLh*TK z7#7rp8T4+#l2bQifo3}N^q&UKUGYNfZNhc$bxt_x#}-KN@?~~G%g8lmKl~Ts$}H|B zQqj|1a^nftX~{@eMKAU9ewl zfPpIGVeelbD6dtg_X)3I{1-on;QsOF3r(mlM^%X3rA;ljJ#k`#Hf-gr54ZY-6sBDz z{OEC-6~&mdgY^=;@$d}h`6VfK2;td0XRY}cp3$@t4|9#;)8W~)%H)mwHs=o*=2~K# zjXq><8O1t(Po?0&OND1$bLe2ib#%P`1bcmQV`prV>C@FukgKFYOKcbzhIfZ~{mod{ z_3e0neXUG`bJtp0EwHZff#^Ocn$2F9K`OsngoYpY@NcUGhx<%~ZN6S?+TK($_{C?0 z1Vfr#d>j79hmYw!ff*iIM*ELyai%(~M|E%0PUTX#fwE%IL~a zEgEe#QJ9pRO{2nF(N!kFSqFmIj6G^JO(|cvYaEU>Kb^sGxCz9{B`iQypQd!$1>O_5 z4)!DGkXz4}ujtEr2KAAY&vi44qe?L8bFM-kWp8iAw2w<^Dd)^w<@dhnQ=HLf<^UKT zXUek2tR_PZUHqBHd%ckjFe}sm`kXRjKI4pOyJ?m%C!iD$Y`X%rabw}v9#v|IbVA>Y zmqkIzlhL#VoI@dz4_aA7)sd=n%}~ny0uox1@Et~lwum7sr0kZZ31t~P7o4Y_z`%`{ zz^11y^mXuLu3Hw+#F28jx$k8UHjCL^4M4qIhqhmP2T-+JJU0e# zSIj-A|0jXECp=HYejN=p83;}4zo=)hjO2%;=(evI=hQ6*>l6p*plZNk!B?gs7= z+a~hlHSn(tapuo$phV4f|O?mTu+j@b<<^^ zOD>_))iI*g3|^C`tK#jq2H?1QJiEVh5#{IA35B*!m~(fK!moj6ttoBN7;IX{wLLqW z*k7GEdKP6YKVMZuTFnL&=4^(sLv)$V!%O(hs7NO4FeIZfI(S#_jo9w3N(ZYuA-la9 ztb#n56Th#S`G(8gPG2W)Z5Jvx;q0Jcx@^>wOSr(eUD&$&Eb9AigVBQ|U^C5>9r$KI zS6&rV_SmjT!}_`6!w3(kJL1Pa?^;URr%o3*0U8sp=kP>?AX!5Be%XE5C>Sc*O4uvvk2S!h_}BpGzv0*Mx^f zr`gVtQg&9G&y~Js&_6gH8fHjfl!GywWBCoYt*{i;7HZSVA>2d3wb@5_Zt#ND8FX6~ zFL=()p=q&K(W3SV9ya3)RGuyC_2LW6IIKmb)(pB~AdH-5#&x{E6}4jKAx&}_ZHD_| zt3{7*(JXk>T5?$MS@7CajSl<<+kMkSIQZCuDRFM0|DMgT>x?FCt3t5RJs>{Tox+07 zub@a{m-7{TFWt5*2)FKchF{+N-e;~!Lj#qChKV|CZ0bd<4i1F{oi*q|kB(^U-~-1- zPhuONF5}#}DZ;0|{5=>Hj!S&>Aod$)&V1CMGnXd_Gk#~&-#Amc)FXCvj**y99JOAj5 z!!Sy5Fvsu+T^7^I&@ilAuxc&FSJByuUZUSso>9;5UOBp5;dozlf^VJCPc{&29m?p{ zfNxm1>tu*)iYaU1S-^Ks>)@3%U6y8Y0Y?Ug%fBtqp!cU=!U#hNI98f5XMT^&f0rp_ zDwW~u+6#(VZV5V7S|Vzj4@QymI>Cyh;u|(@YxF1Jg}lGu5ygG&KGOPU8dMWCOq5M z2m=GRX-2u2X<^RdA`Pi(lZkv{7-ILtJMcQo2=20Ib}%K4 zqP6>ha|h0Oh-kxvQEkF0&MN3~ELfqp%=lZ3i-ycsXetIg)n^WO-lLI0H~6+zgI*c( z{I_gR2!hcpkaH=O(yoVuTG_K(yzXiJGslycIUl|sXVoi7!O7X2jrjKy`)*4S{_VJm zkEe+c8kh>cFCA#!9&b#1c~G>z=f)0=OQ58Z*P`P^C`A4Fh`BN$9G4an-Sn0$9Fi^2^6f9B$Eu*Wk)U&#@resCJ*QD#9$S4 zB|}(zC5f$in@Mw5tIE}WIAP}j1L0m35074FPa*bESjd&?t1t06W!EYi7HKSxi#Sf- z-|5rNC^Hl$=(1&x35~UiWS1uDQlh6C?r^FV-@N5)j0Fz3d&Fi)B(4768Wix%WHmKr|H|A$isl=MXuIm!#eU9nSgddx2^)ujM%E+&vfBh6yx8Vd7^%> zQvaqpnf&gIwf9}&%B518@ck>6hQ5($Z!^HqiZP0sW6pcIBl)Xn@R%yNvP73v{v<4I zcaXo2(V!nYUVwX4S1_Jy#_pHv(;#~lp;4|%f1f+xoj_H1bF!2UJ^zX^Uk3}Go@dyr zo@Q)Xuo1R4-Ec+S?*nMBc}Og9bczEe3Y|=gH;|Nuuu`HpA6<>g?C4vse_o7g`^TXL*O_ zQ=V?;^CzFFkX+jzT~j;3H-UTM%hV~xTv>RtA^`Ue&xc{V<*-p%hyD8r_-$KHC|5~l zA6&DjzBySCs&pv*sem00XhO6quUF~nv}eNv!Ph5;CSGY))SQj{y>Ov3V9Aup!n1(B zSaHe@#2LoGPCL*fo|m;Et602}!1LFxeL=5#8^jtOUod5B47jr(zi5spkbvyU?_wR&$DFa~!|EwdGTXC<> z$&lg~rfkyOrJR$jgI0_AJMM#s3zWmNL)8_cNwFwno_Ft_$Y>Y!Itm^r7G9&Savhs^Ho^+9qP#qZ<(2SpqRdrR1aa1?#qc z6%N(>q8E{oNfcFM=Q16(=;?lCo+;|T_4v20a;*b#I9qLxZ1d|()UczIV`w7HD(lGSM5 zoZUjz>EjgoP>*XX&CtKME{iRw#A~+-Wf6t?WG+*~ZrdBgTenn5cYqyM>u-h*GfGJ; z{EYKHIKqxlZzdg(M4$de$iMZ!K^y$LD0-f@1-h*3t4iGa@1HQT;VhbW*sSPzY`K=< zP=*e@+E-B7YRa`qx{g>zE)ce?lnOY9t;^O%*+36{Odd1>EcngcdX+9)-BO92njGZA z0@W$7>JfY^^M!=YQr7ION3jJe!iu??bgs5DHiv4$;$)tMTKyRV;|2?(j&j3{vnkV< zWrVRG&S2NKOBA~idrKo0`tSovJT1hU-dtPW(NwVy34cC@U09JsX%5Q;|MHEr|G*_o z>Guqk4BXicw|IK5`3b&phDX?ia>Z_B{4i^_tH&R_sr*jnw8Vh2;w;c=#dC4c&I!z> zm1}Fyei8Cx?_&>BeKc>I2#In&@2^Xw@_AcecXuPo-FFF=I~R+0xVN}OEr+h32tObH zK#iX7^~VbryFkl`GU_`*jXwQV5`s9VWB-y(V4)uj-REnwWZw$3KP?BVEevPeIR*T( zBsONIu`fTfDPuyq(8zgI9oETEYOMuZxrX5!_iQT#Oc1s$=Cj_TCOnuU!K1r*u7{n7 zcGZ&wNb7?$JJ~|QQzNk0WkPCI+88luuehl@XEx6MjJwh|h>pKpS+BEeC`Em~yyo&h z@)FSuvjYu^wVh*ntV}C%^Fi+pNU}R2HeyVk3KW_2~zH z`1eQe_-9nzdm^Og7&G>A`BF;lp^NMN^cXaX*jYV7K4zmP`D8wWLykre%HKgY@AatY zZI-ZQ)@jr?y8yYDqM;_)h_>qb;^T@ZqSj8XsrdRCBff1BLb#89L_k0Mpg9NnlG`f@JV-{*3fc+-S_d6l1j0bj6&t`>!6mZdQkMx+_?5 zoq79FeZ`Gtpd^Z!J0{T*zndY=oG%oCColUr4*Mtud3|@2+W{hVEO; zV8;N?Sh%1?12%0Hq(`sg#F%rS9+L*0G;FDRnG>e$+b6y~>c*5;1)sts2X#%bg|4}A}ku<#TI)fkWcs)urcdIlH7-I z-{yjNs5q59SI?wXUHYDnx8nWP#%^do*#)NB@a(%v7214EN$BY6gZk66;O?RTSpGwc z?b&o1uY3_8=OytB6wdYE^;?|ZC5<_xWK#E-|xJf z7s{_^wNv`efwZ$lip@M@;@$gnMa{v(Ml5y`_rAKhz>PO*w0*uUrf3a-=XXkJ*YI$z$=5dKvj& zY{DTO^8}lp>Lk4FgF^FvoJ*^7!D{X#zEjADujOj=u=8E8b$KSrKAEv39W8n``>D|1 z_XGyjmMiW%>$e-zp_yLzpd?F7=X%SDR!!Jx$R(ktz6KdI^- zF{P%!w=hlXsJJE4g86a=Xwg(tdFE}v?i;Sax?2+H-MNe&1vKH8<6i~w>2I2RraSl9 zaqWjoG42=}1Cvj22L28`R+aM%XV`Rw-fCJT%h$(_zr7%0%|xcjeZf&ScSEX7%jibu zChXhSU2eD8f{K%4u!#G_TRja(j5`bNhpeGE-HXi^)oIA>eBoe^yO^}565bwK2a9>$ zS+*l*8?Vk0$Je^CG+3diEwWSzT}V6+@*dyCi@7Cuu4%WTo){;mvfH26k+F9M+=^Bs zS&KIY+zN*sUA)=X)$wGfohox*W5ABRK8qE@#*1TrX;E+SH<)V~!i$V#=KpFf#lKdS z>-Tm>H_JXSck_POr^UJ5dwXI{z&-KA5*Icra4B^UHjz(0S4?O5ZSvqxGkpBYl9gm% z<-MCITcV~<>1&noa*uj(WP}Q-fF=HO&jlr}%`>n5h^b#3Ve>an7A=qC_sDShjH(;d zJlRpP*LCZ44##R`E4W)hgZNCN$vq6?4py$PQ72|>i^dCGAb`KS|1NDp@_Zw!4>Z7t zSwj^%_MAjZ7B+S{jd*Pm(BZ!Ot|K*)*F(+9qEm+~Iqhhp}<=VE1R({Z^Cg=A3}G$Q}^##Fx#E)S}ql zDm>p@p9XW5__K~r#l6wv+04d7T2t2|jLEu>YG1V#dz;cZ-t6{?c*Tu4>y#dK-*yIW zY&#-$O*dy#&)E{(t*_|yf@>t!`{PjuSLn3JjV5n?1`mt>6K7o_oDf$GDgA$oLG5NN z+n)2m_DKbedUfvG@WrNyDq!7VBehz;=NTOmEd3`TNkvC&=&?&2$9Zdinm?e5bEde; z*MkMWUP0xf7s|^j+sU(}KTYQPhd!T*aeePpQ0Lwd;`+(cD?8FNsWa@&S0T$X3%oNb z9A@n;qpNQ|pl!dCA#XCx*u(+zsq&Q$UK^%GeOvCq9lrnBeZZXMFVUp0vTR`{e|{H* z@l213r($b4-!s>L!2H>HLfdYxA?3HNy%*(ioI_B9WAz@=pKHM?gaBB{{Q6M!031rd7cg6j6W9? zb5K%K8Eshf0WFud34PoCkb6ounzhIr4cuH z5eDD$gNtq&G;O~&{#on+Lvmu+5Thh2dUH2KS@#sJ-T48%lsx3mpGY~ED+*^t8A5uc z2YXz+0)BB8WqwBb zbmsd%NVBUK|1&Pdowj!%ZBjVg%@1H-0%K{L>0!u1clNaZa=H;1CZG1`2KBjOPmwQ- zvCIB*_-oGwc(zpnWhJKULvP;OuP>;a=b%o8y4HB9zY821X^1n=4^ix19!yZD>P0u< zK!z_2^)O>?rD{~ax}z{$h3BVa+binBhml42pwllvGauOCaF)GplCX?lMp$LZ89|R{ zK;I-IsJD|a%PY^(_OVnPl&Mcf-Ha5h?+{rG(`rbh4^!fWw2$6QZActtJ#2;Vce*eW zp4DQ~!9sqxNQ*izI1VydAlRmOvkm+Xm$ayZFiG2tel%DpxV|A;Mf?cHGafos=mtZ9K)L&dvtOZV--q*#^h*PVC`>C3&PkSNiLJ0iq&#=t42$o;@Et<)sY?X}_JrJdW#Xnv0xfXyy z?plyh@59u_#?#v?PlYep8wvKm#bXlA`}699Wm8NcY>*M0kQ!51TSx3Sez#c3vp$cw zuO!F$i{u|3w3D+|f5j{#JS@iT^HSi+7(3X_waUY~|AHGQ?L^>Au+LqsF=faAm{`u) z9Wxg2Tv1&d%{|dw;_ia!C?lwy&GS)L@p-2qM>x8z5U;hDfMMSuFs;UnQkQt+frYi= zkFJ^&t<(okl+6W4(z)O}YXZ{`$%oCK^vI*>5hP81Cn{H)vCVu(d`SPPa9!mDmZY8n zUu_#W`qY8OgoR*DpPk|=-iu~chT`z9eIYE0Ysjyslc(cJna^=IEZ30BP35E40ybt7l#Y zQX-v3(KUzv-iHo?!>U(eX@EZqX;dS<&>zB}iV|E?zYV;@ZNXPRjcr(+PAlRvK&?=X zay>m1{e$s5eKvVm3GQ4JC2AyUQPHI@pf=0^{_IUV+OxXqWYcM7~2Pnb;LKImd}!A8t^Sw;lIG8lzVISzJFp1CG2igaw>Y-~6m2 z4RkN4l$EN}>qC|}?tu$L*&ASH`9Q_2QP9DI*}hAo3mLCLqyPdI|%;HoHxANR`Kl9ib4$Z`Ud0vd4b3Fv&`?7Av@H?7*qVuqHuh&;@KabYsdzk ze}wDYrDD()9olT9r?~%asGr1?>=MbN`Y3va&sB;z@&NBKPZM~wBdWRve( zQCOCxuyCp#Ew=8Cmu6^zb>&9dysiMg5A!hK0SEWzq_oGt>eO*(tFB&-&6H?g!uBuLMAF6mvwhXigq6o@nWpD~>y?Mj1RO_V|!KpkeOLJXBIim~}!X9pHj{wQh*>hU>wv z=bEfVat*uR-4116&Dq8*6?%1&>nG2Oc<53kjL9_w8@?yr<`9NA%=s?P!;^gG_w=ds$>a$1sh4>{VN_;Sg->)m)L&yhRpzt)Nzay1C z_ScY;vJ0;LKa$QnuEzfjRw8n`#rL^H+h4$K{m2k!?I~x?1to%WODSet4}k%`MzG$| zfKAN5iwpOfiI!ZK+m@pxzyBU^n#vBRt|JB2C_%3^7{9F81eQw<088>>_g8b>oxx{# ztf528osPp?@4m1+y$`#8MV(Ur(-d}h(q3cfXq1y)!h)pwR7jKwR#Wi!` z_D^k6Q0b1+r|P`l?aG#|UP^to+!u;9GU!giOMJw+0X=z!sY}@jG}s*>Je36Cv?5)w z{%8m>B?i=I%6IseRl25ODytMX)1+0N;I%-3wT1-H@+anae`Wzr|GG|IEBw+7SmT>- znBC6_7M{vr5SLC*@0^!)xN;G@raXrC%Z%X0r*P)^nez=~VbbjLR_yAWMHJ7onHKfZ zB0Fg%_)jo~SA}Lw&{w2*vn|4$id@bXJt40lsYCgFf4nU|8d@z5KjFq|eRvJgIWK;F zW=?&MKL!u?AL4Jm)401xiGDWK2~{mc7^GVOLqqIfN23)L?sdoEop*?TxJEjo$PXvZ z4gmWESGIdVESP$501j(@9 zdneez{k*CcF|>6X*L`Ug;MmDQV9Ik4R1WL#-ryRth23DwObzOAMNNLs-8a{mlDdw- z+P&IP|GG1K^DUavmemUtf)?%QeF!3(%^-849~*U9jk6683B4Na=*<&rw7i=wMyR;3 z{dYG~{gCCd9-2HKcnHEeGfilXDnQ%#?Xd2?Ev(^OM}0#Jnq6)O?FUr}FF50t>Hz5H zsmCtV97UZ+lf}K`B@{676^yLb22t6ZwcD6bom!TVceXQTEb^1j2>L;)6fwpb>3q4k zLBWHm1umuH2^KQT#C-0lm(Yrzrr0A)pFQbw9Dhg(q&!bdD7_k;d28^0>**x81H!a6v7C>pmq5;?$q*V>ihqYrkl$0HEDczvqqmUOn2AXf zHEG2e369IshV4J%*p2M%w03Z&aQR~}*1U=b*MI|XDb9v+8YZLOuo|&PP-nJ?d%^aC zrA(ZtO*U~ku*%a9hWGGemAtn*c~4WY-@x~Wm0GxI#3ON=S|}^~xq_TGw+QOTm8r3R zCoEshdo0&(Y{Hq9^rUJhY;$sF&lTfohf|PjAu6-8i*})jum_g;o3cI;M%3b4U#7H_ z?`$@?pHrV;5TwAWmJcMAW9DedcNgiG*1!fkdl;f_z{Zz- z!R9@kVEUPhXtT2xgis^+6FQmY=OvO|*?6h_F>AKLY%$IIsgGv6)v0~mMR40>0E^C< zv$|=Dv`dmI{B^vEc0I1ahaszAALrICSZsv{ZEuJX^G@S*;SbpMwt+X=F04x}*VDS4 z6{mmFrZ+`bVO7y9vF4}+yXUGz9lF;GtM?V)Nm(9z8)yUf?po0wO?Pb4*dbDZgl^C2 zi|tzmK~bJ7du|y^{Z1E1pZU08&`Bn){;UgMT6O7pWF-WI92CP`0ILd1AugBeCAzEA z_4Yn!y@+Q8YH_x|r3Ov^sV!WdR)D?F50TF!rj|PFTHR$lc*qNq-m1~6@k+R}pDQTb z31z;q%cwr#X5T)eP3VDT5H20A1CG`uROX~X-yX~peqZLdc!h%y9BTnGZ+N_ z3XB>_Lb*aA=7eU*dyoE(HZ1;*8P%V&hwgj_sJ_WrK9Bf*@nnN!OKJVxIO&`R+I)X< z5H%boh<`irn`YBxyj43wrb`ma(Rl&!9d)2$jv31zV#xDOGKGlouGs&&pPb1PaLS1G zSoJ{XueZgYCiygOj4J)$IYE8<>9fbbaxkwdUz)zekaX+X!1&^8G4}(Xk->D-G9c|wQm_F4~hZx zVng_}+l1Y)`+@7894hbXqd`C1&CscbD+Ig?W9rpO)Oc=-aB_h@woM!)uQPwmUD?wi z8_Cb~1r%LXC&y}#Ygzw$#QBPzzfe-GBs}iGbuvK~a&K(KvQSp~E|I*tD#(oe@-W}J zMc$u`SkaZG^BLsS>qH2%J%>F?$H@DWM>78VH>$wJVMgM%2Hxk`s>^+CO(F5@u+BC* zy)9EXTt6P&?#98Fs|O%&kOQsR6N-Xoy*R$wnJvzUB1bbznTeG)8TLH@oiFtP)$uya zuUiHBOskgmOx2~@G7TKsfMV?G%NWlm3a;vm zQw^M9xQ;j57PpeJCPWFrtr9k7&2C)c)(7k+>98HX6*y?Nv+Saa2DL`KgnzjMmz>Sm zI}Jm6W^X3+|HySR8@povtrEyAb7K?cEu>2!_XNcW>MVFp7RLWKNfkVQ>T`AjtGiyLEEJO?4GP->Ovib=yju8qGTwWoXLb+G>H+OB&O_;g~a}M%!W7+!JCT&nvW%e!<`^3&d!?R|yn0Q1a_#vc@Ds z@>p;PmaYCOj^y9l>kj<(??}Q7heAC6ir*vn9OR*9!#++op|dOP!T+7QtZdz%G- zwsr|^*h^QWkbzoz53Ng#>L~7|%6brw#P! zjC-aqSmul`D}10K`ygEA+S2lkD0~-11wGeo_1UJQ9f?L5u;Fygysk#do6Si6O z=edxNKYqc|s48J`RuyHrSW?>@V?6liJkqEQat+C>U}I)m(2CzDXP5uu<5eXXau|F7+7g$*Ld6(!5h|;lOC#S5E;r;MxN|Ts32R$9>0< zo0Nr*cQ_;Qn;DKv)`Yy^5Vj{ifu>$<7xcg8qKd``dH=I+nLEo`8bc5H9o+FtDMtDS z$#1w(y>(cRpM<~q8HpX4HjRC+in5!!@bXbCJ3c*)e9m%B!j@2+HgFUC-gy`@-gC~? z<00t2@0$3R>mg4cl2C%-VWGWJlOij2!Ol0mpmeMb>to9>u5Yzeh|(eHJ~cc)_n|nT zEsm|)o=!ic`m(Y{HJaC}6L#FS8QSI+(}|kTcwxOc=qtFf(YvB4MSrO5)<;V|_vAwN zw6o#^t~XP)VHnz=EW2x9$~shVHpk|=GWBz+bf5m!w~p}YLNTo$`~@R3+oea>Nm#4J zPVB$5H(0FHVRwTVRxfszY4P2=YUEQ`KgJVOIfp7rPoIkY&4d*msuX6?5gQv6V17E! zRMPo^i=w9p&9xGCvV9vmrA!pw8f&wZO)s$BdIx7-hqL$oiKKJY6H?rHHj4gdbQ$qW zFu10`(@Q8a=GCkk%zRD3o>KTgSZFn=0 zGe3JwV{?l((e3+Fq$ha}PS^gQ@ljfDS#T?VScD~9xMqUA>$U0UA`$*EOV5{Cu<9<~ zaZW+15D;I5t)mcjvE@*=f$ybX8{u=iYvP>95>#>e3?Wag;JvadJCPSfos!Rr_j5bY z$HK>;GfoBO&)|IEy+3iQ@Km@TQHWy-j>vsF`aK+J{6G9xkxLPoQIiyi2^uNm(AdPp>yT1<`YpRoS^e6j99M|!VQ1m>k0aBGnc z+u|+a`z|DW;=SC}(#>!++?LM{CTx^8zfILmw&Ykn~un8WpcX%gu~ znS?F;y%jG{8X-=bsKc~PL_G3(gv{!qI`yo03@?7^!0nzEOpMVZ#m8B~i!V-i|4TQp z^gam9?WQE#?Tb@;JP;ELifQG%Ry^6TM>xIV6wS0yqHpU>&|1Toel#?}+UB?7TTOHJ zb+#@o+4M@-?Ry5jMqGp|#etw+W<{3c{Nyv*aIO!rifF}wIoAcL$_?uM$efPF8DrAX zRc!Pz3E6xLll@+C0oN~C2eZ~1LCG^Crg^9dAC(_0zcpE%PIoqx?|YvwpTy!UV(Iti zB;mTDJ{E=cm+y9pce}C|{PwZT@d!IpE^X|JH>p`VcC3c zpZMNLq!w*zQB=VhPjta8GmiOmOQn>#JB6`rv+={@6nNp72d6(8(rrJUF{F7_9L2S- zRnyeuH7a+W7EOuWDc77BUD07_$3z@eQ7!GYPKOr9tDv;^Lvi!87*=;Dg?3NSkzE|a zwWiIVu+Gn%^C8{Yh=7gsTP;YY)LDsrSh5)>+V6sp#X4-bkBBedE6XN@n6iBjv?=~Z zU0G0^3auSrk7zua@6cIw5WhbrGiJh;7 zv@8#3uH}9iS3T0nFc(t!e4%jG5r>^rhALhsr|Yz$zupv~GFZZ@jWcj?{sh6|OMmQa zstk%D`taJV11$?uLSx7i&+z;2jkkKVrruIkO<}BhSOV#Mc86!2Bf2QG6_>5}DZFn} zV5x&-^83*c9|@cDaVyRb%NNp~72u!83*@>K#bQ0~EqaZcFLZ=^DGVbvRl{pTL%0$> zk&TRtp=Cbfq%+Eksd{ZIidTEd>{oYWCM=TL3QRE|SA$k}JO_IGjyZO&1#?XNiqAt* zg^NDd@zXdF&~6#@^f94?W;^UZ=rPZCC_$siZSp>93-{NITD_jWTb&gbT(={;h6fPv zLlK;t3vv9hBl5da=?(|F$Md0#9CwR5->XpgsP1Tdr9b>h^k7||ZlpQiilt{FU9jt+ z68RkWdu&H~>-iA=Wx<5-_er2-v0UfBhi9X`z0?brM>#{6J|&c?q)O4-v;|4O0u-+H zmhX`3{%Eo6MWy(<*#i!5KwP`G5d13I#25UgbM?^{ntkd=U)4g+$TaAO`xmRjf8UB} zPqhlI66Xq*$F!+}>rXA+Ea19hEgtdDgBTc1t|WHGY<7 zS}-nekKjE@LjBGULcR0|$WxTC4~D5&GBii})lZj>9(e}g$DfM%i_BTx5p62@{7Udt zxr!He-vgWZVX!|fl=b`0b?**W;q0zriapwb1IJw#Oj^|`-60THy9Gc={wlVAxC*tr z43m9dRECM4`TL6Bl$|FTv$H|(ae#AndE+_>xdiFq(_NimLHbm7fad@%F4`hwuF%JK zmt@ehiw77bxv{$^){}uv1JtW)QaYc7Tl{%$)Msn9@6|UnzAF(*`s&io#ip2hN*jL7 z3um1I5=c)+N%rqHoATf_u>Kx!g|h;Vt47m-B}wqz{v5V?`pf&GhY|X0WIXPS!h z{j^Dah9ai%-g07mBHO(*oy4-;!lm@NIM|W1G~G_Y%yL8WyDk}JjQMb6wavVt6E zSjeh-YtgZk40to9H?SL>*v=)jsHXZ^S{$!WQzxooa^7RnX+=B}I2UeyqQ2}#qbhY% zwa26ZDKL6PF$Jz{!F&&MD0uF{YOA8D!FGhqJJXS8zn_9%x0z_@&b1kHwCTyvr)8=W zBs8-kez3fadw_uZ) zT&7BEc;>A^#sE0=z@0hOL{Zn8BB@)vE53MLAlK9SsyS1v|3f%!c|k03BJ4OdAEut+ z-Zahw-))^j^L{OcZliftyp<1*Qtbp>^+TUCm1*-_US~`SaP%%8(7WpZW`nhua!fJ) z{^$+&6tQ*WoMrVd_9NSl_LLE^bkl*BJxe|J1Wo zh&g8lrt_z;2rXTDeODCn8z15I=40TxF%8~NG@uPXl=0g13~^y4*9luS$@`!E6Wy5q zu{AVNccrYazcCGZp9y=_e~4-A1^CLFb0AA?p?9qjdm-g~l?$fufcM_h$Od1%9SHY) zOXy~96aGCak#--T#_q37LZ73<#ko0Jv~@!b#9z^e<>3~r(qD`IRAdPY5AY1ypZs%> zrb1(oB?V~s;_j8T;@-|Bq`RvLy+7>{R=!lDqhI|oIC&PF2~}gh+mmqUl0(w$_1w#1 zcn31y-4osQ%~`gACJElJgr2^67`?Xyc8`~VzmhT4>~crbeQ{#HH^o#ppb2;VcU=gb z!o7FtgRw(g0I*A|m{_GiC+fpw`t!^1$d<)Wu)z@4{xxEMm%hT6M-P@uxu>tgENc!s4N^Or$AiOt77c>gGw1dn^y4ElQ|Ed=vJrT?TWtT-d6> zm6Q~0CENQzgW5W8fxKxwA;`g*EsS`GZTG%NzkT64hgS;RAMsFBUmDBC+ayu2R99xp zKih>N|DKl=82Pi9{!VGaw8iFNaMYc(sc`?!?BTK;{#+|Ah{J8VS#V6ljQMxu8sf$E zWhc0ov)^WWd^pMp7IZD4*$0|%YjC?%ae)eZm9Ys8e*1vLPlFmS-Ge2!`24lXjD>H~ zAoDM#!n4U*lswB3Pc2b{8-q&7^I{YJ-aAD&Jzb6E+HJy=x52{W^#ibU^moxDMISym zn^AN08!$b3P;?$@!3Lk>Kc}aqZ05caik$HQm+Jl!Z1j|P7_lGy<22surpD%%C!lL> zp0HK90Q-#zgQ^pDVAR=+oCDv$helU%@==BhKUKo3>jrQnI-FhSKK+<*Z`loBQyQE*5ub5B-rX}=6lK79LHy1ondHfIud7jqs2st@q8e?EormPrt3fzo zOv}ex;Dz^(M3a8S7&7)f3>aYv)mB~E^fRj|()66D_RxS5_m_e$&uY(HR)9)Q`(Wz~ zYw)wwqscKwcta~u{2Ho8Q#N~G_+Wq7A-FT>wU$bhi=>LXUGSInNqKK`z)FvnOeld! zr@Xfbyr#*b-kd^L z&XDQ!A0oa!34z1g#P3`KKV3J8UOoEOcf>6{+PJ6>ei{KS*1(KdU2i5{G2n% zh9=ANvOi9m!p_ua(wpO=U}{i{I~oqlYff+OV|`nph(6sjMD^Eh?8doOgb6EUr_bus zmrm*M_iL;8(Yg@TF2u|0jO7d?W_UuG%$-bO=^JJ0wc7$Slm|d{7d0kHi^t!yhl@pg z4s$ZTFW2gK>}$#NDmBP1W|uJjtUkUJjUjYmGDO@qrtQPKV*HvrVvioDIgk1SmY&)x zG;;>>HHkm=IT-=Iebw07L-F|6_mFfRe`eRetbu2bpNbe@&IU=;Y3zho!rEt?8&gmS zs#OAfiZG_jcX)Q;gE(=q^=T^6{eS`KRl;h{PQ0WUfWO}jgi{yK;dhIfbcNcdo~&U-6uEHy z^cm2g%{%j;y1*O84DQb2!qq9X#ZuUkuS?m-4CS@O+b4wexUqqL@AxC!NXbQ~*U#WJ z_qk72_h1b-*HT-*B$%9X4$oTjmd{fo*6XqAdnI^wkcqg2`%mLrzCpzVZ8-iQfi>?- zrs2t1!pj#OsA%|DEU|bZ9;tC*-`R4S|I|wM{Cr+H1?-pkPjeo}-jr>k2W7f4@B0H-4bSOoIdvFzJ#%AU3RlT@JGl-f6qvCc>L(Y7 zo>NSj?kF|77f@HWbeB3ga~<+O57GK^2c9oE2Nr+r1i?4BA=E1t4YhqhJwu(+uHAy9 zhaRxoir=<=t5L}+Q$dq6CsS`Z;Ij9s{8pETNBw`o#k;N$9<9b6zlq0qz41cN$^m%i z+*i@1OdnPxYch>%cQDgo8*Kb!!8XKd(83#*vbtq_KmRlkWp_J)*=+vZxEYUu7N>+T z&SQM&5(>_*>>%QnE(;m-2rWPR)MTX&CvfY?u3&H<@yx>G(73lvba1y| zH7-^(+Iw@~s!hf;EJ(nmJkz2o(v`WkEG6e_PlSm6T2yu}0UDQ>fyee*)UZ1wpM&b! zxZd7Y5p^rKiBqloS!Kpr8vjfIV4*H8znugzYAxc`NrgOPJ63)l@0HFovQ@tEoE$w- zL{%EfGZTBK41{Mvli7{lTsLw$M+)cF*oF}?Xz3Xw`hC%+wc&Tbyv+dKg_*HMimH?u zzf<^@V~F3AjUmQ(Gu-wyq0`Z>xa8g)(eH;U#mx}#%*+`u|DYPX;~Rq)_Z^a^sB-`D z_q#Cn=@ZfHgB6>oph4S@z86|6bMcZ|KJ<nO!K1+1r@!`hSH@)^f5UXQ`W0yOPoBA#yG&yZ#lRE|)GC4N@yw_rn) zM|ud)?oGn5_%*QN&q26y#*{u=_s8IYH^hBgT-jQaWh9KTmiZ3nZ13_-a;@Fx{~uJ~mP81&O7_Z)BhsIx#k zk>kdSvX_%hVxX*#PG^d}dI%~HSBPyBP1!&z75ZUTS9acBoorTEV{cU_h)lFc@9{Gs zAkasMwKsIDRj14Ssvy?H6XF%kSoA3s`q|G^=n$YqHOBT>Z>9#DIS1_9 zpRe$vk1HfL=(FpPghtU3!qwsdXqek1?=fC(Gp25yk0G#VpXhap&q}9MIXlBrHe;GL zE#RK#$+J3vxb+X|uUvwUt#gF*$O2rX87!|4fk$*%&pvnXgGL9a+{aMre-U2A8o~T)a-Q+}fH(iDM77|FC%-MZY zRp~>GqRg?h5N*A8$#365tL^E+WqUk0FH8K$HH_6<_c*oMA0jyad`0CdI+9x~O^$NG zLE8_C4xkI$x=NVR?QA^Uz7s6deOM`fcJ?p#keQnkUix`NuEkAz8P8&Q{zB6bes5FN zq}SkqA4YV7{}Q|LoV>k)9;1ZOX^w^G=|?+5whxc8JEVQ}DCWM_jj(=Ozaog|5P9 zaqN6^<}EYlaqTI6r@YlA-S0j)w6hv?=eg~+`ywgj z_`-VOKl55tzqB9pCZxg910BdQTN{Hn<%pe@4`AL6E2(~@0?e{AB8`Q~(7WoZczj18 z9yi+vU0Q7+EY^?>j`)KH8Ya*%L!A<;Em61s5Xi}!%=XkJ)AL(7(rg_GJN_#QpJfG! z#oT}S+NK(&{V{~bdAyJPq(s}7?-XM9>S1dnXG`cL!Km9t^zMo?o;g-6294yiDSvkA zs^>uHAYE4TARcpTa;5Qp9ce=67Wk{60NS@L*iL0tN*eV>xXyXkZS5zarbG&p|5(uY ztM0gPSCUvgSVGBC0nMxWgTd=B6sZOX%S-|C>ZiU(M4@nRYZYj{p` zGJG;VkH(Wc<+F^ZogSMLo{QBNj79x*s#N{tHO#J3gBTMF*6p1+1(dr9%yBCAoVy<0 zUpx$%<;wi~Xy9l|6o7a!Q}o_dkV7EAL57xNfk1 zb}ML1zbDSgFlW*TbDBQ?kdWeY4UfjYf}bs;LB~0O%^A6t!Ui3MNqs$->G>7(A$Yhf zd$%1q4%i7ZcU}-*{xD@%wkVO`qq?#khP=*1TH@vFoj}sf0k=M#4p9o7pwl}gw!>j1 zF3RPZR{S#^()B8=O!owj<0fqPJVm;B%UIwY3GKaPhqW^#ptCWQ-8sIQrWZA~e68Z0CA3Jwd%fGX}UP#n?^#~E~h zuMZShlEr_RU3^4%*vS2@siPpz&mI()>9U~@Zs69l{F&0Yh;OeU^e!;~+4C?~fon+S zGf5h7)sTE%4o6{<8ch7D$9>r+Ao-v<^x(Q9)13+gPY( zVslNEINrAe*^CAlyx$TMmUX1#ok+eXS)EmcG&vJgT5RC@R%gnZ*$GeR9}pd~xhL*Q z7o4u*58vuI+pzm8dZ2k)dRyNWLk8`Ya}RXRNti5aKYAu)!pA>cg4^>DD9I%2XoT+l%T0llh-yA<3(#-Y3p^H`ESGYDs8%E1BG3|RAus;`1VC&n} zLaS9Rjz72u6bGcinB&^?)TISpcHbh_8wRjy*HvWGpa{QWw5i53TAsn(xU~R3?OG?_ z#|Ci**Y}g(al%n!7;!j*%?M1V8*j5@H+c?Y(-<@C-E|NszMjNv^Ao91D@VF_h8oMX zTY=A_hl`)MPN`wxHTcI}vF~cmV#5@v*fLYteA19o{2lSl{hQ*WHZ3+bcLT0%J1#vk zLYu1Mu7c+K$Ku8ZJPYY6&+_j2MmY327pHVP0b{upK51qL+VhHK^bMKI)!W#+!~XKOjvDmzvl=SB>jG8^)0pJ% z8tU7Bi|~7^K3;v|1FuGK9q)B7mYK4WI&FUoQ~NZMM!*C-8L1}Qd0mSS1t*Z%hwWl*_;Ced46lDh_-B``DmGYis+_m!KGb4Fc#y3B~)nh8YZNvL)3jUwrY+E`MJ9aud3(b(e*JPuFV54E6$2u?2Os3 zN<<}zC+lOpoMtN9%lZ%3q1W%CVNsDE#LP2ba}`eFt;P4HqraHY&L8bCM884&kj-@h zJxr)3AY0H;y^i;%Hh^u$81Rh&q$hO3&)2^51Je$S|u4+zYlN(cL+k(A<-BNq*9h(YU zG#%k(tP)dDScF~lyF=+Kb=tG@4*~oQzmrjPT%?pw# zT3sURc`p|;cYl)C5SvZEsix~}R6R6As5AA)1KYU=h0itdhd3)h`yMoG-YYJ7rcM?U z1+-9ffOjXqko(hVsPTTE@Sv6V^F|}(HRMLK4%4f>j!VoO;GsD~Ki+mXeAS22PoZoL zpVt=mnJA5!>BV}sub`D9I^b`YHhPyHhVchnWD4A8ozwduTo`KrMf3WyK73vd8C@V$ zYUxqVMQ!|QeOpvKQ;6kzGxqZv zf*NVhae$TlcI$Jf^KKBR6czk_@} z3Vp+Rh<3mDcXsP@nC|QX+0RXxn$(ai%aZzfG-;6v=c`*7DucGMC)1x9Ny~pU2s4#= z4$G)D@|%vkt^vFC-x2&8wOY`8`Uw3-XTbyIH0XCshn+b80gqbp{FNu>JR8xNW;c8k zE<1#<4>J;J)gyhVyrWK|Y9qmeXU7lmDCFP6Rq|W2dW$}r=G}@ny^UZqsnLm7#`rQa z00!htW-qw*Y0Uf_smXU$rhaK5dS4kPW_{w%dpSaQ0`~~`m@`>OJLaop3i~hWW0#TI zu#>%T>8=U#HJuYJ&X)Btd~R)!%f$ICs%PaJia!_f*{mzP!k z&Rd;ssi?^BI2%Ump}$2p5cax3d3raN@?bf29{CPj#x#;n$tZaZ`8Y?D+N$@#6%QZq z;as4M4;47_WScal8^6CaNaVL;t?*FhS-OlYKK&6~gS#>B*yVJ?Jq2?9oX2wqonVBG zF+5gQXA|}J;7@NIF^g*ea_YH8uG=Kp-w_fDvVQ@3i+FZqCjWfD8BoEYF2bBQ^YPyE zjdHep%uHii9nlkYmt7Tibma5G&lNE6LN9oAk>_q(9>Jbd?@2?rKO!vSy}aLe&ocrp zxEYbnlx$(~w5vEZ<_Q!Y9|hB@L)pqjNi;vd45lV^WhxE-(bU>N*(%YTENnJ`S#XK? zmOt-95B|bm&5z4u-T7T0%M9N?bb`P$Q&^`CiPW!gmoWFP4QjYdg0jvIpz>6ajb9#t z+bp>jT}y)ozd*UZ_o1&DlNJBQ4joJdV||`kdDH@kp-A0h0?`$SSPl*l3neid-0nR@aN`_{CG+aUN9}rGqO8G&1c+FqzZHgXK7(3}6a)TrfYGno zNH2CQx*Xptq*xSU|J*_Hx>3M&tsZm{um7@xM%#?`e&;K$oGOUDJ(*>dp44FQ>OY$wG@=K0dHAgM%sdaQm`^**EUQXayIrT%p5S)h}Ye zOIMk-v4nhY)XQtmJ39+jB_m5r)bZ)aqvGQA7VHCO!@fWHNsuXq zv%Q5$RQ22lMlDpQ!Heg?jGf%8sHDyWk4#kjS}HsVEX3LcOXc;a*CYqJwNeGQU+gH# z=Bv|#0%O!YI~Wc;n8aXcJoy|xBpn&9%6vR#;fR|7j;MbZy92Vj)Wd(^u&&=A51;o zOoh$EF+cpiF!|*LuE7}tFE|ULFaM4iakk-&`mFMF8D|13D$ChT9dE|6#gIl(dyWbY zNA=~p$ViDh97r-E)5AmXauSLU?>5rWwL|ewzM9PVrv~36?Sggj-rzP{hlTLnUr0`y zboK^q8f2x$v(z=AVs<=JjM_@>!4|TZUZ?Ql{rj-KqX(Q`!1;~6zM$->HWZ#Zj}MI< zU}&`wSR`<*TFy>9c2HY9vOtHu`^B|t{*z>by71lewxF zuHD!GyYA&d`Zq%go#u_w;a9}?oMKuX`vrfz;r$HfFxVgePtHat{VHJ(9Wrrk$Q5bE zHGR^=CfL_lEAHf3&mL+9w0lgppgrOm&e%`~%NLA>_P16ve6oPHo-yLOSHN?7lGLbTXy%;G+@VceaXvfZ2^Q@7d#m+o_dusb1akv-2@NZ2jtjyIo)T~WUoTRm9I;WoikNV?@xevqw&YX$ho~?5#=b`9) zx;V}{f#rWnr?j=B;F^O5ZItxJBiHP~df7*scs>vVr|lMAR2QPtyaBNJracVkti#+c z1Lm~aLGNLNiqU7lS5qI-v%=WiDU0b?&_roYwk;hn8jnS}`VhP5Gp#Bgjv2wOGILj5 z>ZZ8|-mW!;qce0^Z;puTI5S3=TBuDM+Zy0W<}s)Y*P)-`s<_1Gra0|;5f0w-2t4#G zKtHmWtUI^i^How&Mb(kIUn`c^u{^HT?|u@nvhAvH@J}HY>!rziq@4ZEnKccfTakpNeb2!2i%W&pc>a!1SS;tXJOO=ncjY@& zx@8F0iY=KhXM~#8*~=<&)v4yaA%?#i44c}fvXf&s(SD6%(s2>|ZU}AYdp1yZwoHX3 zriEa_g+MX?ygqfGdJ+CH{6hjQShVmBAH2vE2F}ny^`|N@WN8Ah`{wj`h$HrR_dpyx z`V3YEe}(6(E#XX`Ulfr)3e`h1rG=W#WDxZn4xUhg;A57oJ@N;>e)C3{$p`k%r$i|E z76!5V%~^_`Be~RUf^Gp4I(yj{ht>3hh?7ke91?&l=iL)}^(eyvr(ts6<&eQTOqu&& zOLDTxAC@9susRLVF3sZ1t#LfVB9)fRJ0_&v)W_Gc9`LWGjqxg`oz|`RBz+DeRy^`x9Sbdp?4TsjrYub-4{ARbKJ8GS&6oa=HQ|X~rynZZO zI2NQum5H;V`F1b3I9S5=$7OK;ZH4r8q#jM1_6E$v8gbMnbLKmqXB^+n7TTk(;p^N- z@|tGVBaDq1lt7>Nm4VljVsch%L%#7BnhyUWUG>qZvzTWsUovLv+FCH?S4~+1=XLMs zV}u1#C+K>3Ds%6&iS~`(E9maC!}8Q3WcN!V)8<-*9LamQ7v};-;;fQ1DCf+^Z_E8~^xBRv&EXqW^bf-0x%-8I=Zete zWq*0rd2+H2u6P zK7WhFCGUA{JY9x|%hYAV5)ni9Wy*I)kq1rK)HqGrb4L|6De>&Mh7Pz_y#vqe=K5Zx zk7$vuDFjdF`9AA(;q*=icy?Kh{T-c(Z96-|%Mu+Hy08q(e!I&2KdTejK7#B)ZUDQ@ znDHc@@uQdAx8HPi8Zo{jJ~`bkF5sNBo~j?QV_Ag2c#hxOy2;!(Z3Iof)mYNzR1B}2 zE!g*~#k$}$`3$&1#gI(ay@7wX@73$g*)La~eSD@xC|(xA9_-^oxD?VkYARc~{1jGwtd{SwZT)yQZd?nd&eR5blMA@D zg=;Nu8$<65HP*o<6&J*4iDBHkp?a(aA~$Nl1uxF?e5p+@R9yvW@jN`Cyjs4SvV37g zWmaCe+M!Y$$TQY|f9IK`E3$<#KQyT#VXC}0yLVcRHTO$JjR}{fBbyEA+r&4}YkZx! z>Wn$74$~po%WUEBr4VLa6-ys_oCkq>98A1EV(%%p1#5?2lwTi+RVLd&Yn?Is6w!!Z z7S@z)dBgK7dm6}ZWCt8=(Jgok2s{&H-{8M=vu6;t*1Cg&f(}_loriN5y?NG>4RiAS zff`^XEK%2^uBB!;tyvuuXNI#;=?SDdRztRHa2~!$e*-HcT)6h;13g^S8!7|u04!^r#$30@k=3GOQcJrM8uh*jr+pkE`<O9rWc-CCW9xl zKG4+RJ#moZU180pa;$RmmwO*l1{ttxf67p;dT;sA2tMxz=ELWiO=73e7&bjTk&?zA z7WPK@(wuAKanAEeIQV!m6$Uk-$&oqm$?z@hZ}P^85h}9#7c^;kR;pZ+99`3i9o+Q* ztqvwmAt1qwW*j6c5K4iE3`p>dKosE z8p1DMV<^#9V*&h5o&QEt91*8Oq5bN>VYn^~erdrvdTZ0UYi>f1jV2UQ>4`PA*TfDF zi>ZHd6Bfl~3lY9rG*5q`oHu@Ps2WRFNXA`>k3u8!jT1|HDP%eh5zl85wyTF#(M!LDVJLOM8k{M7 z=3E-*sorwVUL$I;I*lTHU}_5!4p_2MW z{OIK??Gk28!j$c>cHj}wD+N(oI|K5%8vt@&A%0V#hNUWC!M)=#ruJB-(-Brob()#_EG=@Jh`QGF4Ss)Y~{Ll{vxfYzY~<-h#U6E^wOrolSa5NTX9yU(JQw zZ-^amVUr^0Z7d=G>_(hBdA3luO@~~sjFo%R&5hMq)%SQ@s2CxbJ*&mhoM-Uwj^-0& zMv9hi;Qi=K@%wKx)`fF{Une#TF9uCxUpS}Q^oAkSpDQ8T#zy?KQ9;)8m?r6kkA%#> zZ^W%GT&t;A%FaY7Gpz$Wx9jj=@miG@9e7m$OZD|(@p$eH;W?Yx@u!5I zKaDA2n+48ltQG@D7Necfdnle`1|?V8=zkoY1zS~J5QXVWUAjXW2~kN!<(?~wpWTXp z3fSGx~Cc&SmdxAGcH$4%e z#^vLLV=~a|Z_M8Xeb(vtC9Ek;&hI@3@x#c?aCYvpEijKe=1dTk<&FmrkEpLASQf1CH+Uhs6ubqqctg$OlM*e&N=JC}IeE!7dXtdV6ou~vGZbcwy;1#&j+LkY41#^U!fO9 zZ&)tIjc6n5@b0MkX*V>iF=i9`zQ=c2rFr4|v}jMM6bEf_1#gUEH#|4ekcLA-)ID2t z_&o^j_}IfXr@s_@RY1oR9pPw>Ha%Z|9<+{lL!MD5b}@%%6m|6yzNYKZOjDjk9I6S6 z10&hB|29xRdx_kAcm}SNm%|iY4{+^RM-^8)qjOYuVYy2$3|(+Tu~VXCo(pm160E** zKvbR=$A<3TOfw!1fr8TeDX&U?Y;2PPzQNRDt}A4 zFZQ3WA)V_{BlF9kWKk+S4>F>aW~vx2J{6-bJ~MU6*lqx5`&&Ts zF%35A(ng&Ag3nXp3+&Q69x5$%!UqE#wr;{Be8u%7y*pa7jABiakNqnA`ZbQdptUq^ z1NRgx;90J{`@-(sRieQO4L148Ml8&@EPU6|XPd%GaZ#2596n&ht_{(oGMT*`AfeAdmMO)lcOXd5K* zW0#+zbbB6{=*@u5DK_-l$qw&)-Xb2`rbe2-J#e6D5FF)x(@2wUV8ZwF&$%}5!g}tL zxt^Rq;wj>N^;GD!tzI;;ux93aZE4AiVByE20E!M6jwdICGC1wV86)S!Lhou? z#i;TIA}R%9Xf zcge)Y<3%vuy(3h5=~7g&ALhLX7eh3;ANQ&z=*%>Qr2jP8qv5f*(OfDz?a`rB&W;Xu z(*+ZLhsxx9k3li+Ld%JnoEtnBnp@LhcAXhzyz|1>hwh3U9dt?MVt<7PbJJP_W;1RZ zPM=aNQ+i`hJETp}b?O&!XoNZ2z?u7f4N?S4p9~CZJHAFSjL+5H2%RM zVa#?LT=BIZyyMBJQ||sHAC*8%lJNb!xeh&2PlpleKF~bVoBga;BbPaygc_M11;rWQ z{Ra~G(0mI)3=Hm;xna=#(s6dl!e`er$xc|ur*gq2-b%WHSK6q zBEgDhXT|v={n_RA8uYErPrix2W&57Y6ERi{%o@`*)6QABlj`pHR@F?bRJqRZY<5g zx#wcIjkO)vhnn#WEEPPNxn113Q9^rGTVdY0UT`rbob5^7LjSFNB}?AoiCL@XDCVY_ zW1VPb=VVB)xh%fb<+06W+Z6kpUlyE&Zt)lAxv0X=?;2#Y#1b=|?4h|l3%3paE-pn! z=vuUkH0Kba=9?4=2gc6uZx54eQujj9wo zmZW{HbnjjVOy9Uq_VICh3a2{&H7aoJy+5nx8367z5_!5^2`;;L72b}R0ed(bWWyYL zY|-2yE*~nPMN2#2s0VVm5Ut9DGXa>pxK_|Vc^yai`6_&ullSSfMJqDU<7#sL+d#sz zTh74ym-V9NBnx(UmjzYy6ND~H0?2R45FFAW9CsI}(3MnI^j&#QJo-SHl`ru_`!-{F z$89=fx;q9oTLi$<$p*}5aVDC4`!3Uz@}J-Jk5Jt~1-#2FS%Acf>~>}fe-bnB^mxui zob3hj_PP{t+y}4h3Kwr*x{hI9svv1+3RQz7%xBX&tX0<)-yf1vPn$<@$wm*Na!i@d z17%XpZZBldpMk|!W_qKdl@h}(HHszTG8F`PPnISooLeUJ2h8&;-O=^ z;IK~%9sWEGwXG|J)@UPkz1=gsclT*t{6uZ~v{f6=cWDo;*Cw$3AJ&onU#|I4x4|VZ z`@k%%b`bpMHyz&I83%}7V78)}h6&TK(?NZ?{$H+b2up=IWBnjM- zeccYy#albZe!VK?xWxQ$p@1>m0*QK6}j2kV0@N?yfjanX6SGR=`tfQ-K|aio)v-Llv5z# z{Z%KcZ!mntBT?z$9=2k^Zt9u1K%P^ajV<$T!$LI+sQw(nJX}|h-T6nN-STfV#K9Hy zQ+CV0@^`J(bOSW{my6ftXQKhv=KW*oOx~$Wz0Nm6>)=??D?mb#{uXGg(+ei?I`%AY z6K%cxQf55H6TeC)D{lQ=cDs>Qaxz4uUl$*_Bfi+ld2GiG;C!ADGnw=QqjOcj+)Y9u z`Q|t>z#i<&BH3W|Z8SJPO(<^QH^evfiduAMfGV?_ya1Cf9T4WM?3xW@Hfb>sh zY!mOh9(~*tG&PLpE-kR(S{Y>k7oKyH(G|?kn!>@pzsUCeG`yi7CPa6AiMtl9SIkhG ze6^Y1kU~87dNbUfXUVMUROm*ZMj=UQJlhtuoH_*=z}zRgbU@xik!2s;Lz(&SpM$~v z=LP2}`po^o0~FqH9ak;S6L#0YN!R-D-(@5_ow|Z<6`hjl#x|4pJSVJ->L!}pX(qRC z(U^G2M}BfIXGJ!qf%*AGo+B`8v#~oP}zKUygHLd z_q=bQ1*7dT@@I)487pGxl}?KO=i&u@mT~bMe#PW`>0=3XDX4-QoIMr7^Sr`dn$oK2 zG9hha01dAmh~}E%Si?Q#f3scDe_)!ZQ{6<8EC-BurX|-+=9w68)+y?eb$bIABTq%8 zncrpBEfUIC;!K@SYOr&TB^$WVoMwH=5XN&~z#S_FHM=`NW}iN6@RQ}VWquM&FU-e> z*}ui9b*6Ckx&{k}Wr)!_Vh<%iZO~-&tp6Z{jxl1-rN#L5(9^sp%G$I&P*ZV#pXd?E-fZC+ z7UPqJ^U1bYw6_n8T44v}vA>BHx#RRmFE|wPm3Hlj!uut9@`l%ZciNffcJaH_yiqb{ zD`?TcZ{39`)FrJ3ZT#!10fq4ym~iq1jLdR}Q(3iC&N-HWkGl!|Dth9PwrsIWoF1&^ zx2iYuj-gVIonXebXK#bdNRn172CvtmMRG56Gqs10dP*#|vnSfQpAt4s)MN&xDVVEj z1*CQwIL&0b$qa(obM|4FxT6=XiVq=`DVz*s*EDIRbvh#e?&05 z#Lblds!F_^)Ivq>&Rn;&Tb?`Jf!6%p3++d#fY-Au{Mch1Ozvv~0l|7~Dt$rOhd8J? zv4`Ew+eP|EkI1)d;riYV7C3cPFX+j+;)|wirmwwT%iawCLrJ?P;?LgO;mujZcP!6G~7u-4lFvSg}DzlxbYMZ9&_(23}QejUz2pVD^;p zY~<9~k3e_w0Sb5}aJk4{=JN1{)pv|g^ zOr^!j6PeNcl{9(MS()XWX2SJ0Sk$wdm}Sl1&EXNK^wvkNH(rkhn4W}xxdvLhg4p11 zd^YsIE*NsJhszgjw7F6!ZjX;$&e9Y~qcpi=2GHAQ$2ZN;sY`Dg0?sfVu%Ns8t8)*e3%he$Hg*o%( zEc-hu=|b#m&Izw1g2y*^Wz&nVnhsv{4T>Cl0d#~`iI8}@PC!q?0~Or5JEJYB0x zzmhbu(>-;tkI2CH11&S>yM^eT0Nw!PwF>RUB|h4_tFp*@&=29CT$1 z{9P+$OG9tso^QHx)lU)%deR;~_2nJy$Z8{qZ)Ur<43p%|#7V*H)4b zXF=~}cJhj7DOIa41!Y%03(GaxA-g1=?YT-&`>jjOU2nhv^p07CO1o94m@;$&LFv(x)xk;M^A# z$eW_cxx`60UzrI;T3M*=v;_W4u?DHO9`mTL#n=sTu<)cNC0sJa%h!6tsFPtV#3qj7 zZ@rKmZ}h;<1BZ!)oA@0~_M2xHN8p}A+u-LdM3u#{in??+%aEP3YsAV!%CLm%|EE9a z3_Q6bd`*mGQ|D}=6&`8AH$0Ep-p|CrsrFE_T!mHIO~AMLj$p?#KH}%(fn%II&n)Iy zoOiyXbB9eqfAe){KmX8=Cn|&P?s05@cLLczmC9B4eadFKhe8WfJoF`c#x7ChDZoA} zHlgSbF1Xqx^yq3ugNl1V=ch`rV1F}h{4xTMrJWMyhf5i8hHSfIdhq<Z9IZ>>Z z>q}h>i-k@QOID?l+YT5|*9|`No!GSQ4*2t4t?)n< za8|4f6oi<-sTv7OxOo5{ci5AEf&YI}t{331(NpAKjd?9S_68bjT_E$38S|NDK-)`t z2wye?P}Yq9aCUMS?z_yrJY)TE&E|aZ)1r@*Wh%vqGF5q$8uwq+&r@i4D!ATn=FQEzVxgw$D%(vjib)@TF^8L(ILlWPl32NQ=?jj^#(dR_;AIG}!outy=G`M{Z@D_i! z9}YK%_#_Qx`rmXs?5HD-@aKN0{nr)R>B(QL*zCx^Smx~|%$s9~F>)P9DjEqMCEWM) z&Jz7X^2HW=ZMtCR4mx+bz=v0V>E-2dnEX0dcHyrc{r!Ct;+smvqVv|QXn+!hb~+_I zeRv1ao54e#IpU<{LTiTmq0Z4wqW{%q`uoU~A5?e1rSYFBeEVQDihCt243M(Am;xMI zbuaI@p(btZr-J56&Jg@Co*kUHm)>2!EpGAX7VY?%0q>NZ$m`*j^)>;8JW z`F;>~oTMWklBrEr<;n0bcRT(c-|}<;ijg`(T0Os~HEJllq9p?}aFR|5Y_W6)c~%qY zZqvsZf?TLe?1^{1Pm20(dJsNEl`ZSN3#W|ad}+>nQ!^x-n5!%Q&A*4~tL(9`kn`f! zR#B~|7GCR+D7?M}dIaRm3_4xFvn?YLA+nC9z5d^&NZ z5Ij+b&iu-Ut%j$;qk{)ckJ85M_1{Dv&JMaM;s2(6n{ak%4(>2wU}t9mBRQ8i{(L;` za<3IHPi-QbaeDY<%?^3+C;sKD_u3EPsKh!^ZhDEpX$CSMo9vnRGNH^-H( z%#mOy9v0;h5(*44!WkEWA#`8_d$}l<7W=)Dne_1BISGBl{2D1-_5MXCr;osEJap$?<2Ds#j!So9!{?P^v3T+^F6!sm+a(xV1CcI6Ej7APgj#dLSBLGA6J;ygZJ%w^=PnP zkZ^xz0CmsrjebkRxUQ6E)unaB;=2+EoM7idEz-SCS?q=4axX!PlXr)(e_NuFHKAPmWhJAge2) z+KzWT=Fc3C7-+DiH>2=voVIwMb0j7PT!R~^30J|K8C__>$7|h%s==nHRGyTH=!ZAl})aNiUY$!Bd{6T$b>Yj9(4Mx5ux@90s~kYR5`A^Z1w8ZMY?a?ycy# z|PwP76qg99HgX$3dZTy z76A_a6U4POEz8*7STZetZhUxJ^PN((h!)Xir+pGqY-FaTv zFB|B>EMVBiFI2OzH~ttsR47q@fl=qCK|k*uJP(NXx5qA`@0QCSKk~pZngF zo$xE5er9Emlwu;*TyLN`e!+N$I?6kq)}~1LBX1kcsd-EfZxbveZOg3a&KWotSp!Ga|N`sug+v9-&GMF^VmBsz& ziYvO9$a~xpap7hw==sAKR=?3;*FNpQyH&gLw+_~0$uF;C^8Tsvv5A_L>QM$c@$Err zo;mxqiQl>g1qqr*0!YOm7=H~9L;EMjbT+^nN9+>Cpm86_+W0RRZdZ}}4$!7Z(|5PrGcF$f7{ba z#rP4tSL~SU_Gf-O)~Eg_R=?;hlvKHxQuM;c3s6*E}=L$A& z?jw%}fE3e_;JnO&&Cqb9ga@mk_iR&=d2yaDJ1_b_s;42RzXx+{3 z*sD?^FB+yp8`JkfSfMw}_~Obcw!cQ@WzIt1YAHR>QpGj*HDHum49}|AN)2`GqZKp6}~;ewJjQE*(EmEAHdk zMb%r5sCJ+o_zkF{^Ny`x*Sc4DF67|!R4L4fa)2PN!}Mv`ifR1qdv&q^Pj5X4T@M&Q z^)E9Pyi1$R!VP7!!;NUc2QM7=MiuVv`$V?we}n4)7kTM9DXoo-gaLg`!Sw41FgX|wnd!p%il*=8ER}hDfG;gvg_Zj;EIcSaC!#foc!~!+f)}? zBIDVl(rq--tVrhgy@^~l{^cI7u42DipNU=Qh6#VXufIcq$C!ZkZ#q^}{n zbeP}wzpaDXr5d!#-3}>Q2C;ixnSOOA%%5T+@7Duy_aHNH&^Lu4oCjrbcng+|-j%E-Jnp=nhBwf7ZpZtED_nqy5v2XsY>DH8pbeWZnvU!ik* zRe4`+9del!rr-qTuGV0oIa{!z&qrBb7b&e6@d{S0*8*X!IjbM1O|9B#LjLYd46MGa zxR;r19M4{z-$?VOq{D{GgpJ$pi50~baHCv}Exb1b9Rsw)sh^Cg)DYo#jWJ9aYs&_o zXhFBQPD0r=GdzAyi~D6GU~MSBr_Zv+s{6OZ%m99a{$KzL=LW!pqOatgEW?VjEZG$U zC;FRP48PKw#Xp>J_x2?BdR@&GZf`bc_iweMACgs&8^S&Q_9k%d>q+tK_)j$RVORV! z_k~ct$dHx2zK*I{Px79hChYp=0=Sk`i`|kovhC%Y$R_%-@ZUabOm*uD8xGjOC;CA@ zCaa-ZuqT{$ucpvge{8R>DG%j0-0|yo!GTmCNbc;)l5Rgk!xSfB=@lK)?(!Fw9ae)4 zoG&!7^JY?6+)mz|-yUzRd7#)=@9iIq@51&fcGOg7LOMa%YbN?FmQcfLiD4SZqcX3PFAkE8^b{+iyZ%#cE2kKg~c9z<5k2fRUeV{wAECiEtVqCq*`hG?YZl^<36S;78WMZx zGRw1^{WvEEJm37w%+gWxHa*2KW^A^Wez%m#JR>|&66&d_Gl@srD8#7;o|w1=s*@Q? zZI>!CCel5)5Bl{hth)PGOwiG!pBr@XIQN@ON*l|%eOgCjx}6nbu4JQcPPXXTh0kkO z{?g@KIa)9`ZU3a#4h5esLzyo&KC<$dC5QXoxu2s+u>j$zp2gEr@56%`0iMt zs5kr~Hf2A7)O%)daAX5L9^3$%PwkYYSL@KUh;87qwM<;^sK)2wI}o^YC$t%>}Hr2Ma+5vbyw8EFxZ@(s+UmciBzH3HWPc7$d#6y2Jr){)=z3%0>h zjRuWBRwzY+ou=`*#6%eeXD!@Q?bhI$h-p}?U=)YxE+cP{#adV~!qEpMZ?1#NI3 z)B~Ols-{Dxo%oJkQ$BSuzpK`4gGxhR=)`MIv_>&@-sB_<;Cr^OFWTVZb5-tnk6{xQ zC(w|6?d0VenK*jPUB!+_`Ns!Z*!%%T6a@&OLxXvC?ruf>xpqXE`Fz`eRoynh_goWZ ze^#B6yedUmr54HU9I$1h9R$^Wq;r)YVP)oCA>KC!Z|X~+XDI8nVWv>J zvjDXpBr599<9B9EzE47AVJN%HGk^m2y5j5qlpv?Mj+7ee;Lm+$d9MV1mk%8UuS`tg zt};pHnsc*uFtm;OHE9>zc7oMtULm!ONW%N*g|>IqCYdjpxSOBaSG z{Uy%_ftcdJYfcjH-Iis*J3Z_%oRsFT0`*zRTi2e;7b)vaRBe@cK*H$56z8XNB_>u`G^`BPUtNh zHZsN73RSo%3xi9S%;;wvXJQ<^EjsPjA|<&B&`Yj|G*Myg+67_XjC`5Nc_->V`7Wf5 zZV@le@67h+snPD;xdO~6!8eb14pdkKR8^aiW1b~eY+518LQE-fuoQ+bJ})*XtFzL` zo@kKKBFyAj35$1T!L#eG|PGjOz!_`w=&>Ug)(XR&bnEwJ!r^|#6wZRx?w^`wjNGo)rJ32?Wt|3D- z(=cIEw<(kBqjK>j_s9?Cy4Ky%?cmnRkF<~LIfsSs6)p@?V-?@mpzRwIa5__f{(ifl z%P<3oUqk`dey#b7Q(MVeP zQ*l=Cc;P?@f4`=mhN!9(C^%z4PuG<~@UusJmbPTtt?Cq{_Cu)VK862cFM>fQb1+I9 z&!QHsq0EQXV$P>J@+x==aVA^kuY2j!>ym!(>*_~Q>X?O_^~S)!Z&u*Jvn1|ly@mzX zwu;WTEZHRP-Ky>2EDz?KrOIM01()oG(pcsyTStD(53i*I zlqy8&DzR(LK6rYf9c-WZjh2Va#Nb2|dGriz8lrs`c4G&KE;MGNIUo5}-?*T1DWCTb z>fsVqRfv7hGqT;=#2-QCFgl=)^2a)(``#KYkk z{>=M@I$a5t%HKDbv#zlgH1ubIIMUXTC`cK;+I$fY9Q{l!qAL~-Oc4%r)nVt<&S5Vl zT?mc$XA>IKsi>@*{Cgf^MD`h&_D2U^T3E1%ObaUZkCN3a{X!kTJcEBb>Vbh(6uid) zD@MA>cU$m$`TMcZoU9K&j3n4LtWd1BSO;mG8~;>U8B3)PMDK+;m^$&EqDFP%%&3-~ z&mpyHx6F);sJHu8@K&l6!vm${HTe;Y9g+m?Hks4WGF9x=H%|0@A))PgRv39hfXOx0 z)OYSf2pacLaGlFpk)9G*_uLc$rfITC|82mQA$#(FbNy%fnY&P0;s*QVR!j`gAbFr% zm}ne8;kN?#{2Yq=mY7m!etXcU0dWK0L$3aE2V4#)%SY#G)8Y3$Vbpv-t}`)UCPOx3 z%JJ{A=<8C7cYO^1yjl}`TQO-j4H|bdLvWgziF?e>EBc~nUkQ~yX%t8MjDq<`Tgd2y zC(e!foj=ssi1y6P0;dm#AU)1AqxDsZt9yh|rWW)h)dJi8yDQFkt3|a{Wed%m>8D>IynWaret6@u;wd(Y4+BA7@zPmfx zrwRUX+IRG}V1X|zsKb)sobzUl%0Aw($<_wKr9Y@w&Knq(<^fCBDzh;^{jlYHKEzq)P?=nHp48Qv>Vw{SkXTw`42kTG8{+tAh67Oq}#*uLB={Z&=NI;L=3NbpGp-hU)L5{_@v4;S+9tr5EY#(B#QkDSAv|LOJInv}kKgzt z)_L)FzxEc)IkZKtQp`OL%Vpqmtz7)HI*04WN5O(78}PH%VJiA}P~CPToOsW@W4AQ% zV$Tq+zlvrNpI6i7%6GB_8x85QS1)iIdtAJA`3ntdjKad;YGK+PhBND?D0-ou|LL>R z{ye)j@3(lpk?WtQYw;e`2~z*Yvd0Ja(VL5Rg*}q1n6&?(_~v_iknR0LM%O*?`s8+y zu&0S8l}BRlBtv=6!`f6c{3KLVcYrnF#>}g83I2W<8#I{TAV#`tqhqcT94geIxx;J3 z^H$u@f3uci7uurB_jY{3-(^eYbKQRDyKrKuCZzu6Ok)id z`e~dd=r?EJW$kpZ@$UfM&owC4^u0Lvz(`oozJ+S1JL9m&zw&#PI+DINf%ytYczDE{ zxvW;Ay5tZcA@qR@9^my(`7l>Hgr6+C(Krj`+&-f=pA( znBO`xL3Dj34pI$fWn=igx%{5cB@5f_S6aZWA1_tII$lDiSL94&;V^vR# zD_Adnye)<4?jGcsa~PJ_=ZG`>jM?c|KT&(+d$A&Y4_hkTO}oAo$-i+H{in5-SQu{$ z>&I7;+d&bIHSZQS9#Cb+YZqd}Z)2!xEWq0QZHjrV%Q|z`Ia!$+#u>_-pBm7;n~r$9 zK^Y?Sl~^PzfvH74^8e=Q&~%ONaQnIuoH*7<{gflIvSFN1q04!*%Z|f?tH)tyBWEQ= z+=nc>C+<09$rerL%v{+I!HUmZ_m#3?&P8*82)@6qUQYhL)#BbUb@X)R4Onn-i#(v& zl3LgD{Kx0tMfpJ`ws!0sTsZu)aA89Zc6h+Q9bThyRn6$8RvB!F+9uAQsY&PSG%(+x z7q~=4GH2;Zl6-h0E5GiEN3N(Vbkx_(3}}f*Ak4gWOnh0aaJJE~2}(Z?X~X$P3;V9cb)9^vh{*r4EtJeSW)3wxhb zhL=&gbm!m;@m~(k(uP_((QJk;3;PK#I5U`WPFw7-Nl>S($xeqK#;uj{(4*9Xnegvz z`u!WCe1ioguC5p7MEnt79IYbNrzY5O#Ua5V(}>RJoP$MS#-iAnbCAYXz%I+)FwxC| zUFmK@7iuD9juRRw(jyN79t4O1y*|+TA;uW_z*U~)twW`DDW=$N9pZgZ@A=Jr~??<%T&MD@*t4R*@$lDiBc3dvzq(~^nzgQf9Zxoc>`$EH2Y%pfn zk9>I*pKTMOu&BEr-+0f6N=nZ`@Dw9x=3K|9@FHAdX)DaUz;nSyeHHgd4+pz(ru1=x zp@N5Yce)m_pCzJAYyiwLXrh8jD{MJ%URM6oi04+PLho-c#n9ng-#D=df4U?J>pmN^ zJX-^bXkNsbK@Id~W-h3o*a{V#`E1t14Oi}O64JQNGvnN86s#ZREu14|{k9b0%{PAX zuIXwt)BY{byKe`_s6Dw{GCqxJ}UYtpUW3F=tce|HNo5L)kCR z;k5l_iM6gj#Uh__dUNzN3@fvh{~4k~RqZ(oYLgMnK3PXUuMWnwox_A5++Q}!`!FQ> zpM(#y-Kiq+6YO_s7F~~8GBc&W_)ia+P>_u!p6L*_$P7BK9?yRJETR!jRpR;j&op4v zc}Ty#P2S8iAT}QF3|+Yfucr1dy>p4eh<^O%keZDvj`vsi<&{rrv5S8>du{i6(BGj& zV<)I7vPwtxiDD_g7t^~bZ)H(29k6IrTYk)5eekJiAva5NzSrIaewrl!&)Vk(PQBkI+SqZgT#Op_wswS`+za+5U@1*poF=T6=i;sXabj4b zJGid?MP*Lb7_4FoJ`wdi_iZrF{Gumc$1^XqT@QovW-rj}#r20hZeXC@x}X8Cq*QCA zi3Mv_;DNplCH*WC>-v~Mw}4L+<79~KR`(aWEy~0z{NDJlzuMMbleL{Zh<97#;nF@S zQ^~r438t@v?Md8M6=_WCj@}ffEY+ow5+FK-R#LWmMbv>&rKikH2-LGya=0O(~3HxAI0P)%TG_e)dmg(cXyn3;{ z$}sr$(2g8OTH+Xk5>bfcxqh2(iU00*kJdF%4|iicIz3ZX7iLeoUoS%5^9C_wpp+%` zyMex%i9*K5Mf7_dXCb!yfXjc4*f&inP4-&|%IXcY^;$X9Autq}*}>n;bJ%pJ+hy*$}~hh&7&l?+zxD ztpT{^q4C2r(eU8_aigS$>N@gl$6=cChz`0$EejPICzZDnW;@~_hDWFiYTPsZdGb5h zF;EHKagSd4YD1b3bV&%CmVp~G@}Xx&d(L+GK#zVOhR-?yLhZYrIQHsP@kgr^%DC{- zbH!4q>~v6k=$wsCQx?I4^_KAci#<8-SH;keE%|f#z0c9l6#E3VgHH!4>CU@DJj-a0 zpr5PEuBwj1Rr!Vxs&WHEhQ=v0;i4;NZ#I6zv1lM0cR-&^(ySFXzV^Q5lzcD=Qi^Tm zS2@?TZoVs=aWaM>ck5|>xBlp65h0Y^<2@T4fcBG4z?=_mq|~hnWI>c1$rpdiS#+rCdL#Y-<(+=`RI3hoRj1k}#R?0-f{v zfWOR+T$I|sMhx3iIhb!THi=Oc8bSw+Lu#-Njs0*|2cw(sf$NYb6TgTt|c&PRAh#4{L=AzN_3ke>8;cH3ToYlsS(>e0iZwba|~w+j;ioKW0(c z{TQ|)atG}hc3bE_M#L_!*NERwc|m{s-}GOh38sy+g`AW+dVH-9ro5EOuW)bpsJw%4 z>xCB_<@w!5mU4`l^}3*oTqm<7OC1eL>CY zi?OkyPdhz9l^wja6O~;zg6>8s^S_Gtw)CY?c3eu1r}D)EuAfBxLf)r!*Tk%~hXi(* zYg5N3VycxU1aW@vfg^}Fx*5vD)@yQ)z-!o<8v=fjoQwO{fQm*&%jA6;Xm#gf@UzNa zd@89Rah^KHTDZs?xQ74R&RH;Yi$3(cEMalW6LCXBtdKiPhjMq8L!B>)#hMnZ$8~)g zA}Gr*sa{04PzE>BO(9T6!j?b22ut-($TCx0*`W8m&~`|gv6FO^H! z>eNJxJbGK`vB7{;?%#lU8xO;=7#F&|QUliryTwhrCA4#_k;2dNA*+%GS|5aV%kK*I z1~*W?;-d(c`JV8c2CH(Kh?jhK~C6xnr9q=P5Zr%r|f7e^i;(oe0OjLte`sT$Rwl zlB*DSQWY$xSh8;+ZTP-_x{&)m6JL!w1s$?G!1HBGSUa6qdY_sP-DgTjWB4U8WAZ3S zoAHHStklEDciQqTN^8g`AOu4n_{eATT=?qe$>8-v7tA|K*@oVTtjI=)<$mx}^R4j2 z(K2!QJqdMxdP)2+%n!Patfvucbg=L3blK-APGsDc0~!OH#W!Q6EFcE4Ni|Vm#S6${ zUL%DJpuoQ`aT5fA=f667C4Iew(q`phr*t3=uZ@TjS9k?cqRsYe;?ao%Yq7f=in2 zFl&SgJLzkQ59V3OBQbx&yk0>&;qmWg|)>4ED6$)9AQ6w34p8L69tuHb&OEeV?g(mfT zoZr9wasKE%=YH>TU7zdABQ0TGc>`nGl#{TnO4#YEOFIqw!iecr_-4pSka9T26|*^R zklbtX?{4@cis=mZETqz*S|EKmk7m7zkZ7ew&D0mHxLhzf7bd+ybtpsf?z32g11aQ208~ifMo=;hU(L z^gWhIGhbbWIRo^eH28q9o#~u!%QNo$#(I1+iREjA9O8`)v`{!Y7{XT8leI&7ae&i2 zN^fRyMyYqGV)+D#hnLDL2`iHy(urU9L&^fAH=bmJ#SbNL$P5?Gjf+85C0VX1)|MWm zuO+?Qq*a=@;e0=qSC&E!jBZ2m-N|&m`*)5jenji_Jtg@>m;BX)u83S3UD8QP&QW@9 z0?U2ATR}W#MhRMGaj3QN8RyILTpsSdNl3p&+xF713-GHpz6k^OY|0mBfoy_%8E}G4uK8!aJ;F(9}>MG-)jcLS{ zu^04je#O7nq-pu2I932y@0Kv?Y;-8XB_d00tPmS2FBl#V~9d!dWmV339 z=^^v4`-t@Hn^6Uhf#LHJ#BfM87Wnl-X2n3>>$58Mrul*)^B4SNJk|a-aWo(>f|I_k zg^PC9!Sd|?h;s_dB4-)0Z!Ssm_5OD$TO~<+d4$!R4%f@@mNw**)tWf=!7Al+Hm+%--8X0 zJ?P?tA4HqiE1>kDEbyHu1E+o2Z1Un4oj2qL=XE8W${xM|%jVd^lBjKhXe{I79TbCQ zCG+WsQ^|58Z&*C!5e5f;gmdcui8q;k!|FF8diW>vP#;jnB^OS>#-BZOE_N6a&QN32B)VMnBkF66kg_%01qo+@8B^kch!g= zUn(zb%8aEO4hcC&7LF7S8vmrn9{cfE<}!wsT`Bll4S=(`213^;H4OMTi`zc76Tj7; zgzSz%a9q9?!-y39uveb{=UM(yy&P-@4`X3H@+=E1mY$z4%M~gr;qT0kP(DK%kY!-q zZ(y@QdKTCE;3mEM^S-1{yTf*CbWAw3y&J*BJRDEuzIaNs5Kne>W5J5aG~{78%X-if z292np8*@LAQM*~5h@uufP-zBsTdHuwrBEmucZ{3vCM}elpFtOyX+hhPd>VWr1dgg} z!Ocnfg2I0d)c&4^NP4IS_WhyHa!-4S$?i(*X8XXPZZm#dG-J)p(U)W|4zz4U6(;C2 zoV$=q*i}l^Uabb&8v^#D)bVW8Ll}MhDY<{?Aq~CE0Nh!o;Cwb*2)PrD4dqH;6J3YK z6T+eD$3eb>X+#|d^@StX8;H_-DZ$otIvq7Xo72t6qK^buiRMA&n4%!toJo7U_rr!q zlxp?A4LfElLDRBG!65V~UfU_pWxchfx=6+4|7kE^s~+k$_Jx^8Q%ROvJI;cOl73c^DpO{V4W<6gLDP}fE!7&g-v zhCJ8Bs7*;wv-$+tJkn5@%KD^jiyx6Xc1QcHb(VY>*Fd7}>M*^$4W{2t=Co4fh5E~f zX|}WioR?BGmn-l3)gb73Uv zLhEliVZU!Y#NRzHy8X;bC|^9Bx+Ycg1_v~-p=vp7*jY|iH!~ew>tVW5zKFYjS{Z3^ z7Btl+Fb$}h5T@{n4rmO9M=XQse7!2W2MprWP2b~HsP}Xa7_MhI6z>b^ zi#;VIE7ll38TDXd+ay|A6D9s_u7o!}XTth{)-YeN7e0Mc#E|#%xfgY7aN+tn)c<7^ z9qXlsGl(fYbeWK4wv{ODvKvT<6#t3&aM$%}LtK<2BtQI%7p_mD!vo)oX718Keg%cg z73#3HiLo@#D&wXt1)RQGI<*ft2Sq1`fC}5iz4&O38(aOsd6fco|4ks$)8~TOr52pH zU5Xli?hxB2*5m0{qv*Xo4*XzmWz^mu3!gKYX7rAgkP`HP&aZdoI!>xmpP6N3LfJGZ zNLR-*xBJlOJTZ}(%(%FJ5+!wP(UE5Sb+-rJ%uW|gV_t@5stFLw*b&{QSO%`jTgbi@ z4Yzh_2~)?*VY%5R7<*eA=bgMrMvlEf*37mNuDlyYRXvP&I+@im_rugK1#_IrM+zgN zo9Osi{(M}qB4Z)Gg|gL_V9PR~^ZZqD|7%Z9|Ai498`KXRSvKMhk8Yga|1dQ841tp| zDmePeBG6bi9K8MIg`KNeuDw`>`;TRN4Y4Z&N9K_!(gD zjm_YuO*{Gw+zKe%$TlmZ)~-C0wfdM)Zf? zr*$_|AvxR_nYw)PXoj5X~7ujTGD4g4NTDU^FlGkJbFxc+qO%zyMx4V{tgB&?`D40zc6rzDIEOq75)DVWz25oALo_v;O@g9)jk9UJ<}5Y z$Uda|e}uWt9usa)oM2nDH?kCiaVm zDc@Cvo(Jz~L1-{c4pP9nL8`R5)fFs^KI7`rrBJ=LfRm47p7F!%o#yBTY4`u25pwi} zNt9SnQpM$InNW9XFpPy^LQg&8Tnt*ot-P^@Y3gQC`D0O3Q$Y{+jWDLNhJDv=&v z312@*@iC*6(PX3wtO;bSHvQjd&^DUpO1~7X+pmLthUS9wD|L8n?I>90DdEUxMO>z4 zI(4W_hOiw&z+c%=Nb@p7&xQVwc8PJ4jUq{l!5pY!_mq=ntQ|$q!%~C z#)M8gVgV^Pj6v$AK8_rgNXBiSLA>Wwp;UV{>@Jn%O9rVRwfBN8&xZlWp6LkoOpl+E z;W`;3ad_K1crsfS>U>zAww`77%we;Vbq3WC-GyLc11XzoaoXrLFtc(b*K){>YW{SW z_-hW*PF%3xm6~7}G;Yxph;=z_wksncY{pN^Rg=`E!4++2b$>g{OgYOf_ZfmN@}Uqs zjVC(c`Bb`Rm!vL*Ip_+}->c~4Q)(hp6AgT;t4mAg_mYCRDr}jz3Wne7%Wqw!g0{Y@ z628+d>joS%)RD?~FW^G<-k|Fz4}}fR)4^ST5H{X_2L$r;ef48nAtPHSzD;fWvGY=~9XuZ5` z6ot0CH)+?yec-K)^r%caSo$f!qrZm2PLIB*{5(-)`^A zZ_9SP{nd#ke*MnvZq1_>ug61Wk2ZKR4*ANb8MMDw2MPR1>C;iy;bd$D`8hsHIH=A1 zEH8?=h;Rk8whbii1GYn3tmiSY$y_b-qYe2OMinFF zz~i$57L6%}uan&2qP2lw(@!2RF7*-VpJ~Sa-QI9WXCx`-rGz23e}UfOG5p{Cs+g2H zL!#*lPLvl042Yl;6T`Wo)tV^!_z`xw6fv%Xv9R`~BCbp8!(T7HLmk5INp6%P&1THo z?G5+F$BMr9W&6NwE%0pVP5#@(zW9OjgAMdIX}`lbpL_(>2`%I{q_xnYpA+D^Ul_P= zRTX-zOX#UX+u`0kBf*+wuUci;@J(M7a9_Hz#E)aM>@yznpA71k3%G8^+I`>uoo>5?STT{NH6!=LGfbh4i>*6$ zW;N>gS<@>Q?fH9~wei-cSU7%33vPF63ZG@~(g7DOIJd33cqmtfZXB3T)L16qrO>V9 zpC37Bn}RTCv@}iA%ojb^8Gx1^7a;i4FJe4HQxK_2Vb{|DkUQCgUp2kKONqTBgRF$9 z|MjH?ON@AfXnCQ=Ac9twV9w)3O1Nvsb13>?2~(1cg-OF14{_!k&St6!9lN)$q(+(1 zc9fgE1f0LxK%{#$Hq#IAeVH7up{a~_&8I@bqM=}rCofE%6+w+VWw`2>tbPuE4b!j7 zz^S_?!jmD&xYy?aH)}=))%l(&sZjx&x#`^2f?|-FX zEW2mfKNtl)@mnC zJCJVqa1}zNDv9r3V_|Nk3I4A3=ho#h&r_xsv7uYR!r>2Y+)@dd$)+&zVH3J3*ifHc z8hlYaD4IM8TvIi{^2-nG30y-j3=iPC7i*!d&pRl^ zBJy}Sn+?n4kXA_Z&sa9Z--Ql={K1q*!)aA>r1&YzE0JY6r2o9k9ks&+_y1&Y;H<@* zDyv@HA&qlXNK85UCf$q~x9%%OvDOB}&Uh3QXz*-(cQ zPeqRPI(RvVc|2L|BCaEZ?c?RKy5ccs{hIBZkDr7SZ9@PBJ)z^AJ_ZK)!Z|wyd^K+l z@vNBxv+Y`OPv8eIckdL-7FXjb<$km@&7NPVriLG)B4IC^DKs24g)J=8UH-N?ry)H6 zgZpVn_V)XOl`y+yp5zv38o+k!4nN^@N1n({Sr79@#K43(-_H+7rm z#d!vp&^k|3N$twdmK8n*&w{~>i$3sbC3c2A0aJfjK8`W@BS*PGxZW_BSEMQI>Kjc9 z?yGV0{;D(f!fW^$D-WJbvnqCzM=$An+@9cc>a;ThlAl<^!~S2<8V11FRin7mtKI1u zhd~m?<_O;o95;0^^=k@+Iki7=SGh0MkZa+@d)XfQ>OA;pZ46n8nu6NxS9FVQDS5(X zx4~mnXz34gsMW8+zljzwpd*fZ6PZmDa+8T!z9k&HEG0}*7)I?F*YSAi4|GXeLA6?S zc@?z++IlSjs$I3<+bCVZ{nUGUajBYUa2xX|d8pD=O z!Gb&VFw>+s+nU0Zt?aoEz96Y@=bw)dwBu!QbUx1q4v@pRNi`5*>I$E{4Fx5C16=SV zLGFX3t{uZZ#C8aF${I4z33~Mq!-F14B4|UZGVm-*vZ_q!zlSDsZ-;LFVIK3LVX~1}i zlU)d@(TB+?)!26@g~{n|+>4}i`l91IS!=xt{yvlv)*5Z1?``&j*B2e(>3@Hz*C;XB z;-rU<|BZVgK5AY@)X&4q1~6%sYJ(3y!U|u}#sWd(w z<|F$1{yTp3kAc3$vWXnY(;oe&r93j<*f9sP)SL9?$G_k@|1wm=@NT}d1iq5qEV*90MFy+A&K1fv^ zEjlj2E3fYAhK0OXr2CqCV6gy>ywr7gMt#>?92HlEGqODOY)N4f^Izq&r4M z(Pw#vxO{~HEnFm!6JtK3$8vqBjQh*=&Qrow5z0#4eIBn(-o)UfnPWT66ExR((5{S&wLehG6u5$tdSC}MgNyS*j)b@?!IgnCw;8K z-)%;8O_d#g<*N#A4-SRbaw;HP*A&{9+@O8?SukCzE{gW`g0XKt3HMOOVGG6(^@F28 zJ^Lq4wPSuL$J?UIxmLoKxyz}gv&uN93Vl49#rm)AFJ#D84Plp48tV=9h`;6xDmyFL-IV}NlI8uDvV55=SGa8N0Cm@x z4z~UP{d-uAJIxpad*CU|Jt_;Gqm6_SyJax9UpD8^lTJtZv7L;S4Gi>C7MAWD1MgE7 zaeD{3(-i{;lH|=Aa3`@H*Uhk|$$LY==W`2wjag2&bvJQ_CK^I?)pHu0{ehTisG{9t zWg0lz0u-A*qvJm>7L_8uL$9WBbI^8>e~*s$9w;c{NoAN zZuyR2Xihipp3lX0rqecCOL$!~6I3s0VKK{a`R8YJFSLzKr@FdbmIBjW&fvt(6glmj*qdH!4mvo=|15Limj#I@sRcP26M+g@r41arAEB_A-B~#YZzzcEtcH=U3zHpgSr-hkT)ZhTsyx*aIn_GQG>?uZpk{rAGuDtAUBs--#soIw~xg&F~$7d6jQ8~ z8%EN0_JKcn)tLI<9q4j7&26if5fbAzFue!!RkGPFZ!d*44dWpw(Lh)w?xlsHKB5!s zIXcadg<<6mByL0%(wIzW?i#@Vj8{Wp`6!A1aYN2`j2JwZ-u2Q({nP?#(;fsSwrqdfAS<~`Mx~XbhD#SY(w5H|-I2$#d#_2E z)ht+a_9t%5Goyy8Vd9zll`%r=Jk%|dE?coad@M0K_K3VJufsci?m_3Kw_MVE1tGRDh+2Y>bEZ`V-P{Y| zUv_YCijgohK^m{^^5h&dP3W^O14&<3Gy4xtD^df;t|2flyb^^ESNUVu`b`epo*M~Q#L^geE1MgdnohfRUX$D%5L61AS|4JN{F1=BFm@Kwn+{4N2-tof`h99*cnU3vfb$KBj4~G26 zFGK=&ocixL9WaC5RE-MqA$s8?6wgWvDTRr|iYwX-VTJo|za zJLy2r=x=x!w5j*FdEDFDk5q0Z%Z8m30)yGj{k`Q?@Ns-itaqphrYj0)`15M+uv-?r zqn7}gY5E|(Vkn%Lt%FlPpCN~fKjXcS*W_hJI6t9H1^Wg)C+iEokaczS=;^FYPmH|G z-9Dd12aYqB!R0k!(7#}7WBfEqh0;K>LcicO4#JxRJK zJLRM(?WP@VUur6@^VftFrrSTbBLf=#iva7cW?XkomnJ{0=A!%xsOK}54E&yDK3-E4 z;*^uQCaaGtxP)1P1vIO%WP2)1@9)N)Wcu56R_`VCaD`V7T0LGu zLwk3_&MAuQ4sx2leD;b{4AT~TYFlaH@EqcES{ujq$`BpVFY^9vHLh2@0(-`v=B|J0 zBlMZ%OHHc!z-;CN-DHGtf6FAexQqGJ26WSZJ>I@C4H$U4ghU29lAPlmcyiNSn6TZ6 z-*lbT>Z$gUy`1Cb@3@+qNiW5&;ljI=X>!^bB3B;@((%gJGl$hTMIftK&O)$eFMah# zn*Zo=hn`t}Lo(Y=bNh<5&M$~=*{eUbNu*Vmr((;M|?xaIFy56~1Vxpf+<>Ix$ngHDlK0Yy_3F=*XyvG|lXsJv*#8s!Yw zb*D`{*|!=q7}rd^;MZr4kH|c&i8fLmT;?SWtp*>2O zr)Da+%EuO-?H&fX%hWL?r2tgLa?n%7JlFku>5tTGPUccJXb));56eRn)#(iy=>BN4&uR@^ErU$D!7tq48E^ZUk^Q1%xwEQ0v?E+(Bx5`Mg zwI#`)F=tUKiMSiXmAV0)VirzRBZh#Z`(L#CZa_23)F39k8B?8SP!APd{;f$Noml4s zHBYoam9Z;NL>PeKA6v_O9DUmSJX zfKH`;+?kw@^iJm(@Ujm9m+#u>5p@yn$G##8k!r%cl>*%~~>v9HcmX$OY^l~6FdIS7kNSe_28C;L|9(&wI;u#qve$8S~;zAd>& z{QWM9KHmI=CSNZ>*yby|$0Z}2moow;U27z7qkA#`;(QwWDVM8PQ$?Ga(~#DX2u{zH zgwUzE^r`6<=$BEB-QomEJv^Pja>h*VlUGt+5Z~58K0#9OtN$ndrINXm|3kaDdNhs3B-DX+((YuYSp(&7wUwNwI4)>kC4_&#$y!}%Cw(454h zpmKi*JkZq<9*tH(v-o8&X__MH9k?&4hx4vB;b3|}kHul>n55_u2BdJ3b! zLRmrBAeRjrC+3N?%B%$9Gl3R6sf>$Zx9^G555cvLR0zFb8Um4uvR#(&sE9)bDd!B81s zET~7Zcj!bf&IXL>ie1_g?Z=jwzj)))bu#^#E!>H&Vt&a}aPO@wKTezN17}%6ve{4= z6xfbe3ue>7Z(Bt3^VM)*7Q#_|IcQvNDuiYCQ01KuxHH2t=-fA#p`Gn6TBg?E=ut`J zSM>GKS5S9Bfq<;i7WaIfxXL5lC2THvG0IcRC{JCmo%Jt#F%~}!0#=Yo34b_ zUVS9D*X!9G2#c>0^7b4zoMlO@zLQPH7zD!opk6$nYe0*2G~lGhH*8uzkuE=~$$wp0 zNNMm=^gRT$uYn*5uQb$6*?i*zp0U^xo` zce?PDyDm+by_!4Juap+#jb?tz5J*=u!08%SpnKbU!UwV1I05PMq-stsAdA*FACvTr z$KDwULsGO*z4CD6PYO&l5X--bmFmF(B!2eBK3b4V%d>JY)C9)00eBg<}3j~8_ewWZ;9 z$+`dT9ZNOX{&VpOz@ri1veQcNi5p98F7@TJUlr0I!4eD}>q6y71;H^hj`kNC$z;ad z9;hXzeXE^$?JMlNo%9jvRLr6O8-1bAQB^cdTfs%olf%_jo5g4K0^#I~PCT;mG%S)f zfj2Yy2v47D)3~*!e2^2tA+X%w4ZJ{QiUFJJ5g)o=x2zT7c- z-Tx)`$Xr{f$9k&1@gWJHWPlGw9u)s4^M^F1RN>~Ehe3YzDXu9boBl{CCOz8yKseb) zc%|k|gChDsnkVZk((i%q#R(9^G7Iu<{-i1J$iVO|!ymCJ*8W;xEfIEBnOm(Oiw98@y>DoL5eSjt+D zu(7ZdoHJ*OPhD(4pQdrN^QVZPF2`orr|~dUuz}z@HQ~k!F@57Ol-;Jyu(6*Gt#m9R z39BnHXTc0|Ek=sJ&U9$A1FsU(2g4xj>LZlhQU>!PQbm&{DdXzi6B54b1@@iK86l>F z%Fb{i);F4bh?eXRyY6TURauJY_i8D0FwI5KuI*y|VsALcd?J=#jzgqQn>gcXHHI?& z+q-r4{1V1}`V!{P{OM{e=S)Eeyb?zrdFpXq$%JH$odJ8z^sxL;6a2gFh8G(O za;sRqz97#p*{y=d6!(Zb)JKD`nC#O!`<&Bp>WzX^;+Og~TR4OWH5m_@m^4#3J;Mvkc zJTgs%lq6xeW76<_BIm8+G2 zfAJidI!sDvSi`iw<$t(y6EuX2?YT5`;RjM=%IcFzChX8CBNyVo;OT90#LFv|>tJ)D zQsx=bJthe9+1vAA0pnn6ekA#)zGC#4(NyuLI=@w=kdiP@h)HJkbC$M{mrrSLe-+WU z=gO%0p%<#O+eiyzgWRj@Lzcyu^B)70an7D|j@l zDItt|V}*PCGQj3ZBRP?uMa#||g(Z3Vkne0L>=?o{g-U0LPr(-yX|;=+xd>jR%My!O zO`di}2Id#m;f0soFn#JJu3RO_=`z~@o-%Lj1g-ayTgmfx2Et4?cF*Wp$$er>NYe=&xh0>r!m+nq*th2} z6rDAJPX{aU*nw79->kszVvLd7Rg2)lBwM&pCoimuIzpxG0$npbl`+`u1M{BzA)S_t zy~FtR{UVU_>QKjy1R1gMd}DaBsRsME?}rIv+_~;~8T7wQa6P0)}doMJtAHW;1 z{pa~5Y%eld16=GH@NLx?`cTo2Q+ujJ&0=FoT5<>sbx}uY+lLT${}I{!1Zc|F44^Du zrXXHXP!H%9yB1y&U1nOrn$4l0T5y)1GfWT9+%tzaX|<$XT1rSym`ZQ!h`Fdw$|#=^ z2co?R5Z7*rjc49M#-|waTZ8p|TDL(vNFK_PKA~#I6Y;#>JnkU#DFlx_McP6=p_j1~ z6n06|g62E6U`7dDM|;@_OoKri=| z;1{3{kFUuKVUv!~#kY02=QmX8_0XYN;dqO7t+9TYIse)l|B7cc(~arY_c)3E-xo0xw283L{Y!yC;-z6LQk& ztZ^yu+R+*eepO@lJ`?f2Gb6aGT5j~YX|ecUhT3)J$5dACfj(10;C*x({yZ+C8TvoD zZJp{u^^W^=N#T2Pp_)`yARM4a$7-(HHxG75-{o>2b&@cg<=C`d^9>iwEDI!b?!a>;GciLtE?H- zUvFW29d=vUVjPwKw01H{+xwkE^303IY5^ zc29gIehud5&B5ZRk)U`&8GDzn<{T{)@apL`41inpi&|>sRXI(~A8M9S?MoX=Cou%M}mEk_$}ZK79z@zaI)IxD{GW3eG4|lwS?If=nAQu;7841yUJg@QaV3p#Kn`M>5Q3t zwZ$Kn>Ye2S7iwTzfEJ8S{6tFrwBu)yD^<|H$7xJWr`!QH$lHy4*neYjE`fuoKtrSI47n>33wkxs>HKk!p0Wd)btDX-3<|YANhu+Jr300 z(v^S0SV_JbMpQFjgMM%5;%PIunl1g2oYtmwsl{aT$4ZtJIX)-lg%rR0ks>|_ zJVab(42N}PEjYyIH`6#5ix#tt#mmvh;k>sBM9#^e$E+hI`@<`{wFKGeGI%K22f}OR z@$slN4}Y(k1Ld9H@mkdeNI2IjK60T6y$xC+`ppPl@uMo9==6p$S5#oSlf3Y-JBqF` z)8#m2RcbNi4lymB0_!W31y{4TRKe#SWV;v&kt>yOP=g#V8_e!Ua|0g!W8scA&=;H6K-%PA z7{6e4&imOh&~f1lHu|lEi`mb(IR<~R#&R5eNblyfPt?K_e;>fwAX|uc8!ChvE8wNc z8@U7h|De3?{G9%;hrp~3;I4(E@Q3*om&=rJ(;2I9SmGHlZMTA7->Y%rQ1=|E#1Y)M1a}%EQz*Wbq5&Ec zSw7(Nc6c7WA8v1Gz|8?p^qqb^7oDUoTsW3ZjqTqPJErMf@0t!31*PQ9o-a6hC7*NH zjn%s3fAhj2qWCQc{7U{{y-12Wgs8#d-}Tt9$x=R;X=}qXz4@aNBz_ zsKZQo7og1&we2+OA{qEY`> zP$cHTbDxoLgK5YM2PKNyTkL31zP`)2bDCgytr-uL%!6H1BS1IWO4xDMobEf>mv>{C zYp2)Dfd8sIK{WkGCDc#3>Tj4KZc)0~U{beMSF{aGt;?Lt{fFUfS~kHk&B&uRby#+3iVCFwX{B*UJlQd?RRy{ubBM6V%X$ z^{D?m7b_WioW#n;qnqVHnyIO{s6Sa zlQ9`stqXY6jh~%Ay2gA;6e*mp!OM9w!AJEB@67Zechc2iv34!#&u%wg&e+lP`RUv< zrm1+yvY`rgy29F#io%)Q*XRpj1DKh!7_-=GurWc7-7G%i*%Rp68Ck%Ev-eKMvOwlL zoCQZ3TJi6zIdk5q~Dx)5b84f5~p0))9xm)Oip@E!Gq+F`r>q!*I^)b$`5k zRFf9A7n4NBw0s$s?`q;J&G+UgVU>0;xpc?@zO}Sqe&tvAcT@hr_Eb*CV!(a13iuz( zpyf})CA-1*a$3SZDuruv7Q^bh@@RFS-sPYFV&t6fDBI`-#Z4{ZXM>t?f^!YTIgI4} zZ!vDeoEZ=kqzvMd@KZ{Kdy3==ooVxqilsTN3n! z`YWyht(mc0WwQcy#w;a9X@L+mxChfx>fxNDI{avD!ew=X>3we<{_-Ui3@MI;2<7Rp z*hNzqdWmI2HYti$zLCRi)!*Ritp=j9x&|Yr4HK>TX3kI8!1fp)mXM!)S?{!#{oUmi z1RnI{>RWHp#(5p2)^rB6uN;6K7tTpE&%OP#Y4qbrz*7d`yGc*bRg}Td;#0&UuM*?E z9Yx1C9N^b8E|a;&8j>AXO=hpG!N0LDA?fjX?m_>%R7q7@;v-vHYlZG_&qH{95~=Z3 z#2G`MfcX_3xKtxyMY24q7$=JQ+_s~8D^I%oyBBMyHsjqRE)dup4zCiegseG?9iQBn z4`a1=z3T)p4f6o^QF21)y8X21bv@ZJPzm3JJb{tJ&B1uAu`uDfJQgdh;Y^rb`st%xYrX-r56UfT0c?2 zfQ`>VYe^5;e#=Cd+@gSwr5|x_WvbY>bGs{O8A1`u^639~1aPVoxNxSYy&{|;GyblG z0TEqzQj6scWd;Ljl^0|ULaEu{7o1syrto3QTROS=9*JSuXZsTZUHgRAl8f#YxIAMx zTo5O6sTZUK&37YMW}g%s$o_@4U)Rwg`#ZV6YAh#cbtPNn)y0pJogLO9Q!MgQ>=`G`D9 z{byg5^mwUjzhGR{1kuoag1#J5}S8_YvSYPB3wLdMFVE(SX0NnB0gk3 z%b}hY$##%~;StjtYx&%wb{B?o-d>hCB3Yg4ZGJ`yCNqxNkIABd^U{0++p!;VTtIeh zb%0+z3PSCs-!N?QSJ8w_HC%WyO2W^4?~y^PwL&GkKA%iYVdSkpR8?y+805?296rGH z?C?3zsMdgf!^eR1)mCxxvTt}|-)s0D=D=qwYhbj~REh8G<2)_F)ATUQdbZ$BZ|jF9 ziOo<`Q$ijyJ<{66@~CQ~z~39Ih_7C6bR9vQVCm{+Y$qwm5#f(CM!MM;`s^wQwt)KwrVqP{(e{M((9zp#d1_i9txx0 zJmu2mx^c_;;k3vqD<`qC4M+6`P~A9FK9TLUbn??+)~Nwtvu(IA^qLG-wr%F-{bu>? z8M3h2R3GFwDdF+f&932IV~HjEOiT8ec{S3!SCJAfxYj{>58H!TTNiF#KAbN6_)C;y zuZOFGvLPi^1rmct2ssy7j{E+%+^7K=G@$XMWVY40REfW?hKut5bL5ES1gc|qMEs#g z18!;l#Iw6!!MgN)p!c>F$2eHi3y#g4`%P6Ld{Y_?YAqohER##OvI+iqW|M2aAXps` zHAcpAuCEmEN1t(oZU_WRruT>+_7T8W4c4-(t2JvZsliEYKAZJ9)AK^%?c}MDK1x%F z-glFBzf}~~t1Dx>dlP)`{7IU3*Pvcdv?#dSoG)L;vU+UXB)8+N?rPlACm-q!Jz3Up z2Hm{q2l=Owc5c^2mraKyIZ&$0vS`ZZFu0G-+?O%fCB_U0^dhoAw7Ss|fIL|Avth3!u8UoD;FG>*naMuIZe_H4%@yyH9VFRU0=5li8w`f1jc;a`#7o-}rQM7&% zv^Pujo^Faezea^5LN<{-vuDU2 zA!(Qq$p~2$)w!?x`r0cyvRc|xMIrUOJHJ2Rd0w8!IoG-F>+|`%Kl!`(|69ukiu=pz z>35!G7@pD&23AFrRy$JJ$S|KfglSx?sSsv7*^`Je|q=P-|0&R#yJhh_8P zz&+Fh)^Kl+TT~|dKGt8zNNL1Di5CRj20}Ngf5*pDEmf?5W5F_f(xIHbbT)(;e@pqh zrXyP$HkS-Z(_yF7Hq+Gwo5AzCBhuVw(8A%|9K=}}cQx_!0t>N2TnWC^J|VoV4i%DC z7T~f8R@_r?Qp^Zyjlmf;wB?;^<6DmZ1$1KZBd?JT2Xv&dC9$l>q$MySysy;pjV7)i z?j?4O(L!-q0UX`q2DZEJ;;cSvgr${nWP+0}`UUi-EBpCD*~SL^%?mr-7w%Nfaw^9f zuTIQ&h#*c5(#KbOLZDS5X9b)wk|wY#EWfo2Ikb)U6ApPpL#nz#uOnS?rM)2w?(~{| z*0z@{FMJhN-BgG{8Lcp&eQ#>F#{q69>PX~T0oW%O3i7rxd}hnPFNInVGcu8FZ@mTn zx;ueeUn9x>Og($=Fa^rTXk!MssVEH|3!AQ&;kvMn@NaO9a;|GW?(t^ORnuAgu)+|t zCk=wtmU8%c$XM#+x`(}4-ib`>)EVanmBRQj@8}_OOP;ybL@R}k=+?s6>7T4v)1xmK zKQ6>C3Tvo7enEI+WG|V`m9w?IWrH+%cTc;5!H~G*J=N^UyT+=fvbVCeWaU}|NqgpV z_UXnPxDwfjCyrhaPPs(D=Uv~h_XXb1mBLxX+^alTw;PK*dn3)Ra}}P087x1tt=K+7 zhOh6$bFHK+q)&B`TqSi3&|66gWfm-Rjs{FHX$vE>{-OV}i^6U-XZYar4UcX$he(k~g#$@0WKsu7nm==iYNUcu5{9wA}j6hUnm)4gF~LmlY86tQk9O`3Nm~aTzVd zbH{kMj+>!)kk9t@$F{=8fxRv<#1|oExp8jj3<7&(Z7a9 zaHU@X2CGT1#K(^;d)O9zG!BA&*+<$_=Qdm3uno@MHRE?HQ)$^BpjCy2WV>(~OP*0gMNjTYFnkPePjvz4Y9YNO>Nv|}4iPz@xr=9w z!nk=Itk>6*N-Hd3@-GMY{W2HNtiK62rs{}C7sxnc;XfFBv^ylAp48B^o<%=etH{`7 zi0%76gK6v3VS69_XQpOr)beNT5JBn>0>!}@a}kGvz_xEEB4Zc&4JK( zu>o!F^G>nbYv8N7kyNqy1q-rHp(X<7#vE%UoE!C%4)@Bz;sgKa5P3A&G?lWrRZ%pA zXO6}UZ^j#K?3hk`6NQ3W{5xtIo4B@tZ0Ti)p^wjl?6)@zuxuk~KYPvk#Eloqf;6NP zjwM3+O)nb#)By7je502)w1&H9OEEaE9h=i_E*Ye$%i=TFsF=fT_88!;taHGh+thbV z64TK>rt(Wi{47TCOoq^UZ>VtV)OS4Vt`1KAC&e4zO>xWAGHU(1fc~9Zif1_gT>5Z@ zWCUfgu|6K0$GHe%`0jUSVhr=Rwgfg6Y2iW5JTQCa23hP5Zuxdjs3dV@W4R7SUACb2 z-;99)&#JLtG=-5vLX>YgpE*9W9q*n|hz7T0cywnlthRN4-JN-U%HSfKI<+_XA~#{f zM!urm&N_l$q9r!$Z^fM4@6onR|Im6^t}sktB!29!g_eiRsd;pFNWIFvJ?k<-xL7D0 zZnBedJSQ=yBd&w8J$TjwHmUTE@mJSN2?va^*B5;;bABQ#b=aVqfq_?BOS`w%uxY&} z!|xIM^|v$r(I^7V(eG*DJWJ_@Z!1h+s3RUM;;b999|{%M?tB3rd#Mg@?#BzOP3jZAuQSsQEDUPZN5is zo`1ukxqs=X+UMll$y%Jdu>*UTdM&MVUlq=sGKr0P(pI$Q9G)!kJh!*nL%txFl7gPF zo)bjUTyM^LziFbsi%sFBmYOucGG90!(gS3rc{pRJ8br?En(uplPsqtq?Sxj58qyP2 zCq{kLNPkyTJo@yC>Rs$NMJ^3G_Jrx@#FLS`6WK7E2-Q5y?2v-?zf*-mPh&FJ(S!Y6 zGgP$`zUozjdBaj*(Ur~c`gI*1x3N-X=*F(+zEiW)%xd0ix|MTo$;LxMdTCJ05aK;Q5H`oyN@QnOqdU z=wt2oHL&f%2skv+NLqaQJhOSLE4<-v@SjHuKz6T&4s^Ab$f_RXwao&tG>ZEq3-oC= z?_b-`eY_nC6JYlDF~oB6HRk*8GnFs!fun=$ap|fE_>)`7=iUZsTr}@nIzL==TA##v z+HX;5!TUeAkpd3%3R#WdBH!Hi@2Xm~|}^f^Poe}7vkc0(g`za1eQaqP~%iV8)` zuDJeEH6CpILf2>Pgp|#kMKC)7bQNETb+8`Z+V2F@eMZ74-q&{L&V1JYS`p3VojB(= z12muL0E3l$zA2hn_vdp+TC6Vi>}@W9^?G>RqY;&1MHFXP!{BductyAXeSYhRKBx8Z z!O!l{FWd=~H*}@QyFtwH(Q1WOS0jvzeF83pt)M~MQYuVoW>>c|vOLxheVMHdixXMHm=KkR@FUOq=~P-W!?A0i*-b9p41K`o~z>d#4K&!MlXEv^x@1h-@%^>@(rria4UH zuY((#>y-g3M#DC@Y8=(}27IjAs!R(m#;N+oth37iF+9x>zf9Q(BJUpB%Q?~$TAyHT z*V>c3uO@6s&P7zo`_j?;T&(G_O3%3FQ&F?-7ep!MCw5o6?d#jh7U zEt0{*lWLOQ=2@&EUQX^-wMO#^PauAok{U)^NR~}a?7|6c@yjU#JQ!{%e2;L4=3$&lAZ6gLdrc(nebP%?t)9T1g`uTaz_=dxKl=JhZ#@lK%doAzlsC z#R~H$^y7{0@VdR0WY^Y?72H!NvvrM-=*EHh8Eu%%8K*4$0TUm`li>J7rt|W!YOW3* zpMsVS--Q{gj0x#rji+9Jq8n}EXwS9v*#4^-lOL)jX+L!&H@~Co`IZ-SafDo2H0K^$ z^jsmHIjV>6-si&R1}i8UlY?6_4M<3jFf#F_7VgP?rnGso3@Ue<;YWByt^3$h$)*UK z;$>{#R726@qzq^H2SHYXH;m}4D=i#zly&*7CX{_`jcR3OPu0S9bg+RBWyz zq0|6}`MgyooM;1negzoCS!6AH=7LL!?DK=Sv?Z_CFJ2$_j93b$wGU{!{<@O4+fla7 z`ZKW^cbjQUS*O}R&0DpRYCl!8hR;zne)o6G)ioirx9%2=ewg4rzbxelz5!=B6rkVL z7+AS8mRO%mW>s7#PnppHyd9g-wPZ4T_iqV|dd|HNebQAr%dfTVq$Lr*+54@L!n6xc zY@|F;(HRV3`TlCW+W7))@n(O#_Z=sHH~|kXWDzayGg+W%3rWEvA?b>S^mcgwyCD_Q zO#XH@yH4SGx6a_az(RWF{)bJqokOzu{o63Kk1!{99W)PW#I_!Zv}A!bjNO)xV;he{ z7k^!`i@83&++zzbzBs~@p}Nvm&-v^?*($|GFGDn_lpw5=I;f}c4D#JSZ24~>>iq7y zX3jvN;;9Aqi~hlA&1*E%)SracB{HwHWweFGH)@~}Zu-KxO4^5L2JcExaK?n`q+8Vf zN*laCZiui{{);lJ9PE~Sg7z+tB5h51m-^hhH1YK^I5FxcdUQ2m!C`fDezz)2e(TMS zuc{@xpK@=%^>Iio@`Qz)JNjQ1vP!{6=@?O5HL;3seDx{`a9{ZG-O3R`jIWqq`) zNT;uc%Aw4>36%kD*Ux%9NC!8=Ee`rfB4yuL0O#klvTK5Gn5 zAOU}~*q%pj@Z-QD7|H$fYh$C>xgJZP{Svv9Eph*RJ4^B7JRMyBCm=o%X)2R4&c$1s2uXQs&1L2p(G? zIKHuy@PQ{Y^>!UJgZGaw`LGCzWLh9(=}50WM6tr3QN(_FA{#X%2v#;af)pIr>|b-y%+dhghw<;xv##)c4(IXSL3U$|NN!kJvW97Y>GP*;A@b`V z{9V$O=rub+z@U6AE;vP7JcmOJ^ziAORJv@dGwj%?F8K|!WbXqSh596(^VW!iH%)q= zIhpUY7m+0=#FJKh|E#b(1Z&Og;ZK(oj8W7Gb9{`+^GXlqvx~bULX9A3`461P+5U^( z2SbO+g%~(ckG;K-M@}x#k-kicVr|bor)4}d!fk|X)eVK{rOy5B>#{*@2=|2ap}0Ky zukc~}Dl&Pu4*nUJu55XarwNT{lbHYsT5_#ztN1CbcY@Qn5n_>egQ{33LC zZ%7n-xKvHBTFt-X(~3FcPH{y9F zN-PL$gHf-ZD`jiTsU~OO^gD0@PF9^Ee?n3iUid_R*mi^yflZi~F_HZtOQ7Q*Jxq|L zL(tSgK$YzzN1Na52}BD0Y`e4G<~&Qsch3BbYFw`!$TPS*f%GWAqdtc~uJwsTC-6?} z?pC1wcLdCvp&?mrpUB@Vh4f6a0cy~6c=Wyt6z}0Z*9||}6vsJaM1eNyM2;4={ap>; zr6$zv5ky<`nxI?xm=$24XUyj;;P-UQpLCHQ|eXvkg8HdB5L~e}AV6{VOdX*ZVs@bDuz4GJSI=C9)C2r_h#8jk{m#v464w z>w9-K$k+bH@WVc=NtcmA&cNrkU)Hu4XQcNsK_7!z!rtSx^u*d6JQFjPzUdZC>TGo| zNBt5#WU~}(>YH(xuQBV@shRGtE5--E2vaw#AO;39^bU#wcV{m+$ums__m%9Km5=Z^ zQA=8tJc{_*dDBtJdAKxvJZ$Ec5`h6O;uRJ4qG`7Q- zF+h*@ET?Do7voh8P4>Y*fqdGN$P&&QLBc5o*jH&tZuB6lJTw>1@QkN2Tgkk;T8e_2 z4mNmxguZ3&5c2L8R_Msc`l8chGH1M)9}iJ}>oE@cywH-G$6kQUs6$GBKL3jks4*Pa zS1kJ^!}8#{s<-^!K{}F$e>kgiu_GE&yJF@lP1bhsE9(6=3EzhskShl=i0=S>%pbE& zd9Q;jESbUC>E4$(PpMES8Si$f#I+#-bVh2O(spz{p6_x{^?r{} zHN;i&E}(Rm!xGNj?S$Se#YmUD;+(uqlaA2^JG|j(q8;9h$cBsUKhyea`ZzntU(k{D z2bTprgYPzp#`s(i`m6DOcExd6ap{HV_>K32^DaJznD?~b@lu}IAH?36ttJ!y>Pd3b zyX=DbOz^l;h3X^S$eRnH5bpjJ^$(AxE*qb52DpR){k}qvbNkayM^#|g$3s}aOmp$_ zAI{TV5e>fKUE$NiwyeE)ZB*8dRO{`?s=ax;{E z7pF1TrGoh8GH1OyeT0`cETNjeS^8}2Ky+R&A;s@`j{cjCvgX8c(Cq&gQ}>5MhlK`E zG$9}FA83H>wKCE2mOeg7nGTMyjuiM$D*LSFd~fSmnK?ElahWi$KDHwM~ybR`v(aK`qs6TUo6^e7VydU}NeRyl33p3PRrPmh? zaEci zoVpw5V;|EGO3iDw;x-xAi?7E}-?N55bsl5Su^(Feki;_6fR){wLI3^R4hxUT@b0&8 zi0=dR$j{sCTknIae00hrE$R5?C8VnAjPN3*21!wY@=)D*ak8s5E^oR{^V2Tz9w-VQK@bM^*2Ilva} z=t@RKn_xmfA%tzZLwC_6T=1bYvEG8eMXL@v9!m7@Np~^XEXBl56W4hSK()+00cw0lswQ zUVzf2LimWWa6XE21^?wL2lV=>9R4d07esA^UAMZ6S^S2abk^$X0A==GC;ClO?DT<;MEHY$Jvj>tlj#I2>@Z1;?-L*sOuow8j6k zxP;4Fr%*%xMR+6Bv;96&JI83Wk zhbvx*Y+>47-lJs)T6g&GmwFFk*w={stQf*lOk>kp{6GI`{=mvLTj7m&Ff85AIV97o zzzlOqk05P{*zIT6N}ke0o|~BPClmIqwT3X;yJ+p_LhOu|l6~B3y6d(_dWXBqA?#Hn z7Rq*k_Xs&`M{^uOF?;}a~NMgTb3sqU^L2HbqjQCt;`YVF=YrKh8vwM)GqsEE># zh;Hez@;YiTGY?1ZUILFdpC&~CDQsUN@8~J-00E|sc$l*ukFJTK6F7(V@rCOuFVGbC zK9b^+45i7}g@CEfEbPe@l?GJzq!!KZk@WiAyP?o6A2s|Jz*wt~BzL+VHXks68|7RF zDN>i-Ec0US3-js8Vk7)xm2e#$H!<2`xN)^NWqh(mm5# z_&I-`=V7nM z1k*mKN!f2TSmG2lxa?Viy-Zx$tbP?_zBcb2TN|qCp!_l2R8k9}Eb5cL;54X}^yN(m zscrC}3*7V3C*39e*fU%4TSo(2`27&AyJ-kruhyb`>~AQ%%Rg^-by-gF7?t1ql7qUG zH*W{K`~EsidwYwudAAR|G~2-Mc3RS)i#y1x^Jj#M>+|rMtxI~ptmEQdMSCn<8%tl` zsG;gv1^B6Z865GrL`*IwGOG{Ts@-yvxrSsqa~GSPJsYNl>EhqdZy@8%K$ypFV75bV z(#1T6j6BbKRO|iI;*0!1Pf>;=!NYtiRB0MF{WWsS_>y%enM9Y@Ct>m#>GMk z*P3;!9hv$P*FmGWr)&D)iLiZ?4hY`b(u&J_*--6BVj7yr?$4R2+9#{N$)$_(&#dx> zKltTp;g4lIg%-YR@tjILuya8Aoqu)8Gu&@rWwQ`|uXh#;H1sjEuN?Yp)rIU^zc3|0 z!H!f!j%R8Ya?#H%DcS(3xn%|9cV;Mmg@Wr zFg!4Vgo$n0=e;E~IKdS9%x%DrN7j<1QyrjzcMKIibxBu?&=fm`aKF0yL0aM26UN@G z#!$~+5H_z=C?8sk{v%zO)q77-eU%*D)DOd-Um9?8Xd(;r-3`}*?ZEO{5(=ig52U9N znbFIG^D9oIws?eWr&ZyL=d0m#=telYwg7uRDFuy7xunD}iJflLhwKfOkfot54Vk%@ zX$enh>{HGW$9LfJ&I)`MrsA^aZsgbPWu%J^?`B;*E^S@ya_FGlh->DCK-mWai0he; zw^kOz+*dL&>aac@RgMFP(%}&AqAd+Pyq6vQ{!cNjhXJzXAHn6!FB%hQqzgO z%>LL1GKlY%&5!1*=I4_t-s$`#oBf&-LBDw1!1TmkB*x266h#}HvtVo5rJ7by^Dr09 zvgW~XkbPUo=(@T?+Bg?{-So1$mY2%gdz70ILq!fXw`eb)J6+wnpDB6E<_2t zKRC1Zx0#~FEB;aBNbd}`tiPI_-i0?$G89;&H&o7*eZrTf{019RW!J&z0~L7h&L0wiiHkNX6$W4G zlveG&W5V6h5U|TxoV=TNuVm=M@Nzk<_Wy-ryY*#n7wQnkJ2amDI6yn~841zeU2sME zGwAU59rZAmp?Qzv!sWC5Va)6jTzl%S0@qv;9^Pz1HIoI<(DYVJOOxY56Fp!)Z|Hz; z6{ud&lXVu>5laIj?ELOFaP|)EQ^s>-e|C^hA3{NPEE`w6y`lJU;RSg*vKA+dEQ62a zTH2a(B{=?mcXmFtjW}wt0q6Gbhw^V-!S&u`DcV;L4=jx!kwzBGsJKYATbj>nz|5UHD3SsQu3ZJodet1%*ZCi&hau_KkOA~e5s>r(vq<_e-e3E z-9&nF4$s6pBNW|?jA7Sc@t+r?!FxQ{I<5F zJ#Rac_54VByC*XtD**Jf%^_9aSh7Cxk!>0uK{v~8;0TLx}pDskm+uOosO=ET?*4FheJ(j(0r>L z1E+UmPxe=nBc=Mda@Q_!KkEr|iIKFW?mF9bVYKk3dn;-Aml!gv(1RY_QGj``2MIB& z?ZgC-U376q*&Kye2S2#* zy$pwKRzMrQVCCR`#ke)>Exb%}7teXgP_XrcWBt2<-WwySi@-aExVQXhlqrk%N~Vbg z-J$okHaOGmGblap(l_67a7f?1WH`SyRrS)vwVHDkEgYVgJBx6~UpF`vb6-esw3j}Q zY{xdOb{*s-=Xt#lZwU9(gQSz(lb|=BHN4wFZVgOiXB+&XBlq9>$>mbnnb&M*_wi8J zfwRF2;)E9dwpr6(-1mH(@N}a(y~ee|MN(e~HF6f?j`JK-KodQpp$|6BfA9&<_U3KW zBkQ^vG41I6)b_+Ecy4WnZ5}-XpX@B!pXXjvGqllVLI=@d%(4kH8`2^Ue2#&g7@wc9A$0C3?F-m2mi^qM`breZfXUFTlwc?!8X;NSy)Dq z=By#V4!0$2EleyR-DjeHIObu?D*24)n^CF^zS$)fjiJUZ%v z!Ujw^-&j*}s8fKvZaJ~Lca81JiB@Snii5^jS3V532EL@TxS!nR=44gRW+(o+&29UR zbSUPlIXJ~Kp z2Q9t3v*360!JtML|9p*uH6ulM?QbQu^2}#jZbb{_`rTQrYk^AZsrxL)x*jQthv}#2 zXU=cYO}Bun)8CSp|8y|-U@?8khQs-ze72bMW;-wCQM2YM%sDxe^~tpo3$l0@<-Lp0 zeLwfITf0aP9;su&h8^T1*K|6GDZ;_}4KOUQ5f{~+72Gyk!)b>+Tr}5OuQLTXDEfnNPf5U z&qGa{aAEw~K_vUX8*FX6pUR$3=0g1VI?OM91y_D9ho5)&d+JVSCR8L5#YDMeKjjij z&A3T-3^2gzH>pBxMhV@Mn1iQ`4-4~rqsh1o-ih2-L6=nrf#EPUDPqQFIJ3N&>UXL@ z$L7xLbzwDW$2l{5{)MRcJO!hSq;ADmSVHV*A(GEtjqoev6z}QroL7j6QiR}bWiQ@O z*TeB!1-jea0M8_`ahTn7w70V9t;wUM(rh^mzOH{Nl9s@aJ z?L`OPAEFkl{Ij?mZ`nVEdP6~6#`*T{oafZS=jjw?By}#_&4Ps9q~it?wkRZ#rc82# zR;79p{(a2)w!aFaP4cm5P&BDAP!|WB)y4hGt}9x4IWHv^VBgFR;32yw{OVyZb*wdH z!gAL^Vb8cHeEm>}<~r|j-Ye(gGLr?-9i*)G8vA~lcPX@T1cU2lXk+^cf=p-8NBqt( zx;jaC=sE$`>~6$IvU9@3d+M~)+I%$dX|M9GTUp3)(}*85V~q>~Eq`EkvMsY*tw~;% z8?nKPJv8O4FBom%y49q!Y}Dx+pg&56hokNazQ6m!gz-fI`)Fo zKi-Om*BPN%>w5aZE0acatHIUFx-v!BCi4BCjx^xMS+?1I8Vt9t#(6(ZtLEp^&^tKa zcd2j(E|I>vKd`xN2CP4LB`xSwC8lcFu)dGYMH$b&jdI)$>#o?sw+=ifd+iDvGHnQ% zx4RwdIP4o;8fyl=m+SH7?>O?Jyc^UWE#e-tNMT}I9dX|U4GcH$OCKGwgG0sDSk?Ff zHmxlceBPAcEM-S_zQId;I!T82o3}yROm+Cgf19iWw!n!lcCd4z5(f|3MB>MqlX;7W zvh{KQ2Db3PEvl+<)hRo8(EYaSHx$9!*1+#)nv!lpKZu%T3Nc;t@ZL0p zr{*$ovO*8r?HB+VPrTp^>PvTnwlSTy8bUeOaSYbHfh!UJ=)S7!{QJ9zOepw83uBoz)EDk-HO6@vo-lOeOFD2u67%+&q{{Uy z+ifHrJNL9wn+HAE zo;i(*^Q$=PveiE<$@?r!ObCTC2R>I{s=>>CZ^<8ix9s!d16{Fn7jw${;d=4?ugmCTec(waOVPxrGGHKEcb}9aa(z|vpB=+u%eO{*mEo+?>b%Zq&0@ezZ6D2sG>uP(s5JwI3ai0W>P<#dnaTylJkM^% z=vB{QbaE3N|FZ($Wn1yQ;t%4%dGBw>Z-&`Jy}*JqG0N&MvEF~j2no6ByjM4k+}-9u zYj@~LD|D-b{7qh>C)YdnO|hZc3%Ng`djUFkOo4z20VH;*E*q(IQF-8Fsx0v65EEL9$G;?!-mQ-abbkU6SLmU|bm&Ru50tKojB=X)Q}+ zndu`{b9L)@1L^Xb$L!W?o&(yii+y`PP|a1-IU3S`f!~Gg`Z{!LRUQ6rWeDd-xQjlU zct6Ot96Im4KA3*3!TIJLS=uZua`~+xJM6ZNHtrt@?p-vc-J!=>RmZEK)lG)iemxc% zU-XAX5kdS{5ZaH9BYUtKjRP2zjJ=Zf@kAj`Yu%PPT{9M= z2FP*CgRQE))JL8FMlZX_W?2m(&8OS3sal^@bM>z)?^^1Aiwqs(0J|=gV5-S8!OBNh ze0X0AueGctIEFWSM}g%sTvhY`(wZHYej#wY*tQnc)-!|Q9YWOY3~X}cA4PZ!~> z^VeZ}cs`k5o5XhBEuuur3YMJHl(sZ2W(OWVqK-T(w0qS(5XM?V%HJgP-@A|8?Y5BU zywt;gesZB#{Tk3JtQsGs;ep%c~fh;c%E{p0NYpDZep4tvwssFc0)jRp333u`D*= zH!)Ar#e0uV!n*sMnKs5;sv7*3S)U3Qjs!b1vqo*9C0AZP;TN_E*Cyv0_P~N4-!Saf zD>|d*E!k?Og9+?0_3|GEHfL(^qjfuWTKYPp?+-XWlQm-uN<8Q#ln)}E|51y zE{%WjfN3|3AwJ!8(X;TaFn!NDSTIdp68+`mSx_fCIdIfqyrA8S>2H9^u$WJw6F02JKS}! z*r%5PKJWTTwYz4!-N99!PlT;@>&UJ@+BiMAQTgTi61Y2~8P`in$Z=|-6=9V)=CB#- z{ba z@!fW9I?B@o4h;W}6|t9~|FRim_*Yx}ec>={5_0L3#Tz8!JVO+`#)xb7B(X*2o8etm z8<@12e}=pBl%dWUVa>aIG%alqY@eSH{~Kq7Kdp3V#g%WgjI&!c%`QRE!V6@mBj>T4 z`%GInLW|F+Nkv|P?4eZvyin7_2nkfW(pF5s@UuIK*O#LtqK`JVJ7Xf)JNZJ&r&2Wi z^qIEYNb970EKyv7qdNV>WbQLbDs_gy0N%Ydv;i9@Oks!Gv?CX0>!JTB2Cs!Hw3+*k z9$#%I#902veJ2IjZBHgOh?IoPLH1HzSOc`Y_Z^Dl*r&2LyyQNLBdscM(VQ{thx>M- z47|<~hYeR{iyV?=lHq}StN{GL)tR#>H9rW#%SoV~s41=cWklA@(4~h{@-g1&Jw4dd zS-jmyMi`BkT^?`QM z#-P#6!RspddMA-35i3Yu*c-Ieb)`&~6YROxG#J3WVJ|vAWLEb(h>0(Go;@;^T>KIW z=F@NDw`@tMY!gT3W>#VAem9|iTtb@FmIAz-+nSYE8HrDH<+!2GdiXGgb2&IafAr21 z%>Q72a;}#pt9bQ+wq!7O@I9oU^LxReq*^@K zHVJI4D}>~w#h81?n5|Cm6wjH;FqN$a&yDI3$9?HW6Hl<=uTGPkh(wl;t5x%M>u`!w z{~RZ~ZQ7E=OP*|A(Q1XCg)z*o{DD&@0DaSCGnfPy;1cJv@F6Id7^x+*_lLf!=IzB1 zn$op`*=)G;BUFyifA!?qB0Y&&E@ivTS_#p|jqw@p9E={=OecT7j^A_+ zt9DxHwjmn6cNJQ+C)st*gR)eE;?$!=_rp~-8&}e8(?{|i2n%fg+zqaJeWLN-|KXg< z$!y)cXJp@`WERAM`nscIj6C}3BGK{*ar{JZ?C=xe#l9+PY1ShR=7l!+n(W*T; zSR}tp6&+)U{UTi)xRcV^Jr{!sHA45s9$;~57xmi6J=ki)*`b;`GAThH!%a`XqQ!&Z zxUXC~y;ovS>0aSuk~909Yb3PjP)VD3&us55WKQe7aJc&yd{=UknvHr*vNiN@3)i+L zI(ftVWi?pe!j-&X7w9+#jx6K8Bpwu7jxt zc|uE`J#xt(RDWVi_V`$Vac~}HFNmdHCw0Wn=QziptCF^8`flfbVgFlg*kz4riq8v8 zv8~N{(3WXKHPH2rq@S$m;&_C`UnZjp9O^+wa7VgLB zLxtF3Q4AbAJ(K*RGS(`hie`;-^GW9SBsOE}dT_Qi zg}`;1Qdz?n)l3f5;~ANYmSk=E88JVr4W3rMQ7*UmPCL}+Bb+@6r*2*#-&3!%%!Id8 zzD$5lpPSL?^<);3F&)&+xxcG2O*NBU`{`hKO>d!v=k_hA40}JjKzDB1r0jJfA0q-! z!uXuN;?@^D2f?*y{Z;mmvabf6m-@2CZKmXPq>kj6bC(Uzxdg#{kDWXa$mJQW#A}mf zm^-_laN$HB(BoNh^Yw95s=g=e9A+;ma|={6S?Onp?rR)X+>gNWGVJtVI2#bLjog{U zZ`=KbsOPRFoCS^{y$H16ez6*`}E@Zrz0IBaarQlaR$icn3G&mq1>ttu?gtG3U z3FimCOG~E#*K}akz6y*K4Vi3qEAq9_T6p}i*f-V~+je?PEAv0l+24v#{#l<@ zomoy!4NGL_i_O5LxEHu^j|DCXXADrByeOHX-a-pcR};&kpQ{ZsIWkc?0`vh+5# zT~#6EG@d7U1=Se2^E{lMaV1S}PCnW>>oSk<)}lgNj<5SIS9t)s-PVzm|Du?9wI6vB z*_H*qd`Z=pn!<*K_1JYv2HB9=4H^a~jghKUaj@mz!Y5|G!b!4TwZ1cPX1=6#x^_e^8~jzO^RQCIL=bQkl_ zA19W>+K`@3!&rLqcEvMS6KGfT13S&VLi<^6hGw$@{4(zp?9|OAQ#F%Wk=iHKOn%i> zL(&=>!03_(bakFSwwp^;eyZ^yxAAgl6!G<)PwMCBqIQU@Fn;waNK0)(pM6Pm%Lqd- zyqS;QD^J4i2ASCTjxIKWjcO)8!e$Iko6Igw_@O8*kz`L(494~e+qK?#0)5ocG$5i~xr$gjY z&?RIBiF<`bJYPRzs-pLIN0wBB@x|VORrkIm!Z!VeVe4ni~NUY|bJ%5uF@Z6&I)o`Zw;xdh#C6_YqDcSQkgTxnO zO>n-V6?xO8j#lirgXi@ONm|4@^0+{Ge~d~?*K#A|24dVm@zTJ$e94VGM5 zOb&6*x%a-=s;-KMn{}k+Md8e5>kwg9J7?BnQdlAOj5`dmk7g2o4FfjjeMeP~&-Q3*T*N)V10TPqJ6G#S^S_3(vpw_3e7=XA z_gbZz&)OcEQuwMeGV%3k;g$7w{O@Q_GD+j4_+wogJmC|jYzWDxhUdQH=uu%%=y;J_ z%THv_pFE~5Ji3?tn(?X8Shm1vIy8mqNn^9B<$DR!S(T z%tG1S=R6V0UYQx0*?aR-C>4dQ?2(aBX{+w}p6?T~_snPyX(|fE?{xnGdfnH(-{(Bv z^ZC5r%anQk!ca9SWp6l}b3YbdFEWrqA1GM7=}&T@fzPX%jmliXn15gKQ%5&)t^S(O zPNfP5l`p2W*In^*3xEJPKDP~FP?DEdlME`gk`#8@SR(9?ME`A!)t>6P} zSLGBiU1K15y;HCcYdeT-v>nkV$Bex0kWDXnCSmSh9b(QoFbft`;vCnbplN$8^VNOc zvtFahMmidaNptmao{PVdTVgj(Cf!epWO|1ENkwT}rZ@13a!2uuGf%wcd?Nc>y1=6c zg(w_$CSDUX#Mr)ioLL&8X!YJUZLPz=B~kF}ONEd%tqRq*$k@s3kz!k(_juWF0VMKl zp*sJK7~hCwQ?8vQ4=T9VxBYUMG{+J25AZvM(ig;C!;KudFr39qzN$PkpXR){r-SAx z3a;OvM}tamKu`$J8Wa$x;p)=wag$l6fV;H+6+PVZIvuoowg;QX$@ow$hRCx0Nx>Hx z@5L+n4f2e78UD+lZ9=dr+Fzl=$O-{#}i3+dw#B)+aB^` zAJMIMnlNaS7wh1ZLy{Jzvd^DAK=XhFST8k_Y8NS(uU#bl6nq`m%sfxLQb&nVmrU_O z^ETz#`08oimkiLOceMazod;^8yg-GdXK#j1 zR=<&7Hj-Bz+i_=WA^J|PQ?&B#rhL#wvic0w`PBukOv=VW_1CcGyR&@Np=JyPZ?-#n zk+^lbA?l7i292v#AR*h$TJl!Z`u;!eLGTdIGxQIekbe1q}32u#QoPJ zuhXbWhpA@BSIpnm0_yHbr1+keG=bvW|v~%?mZAO$BztN!Ou{l zg))=y!PFjeIRkGV=cM#+%l%3hB3SX}0-|Z1!c6j4z@v#~aK-aBej5=_`j*ZSDieya z`$=yiE!JYC73w5K{3!YTNvQ$B#jGW(740Z<4Bz`zM9mYKa+J~_vQ+GF>)|l9T!M$ zT#RRXRt{9oTh6$YMD0`-8aEztA8O$OgMY%mYVeZ{X!C^sYTB|DMBClcg4@a zJ;hQ<9|LMH&{ltL)q-q{ws;Mf7rzxgJT_z_J1tOVw@hnPrJ2s5Ea>YsaQ&={xpUPy z3v&PzZ~Tf2pN%2^9l0i~KH?;Ga_vKdSLk^>e%%4*Wu($o3%^mHZl!qW^)L9Ixr*!$ zj$<+Ydhl4C=Pq*9rQp8%Say>SWOp^jkqflRob}hJXLUR-wrof4=3O9}+bi+9b_is3 zzm}OYpa{b+{)B(?jl|-~x|sFX7rxhbf+nUVnGK6zwf*~%6D@67bp3thT#YLGiNm74 zl5gQ%z|g7?YsZfueXG<(qucyG;;^~mK}Ih)vRqrTtv?O@Z)gzB{iS$9_zlC#J;m%! zI(VbaOgL`zkJ6i3QckZ37E*AAj9$=szqUwu?hWK!r(Lu2i2Y4BvYtD{J1tnINU;on zg&#koh0Q7`%Kbn_horG3L5#-swSl)g)THN+2t1gkpo-xJW z7Zvb%gbGyZ0PeV(MGRMHiiIZ)(dT-oa>v`hmS@96SH;-3<4OFHTkQB^IhFW#W6@e; zG)lFA$Zbz(WJxt%xi^pva{-c(naTpS9dnx@x$c4Y~Aw)vNV+Em)b?+xMfU{)894{gAiEB}Bj zV}|_bvOhS4dNAYN3&pQ(xg)0e5IlBLfd=lL=$@@l)>T`=9iG`xUFk+VCbc88r`%>M zbGBs;9lr+N9;w6JuUp}&#wzHORfc^+tKr1+TV(BMEs6aKWm6YjqbIkT;mt>8B%#Ys zDmY}|xI*VsQuV0Cg~c#4!#~%3UgnE(4k7UsLjLh#|V)PlX-Tx9E*t zx6nND7CCnA0a?hskg}m+g3lT^_|vlt&17e?`g-0GR!ryY;^#M&dj^=sok#wL@F+q9 z`h5I`<vx?F~iuG(bbqA76bIPYtu2a=nf zT2$wK2|nv^I_vX&XEB#|rRO_F(zqYGuq3AzXTEQQO{N;;x2+-TrazPJ?=cFz`>RTg zY!3@5iGepf6FYjo9%=3Jr&)Z({-KMB>7;9d`?^2);ZbbXPq!ChftMN1{}n}RJaXwv z&NIB>QVFzXCHZnhU9xrA%a*V7f!^E)SKGaoY$(_dzPbtM_{EugYPmobR#)PRHXGr~ zrfZqYrxf8lwF(%q(n##nSr2!tnF9Ae@J`}LE$MS(D7(9h`_YW7*^k=0bk1=L@ZoGy z!=;TR;BXhN`Qu!vz`5jRk-8}3y`Rn*icH%py`a)rS6UHt0L*4+#lszP8h!%}!;g9`5)Nlm*${8!EcEAsp zI>CcCk<{f=1up#K#{Svx`+|j>nJ+&Ge)~P4#F_iYe=z3SF;eL9q9+q-`wORD8^gv^ zwYa8X4>|lU2)a3ZMw!WZ`N;k+`FBGXld}V;d-)jn9bAvfXV!^O5C98SXWnXFYF&u_DQ9d<)GySj3?-TGtsytH2!)rI(8G1`-vUfnc+}o)pcBEHO3jqkGl33Ys*d z5Ir7FfHy0ykeZJ1?CY9X`d_d+c(nY+!YPB;>7g^=&Q?AA*e@R3;s|`7!)L5VGpX`@ zP3CTsVN%9XK{0p&=$qEyPTiaGW6lAJ5K@BqndbU^^`6Ny^Vgex)Z{L8B_<54;qMr4ym6JL_rWbVZ16(zK?>*KqZ zV~bvl{9(JhLeUZ@=}gyC(07-s$2IQVJK>}YA-`qtuf7tUzqzoPjl0O|uz1F1xhQiB zX(x50=bU@FwrMPUjMm1iC}XnW|8nos8{gFmu=YP8BF@G#f zJZ}%t5n9r`<-yGUVPA54d0Upd1(Y1W?Ty?etg%F z`|iiM!|cj9ZOQz`c32RiK~`-k!jTIdxvcY|he$`&SDvgNm>uT339R&iUb^|I+rZ!@%++XLl&vnAqi;JUm8* zA}? zje!Puu!jbO^nXD0IXk`mu5K(UA&WR`q_GrNSLM!jdGVygaj1zfP^J5}cr=yG-e9NPR1XTR^t zN>BeJOP}%#-mMTYIXo097V;e0s6^iP+%LH9b!PMadMI}V)7RDF$xDaGoV!7=KA7_& z+?<8TBQMFzFde+7@T0-6N5PA$DpH%QN*ENGPxEO7wo~cC`fIlpM{{OEib^P)(e4C0 zJDNz-d=uH>!YRa$bD__^v><=$H$hXsUwE|s7|AYqg6p`9M6Y1cOb2-zd!bT zPkY&ykcaJv#wcV#DsAP1Z*GH~U2S;AJAm%ma*|eRa%ODGOXzy^!JOb% zFx%!U>H3%VU%n4l`a$--){;*1-`b=;Lxd1r70G|1p?LDo5IWX80sD^iA@ZaDh~YYY zyi@Ee5B^~YYE#P4^qm}1$UHKBn+*p3o&y%s-%$EaOUg3a%{oi@yy9paXvL+ojwU z3|1{c$6GJKYR*a$x>-#+bae;owr&zUJk}NK1Kdf6Eje`3yj0v!=SxO^xk@@L`G%%0 z9#A$dCiCFRB8(SaD9^ONI~icQ`bh9=>j)v?#*+1({p?M@q2%ahYZm-LK|j8>fZtAy zxYAcgY`qt2KcfH_?hH}R*!g_7Q@(eKJUE2&gi}j#{A4-z7v~F}XNvIZk{8f0e2D11 z#t5&B=gy6xnoxJQ2Jf0JVe4n^ClkiRv$N}_!Y0nCPBclt<#rE=vz9)Y_jm+jUMfPG zhAEu;rH`AR9+%%TKSJ|Ye!*0}qxGJdOLqKKm4=M#%iJes)4F4I_-Vl+W}0Fv7G&$8 zs`EAOqvoEGVhN4C^T{c@ZKSU)-$5OW7oN6X58pdCEoNjL8JIL($mgt%IHe@?%$>unsf{77N~$d#-a1c2SjIh18MkYh+PNY7IZ8u zpki+Up03$0oQoby&hGxe!iL(?o}oLTdQ5xV*q%STFXmA0xiZ6rt;yJo;upK3dBIgwrKw$UB~Q zE#BhAv5_kvsHp*OE_w?tLGuBZ^Sg{64y@!rG1 zuyS{1nQKQ0qlpQ`%&Wyh{d0sja-d*m9=>=MDgG+`zT-UZYqic^zZ2zbZ6DC#Qz6}q-A*_l_u+qb7PXY^^hr`;g`jXCwJ?#8L zZ(-8Ezvz)~t~}ocTgBt-l*MFVpTA^V2=}bX6XmfT%pkp~6l-tW!{t0b^0``%=LPB% ztq!J9?TqoZ6VIJ3y+aKkg?;ZigY)vuppOf~;r{ug{bqmRw2bp5!jBUDn2gozR0Njhq3lU8`|__FQ)Au8Qd2 zTOU7-ih;NdB5c^q@P#6u9NK@Kyj#RwMLUy)RtDg;s9HQSIAI} zz?JWG(6e_n6-^x>vRefj{Ig}(+ZvIr$pZHOodkiOeA&;%GD+Hhk+rk92A_tcW3JOX zlK1=tQ5~m?#hPgXne7TbJxj5$DqJ|fJX?tI;kkvuDxZ{2m0aY>Ut znACtlycd4v=|C})_cXt>^Q6-bYJNS+J3lYXOYn5nT{yLPCGiVWl|BTn zXPLR2={mUvFJ$P6YaZ+ewE@>LCUPDzICF;Fo%Ib@b1zfxF)^8GX9{u3<7`-4WGJ2* zYk=-!hbVIhHBrXWm5m{6YVV;W)Xa+6XQwGSSNc1CVqm$ExN>73o$V0~H`*1i68>R(EjlW~++662r zI-J;WZof&yMCH6SG)}?nWv_^ZnlX9%U<3>3rJBkpxPq9^X)_ameIzS4Wnp75lm z2_?twEN4}Pyz+=S=FLikg?Clq^F{^s8vL2)uh0;${58b60~N~ItMjoKz1xQi`SBCT zs+e51n+kB1);?kOy|ZL7lVQgVA|3g8DO^YH_1pXk zWaH<<10!`QslOXr+D}J3%DtJ@cXosSfT3{mt+BKw?Mq*D;8Dg>xz#nMvdV{;^4~?;N(bWEc@qpD_6tMu6NyU-cK{@{U|@$g z!l-gf@tCm&)}*$lRxO>NQR_QDw`ar6@M-d8w~BGV6ANavYrL4Gp^IY^x5MVpCc5PW zcfXJ7NfwQ>g0&G8{b&d=)v@Qfb6re$RW6^hE*b8gY>RV*e)LK;cRC*~!tRA>uwi=~ z*;%70T^X=}K}-zw>}rW${th6f`O<$v)ia-4`-xqoz+X4O@ zt-#;${7g2kb$=wFS5zDiMibEUwH^k5P9(h=%gZ7no1+Tn5 zFg&~zr{CZx5|%A2T<;`J|2;yvTW~Po46#Xt%GnFP-!bWVNA~zl5ZSJlzz*BmDR;Sn zMKVbg&oMjG(QtE(7W##DCL>2phDW2-q$jGGgz0F}&-p*lXa7^-zrTaTf4q}^(5N$Y zKP!XPqj?sqs|4ed)yde2*7#{yxH2cEaab4U9q&qR`VD}et2L$XyMdhkg~Gy~)!5(s zzA)bTp1AsqIo{aXTiJu~UQ>eV3vNSV)=DyPovP%mwt}tUT{u;!L9b*}afeAbeBXK< zYujxkEdLDA7|b*6#1MD~IMeiT0sdOU-N(}m#pg%$@#SLfYM91%HFZsBTQZ;7{cs}1 zm#x@P<7C>(uWrNNDQ32@6df7wU|JTVMqD)6*+Wyj{6ZH85Be%^Wg5g6^4aUD1O6NG zgl7ij=n{|#RV~BBK5GrJ&8NX|b%+LRGN{LC0kc_omk5%b70-O?$AI%S2WV1H!F`>J z$x&@%^5m}<`?Sweu;Cm(>nj?PPNEt~nzj!L-+#fU(pP#oGnb@am0|g`7j*HhMNr?p z9)Fd!V+lu6>6+2in0?2G<|`G24TmH zamwz`wDrDBIPeu+EZVTt^BKfzTPpK$wpa3D0v_l~hJP-wC4VF6%E#BRWz{>9{@q(N z|HnJRyWR^M4U4I>HbsL|DExXIM202H@b+UJ+5wlsm(LCOrZ5A}PUZfQrQA!KYsva< z{Y8fQ>*2)e&0wB01g5+;mfkJD!rn&g7rGZavxT4M2-EUR;A~3`9=LLwj6EC#rq>g3 zq&gK=eY!>l)$ns~m4&tu zx=T!dm=BS0cgFoCJxHrhc@B4s8ap#GsGl_)eUpNoekg=ze;}1xH1SZRDh*HX483`X z(cL@+KKW0T_vP+#gD4~RV&XVa;6A$y!>zC>u7$SixRv`^3~_9fwK%oT0M8}#B_nQI z!HdUPsAUjI+8wYXOHKG3eq$<>JWPU3S>Mql`WwwPS`AupoVh*VI<$nukuS!Yl8^Or z7P|8)ea#tA@nhY{lf~a?*1}{|3ExLP%GZ(S=e79`*+lR^xf=A;|Dhthkvbe|p^Y!g zu;-LGc>1k^v@h1iOK*F?;>sbgHizF|$Tu>(OCtm(CZkVADOo*3hfdvvEL2YOTPPgE_A=RB?sX-fLdpZcMeipmte2iY4OMA_^Oq{r5dPVbY zWmn>GOB1U0YR^oEO#@%v>sM)ry?QduGMd1A|HU(FFD=#zx61?8UpZFLs<_qdSb|y+}TL^?E30 z?<{LIso47gS@%(swtaOQFP*z9ESPK{KIOdh1)jRp=Y&4&tE|EB70IBrRh^jKFlF|= z22%AI6JV;518!aw33JE1qjhy#B*zj%G>x4m?ses^v9m7Z?#X^|w?RXyO?pD?#-PyK zx*7upv~4JH|s1@A1tiy@``b zG_{*_9Y=@kA=jic#O1$lsClZGO0#1!jX78C&$w7v4~Ak%Cg%;V=mp86J3|~lt1rr* z!X8hvC!-6x=7;~YuE77%- z@8o;r(bk!qI%DjXF%kp=dN~-|>4s0PWcW)xy`Eyz5mM;`7 z+XTzj{6#z0cBIt75b}}>aqii4S}Ev>IbQs(?RGZZJZS_x;D5u+FbgK0DU+W+-Gt*V zO=bJ4){6_(&2VP7%aAot1>Ty(Vw=zTq_LukJUnfPE6gT`)fa4)3N*OV!5fZvIAsZOIFcvx^{@YVoD-RZusXDnH%52uox-Y@_Np@!KI?Jf*V|rcC)oI}>f` zS=n(`IVFZ{yrqxsD(<9tNn3b%P=Rke&JatX6Pc-@kN5ky38$u}LgL;Zcwu`Q9r=7M zjGa}4_CwBsiDw*nd0j&aEt}7bYOm097xdBO+h8KI_(p#=C1bhmF*4d{J-O^9!>R3@ zh1Txy-N%2?U@4{c(^}}bvQoU0ejY;WzY?`4+W1+=0nF$SP-OnWUj3)BLI2zY^G_+b zQmvl+JEKbt`%pZVbB1i|s4Lox=Go(A1BCU3JX=T|rQQ91(KFi7#Oj+4Tlx=_^O?Jy z@bNzaT3PRD$3D&Y<@7Xm=lu(k^dODdeH{%EKg?mrNC`JQQx)&@T_!YI-ozWn50Ld5 zE5v5rb9@o(E{u>B(#>84*kxu6opAIrNqv&QrrT|#L%IrJI{p_r&bMHXcT9tqCo0e~ zz?-#M*g|XA0sYI)XiCO8bsCVv~(cNRNX8n%#_scdLAv(HU!OKko)C&tcRj zAqii!t0ndK9+Lt7`q-_ZTuAEK4}P{Q#Sl|-a${k(;Iz<5YTNraZRIH5Jf(xV2Z4S{ zQimm6q)pG%yG6VY83A?YvY5;zQo#^_ben;X~4*L zWawT^y49-@FLvxm4z+O?2OKiQ#ckdw&feCC$)?{q6F3HHFK7^h{l?6Fo--XWbS(UL zq#1qdrZM~Lm*8{$7HP?7J#5%HO z=`(oGGBqZ%X-F~tD>w^7a*agip?YYe)&;gE*~6#{b$BCm9NSgWiDW--%f8KxRo=(h zswQL3-dZxH_fNW^EDr^Go4{Q)(OAa-$L{JYoLk-pMqMt&HnVQffFAk6rYfEz4T^^B zxnAO=8Jx>n*8`TxG-1h$N<6W66subtMpiwDXB%3E!pkrRxR84bd&X3eb&&>SXx#`F z{MkWh?NHoW(1zz@MZvQEG+n>x6Q<%Nn&tPNOnan-rdKlQ&z}6wII#}9KQdun{wZ`? zR1FS%IEF3m-cel2^Wjf7p9CkLcCe#OBEJ4vMbzRJlEr;=xRbg_c{g`%uDax7-jytQ zWC|nRa<}rHYqWWyo|xyuofnT3bbakGxI4BU-({P!E_KE7$9&FQAMC?^hp!jEo-xAZ z9nZtG9lz;*tyu1aEh5MAsz|_ALu{H~smz|Wxsi%}+I|!A7CI5xMjgDe?uo)-!v%<| zG3K7r2b9)4q4E~qeduh!7MEub?Zi~p{+o@G<9(KQWZqjIXXhe9>9$oxxUIob3?H>u z>>6Z@opNe~z%J$V*mBO_m|i8UD-I-KlVv#5^P$3|?NXT7o}Z;FuEE_C^T5NU6lZ+U zWl8sIxf@KEGkmy9ggaa9_Vr}Xy01~@B6Q!>;_(x&$!N=9D7u=Ar&q{`)4l7YWGr`H ze>tRZtn-GSTU4Y~eJ(?`Nj~+|DngGUHForssd%7H50i`h;pkyokn!Khor{Oro7G;V z<^p$EZ+9oHeTvvwzpz86Ps&_`{A>z(J8F}UAs+WEKN}tD+9no%c0NX4m^G3~?@TZz zW`@vhyE(M!!e`OwjWj^!M^35fu= z()7$bW^yi!X5=k~m(fkQf4UJ%$(;&QBEMqZ^danH?`D$5-3>ENM?o)F5!_9ZG0Xio zd3gOiNh;OB9h>WgquqR9&reM$>Vp^Qb?bm4=VCE_yS|=o2bEJ*}x>)nwQuk=-{5s2~>NEIwbS%Nsx{vn|%2{^4dIs#qBnQ zV|Lx(d(WIN=3 zR*DtVH&O#dp3r$iHTsV|0TX;ji3^$y&^z58R%NKejT;sC*mEeWu?{8ff8$xeMxxwl z+?{X>V;8rOfc^&Lv!53m$p#1whfJY5(;SBm+bCF$I8DVlpE2vI6J0*!1F2ugJ4gRT zE6>j%O%m>O`TzmLBk56omaf?8$!t#AiYZIE7pCM0)H&Ngghe9uRsBaIpDZLPZ?y5W zMT=l@Vgo!m`v-@mPat{6^7Oq2Arw1jcisrd3yTQZqD zkJMi2V{*Ee!fnxIh`()xp=D|G>+D==@Sq%n{-`k5&$r2^#55L_%zLHgmaxfECS?^L zVCU3AsYh%gwq2$o?uwf%&W>)2H`ERJneGQ&8k~-HpW2atKY?V~eHq$p9;|5HEq5N? z1`pC(^uN7f^v$~x9AfkrCQhg&2Df$4{n%`H)K>&wp6B16e1P5mwo7Q&?9AkQb_lo3 zO=149TD%}HB&}}51FI4-D%qMmym^hhuae=%x%P@qb2$fiOg&cFMS!;bYg!mth;C(# zFm|V@n69RS&x&TkFUR)q$VnzmQ8~cc?HxhhhHB&6=flX>$}RBJt_edgeI;*gtbwJa zqUy2^WKdo%xxLo_N7{5#OuOU^4Hi`x7Z3&+s*~lDx^PBoSQF$IjTL=L^wHdQ9>h** zq4uIova~+H#?*6%Q7ZSIpYbFP?aW|&24Me?WTM-pGkMTKAETPq3h9BV@NZTlHpZCK z7iZSPx?@EcTfYYu&W|ImYt^NrKPEEZUZ}3&c35e!l#I8L!GZPHarc@FWX<@+Bxjur zSLH7iT5}Xb%vGcfbyl=z++V8RyBHhB1i^m$GO~mFsXMlqgB(2IN0)k(*$!ojWM^SM ze+SY2rz*C5)}}r^GqB&-cyixEChG9#^3)02gl>n;V5HV>eBxn2%h#?aq5NH8iPd@K ze4c&62z5KOhk^~+^c-h;cvyL{yFSmz{m4|N+QUQ1-dT~Hgv)!XiT3f+1>LT37|{|< znhvcLw>;pklh1*IQI|5>zP>8 zf;||-Ox^#Gi9dM8TkEiL=X|6k5u0LE#g5tM$h%x^lzmnq?~hM{U~6?rHf27U9lc-S zxsE$j4j1Alr~3kB;19Q-B<7CHH{$;UdQN9Q=` zuK9#63P?t0R1-~KKOyF?bn#`H8fo2o?BB{+F1NhMwc~e$QM;Wald0Y`AvcN)z#tHdGg2QuS$8*%+FU3|CYAh0v- zz@dE-Dn@9ELtPh>xQ=|Mu~Un*X4rb_HDd@_NtF2t&OKhfdAH(%g}!(pLWT}^4%2&C zo>0SgQ*SI<;OD6V`NB;<(AQ36%MPs(hq{~Nx#AP>x}7R?9U6;GpZU9>e>Ex5)yE4= zhg`KcgR=9fD8Jg1D9_2xdg!WpB&+wPXt?yeBc_hON&EjTq#dr5;{&MytWs~24?*e7 ztvl~3CR>8{1uf~p;eAZ8HH5zME5Ub@yNmrIL&P1K?QrBdD^fr9H&t788yC;)O)gyI znV)%Dd?&CgYxNp`m{al{2g-KC@_Bwx$2}Jta%*94eGRGQpGm)a(_m$>2XwipC1uaw z$7+}C5>~HpVVatIgn2tn!FW2~_dcj0t?sbvr{eK(VRw?HdX;>7&)-ePIA(d?9RX5p zJ$C=hJ%O>W>5PuWnESXAzHBrTosa6G{)s7Yva|yXJfkJGoD5^Lqlc6Ce5Vo3JE7y> zZi27nP55I{lQPe?{6qnceBnz}I?2S2qYbg&4wtNf$6Uaaa5nhWt)SL%vOLbC^>Rk5+;4WcC#c(uFgx zz66E}1}bTADZMk&&ZDwM6cazk%Q(TLoJJa~%EX1Ep!lWKDaleiZbsqwF{~0CzzjeiQJw23Lg$S}J15k7< z!<~B!71tX5$i;2k%cEfldw<`hes8MKz+nIz6MvUH&`am;3%PQS;rBENqsGg`efiS` z|Nkg1)u*Ip=PvPAtvNove@OV8S3-Mw7U0V=UB%b~mx+$^d-i?d0y=(~KNRHu#NC}# z*z^HY;7vj~CUtdVF2;XI_ksGj%kLm0))KI_Nk;2^GST7rc@oQ+y4~_*q_q?0R;?yU zP61@?ru~X9WscI4w__AT{{)Fz0othF{~&c9+Zp;TspaqNzhH2jDQ8a!c=*6!?!WbA z&z`DEZDWF1*trW(`!)%6rpiQS|Ah4L*2U#Nbx5lZB8$)7OUK44T4%4@N&`H!{3va8 zKzuw_g3%MJ;fwnY($P#qI@7Y38GacC|Jv%H)AX?<_~|sr9j_{FQdbq%Ir4mk>Mfk; z(Ua80YKd{zjBsp^-dU=T4WN0wj+8s_5VSpHK{l%zvg!V2N+*s%xFuHITng3;@6u%M zf^l3C#&o0036<;O9h327dcOgnbFLiUn3af#(5;tjcwN(s2{+)_OhA0HROhopl0b6q@WdCdKeXDIzIybw!AP6gkH zo4hloCRsim!d$YVY3>d~Olv!v4EnE{p4gI%y4Mv%_t-jejyn|YB_0-9-MBfu3~@R= z;l5_J0o`n!hj-K`b9Z6^VZS)vrc4tK&+~xwnhiL7aX)sXuZz&&orvz=b;Ya3+O(q= z;C8JCM6RVLt~<}4-AAK@wgZe{xn2n#y1Gd|wq_2=P%&Va{{|`C4(tZ=Z~A!tt}bY0 z0DW|-8UttcVSPRCk)t$?4VDi8-K*yCoOkNo%k;%q$C-k53&qH^`{dE*U7~DU8|%O6tq zRu8@V?}u<70tU{>xNDidIJoLOG2?gcngna>s86fl%}_J4yhy;3_z0*E^kx6-R3(*dflNE?JT%uPVZ~s5 z(Q)DvvTv;}*6cJP2KQazK6g|>`WEtEV74&(oRd@~Pm#}warHp{oE;n(L~G}3!4rN~ zSzc5CISt!M&Q^74@tfW3Sg|JzTE+Q1{icuz|LGujsz`Z{wL~K;4O%%p0i|h#lsjvQ z-+T>l#D^&N@4C6NLvGpN4sj_oYdxm2by`y5vtYir zEGK(6>ETnq>Ew9XK)AXn4Mobxy>&stl+87GxFV25&Bzgd^FH9&V@KT$${$nfm{J_o zdnWvRyoxOO+l&Kkg>^=kV!7*fQElvV7?xZgH~~9SW+ks&kh^_}5@hJ-1SwHO#{P5ya!Gp`RbgkfXN;MvPM zjQg{XEbIOscpv_RgXT8MpKf_iy74{y*|DqX{%C*hf2qd&K@JiFDm zop{HK?`JGSm3M+RMM-E$jl|c}{fQ=bXLosOPW(D=fMX`VF=YKAvh1!NM46W2ASW&1 z$`}LjC+7nP`mUm#I*))yYCrhjUk3W4O63Ne!CPEAjQX6uw$O5Ljr*eL@K!J&Fy3t`QWf<=&5Cn+dTs4eb<-N z=~6n=>!77PGap`|CC#qh&E|Cpp@TkM!&7~=MfF7^MFT5S{LT`Nn@fnLgcK<#6^J7%|=tz0pjn5gr6e1jRJm8BNr z-GtdIb;PsdtYP+(0<5&%OYFR5;+7A(INV_bFWYtp-LI9XxH25N=1h{i9Vo(^Q(l2y z$8qA#<+?c1VFb`CO?37ZEh)eEZkFG2nXLb7fRiRKB&|%#8#Cik*G?jSatksuUKedz zE(-yP$uNiSa129+$v5{7p{v#wVsgG5MsK)DJbS50YNH3U+K^~EUo^z$bRpT$qndVD zT7-Y`4>=lmg6vV}91NGsLT%4=5IDUVcQ^9;J>JC|6_$sJ)q^2xMj??WYvbr|Ep)Np z5HOPeL8sepY@v^vfHM-YLd#g(*HxRAkk9z0x`8}>XDc?g7;$I94WV1CDXh;az$0Jn z1faeo|Gqx!X0=@LZ0c?pL^@zlqbb-8c}IP?kKpScCzkOCNz4Bnop(G|Zy3fy_TDo> zW*McS@}B3RDJl(0OByOFQ5g*qY0&tUl9u)$*~)m&bMCj&-b&NnWM_}x`|v(q6*otW{L_9JHDEE`KcMkH=aT_J)V$hD&=r_iy<@3?+(iQ zo5uySGf>a;J&lsY~dy@hqAIkLQu{qgn9rr84GR zZXoxGQV{T51C4l<8~Q{AE1q3JTTjOFO>_s~&Fjg`v-JzG)J@t~dvGiJ?wcw318sn# z%Sg^HRdlfj!@>_INPO`+PBGUEmiXNw*7rWLFJiKw>y0v&Qh$#ud!(tRuZ8~7>{A=B z7F;%*K$Ux*G2bqk307>}#TeeUb8M%1)eC()*#3M;qMKL^9r!ExZg~)WqdWW&lW@+9 zYEjZH!q<-d2(AO*iL?d)^;CeUh;C_ zmHsMZk{^%P_8WulL_eNiSv&iTesAd~FtN_siLQ%-={j^%b!jX z@`?j)`&R_~bkz2#7Yxnpn3ESX@`tWez^2g*y~8PBubHxNZ;^;_XD&b62$6d%IQbZT zx^HN6H67=L>>2-qY>)QrVQomV6LSZu+GFF%g9JQBe4mt%1wqO5=}XHK)j zhl%*5N=)J@w{|E2`H6-T!ykWO`%y1u1#>^eE<;FLiV?KAPlErUZAR|Z?k9d`j92@CE z+KF`Ur=a>1l3?`gD$n4@spb;J9|H;|Tw8b0bq`!b3Wd3^yE z@23R6&H<3vxDjF`iF5D(5XjLa(y3ODA;cY~cnYFQ6FuZW5j3M?288 ziPumTj6V7q&C=CHF8wmFt}2^(shdsgOw6D*R=`VIaEBGyQwG8M#^h8(GCId~K+ryO z?uTpwTkg~bAr70kfEnZPO+{tc5E6)nyV}{iO3&f8eKm@cKZ3$2i?9A^HseF~5b|IE zLS@e}QB(Wb?8XvUCt^gVXP2XU=@M{NvyoLlfJmgLq##abCMUx!jB$>cv;gS^FLIRAwCLT^UENev(y#E1{~ zmNnLEpjxCMC%#pH66>FELw~J_Ux+$Mr1QHD>NAp#mV{Zi#-N1UCFIc$QGp^(Mh|wz^0)pSfS;4jF;y}y zI8TIfKI7*Lvm}WF?cgO}M5bG)q2?uX;J*#W$dWf3IWE);#`s?&Bc17M!vS0$8{!{r zzmdahDOjUtfTSN!BtfEeF#U5pVvU|Nq3LD~0z;FJ9j(6qqm#<8L{eLzfvt}`z z7OVmx`;&OKXO&2Q2F<58o07s~{mhmZid=JhAOCx$E18?91R_oI$ij&QY-SVnoJ`${ zM*4>0XE(yMA}O3QH<_tk@fa3&_#?06i+EqZDXd&0;5}K^&DLeq!0!8I!adov`2k2yJIjPm%F16; zRtcV$O~{YKidcRU)xO)?+220K1W#>%)fI-EXxtdYQ|pE);frvZivbl#6Dnf0r_k{b@(lY1*MT$`SJ_<)PwEH(Pa3jLZ_J{aHrF z+`R|K(cGtL+&p_T;hnjlj}I3M^>I&>CbAE3<`mt08P9{NHzcrwD)qr!=(Z=(!9Mq>o5$Df(#M7OF zne13xbRqzx7eUy1lgfq#ypc-bS0($dMj~_R7UYGft8Uc(EqcU02O!{fB3f zgmdBok8$qKFT4u%%ysGkMC=TYx7zX@k@3Ny1s}av>G&zuk-$g$1Ke z`BETlmdI<2+)h@Jc98M4C9|!(iELRt2(;glShr5(byOP27>2x0K}2(}oS>vMii47) zOw|rsPR#!zV{k&1q|#ZPKS>2!W*#A$Z*t&EaRgFsPC?U?B*Eg?PvOpdh2|_QPa2b( zPit8<=Sp~gEtj~xSHX)YcY2`NUbr)_Oi>c-dmhDU7`mgr1vG>FavMrg4k0s1HyFxl z;!E;6B)XV-BRx`4ce5(~Nq?s<$A9sHZOn=Fu_mYvQYOP&mhplmo8Y&ABR7Z#Ci4|x zf*3>oP(OL}`A%rxv!0W=c>$^V(B5iOf7CcvgKYiq6s!czsPnrSGM+30?H3xe z)EIk@9s`>m97Qu?#K_$D9IVu8MDkM)Bd>LmP_dX3YJ#5M24PRYTjuM=0k+1t9DMi6 z5Y$?ULKjPc;hhq8L=$YLIdQ8HGfvHV3Nvv-2Fx+g!T07%vAYjZ&ht(Q;oRQ2UJ(|j zyoM7RA5z~E4)Q7x!eomrC%{V8|LFa>R~t=U?I$*G`?#A zlkZQ-nTaZh=Q8hfv2K??I5$ywy_A9kj|al>F_>pL17uaXC^^h(~yt)qzgggr*f z6Faqj=1+nGx4*HDKf)0TPUwQ{!^YfLpX;P!f(-n7x>J}#`TLo^r&}uGMZ-zVJlb`B zO)Ub+uZYLx%f^DGp$L<^?=P!PnEAez<(tl=IA7K=79an006cx9vYs z?AG1_wTljT0}WQPVV@HjRl!IFCY3>RUv(yU&!^HG<<*dlvxpCP2NP*!u-8? zOn_K9Q<7W;3FBqR(0+uYPs&1VYb9H`KpPjol7n+I4$?k~F+}=#7I+H`a1_~wGW;b$G{h1K`{Vvn?R#lHD&}O# ze)nwPwmxFypO&D|TnSiuQ;FRXFpEf;w1evG0&*mzk|#5>4$8Kvb3bf1VWp4KaPL4c z*?YQ$J)n~eEB9*R0+CiU6hpZ;pX?CZp-!@rb3yk}47%!SiPj!dgtU9IOv%Oj7?HFG1_)MkNa?@h5bo2)aW8{K}n}SSFqtI+Z_1-$`@z|XLTd> z;y!&l5!t#`uudxJFqm}&oxB%{&~3_*2oq=8Z~Ky~Mcv@)BuaGtY^MFoP2g#hL*DG` zLZfmh_uj;YgzaKTI!{heB)^|iJad$ZTx-Ma4Y|S;WT}wXRa65V(!x!zj*y|b$xwtM z(e2@z$nq-vj5{UA3~pOMZb`@rjGJXi*ur);ZFB_$HYbzSUCP)uOcvgan<$*sa#NKB z7tA8KiXwM(c|>Ea4M1{tL&&Z7wC6}hACLH)9nYpyFY7V1r?d#^(mRr(ojmhttp&OG zs0FflZLH4}58lfC4RCc`2Kl_u9e<-af<%69!Oyqy=IZ$-so3FU$<*Eb=?@AG}H!U`Bk-pNa;cD0GOOeI3wyLn)Z2 z_koR?wUMYev_sl^ZEmB;MV8VA;e(L}Ckw_{O-~U5y~EL&vKBUWs2rjUmGI4^i)eI{ zESwDZ#+2O+BKo4kplKt9M)E0cedGQ+0cot?n;5Z)igtDG>E>xRRpt*zlA%t&+{A*$QCf`9#2AVZ%J{>k4p3R zR)-PsP933WsMWl_Oam2G%>%r)lw(p*T~ z(1e_3gkc@(p-RikK_=s#kR=D6z{(GNruWiOWHclNxI&tJY=4gOhW^2h$~-cwcRBfF z-vu8%^f<#CqjCRG8z?uez-_y~BlnGxP@gsd?YO>#6o`rnTJQ@bcP@rMn!bB(9zP1b zm6(suP#@O}2YL3}S921V+5)o6bI1)X6?ApgTjOH^~k1>4%*qB6Hi=04q}6OT*Z{F7(p$|cC$*Hth><`D_kJAleT zM3DE%hnq9xNU9U4XXe>%^mWThQg$v2YL?dsXYxPh5!gf@L6h%~#`!cuTA!-Sj4+D* z!)w54xRxF88epFK$#d4`#rzQthX28T@Qrq0eYlZGG|$ny)}8g-1=XL($3O-q?hg{q z=lUBB@couLj;c*!E}Cb905f_zL@ggyJFl1-Fr9Q?WgoQvGJRpFwz{(LLcJn+D~Bu>%Jo^;s%r2>ugdJISP z!|jbC=uJ^({>FaFh}c`jj(9m<%gch}sV}ULl`&aXCMNKr`#`SeL^NBz8)|p1!56n! zkk}xAz-L{^&Zh!pextvaAH_`9ib=%nzZ!UN|Cfo=D`Px)Wx!>WvmbR3-WDPU?b%=1 z=Z2!BBd`qy7in{=Nh}IDkptUinBuSb%1BMlnJcJ@6yBfrNVY@s903}AB8&trpuRHq zPs}`#RAm2$`p2Xi_^R)G$WY`cf&PR%GWkD_HSnRj(hoVVaj_iO>u z&m(ag+Cb9s5n1!3f~Vw2H5~B;fqa>c0GpjT1kiq5V@OPR#JEgaob)`JCO%HC7Pp7ldp__SJ z*0^fntloZ6T)^+&!d=xm$}Z7)0GqOPu*+L#JikN}o}8GEZU%L-{ztN))AuZ@JROFr zYpK_Cxd{{SeLE>$)CFo4Z`k-5G z-#|u8&W4+8d_(BpV3o(gv+z|&L*X%7P>~E@JWir9mv5nEcO^lLK6@j#=()P11colQkgQZnVRwb~kRpxk;$Loa$)f_aUv7q2%S- zEGV^WMYjHB?D))dVD-ppOdSZKZ;>Xs zWmt8sB4m!T7Vg!2@iy3hdNC)qEDkBuOT+5ggGlO+I=SnV4au9@5DwBsTV$xO@mOoCk5+<7{poO!hVuiQzAf{5nuS>8bmm}LC-7bk#*r=lA9V(pN>PbRI z+|RlJ(0l92bt_&a?ww|Wx0f&Bf?@NMB-+g2cr}d&?1LxOjVAVph{{f za(Qj%xJ5;QW{^wxPQN6HHGTFN`s`_Z--lkij1qKqui+dD5J`I_3B5z1Xrw1J<3SD- zIdve7wFUgw^G6F*PyRrqdz^9BeO0h*v}b-jQzmYQ=}q8JmT*=lS1ND^HoxL;i*g~F z8J$oXrpBFANhEo#{jjrZC1(`)1NF2@!{2`gg}#pe!T{bC(+p@|ECXCNwCp~QRQ%#G znrQ+*n-($CpLep|zP-@0=qcNCDFS`jmCfDB4`<_@rjl}ze%P^0i@OuHfW%oh!Rk#e z+-`d@tbVN({KMDcyV|EnS8Y0s`P+oVC*4M7^lT6UTTLt;@T@^4TH=Vsur+_a| z_DEQpfITzMh)k7h29+Qs?w9yjluU2epN~ZeHN>e_v}5=9Mm*BRyu33LcHL`1=k9(+ zVw8!rS*MP1B$LQns=*yqQbObJlrmdON@3B$R5t1bgNte3+%BGgHFh0ljYic&_hxx+ z{HvpAKfSqqon(rYEtF8X0cVp${619h z>?+D(k(xATShf~FqTC7nZ+_%N?O*o6!VI`#G!AFX=tBpJ<>337nW&d~z(kT#!7lI& z`e|l}?)zH9_r!kl(HV> zCD6h>MG?2f@zIr(Uo>_x6FJ?AtlujmIM#cKRSpj3RrQub`{lFb_o0ROEcI8k#g8M& z^24l44*lL9%;RnZoum0sDR8cdK+B8N$SLZpx7Y7N?qjvk`w}TQvb~iN-IqZYUhIHS z&JLYz-$iQa->HH~1RE8VhDvKBz*;tyl^*9!o*1`-hlv~)^(UU4q}&2-W9M=E_8Z~K za839@PNRl#L+t(q99ZlY$J=`&P`soJ{Mg&hxNO-?LiY_&EqexPQ}1WBsK))fB8ZKd zUy2f_A8G&VG`9YXBk5X3d*9YbbJuh&nV{=K@FyVvUwZ1qCdns3x>OSyJl~BT_bY&} zML%N+$|Rn0?VMsHkn7?}NH$uYd$;9U!QfydseC^M#yoq=D)0NoZqjc7ZnF#*xv~(6 z|M!G5%-0s~*vT}Ped|pqmTyR8pp3vP3vqlgH4=+HQ-z@yBBpZciX-AJyQu7O+KKhghlaw1@h#IJfz954s#g@1GBRi1Dxkseb(shC7V$ zwUkR}n~@ZFb~>QDwM)rU${}x`R*i;?WBFo6xp4oA6rx@ftY4`BkaH^WZ_EVjO{&{e+BvorD8kZ;>->?fQiihB#2%g_a{PU0<+M=(t$26tR16}w zUP^%2i*S^l;Z6?I=kNo44&8aV{F2UmxTJOmMVU}>;&6spoidl8)TJ5Ew7b^*uE}|90ze;&%@T*&Xv_yJ299FIGQJ zyGlI-aJobSk7$v{j>$pJuP$bp_$1;bRSg$JEYOa-C5-d-A^5T36wCXt5}&2s(FngR z_U`jhr1(+|%nlLf{;Y~do9V1RFvc2REmB09Eep8Sv1gc?LNyZSV*+L_ny5_d5z7|k zLg94{q~o81%q=NTKyovGb-FKczTFLz9>kNw`*K+w>qMaWFT&yH&I+c zJA;lVL%4-0=2X|Au-Q_eao9$6DJ=x$&yTp;h-YI!;i6;LoZK#C34;gyb>uxn^9QCuQMrkke0u5wEpv7sB~QD1%G zzgfuFNr_korh;nl4YX3!5Gm~+4@vd0%y954^5VKGu+dxiM*n?cU#_Tz_VF>q^g|AM zP4IE(+bZW(0A&Au~j;T@RM+I zesd<2$BN+YHKpvzX%8X4_Bz_}-+T0QvK$OK?PMk^Tal+zB?aGpOku?z1n@4>dEVT8 zgan5!#7T@IxD<{N_K6JbXa9ww{Kt3d3#6n2D-zj#?I z&6JJitXyB9&ii@XSn69`a#4ezNHGC-_z<4|Esk~|-1-ddgJ5b(v(mH4|9$+``)Z z2tUY`gB{2Pg=kD8&&w&pXK@cw6{}#9={(OrdkXc{+Bt6aQGkA0j~ZwpMX+fXy!iVc zS#$a*%6~l!{BH}ntHTT_OppNH(MYr^+?|+)WkTXL5!^62mml7d4@)nnq9@}OvBgnk z%5e>5?9&v<&Zkwd>Z>;UHn5MG+AYsjFS{?C=VL($I{giZs$K!hbLj=$EAzPxBE_hI z`us)wqfu7rG;*z)W>4xxaJy+FvvMc{UOL=EldR6;B?cPsS1+82++M=2v+Dy6nX@V) zhf$QEn6vs4&N@C^NhaAoh1&z)h|h*GWYD<*M2|agBC4X;L{1H)lFuMH(NxyRn(Eq= zeYGI=Hahr7Ob}7%h1RSn$k*Oh1y?R=v%Mb_adet2jJk1$9bxIq`aFg9X~krfvlud+ zqs>i831SZ>tC8MO-IR+PfKi+U316B8J<~+-i78)@=~Y?C4iH5;Rkq}oQw)6j>TrpVZL0t5^uGUv~~Ca2%h-Z#51 z1?n3=vUx|TmTetI3R-ed<*|Hj6#W~mex*&W(tdL_=S7@beiW;CITL0sv%`ljdf)}W zO~C(D5Sn;ZoHWEFL+-(QC`mSu?kJQAnR|#~F7G7vd-~vd?|uH{*;|SCKAJ_nwT~R| zqxt!2N%;Oxk>*%=#C}Bw=ssjPtqNbJM8%dH`!-FeSL&^@1W~haROvvgW1d$+M{60H z`u96Jg{9yV?=UlxCEqYtMsVKzIKRHDm0e2z&3}LP3hye~H)VmWQW4(3#m6^6$dhRt zxoL$q?2rM;;S*@w@-UJUlL4D^#Ib@`344O_=O>+bgs@Z*dO|(e2{@W5^0p#Z^hE^u zs)zV3PkngGlqq!gS0H&6>x#`L$iwq)Rbr?&$Q~PPg)br0n`aV-hQevrymAbBm!?5B z^rpjy`QmuVOD!Zv`!u7iB$3kT3^Joy6^7THWWwFfvOjbyAY%S{ez9>1y7om9daj;j zL#}TiL3`TZi|Qcl(~f8Jp$_zwr*JRS^|8WzIgoQWi7uKpu}5xXLO`?xe%v33KD?BM zttwJzw(@Qg{Hq@zj`t3#vK(j*2e$@#H`9es>2P+#E@HMN3H( z^+has*G9%W_aM_U8AwrHN&fBNk=phYXnJ6c^NTN|VfaM^S$jYQO<1bJ&0MQ3oabA7RN#8y zMv`|so3(#oCLqE0v6wW*1`Flj;JBqIB7Q32ZO;WK{m01a$yMfczL_A}{W@~`W#>5U zq#_*NbgH1mNtz7#)Pet>eFWOWk@;o|5EMp|ZzUYE6LeP2)^s-k`lv(qN)~LO9RmsJGk^B=BqdNXCKYJ#(MZcR{=J*!F5O z?IGHPQeLK!9dzCqNQ!*190yN_+t34TSRh9_nL7%FoY9y1Pm&fB7cB>lc z@>GHcrxcJ@eLO30$pL9cYvePKfwr1UfWGRHfr|fr<#qNtqZvEyyxsJ>RWEj78Cq!bmdM;A7O7Pq`;GBR`hdc5uPwr34RT)K%>^y zv1%r%)OY<5=@_O&LU&82G6+x&By$xSkY}D0Oj@i+ zEN4;e@=6D^9OiLyhJMTxV#8JJ$z}?dtCG%$4EUNOgZFHkM^s-`!tA`iNH9RPsv_!b zwxGRNv{SXAl5ttEXgybGw5wUdm5S$Fl)8+`kbFqing&sb|pQ@3a@d?>`~S)G|FCE~v@i zrSV!wG*=2T(-ctWrVNs(O8x53BG9ymT_j7j0_xw|@#4m$pc&Jp!0}_GP`j*|)dASO zjWEF%S&ZsIvy5g**6QQasR}TA={Y2y)WT{$&4dkUvUr587kWhs8qX@w{WE~4@&d5C2Gj1MgGCPiHLL}f}mAk`>uroxdxE&7k`I5YKOUYjSItZCtLlOnO=&+nD z1RruE^Dps8bGeydl1B=T3e~`3^lm0Ez5?~0@E|U4DIdm90LT;p!rS%sMYKU+C@St7#?*YPEB`o~Z;1mOc)CYh=h6{aQ%7 z=|!9)!sxR#1ciYNwhAs<7-C9XN(T_QFDv%9v+s{4OxP4tUJ|` zyc?GViwEeOGx~y79G3yt^GaxheR`(15-x7tjqarWVS-KRXJShfPuBkwcA>nElA36C znX(88^`sr;N2-YUm}qqLa~8BoF?cXZ2`%Bfa8?R8nQ4*g#HK+Jk^*#5RYW`+9-9MU zR&FS9b|zXPM?3yZNAuh^ZzdlnHpA`-?&Rc(4EFkxDmY^ElO(8V;!3J_ADz2U*nj;+ zJrz_O?QwGV24tZq2}3hi2=C#>|MkKmLrI+eSe8`nuK>-$2vlk#i}Ohe9jlU}3|0 zG}5bbHzo~gQV8-lFhV*9ZQ%m%4WsS%fmA5U!nH$cyp%1^*~+t}@b|(T5^b7+_Pt@b z9>;7pZ<8LG`A<|Z?;Ay8+eNX?Gx8zy%p5$i)(iVeC_t^zM)bI^idFX)K=hq2$Y$no zbnX)Ute=_49H;$Fia!6~-C-%lD{dnh-c<_orq3pF=Jkl_l!U&*QNn$Da(h4gnl_C) zAi0~#sEG|1Ln1_Tf<8G`*+4rzEjWeq6Oh;n%4Ll^jW(Bu z5R(V#@JC4zFZBDvTD>X(OVNMGDpMSvrXK0xPq!GQu<=CNd;q-P88Pzi-n@WoWf1Lv z$*l>lSV3G7+Wv?Odjn&o8X^3m1vhKc8D#KA9{hJ)KpgEN)a*}(pGy_-k}54!#7cs- zvpO=cNGGfHIzZ3+G}`*#F5+Wc0iq%*jIL!0+B$*y_SLtsE6q2OwN12l(yfYI`hJo9 z9aaNqsVTQLP>*&!Q;x^|1SGzxgIz`QvtRO+Xm{LhG(`7p|D&2{Bx|#6@c_uZk3;vw z``Kf0zhR}X0yA=0wKDnC3n_j^a6Cvsl?Z51@LF z6z-SoMh!Xi&hSGQC7f3xTeNbZ^pyviV>Sul^U_?z{fQ1EZ0gue`tae@QMPt`F}tm% z0mMpvk?dpvnx3D}-3pQv68)UA&;_g)}Zd` z$59f!m9Yr%>`W6$&;@l!6F02UK$XkMk`~^;*EaM}W}qGCv*Z$S_+cis3U)8%qRMx zjgVJw!R@*vil0-BzA7Uex7%6jbI{qN1gy~^h7TnW-=A@9ysZz5#!wIfnCdFq0-Nvox5LzOg&C> zL*KuVb61Wa?~qJr%yGoy?kOVaMi*{Y$34a+L!Hz&Tf!83C-iVAll@vFE_j-94_QQt zVb6XExRrf?chh+@(TZq>!>?zMyi*yh>B1^dSpSZEl-9&1^lp&b?ns_wYLnX&Q$fL# zhhIZ@c*+axiA6xB*$ZI30%g*tS1nk38y)gHfHD?ODm`P_R zau;?2b81+P_)97Q(%OZP=nb|tu>$V(ieiU>VpM!b3O)v>G0QJ4AYv2g+=k;!82QBt z_Ef@ao&|aNR0U5dqHM$Eo$S3w`lRPrBaB~e%(aZNLN}*MLhyof!XEAP?HSC)$-Q#;U1LVvv=`#rD;40# zkv?`r#~iEM2&1Hog>&13inc%f5>Q&8HnIA_hqn&;c%-*QK~oAIE*yjQ-b*Luf_4z& zt{{KBi*($s0F6t*%t%&UO&|qJB3;;ey-g&g@gF#C`A%$nxYDMQ0R4a2n@Q#>wbBi2q>FQYJxqf-rzy>X+HudfkUV-qK(&8j_=^=N}=ZZ}B z!HAdgc?|Ye(Zx1P!~_S=KR_CF`T0AGYT(X<1B}2!8T+)#f+2Ea8OjjYf24(K5T8ld zo3RK_)!{ajx(j!50~hKoOpC_X)GP@_=D?V$v3SH=D7{q%H2MutZIlgZn3xA+_v}JF zI@!z`y1$(&JT9E=$E%cKrmiO|Eh9-bdVpW0h{JZul8mB9 zVEn=x1vh;|{gm_L&>F`xfH}nJaua}@E$LD!;fWuv0PUqO$a9-@c$AVNRBxS25)^w_ ztKoE5SnY`8clV)FG+!WQx&m)VxsGVoBN*)Hb> zq`y%bX1r-*O%xGHy59<<+?3N(*vcgIPU0HmUoy9m1`#Vw2g!NbSgc_#QJIkrD(}Cc z86Edg9U}$bClY3acYS%nAbj{GV91rHl9r`6fu}-m;qKG{*tcK6 zgn#npakMXETcHA}p1KfkpuV-$59=wzb%@O_XrjGxW4LtB|B&rrS%_)9jEJ%p>F{j? z$&v-wz*4noOdwh_7cHJ8OGLFeNH}JK!*mX#akSgCo_2u+ z%?%)@68dTHa~gWFp^sg)vkZ0>JY?!7Qmvma0jirVS+Wq3O92vscQAu1$Ci-nioN6HIkh;`5}Ve7}%f=B>M@v>~rtt&a8VEvHK3k1>KkOUguK$(zHn4R-Il6`O01g@88 zXG-57+B2PI;hUxjeTFYSCqsxL#`C9NLfv{&F!q8ka(7)uMm^1fa*bbT*(N7`v~CJ4 zX$nNunzFc{T^vr^zUM8WeumZ|8g}nEZM;Dq^IAx=De#bNm@?n$-96q(0+zEcm z_PZ58XV_9~*G9X$L}_N{*A6u0j~)53JPX$S_Y=)Hp1>G>H4`j6(uhnHCOejw=t5{q z3r|a4ovfgIyevl*GQwFEKQsWTgJ#@&o&!mfr=3LqE}(6h9^_knI;?in##U92`SpXp z0h+{d@iB9(a!-*C=~s+%lRPP*olxJ(9x-0edYGsv1+IR^WPV!F0E8P=9RBVRNx z6Fw0UoW3)G3)o$X3TtJcZPsPfs4|0Sm^}vbqA^$tjxb#pbKs!cALP3FA~rsv4wpZF zVlE{8VG~w9hNZMCYDEl#F4#zc!t@DjJMALR_+`SVH4yarfPqAT>MG%C~H zqTlz?{DBPi;N>j1e^VDvQoV;>P7@PcF@A#Hzs}E}6`Bp3AI2~Tk5!@VVsbD+X(GGX zbR0=sL3>7~JSR$b#-denicdr7W#56qmYi_=HR67BJ+&_Qpfzc&@5KWioFuGq)ZT{oM=-fV)|`eMR)E>T|z zhkj*{*P{H6q?w{@~=2h-8zEp%^O{*~Pj=0#3YueH-+ zJ?>@B9`=%F66|$x!X{#_xRmx6oY)kBT+N%>bLHU7woi;=O(0Q8 zq}k`{dgfTcCgQlT6yieK*~-p3luSJpekEU7^EV7-kF-Hxw+`33d@Hl*&O}b`#v7(~ zvO2j~K=%Ph58Qq~nq;p_hupR@RATr50nIU0eE!Is*z8LEF2nFue25vYE@5wq$U;)Y zSGMzuKDj2_05go#Ip+`K(YhMi`%`#Xcn^=>-wh&8YjE>M9l{hngdm$==tRN?bUap? z`m#PU4Gk6~U|l)O|j*+QE5e9w}t4m@?X9 zI7*<&Ie3QQ6;nnDD*v6uUxD7kDFb2L9Sz}K#Z^}sdL-;ohq)S=vXcXi*Z(0!PY3j9 zo;>HjNRD@rYI1pUhVbK|8S9$=lXdW~fhXN*MBxvM`m6If^Sv$X$X#XKR{_K=_re{4 zJD3gq1b+Uu#Jws}xWGvc9+Xc+jq*QOo#`pmFA+)e(_v^M)&1Y5N;B(+;)wknaY6n# zS@Jh@3wc53?N-kWqMY7~rXP|9^O-i}&n&v1ze#}?Q|IAol$b8eibVA6=FLOnxNVmoJO!tLYuGU5aUKFd@B`H6VGbg-te-Lz8nBT(Ic9`svY-0L3}YJEaJf+A6rIhrZi!)c-nAy10u-U(-Bj}KqdObgBmu$q zFCl({2hDg4!-l;Z@jk=Rtk3ZbIJUh4-I*wbi|@+Az|C(=bGIz%d_tMhhSdyQ8(>tN z6}UKKHKC@to!$q+Eguu!%S&Xiy#elLt8+6PU!xOUGEnH8h!|!D8G8H}#veAua`w^8 z>^W)hCbkqw>z~8HBC7C_lrSS)*3vysV6V+%#yA_Hyq%JuC?d~JXg*3d-RXj6Up_f_ z^M8)c!;$JQ4CAu*-b#ZIQlT{5?|W1lM5Vol2Bp3HR4Rm2WHnWaw(M2hbMAX-5A8Ih zjF!r%WR>6HUvS;`zUO(L=kttX>!*B0eQyKFRL)`>V9q(QL!yYo=VfhkpvDl zBlisCq=S-g!lN@qMV0D#xa~oX@IbZ(4Ae9*q+FMF^@VkW)Z?Uv0;X8h2QEaLNOoq8 z>Gr6sX!wIlrqSeMrY-wBpb$@gvLLnt%0Xud?_V3~01A^Gn8lXscxKGO?s*4j z)(SedM3a#Rb@6h7F zM3?NDpyz*;7Dimb;f|3o?7&4xysLz238q3GI_+fqAL;%Lg0=VYL7@FWt=e8Gw9sEPl!!t48+*^T^M{^tD#2M*q)PBGW;_3L;@ z9$EvrUlg&yz)V8qoY!h7NM^;CAF#R6yf2tt>Ke3a8W ztTUC;(LJ)D`H~XmwwF>bVIk{xuL%zwF_7#m+f28$a}HJEIFgp;NmBX$@QQtVVECX~ zntZneAzFsS&4_{_msRmi#5*Cg|9WxZd)b--NvJa(n zkduflThxG)O7tYUM^_3`4<|`_@)Kd!WkVL7+kpF&7ZCOAaCVXNY?IZE$mT<@z_X6C zxC7n`m5GzsUNsr%@|&DhGq93Qd{%|0x!==nhA!zdRtXzVNoaV4Dcjkn5us97Qu=!^ zq{Jy=q0y=CF7l0i|6u2jrNn!bDeI>w#nn4x$miZ)z%h$=8+liEYcDq|+OYYkF+{s8 z7VT4ej}M&+X#P=8;+w6G*>i8xZGYNnztB&pz`LbKYDa_eG7YpfJr7&PnKFHTH@6S7 zA|lzIP{R9p19_HYxke7t@#Q%(=NoXTa~+%8P>7rVz87Bbp3r+Cd^b2*Azu4;37amd z$ECTKS$^-sbc$syu8dQYw9hspgGoIuk32wzuDZi+^O?Ejiz89j4ug2^$ydm70@=KE z?D^+5RJ6Pg>bF~IsbMP)=6ndvK^<^&IM-foy%Trw1LyKA+pcM8Y=q-LVRhm+d}OLE z$vLuvfI=r0+)E@4x5v;m<1S;`;~D z2ib_aw3p&x{c*ps5*@PmJuNM(!3AH>GLxNR$T=pKc(#6|H&TpQ;${hMFN|i!gn+K3r5;;EcK3}l&yVB7jN)q2kSmzOP_Nr zWJ)Xau~9)iLu*z=M>4Rxiq7jiiO1m+FqM1AN6QC6TJSXXVp{<|`P&5Z{oTd)Ip5nN z=OBFMceS1K)G%V-06{jxnw3wfMT^iPs(3~X5+yp4^9Res^no?o_3;;;w=pN2yjg=e) zIi3eOSJ#3{`|r``GW)>mPl04eM+n`)v!8#{+i|`Z=buK5V%n<|QSdb30+`!v-W950d%!qFEqXOS9FElW1=d$6x;_T3cDQxI36L>PmM6&wPNZMnqK1=7bT_q)!jJRdX4sZ_GuTRH_ z(u1*N`2l|a-Q@yZ?39^2lQnh&*CG4m3ApbkKC;kF zjyucj;=(|5I}1;|o3ENWjBx{##rW#6oSEu7i4f7=Fj}6f+I0_a;{iH215}csY2_agMz&N818a@av zLF-xXN5639SA7_#=gR_mzeO>>OE@Lhg6m?QmvNHPmj^{`U*GRIV7<1)cgr&2*k(tG zs`!QAscOioavD&(+?V9CaHiy#i;DMJK=Jz(I5S`LQ z#Jf4ZhSRQl=pJ1a-1j<%mc;gC$1>~DW~`dT=JzMcdPC8CifTS<0MWh#h%XEg)1J5Ut%a-b>T~$DJ z8``K{4ewzrR+LN`9StijG%;4?3RK#evENn2c;lWU(U0o~XE}Gyah3=|TymK0fJPip z@R&0s)-nz4Li`;e50`khDmqXZPdc3yt0elesWm_F^|d56>QEvbZBdKI`zc78y!afc z)WN8T47gPEoBlAD;sA*Yd2}We9H;WU>a&q>rvExtTGfsvs&C-j{Wdzk<}dzNHVkG* z%8>FFC473~jQER!8#6C!#Jee{x_vCh1z*u+v9e@-WDt46nRrr}<79WzSSsUn8UH%< zCC|hyFqLf?nDq*?STF_lrS=Ej4*_Ivi-6Zr7w+=>9cYE3~WB(Po2O{>swY2H%yOIeWpEwQj^HPhKa`s^4s3+hucQg?O^3Sni zq7a^L!>$;8#5={2G|yNa%4GB;Q>rB0I*h`rpO}=cA?e?InDts%glo1gAwCW-foxaB z6$YX3DASoKx#i%5;6D(}jtZ07tfjVkx`cT-yWLaNMjyY)f~rJ?S>$$LzWreus=ps( z?206p61PwbMQ3(jvkj+s=t%C29m(qW8+K&>bI=$vmnlYc;$x=4lRABX&b zpbN^RtX2yf#N8aPJWz}(F(O(ZAe(e4vp*ciAZts_#xNQSO&>5a4X313NQY zQ3@BoK#Eir=*!=nhdczDqNWn_>Dst4>WVluMu8<<xi^tg}*08Yu9#7j1YGIJvJvsF&)SGWZ4H@BwsAq?z#V{ z(_1m7NBEKO8U^wvn7?^jBf!sJpZ(?@m`|d=5SwcOG}scS{5F8sA;^jr8DNUldLiHJ z86CrUcWEMlo;{QWJ$WuQxA%E^ICKFk{N9L*|5K6-d9;a|ne$!l$P^+`pF{?G8sm=> z@o>SknObwt>XkvA5TUmd>;qLW$iKbY>oUgVH~v^Q4u&oA<-JRlSR)-lySy%8FO+bH z-g){KUD<5)?|9lzUSdCPnQ++DN%H*c+wQ%6%%^&^t@0 zcw_Te7bSII1!fw1l5S3F&^%gJW7phaMVKO8(#2hChuHZn1OGnodrv32eEI|B#$rqiClw1SW3Je zs@KgGH~QVC)eSW`XxToN5+#Q4d@A|!g>#6vn6Ubd^3sF>DJ1908DY+Wet0h4AJ&w% zQ}ryKoBMVOuHM}NJ-HWG>*Hc!z?4{4W8R8eZVsnz1+$pPr}y~jPdIy!(+Ib@f1td> zkQv+?!G!v&czW#2Zm)~!Fh0ZYg+W&j`{u|T-v1&)hI_h+Gr8SG*pvZPew-c3dzmvf ztrC_UAHZtfRO5^u1L)ZzRroYkk2j2EikIykz@p`K@ZI7*tUM%#W||k{0J@S?*_1=8 zkqS<}uopJ|a%7=lyrZFAhL|WE6V@2mNMjPs$d^sdZZV&=@ukiN&WBOu9_3b?HfjV7 z+OQ8KBgB$5y?p8NwxMiDgB1H8e#x0$I?OFn3G08KhyOm!Vj=Tor0>TE5z}gUS`&Q< z=bZluhqv?~-_vyQWT_I^%jvLZGYT+fmoaR(bz9i0s3pm=o!&je4@mpr@i`^b+2$#o zamxEHUERzoDX(j zUjjL06~p?8(=d3Y4Oym<3|n{0O3jWog5SsMMZug~B5fBzSMTI}c}*<3;v=>Sv|?JT z8*uITLu}mGzP!(@rzEb`o<8H+-45#(^m}!bG@075XPlq#S)4*j7Q2)2Jj<{D&;y2z za$@&5yEQ%e5BRvqLhRmVjMDUiOBOz4*<>xedw9Ay@T5Fj`Kt<5oFZ9$Ybabw$;M4f z7jfRR7KElxm84I2B)EH;vaQ4Q@wfk6@R*%M-9oGJ-G|q(HKP)Abky)t%yuDYN&w4@ zQjy+rZxL62ctFF4RH2pXF4ljy0jcCV^Lu&2?kxX6rF879m_wE>TMFwFmGN6e1YA13 zl_{*`Z18pR#B%H%+7OwEFyk`#xxRwSr&Ms$_8`GBdpvvMtSoKI{35<~yi>IAbu~Js z>|)!!7m;w@Iknr)gndeCp>0Lk$mAB2{E;27&r=QSrBU#}S&uFGkN35WmLrj#7GQ0t ziNk|cpzojyY}_wPtXDZAbds<1W~r6*Ws(x@^Fp4;s4C+to+H0pvXE`>Rf6tuW$eV^ zv2>^Zb=>yJpV$;EB4$H0u;$eP_&vIY-g}aRoicq1^Xq|d{laR|7P(6N8WAc^P4ytBc#mhC?ul*>jPt)* zT(qf?l`0;DLsz&K8kY@cpPI6v&N+DfjuRQb&=ev%xGyng5^V05!=@~1!cRZGgGQhA zY_T=x8r9nZy%`1GpZH9hoLtXxZ}*%r9=EivrSdW1=OTKbr}f+_(8T z^>i_q6Xwik`<1t`to#}Xqi21=-hX~Ejix|S%e&I7Hl88RTgOtzLm7Cr-(ZsGBSWsP zQb(3P6{hUhVlU+Q9U&(RdQTn#7JpSFOPoVQUHDvc|t6U4_1^OJaxxZ+Q7K0BXSkjO@ z%vrXK9MDXGnIVe22Q$2z(^B$Z4)*Jz*gfYjb5F(LU1AsrW@G`^dxH%33SBwSisiNV z&ND(Rb43lJBlRTjR3(m*xtie`R-bTnNtIZ`Tmy>%vplBPDge7VKyGl z!2^bhel;vYP|#Ola`&yIGLlkp!jS@ab(3@3ZpG7O zF(E7FFbQAP#(G&qzuhfVjEkuJTqyL--;i*j)JGX)Y{t4x-yP~m%y zBHVwc#BRnFV7|*h7^rneP*Kv7c=G<A<@97}J5p%o#g-S*z+ec5~lHtWjuUZ9*qhYBZwXw2@@w=FLGW~iOX;JKzp`2S=XtKOQxPL&UWw5-UWWd>X$)mRlF%=3^kQ3 zsOj5%KlQo)2Y1;gk@r7s87kUHf5u%T=l8pl>Qr@1Q}BVKmmS%Up9Q!!F&B39$`R^c zUPHtAgJ8>AbCPvN3$F!SDz^F}&t#8UNl#AAW8^vlam>Sz<;%!|Jvy-I{1i#l^vA-l zXcHFNs)L)_=YYq*W3`SJd&`RlRQ3ma|13?)O`U4^J+uYfM)9S6I12{*QkW!_eQQQbRHyglN(Xw0~eSe6{bzxzu_`AFV5?xM%k zN}8zIzCu(#;YXg0kR`)-N5F!uQGCzUVJEb+G3ci}(SL2hXM!P;d3vC6CX-F>^8*92 z7Q<@8OYD$&6~3LnS3Ij{F4XaT@6fmenxVIdos(_Esq%kW?W2wK;idu%5v?RDgXa@H zi3ZLd7TvA4_k7R)&%G4Meimm$ErJ@6p&gOe}Nl z3+zwj?7^}`8srLWlv_Q9*|+mlCZx~vWS188kZy^J1iSbTG+M3$r&*YY3}X9{X=hdNzF#=)>aQe=6r_Rs zy0nvYg*w-;F=%uxrSU8)p>HIAgHcO41g-ED@Qsc?`#V38?io~r60Bm64w#Z2zI-3c$bpGN>Zn>u28In8O1$^1g|sXsR2lCB zDr)OlOKuz58p@I`y?w@_bey6*92OnVgqQ%{2XVi@tKLO72G4#Vj`C-=k8Ons#-DL? z>PMCovyI#_<(`u^ql+=6*5p|}y2-sgQN^~%g~{V3LJcpmzk^e1QSQXoD>5oJF{fm_5>rV*Tt zC6iRiwn;>6_9YF2*5`D4W5ReA^3e=LcMSzojp6_KX#)I@z%S zcN+1ydjp%9kjOq5@*M8F6(mshAq?jIGB=Z=;lc@Lw(WT?I`>j1s={%hT+>E6Wu*f- zyW80&@`p4CuMgYAJA?j^C9ERd6m)`3CF{aXx_yt+`?a85!)bDK zydBew5@YXuW5}cWcMvAaSy-!PL7(%3S<%%(d~=>b)Y}|E+A9s|`Jr%)>Jo?B+#~vH zkn53F1-3P!3hD3#EFn7-4w+`6y4MQwYrh5@rBfx_$y;GgkSTk`wQGYY4Wcujdr!b|4mfj$MxRR2YH2agS6Ab}MlW{zpdrbds)o2wfvs#a zWoMV?Vyt}tNorUHdpToMbwCW<(b&pl60`9|jRtucbeqm!hInh@Blv3Y0|t4h;>Vjw z!uI?L%xiE5nlAY&s!skU3g&&^k!>YU!<#Od!vZdtYP^QJNuU)@OUIz`N#wBn%9Z>-_% zI^pzfXUP=TAANJpjtCaUn;iXn7mNGmh`;p3D9 z_@MQU>Sn7*$5&YjO6P|V&tx?`zHH^@t~7q_rX+tFamJ?*Xz+3?`ue{ApM z7F0EiV~r&ENxHqM2X6)~X2Z^4^d`-+MVaW+@<58N@yo9&#CNF8Yn zn(lnTOlwVv)h;#s@w5OmL+j{-p&2N;K7wc}uZ2cMWo+Nd`I80fS$RMk{%%$#YB8Jz zk)DqWM$Ld(s@I_Wmm(fL-d6IaRvl$4TnYJv0S2#Fe$`fTePJg$kGV+3 z@weL*d!D5#8$~oZXJn>=2KL*r6qa%>P)%zl+8;*Puy!E4DN~a~4N2+NYF1VB$Gs=V ziFODdsB3g3PM_w+L<-j+<$_c)n+rBG!h5ol-{qtiUSB1Tz0L>*3fJ&epRr`*@Li;6 zjwU`iwG8BP-_j=a5)7I59O^P+VCi8c?h!pDOu8G(PWfn{{m22LHFPr#cdNvI+HUOL zt9lr4N*S-2%5>{C%U)#R^0}+XW|w4$;&a$5Dh}*M&EhwJY+UA`MWzoR;w`f%esF#S zXRS<#rKUOxK`BDzaT}I{P{*59467!cdm^nBgO3{`p)<5i+!Gq;Frika-84-7bw$$AZEXL2;-e zb5`ZKvzbc5st19v_ni{j{#!*APlvGd%obcUDN^ zlB~R`KpocQVSAPiak;EY#@y7xdt-Y+m-fD>tPmp$X2IJncZCrlS`zniJJ&9M`^%c| zm~hRD9T{_+vu(fN^}cU-f6#3(8n2H2Zwld7k}ETHke3$rI?%n(FEc5^aKVr?ZA>C( zI(6_^PH!-x<VdY4Gx(DVcah4FRl0MFP(*@f^_md1G1D zzfid7lZo4xttMaZYd~zHE*|9^sy+M5na$p8+_qSkYzyYx&Rz;qVq{3JH_MV0dzCPA z`~_jj!WB$$QU|tV&K1g@71KMxHP~m|Fm|@pkoQWc;kn>;+QoRWbIrx;m7F2^W)-}h zt%CpcO@K)=0@<;*Ef}ITj+{@x%gk_deZmIKafe)z^%tzAccV1$z*6Ly}-+aMR@e#$+4t%+6g>ZP*9VjPCxT|D3{o=QP zRm(P^#rju_WNf050U4Orw2I9B;6sjU>frM?Nud1nD~;z|pv|0zv^6^zOpQ5jq{s|j zTwB9bM*KpPTSwvd#ieX-zqfcJ&P(XJvHJ0jLLp!t755#(EFLwXW6&$M>9oHPHP~5l za6yw0@YRU@UEGLuLqf@=fC$!)=3&$$L-HZxDyS$aqqTZZ=<>JwKa!E=sii{dh4(b7 zR9QN@alf#4^I+n!k^iCMQJdJHIh%3RhDf(!a8cy37{h*#`n6L+*A(~Kal z+s&9qSq^?4YCxK|mO~)#=(>0@=U zY59Dr-O+<371rX;f%n*j8wX&uj}{i)lz@6|Pgb9tgOV|0$k;|x*dM8ktw)!3Yw|1B zY2nHJmQdpqP2pMwYTQ`_CYQtEyRQ;%iHs6;v2&-FeaFBR&Mfpn0+np5!5p2ttnR8Q zxzD@v5<^R2VsVe#Dmf7u}Y1SNoG3{xh#>84`v-cgk zJg{L^{R`o)NC}HZ)>GFlbC_cvF{U2&B3=E+VbPk{^JoD4Gp?XM+ZZ~X<6d z&d2CWs+KJgAN$JLBR>7{t&48AzkS!NYnbf$ANjEUIe7O{MMaCl-8=m3qYNYenv*4w zDME^>jr7+ILXO2cyDd7bjRyS+g)UaWhBY5h=F$qmv0os3TxvzFwtFU>GmSotAxbE40?p&@WG3?)@WPB??5Ry(cz@7T;*hP} zy~Dph(1N3FE)ZX-9ou7CjP^m3NZiH>2)@R9H%6@hE5E@^Zlr?r*mGm@ysQV94lKgE z3)jN?)4e(KN(X(GB#P`!lvu0J2V~!EnObWI?7NsJF};#Zr)P034zA&K+y6*8-$(JA z7XI9n1Sk7GW3|s4abfxd&R5vQnr~%d^!>ZAq2VgjZ&OBxdsl^Be^;{kCwZPxv_~-4 z6;q9o)hJqI&%XCHBuhrBq4tDkYWl*I-8!3tm8UikXY*CysKYyMzQlL$^IO+*W}2=( ziQ;#wT=Od^<6R0(*PlRYmI`Lf%@BeGn^yLJ+Aik`CGh0rM z^%MTP^9^G8Ond6*)tyn@8q$IZ_uepP<8^|i?oi1KNsI7^8MDi2T39(Y8FW3*&;rg= za{LoRuo@esNl|n#jv4bCp)3ug1hEKktj5f(#cbAJ6EgC#Ha>2;33G4$q6+yLxU>wz zWVu(zY36FEd%2O>@yu_9cK_#Je@`L*j4%C2itue8QQ^VBxC`{C`VR*L+6?4uDx<;z-be^u{*G!Q(d7%xPzN-%g zH_J2QZ8zy+&fm^a3MAI5k3i0g@7v>!cl#tucQoM4x!$C1<^#dp!bU1H&4ZK_IJ5kZ z!(-Pjt`~;)$B+GH(jzG^=q2mVSU63>L_2Q5g#jvfV{LIacX##YYdCaoZ=!SP1lgQx zf@Z&mgCA!d_Zwb~{g$5u{n-Jayg>;Mn%xq0`QEK|8RPZw?sU$wEp*K7Z)h~2lmX9* zU!T^9_NC{@q>C|Z+Rrq!|4zu1q-4k*pNE+iuc7hxo}w)`GVpNdCg{1pf_pj@u>DY} z$c6S~7Clv@KNk&QcCTDO!O&E)*Q-<9`kC{S|K#4n0M)hfJ0>;67*3UN69@GRTwFquJ=7&J< z^_tQPvu={*iyu2v-9A%ptPC6ANU*z+_A?&6&lK1;sCeX%Mw>E9EcZJNj&Zpce3^S%jB2eyhX zaveUhL6*IZUqY03s$;3Ng2uKtQTZO(XtyMg=+w1?++Yn%2}y>^0|v}z=r_#Dm`wH; z%mMd-255h81RO5T;9N2zyj=B8I1~Mns% z_$?s^^mUf9Sv{*!DWXhBtosIk?kM3`Un3fk;L7f#D@wBrpR$Yl_6XxP43k`~>J&b9 znlN84-l3xqMOKAIu-Fo7Y5%MQa&==LvMxmlm%p%uz(W(+gUK?|JG~`vsl1ZfDdwT^ zo~y#qxGykyoEk3HFrcGb&6(Q8S`=1fv6;k%`=wNH^cM;2iV0@sk`~-BA)4&GZ^r%( zQ^B++_E7SI_ooENNpIaQg=UM@qAR*p7?EBs=xp>N)h&AHKHr>PUMkPjB{e*EpUD>V zIRH2RXraruJG{%Z7n}Vw6MIbbAXC$fVU>$ECZ_HJm2btYr*}Qd>+gR=gT=?MQd3*HE52b$GLaQ{!Ip3rDsZBkI=^233tK!+fSNLvvBlGPh#|B0~}qd zj5nnlU}q9%c^%Kivw_vHrdKX)o2n?SH@^e2y_AWRYc)d`%L;nE+}QGU+?!i&sOk*yQh=FLGZ3tMdB0mu=}oxxBDZjH5W$Pe4r1GRN!Q*@AUcH0`TTNecxmsckkzs*7DNm zxz|XqiZjC2P))pldIz{VR?xjmN^rSBGgzn|f)nLR_-mwwj?|Aug; zBHzyo%YV@H{CZITr-UbrpU?>}hqGP*V)T0v#_w*ILCabh_v4A~?9!UDPCRyfDf#_x zpIBU*jR$=`fV&1~Fq-m4C+?TXiLhqdlxi?M`n3@KN)?8k)RheW+*91e)YVkxU2>^~ zY{#_NVf1CoXS3_BVVF9X+>qi27lZ5ehHqwP<)5xFu&TdY{ zyc49LT$r(6l|5D}#2ZU91&>4z=*@q>#?IBIA5-_RrT#6bUCp{Rb|8 zY>|xA?M+~cN=x^&=42+CZo-co~_04bypxYtzA%((~=C{xw?6n~6iKc=RmX!Uq9qxlTPT;<=pr#0|nd`MBt_P4k}=N#N>Q6;na z4Z{CF1tFSPuut4~>Hy7D$ITS}TVyQJUs)%PAF0PSoN2+@dFkCV-1lh_hP<0e+GbS1 z@EQDFFAao-L`SxAPA*=ys)h@XGlXZ;igDh*191LAA5!#C3)enZ5uyzhnCgZ1Jpa`| zeGi2|>n|;-;qm)Ku6ZR)4baBInhUVs@;O^p*oe*PbIIz^UF-@!y6;bTAvgy3vBE=D zcsJ%Top{B7IR8>Xf5UsUWwr?`GqsWSx2-3eHogG|0~HiSpN8JU1DS1J3wq95LSi4P zF~7NpwifN6Kj8=beW;9QVqXgPua0B&itQ=0f5)r) z)b2nd^%}_E#gd(5+td!I=%s;$n^L=HwM}+0Du5lS`#TUG`zT|?#vxFclFZ)K>S5Wt zFT!o7Cp70uA$tET6P(TC;hLE;uFCx_?()XiF004w@6uV1y7jaNXJyQq6i9mFR6?6g zac)^IIFD+l9$#~K7pDc!qV578p2tbL=?HQ!*08oMzmUf~A-H2HTkh71CPf->QeKu= zX>g`%Op~~)=iW zMI8TpYqyVm*TGz#fB)V+!ykq>;FEm_^KboxEhS3myS0ztFClC?_pqJMdPuAHItVV| z)wo$cg}H9sND{4Oq(18kh}|uBYTZ(Zs_$o$Qwd7s<51p7{b&a$9o1lOEjYi6>&874=pnw+qPbSg>u|eRP|b@ni0o- zaBg#^%2?rdY7G5(yb{;V6w`Y)4PYOxj2q6D(4&zfn6HtIbi}a+a`K)L(R-`X9%goa^p4lGc-?h^z@C=8sspY(%v2_5M{qU5aYi%QaBU(T4ng#o4kU?C3vz)Z_W+sH6pS{zBeEdb$*3 z`3?9e?>GxjKTOUBDbP)`E~Dc;GeVZgl8%8|ICrTl^ti9VCQiSOrQZ`_5Zo7%1uaRN z*8q|GTTixgK!1GpN{tfB7hGGb!HbP4tna~6sOVJT-3K>d^xqNe)D{Vni%ZBD*MmaT zr##%g(268aKT3j+n&G0tN$_^$Cz>Odf$C2Wz(7;}9q3fT1aTihW)JtnbSO%-j@8hS zgXge)Vbut7DXb%@9elGIaaC&?8K7~9Z5VzP!%aL%vcehA`;?FJ=Nn*eznDO6c;#OzK~YtCgg5VUh{_S!yaV9aSOj;t6aVtB(UmJcHvNUbN(R z5z76UN8Svo00j#*R0s*?9l1l8mSzsh9j=2xC(?zW9mQyH`3OvU+=pm^Hfry*753~_ zV4i0+@s{s>I?iq{JA6u&SGnFKcl;KC8^1?r#$W8-!`JR_!q{gENZHWcERerJGJ*_9 zD653opo+CY@49{L8s4%}sjMl~>zB}hZ>q4jk%T^ZV?dr5@{a8HH>mqg6Q<;1BMrOR zK<=J-11q~cU8_z(dd6lJ=G21iGQOm7pBj6=Ar0fIt6*#7GuYjvf}=Vsgh#U`FllNV z%J$ZWWS2V83I2A7TSMvZiStR?1XcWJeUo-E8}njvP?z@$Y@hlM*0^e-=Z*8-Jb^cg zV%`B~Pc}|*fTlyrcqiQnD(jQkjyOFG-tk>H!5-5wFAA{tgjYhz<~XSIQ^L9_wc^pI z7O(@{2mVaq3VSwmJ^lTF&y%4+q%z8fEVgUF<@Y&@FIUQjb1&SbgZ;^P&)pC*p649B zouI4JdArIlte;;BH;yf3=lSo~sy1EdSKNb?f8+1v!5_t4KK5(AiqaMF64pF&k1*@k zFo{OI0yLgBQ-E`7XcEt%6xO|g(4Qr+hUbxc@Tf$eRZH3Shl}KA&CepP5RX8Ljk=YM1 zAzN%Mk@5Z1u2YpowWVRHWHKp^UkyepImh7SZg}~80~?saOMm>QLd9fbTC-JATD|EL zT=G^XcATYo+Sg4GEgr*Ykdic|<|3V4;3o9ZR+LtmX0ewqqsf|iGSZ%Fiio|-INH}Y z1E-wxA!km@kQo7LIAUvPcSh-2Y!)s&^%D{W2RJyH`&!pe5xP2^Lu@Nh^kyH`>&OS0 za3#E_oI|l>4tq0EUYcc#q;uq1VSk7ThSEa-n}1M)**RFO(F{!W#j<-*Pr8>w&lZ?am&m?ZEWDIzr$ zntsk;=4WK2M`AaUdDT&3%XdXsSSdrgX84Ub1sqXVE6n}ghaIY~#_{%jAhAppVomiW zk!K2v3+C9e;|=}r26;)XeeY1^F*ee7S-*)1j3zo<7oFg80UXv0W5aE2r1J_^5WkPk zZtlLC=wtL-m_J*Yi8p*e-2ihK?i>h<9Tjnc=LPYPmfdXEuV!pBPhrc?xUlv=$~Z{o zHk=zak5xp;NQW&wPHN&6sL!5Ev|M9F+N_iaZP&)YFXKQzS&JDsUB^(83==Hx3pf7L zk~~hGDC)X_re|B=NZtG5p03YmCEqI)E{FN7} zWY!$k`lSlZs}h;t=QfyO)`TCWndGGJAr^K!4Ku?glMmU+@La_N4>wPRe@SnyuQJF& zb-$xL&45kmg2X%xxAaSZwI6gz=o)QY-0mTK zy{f?e3uwiOfhXwBrbFutDEsaj;FkuI|$Mp`jbkB2RzMIAMJJ;P|q?6r(j|0{b`LAkB93{oV2`Xf5bv=xT zRmKCie+&0kjAJrA+Hjs|3?!cWDhiCML}keoy8Gu`qFBjUnlrD^#MwV+EAMeI^avvt z2K)u{9hw;8kPh=~jM$-760`~%L0n>oz`zV;+~es6UA!*`6CF%!m4)<44{6o1T&$?l zfOSPN@R)zT4`a58yLbYQ$9|ywk$84qeLW4TO2-E|ocYJ^q5mnHV6cu zfTHy5jB_kqYmeY*;3By>Ss6T@o3f_j20YLsftdM4usE%BoS-p)j7U2V7H3qkXQw;R z!QM>K<1dOGK0_l1loVgiMN=z1AOpU@ynkE^{jo^A`X=wT{9S|V*F>?9%hupmu7XcS zKY)beyIAh-R+L+QjCh6iWD5%z$~lcBN69DfdaZ!R?E&yff409;R=Tvl9_CJ1CGy&u zhoA20!G#7(QlX=TGhQzf-~ZD|t(R8gl>hdzKO^?TzID8V;KUQKoovR`y^3&*_X=X% z(id#PlyURnux_3}U}6rY3Nj?b!;w|gUqOYWlkl)I6ke68ps;$ekX^Q%Jxk%86mJFE z<$HM_@d4xJMl!2dV{-HDK%BU-2eI|iV@(IHV#D$oWcc;~c$u$+>SdwbzL$6Ba&WGP z40%2^ht5w@kw#DK0ON2qa%6)tCXHSwh?pDmAFC`aY?(v7UX141V9rhI7sWjMHj#sC zxp!J%WcikHG+e5VF?o@oI8B?)P|U{RWBx%Jb%0e78WLVCE-V=u#yW#~qV30EK`Hhb zeN+1mOWYl4tbZXy^55$z^HS;E#dDcNj^E%CN=Z)V8DY`GbhK@pN$g*3Ae{@fajnY% zFrCXYWmj_WoVN@yj}HT#zbg2qtwRunC9qm?GaCMx0ELA!*st&Jv8dLGW*usTbk2M` zM^oudlMzgPgpIT$xQ!e$GbWqHsNlg{7vaq8nao(iXQojQxuUmU{Blhij&pAYhd-+1 zP`er~ohk!eIn#-*1$aqh!1u{Y;m9$4$(QUk-TS$0k}-Nm7Saz#is|O@Hqzka2llXy$IsaMeQ(9GbKwHrrQ;%Bv@_b?^J*lgnY^ zJdKyM=kIE?eX@_mUM+r&)u3Lf$#rK{ds>rw+113bRUkgtsr*cC+O#k zg?QH8n`|ghKy)lShn4~|{kHtFk$EYa2j)Rk#6KWsSscN(Au^*uGa6#~7^m)E$l3H6 zL+NFfL;kjw>@=~a4s(>~v?-LFGVFxjc{9Gt|zj$(U(He5y z(Hu*MS|H6@i*nwDc*(_*n5O;+_HNoJZ(ae8${o}?ydOPS4@SrAKsu_d2sb^S3P)B} z!MW+$IB>sLd0%KxcYYM|??(Sj)z{>*=I`z5B}2Nf*~o-uo@IS!fte#-my??cv23Lk z>p(dN>#KBd)@ye#3Rq2Zw|&CI16)v93v~HnZawQY_*8v?V5}QS-Y7(aA!oS2{u3jH zH2C4azQEFB+w6TbtI#jY0b}_E>Y6Bnj z6#Am9414ZvCeAsN!HZ>r`J6urIRWJqvn;WWI{^OME^*6u6yR&_JlsAM2g{g7WV2B& zduJO;-wEEJM0im(sym%CyV8xNZF^{I;3N`QGaHk$zJS_xEW7_J!mMFGlD{e(oS2{A z@zv3hKBKzga{OhpkT`8C=M2jq;l+I&kkj)NntGYGR=i(!a*qRj5w6WIP}HkBC62Nx ziHKjYFrCKzlS1}s3i$VHcv9Qv%>DSX8k4q$k{m4&d2m&X-qlIaA3mNorZInSk|t?d zHy4(e=+$SsYRiN@hpDgp4H~`J024IwXmFR5ugHC=N|opk^#KtY6sL0;`MxxO@u%O2 zuakznJXyrELJa!Jm(=;}B<<;9T$hjpi6&~U{!KXsq_F3|84q+CJ11K;;cHi&>14*L zbOl3;cpZ)Xmw6f|=BiH0d%?O(gzqM2aLvp&^4ZCP{}et<2Edre*$%V)V*xm(tffJo z0)DN7d_;$dV%g)Ky_&>3P(qqnZqfz^ZMfHJK@V%zV148qNU(e;bM`l=k2bh<`74WR zU#yP~?-g7gRB}FREck12!z4G&fvmcsi)QL#=wG{t-t4Nult1mr7MomIj)MhXc_W4- zPW{g^w|WC~tr-WW6U9_)!*U3ttYE@uchDav#J-NpN<(^(b~V4p8n(Z*>{>)MPU~Ro zmOC(G+9vvhX)^U?XUO_eA@@@+#s5735@c*Zu6m1c>n*R5IbRh~g9o>;?a1|pEYwO; z-+U~=zT#VVYHmCmHD0|`4k+3==~Tu7d&SbT9Stz=wJx@W{>66qrF6=#Ok+HKZp6Fp z7_7uI9!ptoU=FL)E60cFLQ>k6K=02i#DuZThPo~Hya z!vQdiVw|I9oa|MnIi;bGFh5bD+7V$4uh~4LLrU_Y+KNv5P{DG)gNSKGE12|;LBZq1 zk*t^>u9ah7q>vcJ7R!iV0fzj39%@(U6W!|)?4EK&R;R5+eOsk`dD2Uj{u2Z#^B8(M1$tT!-0NY*^~kd zQ;)r(U5(41pH?NU_944s3|Lgp8Ls8o7q0Vr3qGr4m~0pABq}1tVD)6I%_@$VRk-!R$YW8tuvs9?V_p7Ptu~I%C9^8(~GRv z_&^+;Yxo1FaomD;X=mp=xS2RkG{Mf`M!39hh}&CNh$k*skpXEmd}f-=H(qWdbAG;G sKSox)8ex=5#6>8wn*pB{m5}*Z8yj3u*=i)Ce-ka<declare_parameter( - "target_topic", "/sensing/lidar/top/velodyne_packets", descriptor); + "target_topic", "/velodyne_packets", descriptor); target_topic = this->get_parameter("target_topic").as_string(); } @@ -315,7 +315,6 @@ void VelodyneRosDecoderTest::ReadBag() storage_options.uri = bag_path; storage_options.storage_id = storage_id; - converter_options.output_serialization_format = format; //"cdr"; rclcpp::Serialization serialization; nebula::drivers::NebulaPointCloudPtr pointcloud(new nebula::drivers::NebulaPointCloud); // nebula::drivers::NebulaPointCloudPtr ref_pointcloud(new nebula::drivers::NebulaPointCloud); From cf6868786530b40de0347b7f5c3eb5adbe0aa137 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 20 May 2024 20:35:35 +0900 Subject: [PATCH 058/122] chore(velodyne_scan_decoder.hpp): explicitly initialize some fields for clarity --- .../decoders/velodyne_scan_decoder.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp index 1d8cb9255..02209c5b2 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp @@ -134,9 +134,9 @@ enum RETURN_TYPE { class VelodyneScanDecoder { private: - size_t processed_packets_; - uint32_t prev_packet_first_azm_phased_; - bool has_scanned_; + size_t processed_packets_{0}; + uint32_t prev_packet_first_azm_phased_{0}; + bool has_scanned_{false}; protected: /// @brief Checks if the current packet completes the ongoing scan. @@ -204,7 +204,7 @@ class VelodyneScanDecoder /// @brief Virtual function for getting the flag indicating whether one cycle is ready /// @return Readied - virtual bool hasScanned() { + bool hasScanned() { return has_scanned_; } From 2f318057b2ff12c7c6a2973fd43e1197f5587988 Mon Sep 17 00:00:00 2001 From: amadeuszsz Date: Fri, 17 May 2024 18:59:20 +0900 Subject: [PATCH 059/122] feat(nebula_ros): add velodyne json schema Signed-off-by: amadeuszsz --- nebula_ros/config/velodyne/VLP16.param.yaml | 21 +++ nebula_ros/config/velodyne/VLP16.yaml | 10 -- nebula_ros/config/velodyne/VLP32.param.yaml | 21 +++ nebula_ros/config/velodyne/VLP32.yaml | 10 -- nebula_ros/config/velodyne/VLS128.param.yaml | 21 +++ nebula_ros/config/velodyne/VLS128.yaml | 10 -- nebula_ros/launch/velodyne_launch_all_hw.xml | 42 +---- .../velodyne_ros_wrapper_node.schema.json | 169 ++++++++++++++++++ nebula_ros/src/velodyne/decoder_wrapper.cpp | 2 +- .../src/velodyne/hw_interface_wrapper.cpp | 2 +- .../src/velodyne/hw_monitor_wrapper.cpp | 4 +- .../src/velodyne/velodyne_ros_wrapper.cpp | 28 +-- 12 files changed, 255 insertions(+), 85 deletions(-) create mode 100644 nebula_ros/config/velodyne/VLP16.param.yaml delete mode 100644 nebula_ros/config/velodyne/VLP16.yaml create mode 100644 nebula_ros/config/velodyne/VLP32.param.yaml delete mode 100644 nebula_ros/config/velodyne/VLP32.yaml create mode 100644 nebula_ros/config/velodyne/VLS128.param.yaml delete mode 100644 nebula_ros/config/velodyne/VLS128.yaml create mode 100644 nebula_ros/schema/velodyne_ros_wrapper_node.schema.json diff --git a/nebula_ros/config/velodyne/VLP16.param.yaml b/nebula_ros/config/velodyne/VLP16.param.yaml new file mode 100644 index 000000000..aa7a224fa --- /dev/null +++ b/nebula_ros/config/velodyne/VLP16.param.yaml @@ -0,0 +1,21 @@ +/**: + ros__parameters: + calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLP16.yaml" + setup_sensor: true + diag_span: 1000 + advanced_diagnostics: false + launch_hw: false + sensor_model: "VLP16" + return_mode: "Dual" + host_ip: "255.255.255.255" + sensor_ip: "192.168.1.201" + data_port: 2368 + gnss_port: 2369 + frame_id: velodyne + scan_phase: 1.0 + min_range: 3. + max_range: 300. + packet_mtu_size: 1500 + rotation_speed: 360 + cloud_min_angle: 0 + cloud_max_angle: 360 diff --git a/nebula_ros/config/velodyne/VLP16.yaml b/nebula_ros/config/velodyne/VLP16.yaml deleted file mode 100644 index 1daf3a4c6..000000000 --- a/nebula_ros/config/velodyne/VLP16.yaml +++ /dev/null @@ -1,10 +0,0 @@ -/**: - ros__parameters: - sensor_model: "VLP16" - sensor_ip: "192.168.1.201" - host_ip: "255.255.255.255" - frame_id: "velodyne" - data_port: 2368 - gnss_port: 2369 - setup_sensor: True - online: True diff --git a/nebula_ros/config/velodyne/VLP32.param.yaml b/nebula_ros/config/velodyne/VLP32.param.yaml new file mode 100644 index 000000000..0e0ac7827 --- /dev/null +++ b/nebula_ros/config/velodyne/VLP32.param.yaml @@ -0,0 +1,21 @@ +/**: + ros__parameters: + calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLP32.yaml" + setup_sensor: true + diag_span: 1000 + advanced_diagnostics: false + launch_hw: false + sensor_model: "VLP32" + return_mode: "Dual" + host_ip: "255.255.255.255" + sensor_ip: "192.168.1.201" + data_port: 2368 + gnss_port: 2369 + frame_id: velodyne + scan_phase: 1.0 + min_range: 3. + max_range: 300. + packet_mtu_size: 1500 + rotation_speed: 360 + cloud_min_angle: 0 + cloud_max_angle: 360 diff --git a/nebula_ros/config/velodyne/VLP32.yaml b/nebula_ros/config/velodyne/VLP32.yaml deleted file mode 100644 index ef5ae14c1..000000000 --- a/nebula_ros/config/velodyne/VLP32.yaml +++ /dev/null @@ -1,10 +0,0 @@ -/**: - ros__parameters: - sensor_model: "VLP32" - sensor_ip: "192.168.1.201" - host_ip: "255.255.255.255" - frame_id: "velodyne" - data_port: 2368 - gnss_port: 2369 - setup_sensor: True - online: True diff --git a/nebula_ros/config/velodyne/VLS128.param.yaml b/nebula_ros/config/velodyne/VLS128.param.yaml new file mode 100644 index 000000000..b254dd750 --- /dev/null +++ b/nebula_ros/config/velodyne/VLS128.param.yaml @@ -0,0 +1,21 @@ +/**: + ros__parameters: + calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLS128.yaml" + setup_sensor: true + diag_span: 1000 + advanced_diagnostics: false + launch_hw: false + sensor_model: "VLS128" + return_mode: "Dual" + host_ip: "255.255.255.255" + sensor_ip: "192.168.1.201" + data_port: 2368 + gnss_port: 2369 + frame_id: velodyne + scan_phase: 0.0 + min_range: 3.0 + max_range: 300.0 + packet_mtu_size: 1500 + rotation_speed: 360 + cloud_min_angle: 0 + cloud_max_angle: 360 diff --git a/nebula_ros/config/velodyne/VLS128.yaml b/nebula_ros/config/velodyne/VLS128.yaml deleted file mode 100644 index db73ecc05..000000000 --- a/nebula_ros/config/velodyne/VLS128.yaml +++ /dev/null @@ -1,10 +0,0 @@ -/**: - ros__parameters: - sensor_model: "VLS128" - sensor_ip: "192.168.1.201" - host_ip: "255.255.255.255" - frame_id: "velodyne" - data_port: 2368 - gnss_port: 2369 - setup_sensor: True - online: True diff --git a/nebula_ros/launch/velodyne_launch_all_hw.xml b/nebula_ros/launch/velodyne_launch_all_hw.xml index 717aa5afd..11f1ead12 100644 --- a/nebula_ros/launch/velodyne_launch_all_hw.xml +++ b/nebula_ros/launch/velodyne_launch_all_hw.xml @@ -1,42 +1,10 @@ - - - - - + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + diff --git a/nebula_ros/schema/velodyne_ros_wrapper_node.schema.json b/nebula_ros/schema/velodyne_ros_wrapper_node.schema.json new file mode 100644 index 000000000..a7d67a64f --- /dev/null +++ b/nebula_ros/schema/velodyne_ros_wrapper_node.schema.json @@ -0,0 +1,169 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Nebula Velodyne nodes", + "type": "object", + "definitions": { + "velodyne_ros_wrapper_node": { + "type": "object", + "properties": { + "calibration_file": { + "type": "string", + "default": "$(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml", + "description": "Sensor calibration file." + }, + "setup_sensor": { + "type": "boolean", + "default": true, + "readOnly": true, + "description": "Enable sensor setup on hw-driver." + }, + "diag_span": { + "type": "integer", + "default": 1000, + "minimum": 0, + "readOnly": true, + "description": "Diagnostics rate." + }, + "advanced_diagnostics": { + "type": "boolean", + "default": false, + "readOnly": true, + "description": "Enable advanced diagnostics." + }, + "launch_hw": { + "type": "boolean", + "readOnly": false, + "description": "Launch hardware." + }, + "sensor_model": { + "type": "string", + "readOnly": true, + "enum": ["VLP16", "VLP32", "VLS128"], + "description": "Lidar model." + }, + "return_mode": { + "type": "string", + "enum":["SingleFirst", "SingleStrongest", "SingleLast", "Dual"], + "description": "Sensor return mode." + }, + "host_ip": { + "type": "string", + "default": "255.255.255.255", + "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", + "readOnly": true, + "description": "Broadcast IP from Sensor." + }, + "sensor_ip": { + "type": "string", + "default": "192.168.1.201", + "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", + "readOnly": true, + "description": "Lidar Sensor IP." + }, + "data_port": { + "type": "integer", + "default": 2368, + "minimum": 0, + "readOnly": true, + "description": "Lidar Data Port." + }, + "gnss_port": { + "type": "integer", + "default": 2369, + "minimum": 0, + "readOnly": true, + "description": "Lidar GNSS Port." + }, + "frame_id": { + "type": "string", + "default": "velodyne", + "description": "Pointcloud frame_id." + }, + "scan_phase": { + "type": "number", + "default": 0.0, + "minimum": 0.0, + "maximum": 360.0, + "description": "Sensor scan phase." + }, + "min_range": { + "type": "number", + "default": 0.3, + "minimum": 0.0, + "description": "Sensor minimum single point range." + }, + "max_range": { + "type": "number", + "default": 300.0, + "minimum": 0.0, + "description": "Sensor maximum single point range." + }, + "packet_mtu_size": { + "type": "integer", + "default": 1500, + "minimum": 0, + "readOnly": true, + "description": "Packet MTU size." + }, + "rotation_speed": { + "type": "integer", + "default": 600, + "minimum": 300, + "maximum": 1200, + "multipleOf": 60, + "description": "Motor RPM, the sensor's internal spin rate." + }, + "cloud_min_angle": { + "type": "integer", + "default": 0, + "minimum": 0, + "maximum": 360, + "description": "Field of View, start degrees." + }, + "cloud_max_angle": { + "type": "integer", + "default": 360, + "minimum": 0, + "maximum": 360, + "description": "Field of View, end degrees." + } + }, + "required": [ + "calibration_file", + "setup_sensor", + "diag_span", + "advanced_diagnostics", + "launch_hw", + "sensor_model", + "return_mode", + "host_ip", + "sensor_ip", + "data_port", + "gnss_port", + "frame_id", + "scan_phase", + "min_range", + "max_range", + "packet_mtu_size", + "rotation_speed", + "cloud_min_angle", + "cloud_max_angle" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/velodyne_ros_wrapper_node" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} \ No newline at end of file diff --git a/nebula_ros/src/velodyne/decoder_wrapper.cpp b/nebula_ros/src/velodyne/decoder_wrapper.cpp index cfbf21869..d07383fbe 100644 --- a/nebula_ros/src/velodyne/decoder_wrapper.cpp +++ b/nebula_ros/src/velodyne/decoder_wrapper.cpp @@ -20,7 +20,7 @@ VelodyneDecoderWrapper::VelodyneDecoderWrapper(rclcpp::Node* const parent_node, throw std::runtime_error("VelodyneDecoderWrapper cannot be instantiated without a valid config!"); } - calibration_file_path_ = parent_node->declare_parameter("calibration_file", "", param_read_write()); + calibration_file_path_ = parent_node->declare_parameter("calibration_file", param_read_write()); auto calibration_result = GetCalibrationData(calibration_file_path_); if (!calibration_result.has_value()) diff --git a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp index 8ce73a2a8..38091f89b 100644 --- a/nebula_ros/src/velodyne/hw_interface_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_interface_wrapper.cpp @@ -11,7 +11,7 @@ VelodyneHwInterfaceWrapper::VelodyneHwInterfaceWrapper( , logger_(parent_node->get_logger().get_child("HwInterfaceWrapper")) , status_(Status::NOT_INITIALIZED) { - setup_sensor_ = parent_node->declare_parameter("setup_sensor", true, param_read_only()); + setup_sensor_ = parent_node->declare_parameter("setup_sensor", param_read_only()); hw_interface_->SetLogger(std::make_shared(parent_node->get_logger().get_child("HwInterface"))); status_ = hw_interface_->InitializeSensorConfiguration(config); diff --git a/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp index 836f81e6b..11bbff4c4 100644 --- a/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/velodyne/hw_monitor_wrapper.cpp @@ -14,8 +14,8 @@ VelodyneHwMonitorWrapper::VelodyneHwMonitorWrapper(rclcpp::Node* const parent_no , parent_node_(parent_node) , sensor_configuration_(config) { - diag_span_ = parent_node->declare_parameter("diag_span", 1000, param_read_only()); - show_advanced_diagnostics_ = parent_node->declare_parameter("advanced_diagnostics", false, param_read_only()); + diag_span_ = parent_node->declare_parameter("diag_span", param_read_only()); + show_advanced_diagnostics_ = parent_node->declare_parameter("advanced_diagnostics", param_read_only()); std::cout << "Get model name and serial." << std::endl; auto str = hw_interface_->GetSnapshot(); diff --git a/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp index 88df4a529..d8246e7b5 100644 --- a/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp +++ b/nebula_ros/src/velodyne/velodyne_ros_wrapper.cpp @@ -69,44 +69,44 @@ nebula::Status VelodyneRosWrapper::DeclareAndGetSensorConfigParams() { nebula::drivers::VelodyneSensorConfiguration config; - auto _sensor_model = declare_parameter("sensor_model", "", param_read_only()); + auto _sensor_model = declare_parameter("sensor_model", param_read_only()); config.sensor_model = drivers::SensorModelFromString(_sensor_model); - auto _return_mode = declare_parameter("return_mode", "", param_read_write()); + auto _return_mode = declare_parameter("return_mode", param_read_write()); config.return_mode = drivers::ReturnModeFromString(_return_mode); - config.host_ip = declare_parameter("host_ip", "255.255.255.255", param_read_only()); - config.sensor_ip = declare_parameter("sensor_ip", "192.168.1.201", param_read_only()); - config.data_port = declare_parameter("data_port", 2368, param_read_only()); - config.gnss_port = declare_parameter("gnss_port", 2369, param_read_only()); - config.frame_id = declare_parameter("frame_id", "pandar", param_read_write()); + config.host_ip = declare_parameter("host_ip", param_read_only()); + config.sensor_ip = declare_parameter("sensor_ip", param_read_only()); + config.data_port = declare_parameter("data_port", param_read_only()); + config.gnss_port = declare_parameter("gnss_port", param_read_only()); + config.frame_id = declare_parameter("frame_id", param_read_write()); { rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.])"; descriptor.floating_point_range = float_range(0, 360, 0.01); - config.scan_phase = declare_parameter("scan_phase", 0., descriptor); + config.scan_phase = declare_parameter("scan_phase", descriptor); } - config.min_range = declare_parameter("min_range", 0.3, param_read_write()); - config.max_range = declare_parameter("max_range", 300., param_read_write()); - config.packet_mtu_size = declare_parameter("packet_mtu_size", 1500, param_read_only()); + config.min_range = declare_parameter("min_range", param_read_write()); + config.max_range = declare_parameter("max_range", param_read_write()); + config.packet_mtu_size = declare_parameter("packet_mtu_size", param_read_only()); { rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); descriptor.additional_constraints = "from 300 to 1200, in increments of 60"; descriptor.integer_range = int_range(300, 1200, 60); - config.rotation_speed = declare_parameter("rotation_speed", 600, descriptor); + config.rotation_speed = declare_parameter("rotation_speed", descriptor); } { rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); descriptor.integer_range = int_range(0, 360, 1); - config.cloud_min_angle = declare_parameter("cloud_min_angle", 0, descriptor); + config.cloud_min_angle = declare_parameter("cloud_min_angle", descriptor); } { rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); descriptor.integer_range = int_range(0, 360, 1); - config.cloud_max_angle = declare_parameter("cloud_max_angle", 360, descriptor); + config.cloud_max_angle = declare_parameter("cloud_max_angle", descriptor); } auto new_cfg_ptr = std::make_shared(config); From 0de4ffb90447d49ba2c0213cedc0ad76e0046d4f Mon Sep 17 00:00:00 2001 From: amadeuszsz Date: Mon, 20 May 2024 19:56:18 +0900 Subject: [PATCH 060/122] chore(nebula_ros): update config Signed-off-by: amadeuszsz --- nebula_ros/config/velodyne/VLP16.param.yaml | 12 ++++++------ nebula_ros/config/velodyne/VLP32.param.yaml | 12 ++++++------ nebula_ros/config/velodyne/VLS128.param.yaml | 6 +++--- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/nebula_ros/config/velodyne/VLP16.param.yaml b/nebula_ros/config/velodyne/VLP16.param.yaml index aa7a224fa..6c0e35cbe 100644 --- a/nebula_ros/config/velodyne/VLP16.param.yaml +++ b/nebula_ros/config/velodyne/VLP16.param.yaml @@ -1,20 +1,20 @@ /**: ros__parameters: - calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLP16.yaml" + calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLS128.yaml" setup_sensor: true diag_span: 1000 advanced_diagnostics: false launch_hw: false - sensor_model: "VLP16" - return_mode: "Dual" + sensor_model: VLP16 + return_mode: Dual host_ip: "255.255.255.255" sensor_ip: "192.168.1.201" data_port: 2368 gnss_port: 2369 frame_id: velodyne - scan_phase: 1.0 - min_range: 3. - max_range: 300. + scan_phase: 0.0 + min_range: 0.3 + max_range: 300.0 packet_mtu_size: 1500 rotation_speed: 360 cloud_min_angle: 0 diff --git a/nebula_ros/config/velodyne/VLP32.param.yaml b/nebula_ros/config/velodyne/VLP32.param.yaml index 0e0ac7827..bf6d1e041 100644 --- a/nebula_ros/config/velodyne/VLP32.param.yaml +++ b/nebula_ros/config/velodyne/VLP32.param.yaml @@ -1,20 +1,20 @@ /**: ros__parameters: - calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLP32.yaml" + calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLS128.yaml" setup_sensor: true diag_span: 1000 advanced_diagnostics: false launch_hw: false - sensor_model: "VLP32" - return_mode: "Dual" + sensor_model: VLP32 + return_mode: Dual host_ip: "255.255.255.255" sensor_ip: "192.168.1.201" data_port: 2368 gnss_port: 2369 frame_id: velodyne - scan_phase: 1.0 - min_range: 3. - max_range: 300. + scan_phase: 0.0 + min_range: 0.3 + max_range: 300.0 packet_mtu_size: 1500 rotation_speed: 360 cloud_min_angle: 0 diff --git a/nebula_ros/config/velodyne/VLS128.param.yaml b/nebula_ros/config/velodyne/VLS128.param.yaml index b254dd750..19c1cfdb7 100644 --- a/nebula_ros/config/velodyne/VLS128.param.yaml +++ b/nebula_ros/config/velodyne/VLS128.param.yaml @@ -5,15 +5,15 @@ diag_span: 1000 advanced_diagnostics: false launch_hw: false - sensor_model: "VLS128" - return_mode: "Dual" + sensor_model: VLS128 + return_mode: Dual host_ip: "255.255.255.255" sensor_ip: "192.168.1.201" data_port: 2368 gnss_port: 2369 frame_id: velodyne scan_phase: 0.0 - min_range: 3.0 + min_range: 0.3 max_range: 300.0 packet_mtu_size: 1500 rotation_speed: 360 From a39a16743be629d714d437c6170fcd0424ad33bb Mon Sep 17 00:00:00 2001 From: amadeuszsz Date: Mon, 20 May 2024 19:58:19 +0900 Subject: [PATCH 061/122] chore(nebula_ros): update schema Signed-off-by: amadeuszsz --- ...per_node.schema.json => VLP16.schema.json} | 8 +- nebula_ros/schema/VLP32.schema.json | 171 ++++++++++++++++++ nebula_ros/schema/VLS128.schema.json | 171 ++++++++++++++++++ 3 files changed, 347 insertions(+), 3 deletions(-) rename nebula_ros/schema/{velodyne_ros_wrapper_node.schema.json => VLP16.schema.json} (96%) create mode 100644 nebula_ros/schema/VLP32.schema.json create mode 100644 nebula_ros/schema/VLS128.schema.json diff --git a/nebula_ros/schema/velodyne_ros_wrapper_node.schema.json b/nebula_ros/schema/VLP16.schema.json similarity index 96% rename from nebula_ros/schema/velodyne_ros_wrapper_node.schema.json rename to nebula_ros/schema/VLP16.schema.json index a7d67a64f..4c04002ad 100644 --- a/nebula_ros/schema/velodyne_ros_wrapper_node.schema.json +++ b/nebula_ros/schema/VLP16.schema.json @@ -1,14 +1,16 @@ { "$schema": "http://json-schema.org/draft-07/schema#", - "title": "Parameters for Nebula Velodyne nodes", + "vendor": "velodyne", + "title": "Parameters for Nebula Velodyne VLP16", "type": "object", "definitions": { - "velodyne_ros_wrapper_node": { + "VLP16": { "type": "object", "properties": { "calibration_file": { "type": "string", "default": "$(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml", + "pattern": "^.*\\.yaml$", "description": "Sensor calibration file." }, "setup_sensor": { @@ -157,7 +159,7 @@ "type": "object", "properties": { "ros__parameters": { - "$ref": "#/definitions/velodyne_ros_wrapper_node" + "$ref": "#/definitions/VLP16" } }, "required": ["ros__parameters"], diff --git a/nebula_ros/schema/VLP32.schema.json b/nebula_ros/schema/VLP32.schema.json new file mode 100644 index 000000000..de2cae395 --- /dev/null +++ b/nebula_ros/schema/VLP32.schema.json @@ -0,0 +1,171 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "vendor": "velodyne", + "title": "Parameters for Nebula Velodyne VLP32", + "type": "object", + "definitions": { + "VLP32": { + "type": "object", + "properties": { + "calibration_file": { + "type": "string", + "default": "$(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml", + "pattern": "^.*\\.yaml$", + "description": "Sensor calibration file." + }, + "setup_sensor": { + "type": "boolean", + "default": true, + "readOnly": true, + "description": "Enable sensor setup on hw-driver." + }, + "diag_span": { + "type": "integer", + "default": 1000, + "minimum": 0, + "readOnly": true, + "description": "Diagnostics rate." + }, + "advanced_diagnostics": { + "type": "boolean", + "default": false, + "readOnly": true, + "description": "Enable advanced diagnostics." + }, + "launch_hw": { + "type": "boolean", + "readOnly": false, + "description": "Launch hardware." + }, + "sensor_model": { + "type": "string", + "readOnly": true, + "enum": ["VLP16", "VLP32", "VLS128"], + "description": "Lidar model." + }, + "return_mode": { + "type": "string", + "enum":["SingleFirst", "SingleStrongest", "SingleLast", "Dual"], + "description": "Sensor return mode." + }, + "host_ip": { + "type": "string", + "default": "255.255.255.255", + "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", + "readOnly": true, + "description": "Broadcast IP from Sensor." + }, + "sensor_ip": { + "type": "string", + "default": "192.168.1.201", + "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", + "readOnly": true, + "description": "Lidar Sensor IP." + }, + "data_port": { + "type": "integer", + "default": 2368, + "minimum": 0, + "readOnly": true, + "description": "Lidar Data Port." + }, + "gnss_port": { + "type": "integer", + "default": 2369, + "minimum": 0, + "readOnly": true, + "description": "Lidar GNSS Port." + }, + "frame_id": { + "type": "string", + "default": "velodyne", + "description": "Pointcloud frame_id." + }, + "scan_phase": { + "type": "number", + "default": 0.0, + "minimum": 0.0, + "maximum": 360.0, + "description": "Sensor scan phase." + }, + "min_range": { + "type": "number", + "default": 0.3, + "minimum": 0.0, + "description": "Sensor minimum single point range." + }, + "max_range": { + "type": "number", + "default": 300.0, + "minimum": 0.0, + "description": "Sensor maximum single point range." + }, + "packet_mtu_size": { + "type": "integer", + "default": 1500, + "minimum": 0, + "readOnly": true, + "description": "Packet MTU size." + }, + "rotation_speed": { + "type": "integer", + "default": 600, + "minimum": 300, + "maximum": 1200, + "multipleOf": 60, + "description": "Motor RPM, the sensor's internal spin rate." + }, + "cloud_min_angle": { + "type": "integer", + "default": 0, + "minimum": 0, + "maximum": 360, + "description": "Field of View, start degrees." + }, + "cloud_max_angle": { + "type": "integer", + "default": 360, + "minimum": 0, + "maximum": 360, + "description": "Field of View, end degrees." + } + }, + "required": [ + "calibration_file", + "setup_sensor", + "diag_span", + "advanced_diagnostics", + "launch_hw", + "sensor_model", + "return_mode", + "host_ip", + "sensor_ip", + "data_port", + "gnss_port", + "frame_id", + "scan_phase", + "min_range", + "max_range", + "packet_mtu_size", + "rotation_speed", + "cloud_min_angle", + "cloud_max_angle" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/VLP32" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} \ No newline at end of file diff --git a/nebula_ros/schema/VLS128.schema.json b/nebula_ros/schema/VLS128.schema.json new file mode 100644 index 000000000..0a49b8fb6 --- /dev/null +++ b/nebula_ros/schema/VLS128.schema.json @@ -0,0 +1,171 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "vendor": "velodyne", + "title": "Parameters for Nebula Velodyne VLS128", + "type": "object", + "definitions": { + "VLS128": { + "type": "object", + "properties": { + "calibration_file": { + "type": "string", + "default": "$(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml", + "pattern": "^.*\\.yaml$", + "description": "Sensor calibration file." + }, + "setup_sensor": { + "type": "boolean", + "default": true, + "readOnly": true, + "description": "Enable sensor setup on hw-driver." + }, + "diag_span": { + "type": "integer", + "default": 1000, + "minimum": 0, + "readOnly": true, + "description": "Diagnostics rate." + }, + "advanced_diagnostics": { + "type": "boolean", + "default": false, + "readOnly": true, + "description": "Enable advanced diagnostics." + }, + "launch_hw": { + "type": "boolean", + "readOnly": false, + "description": "Launch hardware." + }, + "sensor_model": { + "type": "string", + "readOnly": true, + "enum": ["VLP16", "VLP32", "VLS128"], + "description": "Lidar model." + }, + "return_mode": { + "type": "string", + "enum":["SingleFirst", "SingleStrongest", "SingleLast", "Dual"], + "description": "Sensor return mode." + }, + "host_ip": { + "type": "string", + "default": "255.255.255.255", + "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", + "readOnly": true, + "description": "Broadcast IP from Sensor." + }, + "sensor_ip": { + "type": "string", + "default": "192.168.1.201", + "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", + "readOnly": true, + "description": "Lidar Sensor IP." + }, + "data_port": { + "type": "integer", + "default": 2368, + "minimum": 0, + "readOnly": true, + "description": "Lidar Data Port." + }, + "gnss_port": { + "type": "integer", + "default": 2369, + "minimum": 0, + "readOnly": true, + "description": "Lidar GNSS Port." + }, + "frame_id": { + "type": "string", + "default": "velodyne", + "description": "Pointcloud frame_id." + }, + "scan_phase": { + "type": "number", + "default": 0.0, + "minimum": 0.0, + "maximum": 360.0, + "description": "Sensor scan phase." + }, + "min_range": { + "type": "number", + "default": 0.3, + "minimum": 0.0, + "description": "Sensor minimum single point range." + }, + "max_range": { + "type": "number", + "default": 300.0, + "minimum": 0.0, + "description": "Sensor maximum single point range." + }, + "packet_mtu_size": { + "type": "integer", + "default": 1500, + "minimum": 0, + "readOnly": true, + "description": "Packet MTU size." + }, + "rotation_speed": { + "type": "integer", + "default": 600, + "minimum": 300, + "maximum": 1200, + "multipleOf": 60, + "description": "Motor RPM, the sensor's internal spin rate." + }, + "cloud_min_angle": { + "type": "integer", + "default": 0, + "minimum": 0, + "maximum": 360, + "description": "Field of View, start degrees." + }, + "cloud_max_angle": { + "type": "integer", + "default": 360, + "minimum": 0, + "maximum": 360, + "description": "Field of View, end degrees." + } + }, + "required": [ + "calibration_file", + "setup_sensor", + "diag_span", + "advanced_diagnostics", + "launch_hw", + "sensor_model", + "return_mode", + "host_ip", + "sensor_ip", + "data_port", + "gnss_port", + "frame_id", + "scan_phase", + "min_range", + "max_range", + "packet_mtu_size", + "rotation_speed", + "cloud_min_angle", + "cloud_max_angle" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/VLS128" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} \ No newline at end of file From 236600d5fb026ada7b6ca5456d31c9016754e607 Mon Sep 17 00:00:00 2001 From: amadeuszsz Date: Mon, 20 May 2024 19:59:09 +0900 Subject: [PATCH 062/122] chore(nebula): add json schema workflow Signed-off-by: amadeuszsz --- .github/workflows/json-schema-check.yaml | 44 +++++++++++++++++ .github/workflows/validate_json.schemas.py | 56 ++++++++++++++++++++++ 2 files changed, 100 insertions(+) create mode 100644 .github/workflows/json-schema-check.yaml create mode 100644 .github/workflows/validate_json.schemas.py diff --git a/.github/workflows/json-schema-check.yaml b/.github/workflows/json-schema-check.yaml new file mode 100644 index 000000000..a24dc0444 --- /dev/null +++ b/.github/workflows/json-schema-check.yaml @@ -0,0 +1,44 @@ +name: json-schema-check + +on: + pull_request: + workflow_dispatch: + +jobs: + check-if-relevant-files-changed: + runs-on: ubuntu-latest + outputs: + run-check: ${{ steps.paths_filter.outputs.json_or_yaml }} + steps: + - uses: actions/checkout@v4 + - uses: dorny/paths-filter@v3 + id: paths_filter + with: + filters: | + json_or_yaml: + - '**/schema/*.schema.json' + - '**/config/*.param.yaml' + + json-schema-check: + needs: check-if-relevant-files-changed + if: needs.check-if-relevant-files-changed.outputs.run-check == 'true' + runs-on: ubuntu-latest + steps: + - name: Check out repository + uses: actions/checkout@v4 + + - name: Install dependencies + run: pip install check-jsonschema colorama + shell: bash + + - name: Validate schemas + run: python ${GITHUB_ACTION_PATH}/validate_json_schemas.py + shell: bash + + no-relevant-changes: + needs: check-if-relevant-files-changed + if: needs.check-if-relevant-files-changed.outputs.run-check == 'false' + runs-on: ubuntu-latest + steps: + - name: Dummy step + run: echo "No relevant changes, passing check" \ No newline at end of file diff --git a/.github/workflows/validate_json.schemas.py b/.github/workflows/validate_json.schemas.py new file mode 100644 index 000000000..b33fa11c2 --- /dev/null +++ b/.github/workflows/validate_json.schemas.py @@ -0,0 +1,56 @@ +# https://github.com/autowarefoundation/autoware-github-actions/blob/61bc6c5399f6e9ce1928d1e1112f9c75e015167f/json-schema-check/validate_json_schemas.py + +import os +import subprocess +import glob +import colorama +import json + +colorama.init(autoreset=True, strip=False) + +def main(): + validation_failed = False + + for schema_path in glob.glob('./**/schema/**/*.schema.json', recursive=True): + with open(schema_path) as f: + schema = json.load(f) + schema_file = os.path.relpath(schema_path, './') + base_name = os.path.basename(schema_file).replace('.schema.json', '') + config_dir = os.path.dirname(schema_file).replace('schema', os.path.join('config', schema['vendor'])) + print(base_name) + print(config_dir) + + str_indentation = ' ' * 4 + config_files = glob.glob(f'{config_dir}/{base_name}*.param.yaml') + if not config_files: + print(colorama.Fore.YELLOW + f'{str_indentation}No configuration files found for schema {schema_file}.') + continue + + for config_file in config_files: + print( + colorama.Style.BRIGHT + '🔍 Validating: ' + + colorama.Style.RESET_ALL + + colorama.Fore.CYAN + f'{config_file} ' + + colorama.Style.RESET_ALL + '🆚 ' + + colorama.Fore.BLUE + f'{schema_file}' + + colorama.Style.RESET_ALL, + end=' ' + ) + result = subprocess.run(['check-jsonschema', '--schemafile', schema_file, config_file], capture_output=True) + if result.returncode != 0: + print(colorama.Fore.RED + '❌ Failed') + for line in result.stdout.decode('utf-8').split('\n'): + if line: + print(colorama.Fore.RED + str_indentation + line) + validation_failed = True + else: + print(colorama.Fore.GREEN + '✅ Passed') + + if validation_failed: + print(colorama.Style.BRIGHT + colorama.Fore.RED + '❗ Validation failed for one or more files.') + exit(1) + else: + print(colorama.Style.BRIGHT + colorama.Fore.GREEN + '✔️ All validations passed successfully.') + +if __name__ == "__main__": + main() \ No newline at end of file From 30d963dcd91765fa1cd297cdbe5c3d18a84fe63e Mon Sep 17 00:00:00 2001 From: amadeuszsz Date: Tue, 21 May 2024 18:35:39 +0900 Subject: [PATCH 063/122] ci(nebula): use of autoware actions repo Signed-off-by: amadeuszsz --- .github/workflows/json-schema-check.yaml | 12 ++--- .github/workflows/validate_json.schemas.py | 56 ---------------------- 2 files changed, 4 insertions(+), 64 deletions(-) delete mode 100644 .github/workflows/validate_json.schemas.py diff --git a/.github/workflows/json-schema-check.yaml b/.github/workflows/json-schema-check.yaml index a24dc0444..00482c2b5 100644 --- a/.github/workflows/json-schema-check.yaml +++ b/.github/workflows/json-schema-check.yaml @@ -17,7 +17,8 @@ jobs: filters: | json_or_yaml: - '**/schema/*.schema.json' - - '**/config/*.param.yaml' + - '**/schema/sub/.json' + - '**/config/**/*.param.yaml' json-schema-check: needs: check-if-relevant-files-changed @@ -27,13 +28,8 @@ jobs: - name: Check out repository uses: actions/checkout@v4 - - name: Install dependencies - run: pip install check-jsonschema colorama - shell: bash - - - name: Validate schemas - run: python ${GITHUB_ACTION_PATH}/validate_json_schemas.py - shell: bash + - name: Run json-schema-check + uses: autowarefoundation/autoware-github-actions/json-schema-check@v1 no-relevant-changes: needs: check-if-relevant-files-changed diff --git a/.github/workflows/validate_json.schemas.py b/.github/workflows/validate_json.schemas.py deleted file mode 100644 index b33fa11c2..000000000 --- a/.github/workflows/validate_json.schemas.py +++ /dev/null @@ -1,56 +0,0 @@ -# https://github.com/autowarefoundation/autoware-github-actions/blob/61bc6c5399f6e9ce1928d1e1112f9c75e015167f/json-schema-check/validate_json_schemas.py - -import os -import subprocess -import glob -import colorama -import json - -colorama.init(autoreset=True, strip=False) - -def main(): - validation_failed = False - - for schema_path in glob.glob('./**/schema/**/*.schema.json', recursive=True): - with open(schema_path) as f: - schema = json.load(f) - schema_file = os.path.relpath(schema_path, './') - base_name = os.path.basename(schema_file).replace('.schema.json', '') - config_dir = os.path.dirname(schema_file).replace('schema', os.path.join('config', schema['vendor'])) - print(base_name) - print(config_dir) - - str_indentation = ' ' * 4 - config_files = glob.glob(f'{config_dir}/{base_name}*.param.yaml') - if not config_files: - print(colorama.Fore.YELLOW + f'{str_indentation}No configuration files found for schema {schema_file}.') - continue - - for config_file in config_files: - print( - colorama.Style.BRIGHT + '🔍 Validating: ' + - colorama.Style.RESET_ALL + - colorama.Fore.CYAN + f'{config_file} ' + - colorama.Style.RESET_ALL + '🆚 ' + - colorama.Fore.BLUE + f'{schema_file}' + - colorama.Style.RESET_ALL, - end=' ' - ) - result = subprocess.run(['check-jsonschema', '--schemafile', schema_file, config_file], capture_output=True) - if result.returncode != 0: - print(colorama.Fore.RED + '❌ Failed') - for line in result.stdout.decode('utf-8').split('\n'): - if line: - print(colorama.Fore.RED + str_indentation + line) - validation_failed = True - else: - print(colorama.Fore.GREEN + '✅ Passed') - - if validation_failed: - print(colorama.Style.BRIGHT + colorama.Fore.RED + '❗ Validation failed for one or more files.') - exit(1) - else: - print(colorama.Style.BRIGHT + colorama.Fore.GREEN + '✔️ All validations passed successfully.') - -if __name__ == "__main__": - main() \ No newline at end of file From 051228365c92da5db323c171280f6742dd9754fc Mon Sep 17 00:00:00 2001 From: amadeuszsz Date: Tue, 21 May 2024 18:43:35 +0900 Subject: [PATCH 064/122] chore(nebula_ros): add schema composition Signed-off-by: amadeuszsz --- .../{ => lidar}/velodyne/VLP16.param.yaml | 2 +- .../{ => lidar}/velodyne/VLP32.param.yaml | 2 +- .../{ => lidar}/velodyne/VLS128.param.yaml | 0 nebula_ros/launch/velodyne_launch_all_hw.xml | 2 +- nebula_ros/schema/VLP16.schema.json | 160 ++---------------- nebula_ros/schema/VLP32.schema.json | 160 ++---------------- nebula_ros/schema/VLS128.schema.json | 160 ++---------------- nebula_ros/schema/sub/lidar.json | 35 ++++ nebula_ros/schema/sub/nebula.json | 44 +++++ nebula_ros/schema/sub/velodyne.json | 123 ++++++++++++++ 10 files changed, 244 insertions(+), 444 deletions(-) rename nebula_ros/config/{ => lidar}/velodyne/VLP16.param.yaml (95%) rename nebula_ros/config/{ => lidar}/velodyne/VLP32.param.yaml (95%) rename nebula_ros/config/{ => lidar}/velodyne/VLS128.param.yaml (100%) create mode 100644 nebula_ros/schema/sub/lidar.json create mode 100644 nebula_ros/schema/sub/nebula.json create mode 100644 nebula_ros/schema/sub/velodyne.json diff --git a/nebula_ros/config/velodyne/VLP16.param.yaml b/nebula_ros/config/lidar/velodyne/VLP16.param.yaml similarity index 95% rename from nebula_ros/config/velodyne/VLP16.param.yaml rename to nebula_ros/config/lidar/velodyne/VLP16.param.yaml index 6c0e35cbe..9ce09de50 100644 --- a/nebula_ros/config/velodyne/VLP16.param.yaml +++ b/nebula_ros/config/lidar/velodyne/VLP16.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLS128.yaml" + calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLP16.yaml" setup_sensor: true diag_span: 1000 advanced_diagnostics: false diff --git a/nebula_ros/config/velodyne/VLP32.param.yaml b/nebula_ros/config/lidar/velodyne/VLP32.param.yaml similarity index 95% rename from nebula_ros/config/velodyne/VLP32.param.yaml rename to nebula_ros/config/lidar/velodyne/VLP32.param.yaml index bf6d1e041..d2f328476 100644 --- a/nebula_ros/config/velodyne/VLP32.param.yaml +++ b/nebula_ros/config/lidar/velodyne/VLP32.param.yaml @@ -1,6 +1,6 @@ /**: ros__parameters: - calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLS128.yaml" + calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLP32.yaml" setup_sensor: true diag_span: 1000 advanced_diagnostics: false diff --git a/nebula_ros/config/velodyne/VLS128.param.yaml b/nebula_ros/config/lidar/velodyne/VLS128.param.yaml similarity index 100% rename from nebula_ros/config/velodyne/VLS128.param.yaml rename to nebula_ros/config/lidar/velodyne/VLS128.param.yaml diff --git a/nebula_ros/launch/velodyne_launch_all_hw.xml b/nebula_ros/launch/velodyne_launch_all_hw.xml index 11f1ead12..d2f030b29 100644 --- a/nebula_ros/launch/velodyne_launch_all_hw.xml +++ b/nebula_ros/launch/velodyne_launch_all_hw.xml @@ -1,7 +1,7 @@ - + diff --git a/nebula_ros/schema/VLP16.schema.json b/nebula_ros/schema/VLP16.schema.json index 4c04002ad..4aadb40a4 100644 --- a/nebula_ros/schema/VLP16.schema.json +++ b/nebula_ros/schema/VLP16.schema.json @@ -1,157 +1,19 @@ { "$schema": "http://json-schema.org/draft-07/schema#", - "vendor": "velodyne", - "title": "Parameters for Nebula Velodyne VLP16", + "title": "LiDAR Velodyne VLP16 parameters.", "type": "object", "definitions": { "VLP16": { "type": "object", "properties": { - "calibration_file": { - "type": "string", - "default": "$(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml", - "pattern": "^.*\\.yaml$", - "description": "Sensor calibration file." - }, - "setup_sensor": { - "type": "boolean", - "default": true, - "readOnly": true, - "description": "Enable sensor setup on hw-driver." - }, - "diag_span": { - "type": "integer", - "default": 1000, - "minimum": 0, - "readOnly": true, - "description": "Diagnostics rate." - }, - "advanced_diagnostics": { - "type": "boolean", - "default": false, - "readOnly": true, - "description": "Enable advanced diagnostics." - }, - "launch_hw": { - "type": "boolean", - "readOnly": false, - "description": "Launch hardware." - }, - "sensor_model": { - "type": "string", - "readOnly": true, - "enum": ["VLP16", "VLP32", "VLS128"], - "description": "Lidar model." - }, - "return_mode": { - "type": "string", - "enum":["SingleFirst", "SingleStrongest", "SingleLast", "Dual"], - "description": "Sensor return mode." - }, - "host_ip": { - "type": "string", - "default": "255.255.255.255", - "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", - "readOnly": true, - "description": "Broadcast IP from Sensor." - }, - "sensor_ip": { - "type": "string", - "default": "192.168.1.201", - "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", - "readOnly": true, - "description": "Lidar Sensor IP." - }, - "data_port": { - "type": "integer", - "default": 2368, - "minimum": 0, - "readOnly": true, - "description": "Lidar Data Port." - }, - "gnss_port": { - "type": "integer", - "default": 2369, - "minimum": 0, - "readOnly": true, - "description": "Lidar GNSS Port." - }, - "frame_id": { - "type": "string", - "default": "velodyne", - "description": "Pointcloud frame_id." - }, - "scan_phase": { - "type": "number", - "default": 0.0, - "minimum": 0.0, - "maximum": 360.0, - "description": "Sensor scan phase." - }, - "min_range": { - "type": "number", - "default": 0.3, - "minimum": 0.0, - "description": "Sensor minimum single point range." - }, - "max_range": { - "type": "number", - "default": 300.0, - "minimum": 0.0, - "description": "Sensor maximum single point range." - }, - "packet_mtu_size": { - "type": "integer", - "default": 1500, - "minimum": 0, - "readOnly": true, - "description": "Packet MTU size." - }, - "rotation_speed": { - "type": "integer", - "default": 600, - "minimum": 300, - "maximum": 1200, - "multipleOf": 60, - "description": "Motor RPM, the sensor's internal spin rate." - }, - "cloud_min_angle": { - "type": "integer", - "default": 0, - "minimum": 0, - "maximum": 360, - "description": "Field of View, start degrees." - }, - "cloud_max_angle": { - "type": "integer", - "default": 360, - "minimum": 0, - "maximum": 360, - "description": "Field of View, end degrees." - } }, - "required": [ - "calibration_file", - "setup_sensor", - "diag_span", - "advanced_diagnostics", - "launch_hw", - "sensor_model", - "return_mode", - "host_ip", - "sensor_ip", - "data_port", - "gnss_port", - "frame_id", - "scan_phase", - "min_range", - "max_range", - "packet_mtu_size", - "rotation_speed", - "cloud_min_angle", - "cloud_max_angle" + "allOf": [ + { + "$ref": "sub/velodyne.json#/definitions/velodyne" + } ], - "additionalProperties": false + "required": [ + ] } }, "properties": { @@ -162,10 +24,14 @@ "$ref": "#/definitions/VLP16" } }, - "required": ["ros__parameters"], + "required": [ + "ros__parameters" + ], "additionalProperties": false } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } \ No newline at end of file diff --git a/nebula_ros/schema/VLP32.schema.json b/nebula_ros/schema/VLP32.schema.json index de2cae395..9adb5d98b 100644 --- a/nebula_ros/schema/VLP32.schema.json +++ b/nebula_ros/schema/VLP32.schema.json @@ -1,157 +1,19 @@ { "$schema": "http://json-schema.org/draft-07/schema#", - "vendor": "velodyne", - "title": "Parameters for Nebula Velodyne VLP32", + "title": "LiDAR Velodyne VLP32 parameters.", "type": "object", "definitions": { "VLP32": { "type": "object", "properties": { - "calibration_file": { - "type": "string", - "default": "$(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml", - "pattern": "^.*\\.yaml$", - "description": "Sensor calibration file." - }, - "setup_sensor": { - "type": "boolean", - "default": true, - "readOnly": true, - "description": "Enable sensor setup on hw-driver." - }, - "diag_span": { - "type": "integer", - "default": 1000, - "minimum": 0, - "readOnly": true, - "description": "Diagnostics rate." - }, - "advanced_diagnostics": { - "type": "boolean", - "default": false, - "readOnly": true, - "description": "Enable advanced diagnostics." - }, - "launch_hw": { - "type": "boolean", - "readOnly": false, - "description": "Launch hardware." - }, - "sensor_model": { - "type": "string", - "readOnly": true, - "enum": ["VLP16", "VLP32", "VLS128"], - "description": "Lidar model." - }, - "return_mode": { - "type": "string", - "enum":["SingleFirst", "SingleStrongest", "SingleLast", "Dual"], - "description": "Sensor return mode." - }, - "host_ip": { - "type": "string", - "default": "255.255.255.255", - "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", - "readOnly": true, - "description": "Broadcast IP from Sensor." - }, - "sensor_ip": { - "type": "string", - "default": "192.168.1.201", - "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", - "readOnly": true, - "description": "Lidar Sensor IP." - }, - "data_port": { - "type": "integer", - "default": 2368, - "minimum": 0, - "readOnly": true, - "description": "Lidar Data Port." - }, - "gnss_port": { - "type": "integer", - "default": 2369, - "minimum": 0, - "readOnly": true, - "description": "Lidar GNSS Port." - }, - "frame_id": { - "type": "string", - "default": "velodyne", - "description": "Pointcloud frame_id." - }, - "scan_phase": { - "type": "number", - "default": 0.0, - "minimum": 0.0, - "maximum": 360.0, - "description": "Sensor scan phase." - }, - "min_range": { - "type": "number", - "default": 0.3, - "minimum": 0.0, - "description": "Sensor minimum single point range." - }, - "max_range": { - "type": "number", - "default": 300.0, - "minimum": 0.0, - "description": "Sensor maximum single point range." - }, - "packet_mtu_size": { - "type": "integer", - "default": 1500, - "minimum": 0, - "readOnly": true, - "description": "Packet MTU size." - }, - "rotation_speed": { - "type": "integer", - "default": 600, - "minimum": 300, - "maximum": 1200, - "multipleOf": 60, - "description": "Motor RPM, the sensor's internal spin rate." - }, - "cloud_min_angle": { - "type": "integer", - "default": 0, - "minimum": 0, - "maximum": 360, - "description": "Field of View, start degrees." - }, - "cloud_max_angle": { - "type": "integer", - "default": 360, - "minimum": 0, - "maximum": 360, - "description": "Field of View, end degrees." - } }, - "required": [ - "calibration_file", - "setup_sensor", - "diag_span", - "advanced_diagnostics", - "launch_hw", - "sensor_model", - "return_mode", - "host_ip", - "sensor_ip", - "data_port", - "gnss_port", - "frame_id", - "scan_phase", - "min_range", - "max_range", - "packet_mtu_size", - "rotation_speed", - "cloud_min_angle", - "cloud_max_angle" + "allOf": [ + { + "$ref": "sub/velodyne.json#/definitions/velodyne" + } ], - "additionalProperties": false + "required": [ + ] } }, "properties": { @@ -162,10 +24,14 @@ "$ref": "#/definitions/VLP32" } }, - "required": ["ros__parameters"], + "required": [ + "ros__parameters" + ], "additionalProperties": false } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } \ No newline at end of file diff --git a/nebula_ros/schema/VLS128.schema.json b/nebula_ros/schema/VLS128.schema.json index 0a49b8fb6..8b5d6375b 100644 --- a/nebula_ros/schema/VLS128.schema.json +++ b/nebula_ros/schema/VLS128.schema.json @@ -1,157 +1,19 @@ { "$schema": "http://json-schema.org/draft-07/schema#", - "vendor": "velodyne", - "title": "Parameters for Nebula Velodyne VLS128", + "title": "LiDAR Velodyne VLS128 parameters.", "type": "object", "definitions": { "VLS128": { "type": "object", "properties": { - "calibration_file": { - "type": "string", - "default": "$(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml", - "pattern": "^.*\\.yaml$", - "description": "Sensor calibration file." - }, - "setup_sensor": { - "type": "boolean", - "default": true, - "readOnly": true, - "description": "Enable sensor setup on hw-driver." - }, - "diag_span": { - "type": "integer", - "default": 1000, - "minimum": 0, - "readOnly": true, - "description": "Diagnostics rate." - }, - "advanced_diagnostics": { - "type": "boolean", - "default": false, - "readOnly": true, - "description": "Enable advanced diagnostics." - }, - "launch_hw": { - "type": "boolean", - "readOnly": false, - "description": "Launch hardware." - }, - "sensor_model": { - "type": "string", - "readOnly": true, - "enum": ["VLP16", "VLP32", "VLS128"], - "description": "Lidar model." - }, - "return_mode": { - "type": "string", - "enum":["SingleFirst", "SingleStrongest", "SingleLast", "Dual"], - "description": "Sensor return mode." - }, - "host_ip": { - "type": "string", - "default": "255.255.255.255", - "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", - "readOnly": true, - "description": "Broadcast IP from Sensor." - }, - "sensor_ip": { - "type": "string", - "default": "192.168.1.201", - "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", - "readOnly": true, - "description": "Lidar Sensor IP." - }, - "data_port": { - "type": "integer", - "default": 2368, - "minimum": 0, - "readOnly": true, - "description": "Lidar Data Port." - }, - "gnss_port": { - "type": "integer", - "default": 2369, - "minimum": 0, - "readOnly": true, - "description": "Lidar GNSS Port." - }, - "frame_id": { - "type": "string", - "default": "velodyne", - "description": "Pointcloud frame_id." - }, - "scan_phase": { - "type": "number", - "default": 0.0, - "minimum": 0.0, - "maximum": 360.0, - "description": "Sensor scan phase." - }, - "min_range": { - "type": "number", - "default": 0.3, - "minimum": 0.0, - "description": "Sensor minimum single point range." - }, - "max_range": { - "type": "number", - "default": 300.0, - "minimum": 0.0, - "description": "Sensor maximum single point range." - }, - "packet_mtu_size": { - "type": "integer", - "default": 1500, - "minimum": 0, - "readOnly": true, - "description": "Packet MTU size." - }, - "rotation_speed": { - "type": "integer", - "default": 600, - "minimum": 300, - "maximum": 1200, - "multipleOf": 60, - "description": "Motor RPM, the sensor's internal spin rate." - }, - "cloud_min_angle": { - "type": "integer", - "default": 0, - "minimum": 0, - "maximum": 360, - "description": "Field of View, start degrees." - }, - "cloud_max_angle": { - "type": "integer", - "default": 360, - "minimum": 0, - "maximum": 360, - "description": "Field of View, end degrees." - } }, - "required": [ - "calibration_file", - "setup_sensor", - "diag_span", - "advanced_diagnostics", - "launch_hw", - "sensor_model", - "return_mode", - "host_ip", - "sensor_ip", - "data_port", - "gnss_port", - "frame_id", - "scan_phase", - "min_range", - "max_range", - "packet_mtu_size", - "rotation_speed", - "cloud_min_angle", - "cloud_max_angle" + "allOf": [ + { + "$ref": "sub/velodyne.json#/definitions/velodyne" + } ], - "additionalProperties": false + "required": [ + ] } }, "properties": { @@ -162,10 +24,14 @@ "$ref": "#/definitions/VLS128" } }, - "required": ["ros__parameters"], + "required": [ + "ros__parameters" + ], "additionalProperties": false } }, - "required": ["/**"], + "required": [ + "/**" + ], "additionalProperties": false } \ No newline at end of file diff --git a/nebula_ros/schema/sub/lidar.json b/nebula_ros/schema/sub/lidar.json new file mode 100644 index 000000000..b12e242fd --- /dev/null +++ b/nebula_ros/schema/sub/lidar.json @@ -0,0 +1,35 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "LiDAR common parameters.", + "type": "object", + "definitions": { + "lidar": { + "type": "object", + "properties": { + "diag_span": { + "type": "integer", + "default": 1000, + "minimum": 0, + "readOnly": true, + "description": "Diagnostics rate." + }, + "scan_phase": { + "type": "number", + "default": 0.0, + "minimum": 0.0, + "maximum": 360.0, + "description": "Sensor scan phase." + } + }, + "allOf": [ + { + "$ref": "nebula.json#/definitions/nebula" + } + ], + "required": [ + "diag_span", + "scan_phase" + ] + } + } +} \ No newline at end of file diff --git a/nebula_ros/schema/sub/nebula.json b/nebula_ros/schema/sub/nebula.json new file mode 100644 index 000000000..6f977cf41 --- /dev/null +++ b/nebula_ros/schema/sub/nebula.json @@ -0,0 +1,44 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Sensors common parameters.", + "type": "object", + "definitions": { + "nebula": { + "type": "object", + "properties": { + "host_ip": { + "type": "string", + "default": "255.255.255.255", + "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", + "readOnly": true, + "description": "Host IPv4 address." + }, + "sensor_ip": { + "type": "string", + "default": "192.168.1.201", + "pattern": "^((25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\\.){3}(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$", + "readOnly": true, + "description": "Sensor IPv4 address." + }, + "data_port": { + "type": "integer", + "default": 2368, + "minimum": 0, + "readOnly": true, + "description": "Sensor data port." + }, + "frame_id": { + "type": "string", + "default": "data_link", + "description": "Sensor data frame_id." + } + }, + "required": [ + "host_ip", + "sensor_ip", + "data_port", + "frame_id" + ] + } + } +} \ No newline at end of file diff --git a/nebula_ros/schema/sub/velodyne.json b/nebula_ros/schema/sub/velodyne.json new file mode 100644 index 000000000..1c2e186b8 --- /dev/null +++ b/nebula_ros/schema/sub/velodyne.json @@ -0,0 +1,123 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "LiDAR Velodyne common parameters.", + "type": "object", + "definitions": { + "velodyne": { + "type": "object", + "properties": { + "calibration_file": { + "type": "string", + "default": "$(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml", + "pattern": "^.*\\.yaml$", + "description": "Sensor calibration file." + }, + "setup_sensor": { + "type": "boolean", + "default": true, + "readOnly": true, + "description": "Enable sensor setup on hw-driver." + }, + "advanced_diagnostics": { + "type": "boolean", + "default": false, + "readOnly": true, + "description": "Enable advanced diagnostics." + }, + "launch_hw": { + "type": "boolean", + "readOnly": false, + "description": "Launch hardware." + }, + "sensor_model": { + "type": "string", + "readOnly": true, + "enum": [ + "VLP16", + "VLP32", + "VLS128" + ], + "description": "LiDAR model." + }, + "return_mode": { + "type": "string", + "enum": [ + "SingleStrongest", + "SingleLast", + "Dual", + "SingleFirst" + ], + "description": "LiDAR return mode." + }, + "gnss_port": { + "type": "integer", + "default": 2369, + "minimum": 0, + "readOnly": true, + "description": "LiDAR GNSS port." + }, + "min_range": { + "type": "number", + "default": 0.3, + "minimum": 0.0, + "description": "Sensor minimum single point range." + }, + "max_range": { + "type": "number", + "default": 300.0, + "minimum": 0.0, + "description": "Sensor maximum single point range." + }, + "packet_mtu_size": { + "type": "integer", + "default": 1500, + "minimum": 0, + "readOnly": true, + "description": "Packet MTU size." + }, + "rotation_speed": { + "type": "integer", + "default": 600, + "minimum": 300, + "maximum": 1200, + "multipleOf": 60, + "description": "Motor RPM, the sensor's internal spin rate." + }, + "cloud_min_angle": { + "type": "integer", + "default": 0, + "minimum": 0, + "maximum": 360, + "description": "Field of View, start degrees." + }, + "cloud_max_angle": { + "type": "integer", + "default": 360, + "minimum": 0, + "maximum": 360, + "description": "Field of View, end degrees." + } + }, + "allOf": [ + { + "$ref": "lidar.json#/definitions/lidar" + } + ], + "required": [ + "calibration_file", + "setup_sensor", + "advanced_diagnostics", + "launch_hw", + "sensor_model", + "return_mode", + "gnss_port", + "min_range", + "max_range", + "packet_mtu_size", + "rotation_speed", + "cloud_min_angle", + "cloud_max_angle" + ] + } + } +} \ No newline at end of file From dff369f1928e629de21cc2151b46b27c046c3585 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 14:22:15 +0900 Subject: [PATCH 065/122] chore(pre-commit): autoupdate hooks --- .pre-commit-config.yaml | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 13c31ce62..b4c2e9f2f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -4,7 +4,7 @@ ci: repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.1.0 + rev: v4.6.0 hooks: - id: check-json - id: check-merge-conflict @@ -18,51 +18,51 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.30.0 + rev: v0.40.0 hooks: - id: markdownlint args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v2.5.1 + rev: v4.0.0-alpha.8 hooks: - id: prettier - repo: https://github.com/adrienverge/yamllint - rev: v1.26.3 + rev: v1.35.1 hooks: - id: yamllint - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.4.0 + rev: v0.8.0 hooks: - id: prettier-package-xml - id: sort-package-xml - repo: https://github.com/shellcheck-py/shellcheck-py - rev: v0.8.0.3 + rev: v0.10.0.1 hooks: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.4.2-1 + rev: v3.8.0-1 hooks: - id: shfmt args: [-w, -s, -i=4] - repo: https://github.com/pycqa/isort - rev: 5.12.0 + rev: 5.13.2 hooks: - id: isort - repo: https://github.com/psf/black - rev: 22.1.0 + rev: 24.4.2 hooks: - id: black args: [--line-length=100] - repo: https://github.com/PyCQA/flake8 - rev: 4.0.1 + rev: 7.0.0 hooks: - id: flake8 additional_dependencies: @@ -78,12 +78,12 @@ repos: ] - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v13.0.0 + rev: v18.1.5 hooks: - id: clang-format - repo: https://github.com/cpplint/cpplint - rev: 1.5.5 + rev: 1.6.1 hooks: - id: cpplint args: [--quiet] From e7a804987ecb3c540c587b86640e7b44e1ba4cb1 Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Thu, 21 Mar 2024 16:58:45 +0900 Subject: [PATCH 066/122] fix(hesai_decoder): print config instead of config address --- .../nebula_decoders_hesai/decoders/hesai_decoder.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index 7bdfd069e..b81b45d44 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -213,7 +213,7 @@ class HesaiDecoder : public HesaiScanDecoder logger_(rclcpp::get_logger("HesaiDecoder")) { logger_.set_level(rclcpp::Logger::Level::Debug); - RCLCPP_INFO_STREAM(logger_, sensor_configuration_); + RCLCPP_INFO_STREAM(logger_, *sensor_configuration_); decode_pc_.reset(new NebulaPointCloud); output_pc_.reset(new NebulaPointCloud); From 737e752a5dac4091a45eb0fc2b38113a24cb5a8c Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Thu, 21 Mar 2024 17:01:34 +0900 Subject: [PATCH 067/122] refactor(nebula_ros): combine Hesai wrapper nodes into one This is step one of the single node refactoring of Nebula. In this step, only the three Hesai wrapper nodes were combined into one, and no optimizations have been done that are made possible by this refactoring. The next step is to do those optimizations (e.g. get rid of unnecessary pointcloud copying). --- nebula_common/CMakeLists.txt | 2 + nebula_ros/CMakeLists.txt | 31 +- .../common/nebula_ros_wrapper_base.hpp | 68 + .../hesai/hesai_decoder_ros_wrapper.hpp | 106 -- .../hesai/hesai_hw_interface_ros_wrapper.hpp | 100 -- ..._ros_wrapper.hpp => hesai_ros_wrapper.hpp} | 194 ++- nebula_ros/launch/hesai_launch_all_hw.xml | 68 +- .../launch/hesai_launch_component.launch.xml | 115 -- .../src/hesai/hesai_decoder_ros_wrapper.cpp | 488 ------- .../hesai/hesai_hw_interface_ros_wrapper.cpp | 510 ------- .../hesai/hesai_hw_monitor_ros_wrapper.cpp | 620 --------- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 1234 +++++++++++++++++ 12 files changed, 1475 insertions(+), 2061 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp delete mode 100644 nebula_ros/include/nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp delete mode 100644 nebula_ros/include/nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp rename nebula_ros/include/nebula_ros/hesai/{hesai_hw_monitor_ros_wrapper.hpp => hesai_ros_wrapper.hpp} (53%) delete mode 100644 nebula_ros/launch/hesai_launch_component.launch.xml delete mode 100644 nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp delete mode 100644 nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp delete mode 100644 nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp create mode 100644 nebula_ros/src/hesai/hesai_ros_wrapper.cpp diff --git a/nebula_common/CMakeLists.txt b/nebula_common/CMakeLists.txt index 4c146736c..154f8e453 100644 --- a/nebula_common/CMakeLists.txt +++ b/nebula_common/CMakeLists.txt @@ -40,6 +40,8 @@ ament_auto_add_library(nebula_common SHARED src/velodyne/velodyne_calibration_decoder.cpp ) +target_link_libraries(nebula_common yaml-cpp) + ament_auto_package() # Set ROS_DISTRO macros diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index dd81e1ac0..18ce06aad 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -33,34 +33,13 @@ include_directories( ) link_libraries(${YAML_CPP_LIBRARIES} ${PCL_LIBRARIES}) ## Hesai -# Hw Interface -ament_auto_add_library(hesai_hw_ros_wrapper SHARED - src/hesai/hesai_hw_interface_ros_wrapper.cpp - ) - -rclcpp_components_register_node(hesai_hw_ros_wrapper - PLUGIN "HesaiHwInterfaceRosWrapper" - EXECUTABLE hesai_hw_interface_ros_wrapper_node - ) - -# Monitor -ament_auto_add_library(hesai_hw_monitor_ros_wrapper SHARED - src/hesai/hesai_hw_monitor_ros_wrapper.cpp - ) - -rclcpp_components_register_node(hesai_hw_monitor_ros_wrapper - PLUGIN "HesaiHwMonitorRosWrapper" - EXECUTABLE hesai_hw_monitor_ros_wrapper_node - ) - -# DriverDecoder -ament_auto_add_library(hesai_driver_ros_wrapper SHARED - src/hesai/hesai_decoder_ros_wrapper.cpp +ament_auto_add_library(hesai_ros_wrapper SHARED + src/hesai/hesai_ros_wrapper.cpp ) -rclcpp_components_register_node(hesai_driver_ros_wrapper - PLUGIN "HesaiDriverRosWrapper" - EXECUTABLE hesai_driver_ros_wrapper_node +rclcpp_components_register_node(hesai_ros_wrapper + PLUGIN "HesaiRosWrapper" + EXECUTABLE hesai_ros_wrapper_node ) ## Velodyne diff --git a/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp b/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp new file mode 100644 index 000000000..5aaeb634b --- /dev/null +++ b/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp @@ -0,0 +1,68 @@ +#pragma once + +#include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" + +#include +#include +#include + +#include + +#include +#include + +namespace nebula +{ +namespace ros +{ +/// @brief Base class for ros wrapper of each sensor driver +class NebulaRosWrapperBase +{ +public: + NebulaRosWrapperBase() = default; + + NebulaRosWrapperBase(NebulaRosWrapperBase && c) = delete; + NebulaRosWrapperBase & operator=(NebulaRosWrapperBase && c) = delete; + NebulaRosWrapperBase(const NebulaRosWrapperBase & c) = delete; + NebulaRosWrapperBase & operator=(const NebulaRosWrapperBase & c) = delete; + + /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) + /// @return Resulting status + virtual Status StreamStart() = 0; + + /// @brief Stop point cloud streaming (not used) + /// @return Resulting status + virtual Status StreamStop() = 0; + + /// @brief Shutdown (not used) + /// @return Resulting status + virtual Status Shutdown() = 0; + +private: + /// @brief Virtual function for initializing hardware interface ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + virtual Status InitializeHwInterface( + const drivers::SensorConfigurationBase & sensor_configuration) = 0; + + /// @brief Virtual function for initializing hardware monitor ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + virtual Status InitializeHwMonitor( + const drivers::SensorConfigurationBase & sensor_configuration) = 0; + + /// @brief Virtual function for initializing ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + /// @return Resulting status + virtual Status InitializeCloudDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) = 0; + + /// @brief Point cloud publisher + rclcpp::Publisher::SharedPtr cloud_pub_; +}; + +} // namespace ros +} // namespace nebula diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp deleted file mode 100644 index 52518fcd0..000000000 --- a/nebula_ros/include/nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp +++ /dev/null @@ -1,106 +0,0 @@ -#ifndef NEBULA_HesaiDriverRosWrapper_H -#define NEBULA_HesaiDriverRosWrapper_H - -#include "nebula_common/hesai/hesai_common.hpp" -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" -#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" -#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" -#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" - -#include -#include -#include -#include - -#include - -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" - -namespace nebula -{ -namespace ros -{ -/// @brief Ros wrapper of hesai driver -class HesaiDriverRosWrapper final : public rclcpp::Node, NebulaDriverRosWrapperBase -{ - std::shared_ptr driver_ptr_; - Status wrapper_status_; - rclcpp::Subscription::SharedPtr pandar_scan_sub_; - rclcpp::Publisher::SharedPtr nebula_points_pub_; - rclcpp::Publisher::SharedPtr aw_points_ex_pub_; - rclcpp::Publisher::SharedPtr aw_points_base_pub_; - - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; - std::shared_ptr correction_cfg_ptr_; - - drivers::HesaiHwInterface hw_interface_; - - /// @brief Initializing ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Initializing ros wrapper for AT - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration); - - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @param calibration_configuration Output of CalibrationConfiguration - /// @param correction_configuration Output of CorrectionConfiguration (for AT) - /// @return Resulting status - Status GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration, - drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration); - - /// @brief Convert seconds to chrono::nanoseconds - /// @param seconds - /// @return chrono::nanoseconds - static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) - { - return std::chrono::duration_cast( - std::chrono::duration(seconds)); - } - - /*** - * Publishes a sensor_msgs::msg::PointCloud2 to the specified publisher - * @param pointcloud unique pointer containing the point cloud to publish - * @param publisher - */ - void PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher); - -public: - explicit HesaiDriverRosWrapper(const rclcpp::NodeOptions & options); - - /// @brief Callback for PandarScan subscriber - /// @param scan_msg Received PandarScan - void ReceiveScanMsgCallback(const pandar_msgs::msg::PandarScan::SharedPtr scan_msg); - - /// @brief Get current status of this driver - /// @return Current status - Status GetStatus(); - -private: - /// @brief File path of Correction data (Only required only for AT) - std::string correction_file_path; -}; - -} // namespace ros -} // namespace nebula - -#endif // NEBULA_HesaiDriverRosWrapper_H diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp deleted file mode 100644 index 1802f87b2..000000000 --- a/nebula_ros/include/nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp +++ /dev/null @@ -1,100 +0,0 @@ -#ifndef NEBULA_HesaiHwInterfaceRosWrapper_H -#define NEBULA_HesaiHwInterfaceRosWrapper_H - -#include "nebula_common/hesai/hesai_common.hpp" -#include "nebula_common/nebula_common.hpp" -#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" -#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" -#include "boost_tcp_driver/tcp_driver.hpp" - -#include -#include -#include - -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" - -#include - -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Get parameter from rclcpp::Parameter -/// @tparam T -/// @param p Parameter from rclcpp parameter callback -/// @param name Target parameter name -/// @param value Corresponding value -/// @return Whether the target name existed -template -bool get_param(const std::vector & p, const std::string & name, T & value) -{ - auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { - return parameter.get_name() == name; - }); - if (it != p.cend()) { - value = it->template get_value(); - return true; - } - return false; -} - -/// @brief Hardware interface ros wrapper of hesai driver -class HesaiHwInterfaceRosWrapper final : public rclcpp::Node, NebulaHwInterfaceWrapperBase -{ - drivers::HesaiHwInterface hw_interface_; - Status interface_status_; - - drivers::HesaiSensorConfiguration sensor_configuration_; - - /// @brief Received Hesai message publisher - rclcpp::Publisher::SharedPtr pandar_scan_pub_; - - /// @brief Initializing hardware interface ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - Status InitializeHwInterface( - const drivers::SensorConfigurationBase & sensor_configuration) override; - /// @brief Callback for receiving PandarScan - /// @param scan_buffer Received PandarScan - void ReceiveScanDataCallback(std::unique_ptr scan_buffer); - -public: - explicit HesaiHwInterfaceRosWrapper(const rclcpp::NodeOptions & options); - ~HesaiHwInterfaceRosWrapper() noexcept override; - /// @brief Start point cloud streaming (Call SensorInterfaceStart of HwInterface) - /// @return Resulting status - Status StreamStart() override; - /// @brief Stop point cloud streaming (not used) - /// @return Resulting status - Status StreamStop() override; - /// @brief Shutdown (not used) - /// @return Resulting status - Status Shutdown() override; - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @return Resulting status - Status GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration); - -private: - uint16_t delay_hw_ms_; - bool retry_hw_; - std::mutex mtx_config_; - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - /// @brief rclcpp parameter callback - /// @param parameters Received parameters - /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); - /// @brief Updating rclcpp parameter - /// @return SetParametersResult - std::vector updateParameters(); -}; - -} // namespace ros -} // namespace nebula - -#endif // NEBULA_HesaiHwInterfaceRosWrapper_H diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp similarity index 53% rename from nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp rename to nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index cf8739279..283f63c68 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -1,24 +1,29 @@ -#ifndef NEBULA_HesaiHwMonitorRosWrapper_H -#define NEBULA_HesaiHwMonitorRosWrapper_H +#pragma once +#include "boost_tcp_driver/tcp_driver.hpp" #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" +#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" +#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" #include "nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp" -#include "boost_tcp_driver/tcp_driver.hpp" +#include "nebula_ros/common/nebula_ros_wrapper_base.hpp" #include #include #include #include -#include +#include "pandar_msgs/msg/pandar_packet.hpp" +#include "pandar_msgs/msg/pandar_scan.hpp" -#include #include #include #include +#include +#include #include #include @@ -26,6 +31,7 @@ namespace nebula { namespace ros { + /// @brief Get parameter from rclcpp::Parameter /// @tparam T /// @param p Parameter from rclcpp parameter callback @@ -45,39 +51,106 @@ bool get_param(const std::vector & p, const std::string & nam return false; } -/// @brief Hardware monitor ros wrapper of hesai driver -class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapperBase +/// @brief Ros wrapper of hesai driver +class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase { - drivers::HesaiHwInterface hw_interface_; - Status interface_status_; +public: + explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); + ~HesaiRosWrapper(); - drivers::HesaiSensorConfiguration sensor_configuration_; + /// @brief Callback for PandarScan subscriber + /// @param scan_msg Received PandarScan + void ReceiveScanMsgCallback(const pandar_msgs::msg::PandarScan::SharedPtr scan_msg); - /// @brief Initializing hardware monitor ros wrapper + /// @brief Get current status of this driver + /// @return Current status + Status GetStatus(); + + /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) + /// @return Resulting status + Status StreamStart() override; + /// @brief Stop point cloud streaming (not used) + /// @return Resulting status + Status StreamStop() override; + /// @brief Shutdown (not used) + /// @return Resulting status + Status Shutdown() override; + +private: + /// @brief Initializing ros wrapper /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver /// @return Resulting status - Status InitializeHwMonitor( - const drivers::SensorConfigurationBase & sensor_configuration) override; + Status InitializeCloudDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) override; + + /// @brief Initializing ros wrapper for AT + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + /// @param correction_configuration CorrectionConfiguration for this driver + /// @return Resulting status + Status InitializeCloudDriver( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration, + const std::shared_ptr & correction_configuration); -public: - explicit HesaiHwMonitorRosWrapper(const rclcpp::NodeOptions & options); - ~HesaiHwMonitorRosWrapper() noexcept override; - /// @brief Not used - /// @return Current status - Status MonitorStart() override; - /// @brief Not used - /// @return Status::OK - Status MonitorStop() override; - /// @brief Not used - /// @return Status::OK - Status Shutdown() override; /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration /// @return Resulting status - Status GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration); + Status GetParameters( + drivers::HesaiSensorConfiguration & sensor_configuration); + + /// @brief Get calibration data from the sensor + /// @param calibration_configuration Output of CalibrationConfiguration + /// @param correction_configuration Output of CorrectionConfiguration (for AT) + /// @return Resulting status + Status GetCalibrationData( + drivers::HesaiCalibrationConfiguration & calibration_configuration, + drivers::HesaiCorrection & correction_configuration); + + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast( + std::chrono::duration(seconds)); + } + + /*** + * Publishes a sensor_msgs::msg::PointCloud2 to the specified publisher + * @param pointcloud unique pointer containing the point cloud to publish + * @param publisher + */ + void PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher); + + /// @brief Initializing hardware interface ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + Status InitializeHwInterface( + const drivers::SensorConfigurationBase & sensor_configuration) override; + /// @brief Callback for receiving PandarScan + /// @param scan_buffer Received PandarScan + void ReceiveScanDataCallback(std::unique_ptr scan_buffer); + + /// @brief rclcpp parameter callback + /// @param parameters Received parameters + /// @return SetParametersResult + rcl_interfaces::msg::SetParametersResult paramCallback( + const std::vector & parameters); + /// @brief Updating rclcpp parameter + /// @return SetParametersResult + std::vector updateParameters(); + + /// @brief Initializing hardware monitor ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @return Resulting status + Status InitializeHwMonitor( + const drivers::SensorConfigurationBase & sensor_configuration) override; -private: - diagnostic_updater::Updater diagnostics_updater_; /// @brief Initializing diagnostics void InitializeHesaiDiagnostics(); /// @brief Callback of the timer for getting the current lidar status @@ -107,6 +180,49 @@ class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapp /// @brief Check voltage information from HesaiLidarStatus for diagnostic_updater via tcp /// @param diagnostics DiagnosticStatusWrapper void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); + /// @brief Get value from property_tree + /// @param pt property_tree + /// @param key Pey string + /// @return Value + std::string GetPtreeValue(boost::property_tree::ptree * pt, const std::string & key); + /// @brief Making fixed precision string + /// @param val Target value + /// @param pre Precision + /// @return Created string + std::string GetFixedPrecisionString(double val, int pre = 2); + + std::shared_ptr driver_ptr_; + Status wrapper_status_; + rclcpp::Subscription::SharedPtr pandar_scan_sub_; + rclcpp::Publisher::SharedPtr nebula_points_pub_; + rclcpp::Publisher::SharedPtr aw_points_ex_pub_; + rclcpp::Publisher::SharedPtr aw_points_base_pub_; + + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; + std::shared_ptr correction_cfg_ptr_; + + Status interface_status_; + + //todo: temporary class member during single node refactoring + bool launch_hw_; + + //todo: temporary class member during single node refactoring + std::string calibration_file_path; + /// @brief File path of Correction data (Only required only for AT) + std::string correction_file_path; + + /// @brief Received Hesai message publisher + rclcpp::Publisher::SharedPtr pandar_scan_pub_; + + drivers::HesaiHwInterface hw_interface_; + + uint16_t delay_hw_ms_; + bool retry_hw_; + std::mutex mtx_config_; + OnSetParametersCallbackHandle::SharedPtr set_param_res_; + + diagnostic_updater::Updater diagnostics_updater_; rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; rclcpp::TimerBase::SharedPtr diagnostics_update_monitor_timer_; @@ -128,24 +244,6 @@ class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapp std::mutex mtx_diag; std::mutex mtx_status; std::mutex mtx_lidar_monitor; - // std::timed_mutex mtx_lidar_monitor; - std::mutex mtx_config_; - OnSetParametersCallbackHandle::SharedPtr set_param_res_; - /// @brief rclcpp parameter callback - /// @param parameters Received parameters - /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); - /// @brief Get value from property_tree - /// @param pt property_tree - /// @param key Pey string - /// @return Value - std::string GetPtreeValue(boost::property_tree::ptree * pt, const std::string & key); - /// @brief Making fixed precision string - /// @param val Target value - /// @param pre Precision - /// @return Created string - std::string GetFixedPrecisionString(double val, int pre = 2); std::string info_model; std::string info_serial; @@ -158,9 +256,9 @@ class HesaiHwMonitorRosWrapper final : public rclcpp::Node, NebulaHwMonitorWrapp std::string message_sep; std::vector temperature_names; + + bool setup_sensor; }; } // namespace ros } // namespace nebula - -#endif // NEBULA_HesaiHwMonitorRosWrapper_H diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index f4a1cd41c..579852fb8 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -35,8 +35,8 @@ - + @@ -45,52 +45,24 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + diff --git a/nebula_ros/launch/hesai_launch_component.launch.xml b/nebula_ros/launch/hesai_launch_component.launch.xml deleted file mode 100644 index 75c7414da..000000000 --- a/nebula_ros/launch/hesai_launch_component.launch.xml +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp deleted file mode 100644 index 6f27d547e..000000000 --- a/nebula_ros/src/hesai/hesai_decoder_ros_wrapper.cpp +++ /dev/null @@ -1,488 +0,0 @@ -#include "nebula_ros/hesai/hesai_decoder_ros_wrapper.hpp" - -namespace nebula -{ -namespace ros -{ -HesaiDriverRosWrapper::HesaiDriverRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_driver_ros_wrapper", options), hw_interface_() -{ - drivers::HesaiCalibrationConfiguration calibration_configuration; - drivers::HesaiSensorConfiguration sensor_configuration; - drivers::HesaiCorrection correction_configuration; - - setvbuf(stdout, NULL, _IONBF, BUFSIZ); - - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - - wrapper_status_ = - GetParameters(sensor_configuration, calibration_configuration, correction_configuration); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return; - } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - - calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); - - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - correction_cfg_ptr_ = std::make_shared(correction_configuration); - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); - } else { - wrapper_status_ = InitializeDriver( - std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); - } - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), - qos_profile); - pandar_scan_sub_ = create_subscription( - "pandar_packets", qos, - std::bind(&HesaiDriverRosWrapper::ReceiveScanMsgCallback, this, std::placeholders::_1)); - nebula_points_pub_ = - this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); - aw_points_base_pub_ = - this->create_publisher("aw_points", rclcpp::SensorDataQoS()); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", rclcpp::SensorDataQoS()); -} - -void HesaiDriverRosWrapper::ReceiveScanMsgCallback( - const pandar_msgs::msg::PandarScan::SharedPtr scan_msg) -{ - auto t_start = std::chrono::high_resolution_clock::now(); - std::tuple pointcloud_ts = - driver_ptr_->ConvertScanToPointcloud(scan_msg); - nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - - if (pointcloud == nullptr) { - RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); - return; - }; - if ( - nebula_points_pub_->get_subscription_count() > 0 || - nebula_points_pub_->get_intra_process_subscription_count() > 0) { - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); - } - if ( - aw_points_base_pub_->get_subscription_count() > 0 || - aw_points_base_pub_->get_intra_process_subscription_count() > 0) { - const auto autoware_cloud_xyzi = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); - } - if ( - aw_points_ex_pub_->get_subscription_count() > 0 || - aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - const auto autoware_ex_cloud = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); - } - - auto runtime = std::chrono::high_resolution_clock::now() - t_start; - RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); -} - -void HesaiDriverRosWrapper::PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher) -{ - if (pointcloud->header.stamp.sec < 0) { - RCLCPP_WARN_STREAM(this->get_logger(), "Timestamp error, verify clock source."); - } - pointcloud->header.frame_id = sensor_cfg_ptr_->frame_id; - publisher->publish(std::move(pointcloud)); -} - -Status HesaiDriverRosWrapper::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) -{ - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiDriverRosWrapper::InitializeDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration), - std::static_pointer_cast(correction_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiDriverRosWrapper::GetStatus() { return wrapper_status_; } - -Status HesaiDriverRosWrapper::GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration, - drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("calibration_file", "", descriptor); - calibration_configuration.calibration_file = - this->get_parameter("calibration_file").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("min_range", 0.3, descriptor); - sensor_configuration.min_range = this->get_parameter("min_range").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("max_range", 300., descriptor); - sensor_configuration.max_range = this->get_parameter("max_range").as_double(); - } - if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("correction_file", "", descriptor); - correction_file_path = this->get_parameter("correction_file").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = - this->get_parameter("dual_return_distance_threshold").as_double(); - } - bool launch_hw; - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("launch_hw", "", descriptor); - launch_hw = this->get_parameter("launch_hw").as_bool(); - } - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { - return Status::SENSOR_CONFIG_ERROR; - } - - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration); - - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - - bool run_local = !launch_hw; - if (sensor_configuration.sensor_model != drivers::SensorModel::HESAI_PANDARAT128) { - std::string calibration_file_path_from_sensor; - if (launch_hw && !calibration_configuration.calibration_file.empty()) { - int ext_pos = calibration_configuration.calibration_file.find_last_of('.'); - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(0, ext_pos); - calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(ext_pos, calibration_configuration.calibration_file.size() - ext_pos); - } - if(launch_hw) { - run_local = false; - RCLCPP_INFO_STREAM( - this->get_logger(), "Trying to acquire calibration data from sensor: '" - << sensor_configuration.sensor_ip << "'"); - std::future future = std::async(std::launch::async, - [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { - if (hw_interface_.InitializeTcpDriver() == Status::OK) { - auto str = hw_interface_.GetLidarCalibrationString(); - auto rt = calibration_configuration.SaveFileFromString( - calibration_file_path_from_sensor, str); - RCLCPP_ERROR_STREAM(get_logger(), str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromString success:" - << calibration_file_path_from_sensor << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromString failed:" - << calibration_file_path_from_sensor << "\n"); - } - rt = calibration_configuration.LoadFromString(str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), - "LoadFromString success:" << str << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), - "LoadFromString failed:" << str << "\n"); - } - } else { - run_local = true; - } - }); - std::future_status status; - status = future.wait_for(std::chrono::milliseconds(5000)); - if (status == std::future_status::timeout) { - std::cerr << "# std::future_status::timeout\n"; - RCLCPP_ERROR_STREAM(get_logger(), "GetCalibration Timeout"); - run_local = true; - } else if (status == std::future_status::ready && !run_local) { - RCLCPP_INFO_STREAM( - this->get_logger(), "Acquired calibration data from sensor: '" - << sensor_configuration.sensor_ip << "'"); - RCLCPP_INFO_STREAM( - this->get_logger(), "The calibration has been saved in '" - << calibration_file_path_from_sensor << "'"); - } - } - if(run_local) { - RCLCPP_WARN_STREAM(get_logger(), "Running locally"); - bool run_org = false; - if (calibration_file_path_from_sensor.empty()) { - run_org = true; - } else { - RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_file_path_from_sensor); - auto cal_status = - calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); - - if (cal_status != Status::OK) { - run_org = true; - }else{ - RCLCPP_INFO_STREAM( - this->get_logger(), "Load calibration data from: '" - << calibration_file_path_from_sensor << "'"); - } - } - if(run_org) { - RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_configuration.calibration_file); - if (calibration_configuration.calibration_file.empty()) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = - calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); - - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), - "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); - return cal_status; - }else{ - RCLCPP_INFO_STREAM( - this->get_logger(), "Load calibration data from: '" - << calibration_configuration.calibration_file << "'"); - } - } - } - } - } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 - std::string correction_file_path_from_sensor; - if (launch_hw && !correction_file_path.empty()) { - int ext_pos = correction_file_path.find_last_of('.'); - correction_file_path_from_sensor += correction_file_path.substr(0, ext_pos); - correction_file_path_from_sensor += "_from_sensor"; - correction_file_path_from_sensor += correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); - } - std::future future = std::async(std::launch::async, [this, &correction_configuration, &correction_file_path_from_sensor, &run_local, &launch_hw]() { - if (launch_hw && hw_interface_.InitializeTcpDriver() == Status::OK) { - RCLCPP_INFO_STREAM( - this->get_logger(), "Trying to acquire calibration data from sensor"); - auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); - RCLCPP_INFO_STREAM(get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); - auto rt = correction_configuration.SaveFileFromBinary(correction_file_path_from_sensor, received_bytes); - if(rt == Status::OK) - { - RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromBinary failed:" << correction_file_path_from_sensor << ". Falling back to offline calibration file."); - run_local = true; - } - rt = correction_configuration.LoadFromBinary(received_bytes); - if(rt == Status::OK) - { - RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); - run_local = false; - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "LoadFromBinary failed" << ". Falling back to offline calibration file."); - run_local = true; - } - }else{ - RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); - run_local = true; - } - }); - if (!run_local) { - std::future_status status; - status = future.wait_for(std::chrono::milliseconds(8000)); - if (status == std::future_status::timeout) { - std::cerr << "# std::future_status::timeout\n"; - run_local = true; - } else if (status == std::future_status::ready && !run_local) { - RCLCPP_INFO_STREAM( - this->get_logger(), "Acquired correction data from sensor: '" - << sensor_configuration.sensor_ip << "'"); - RCLCPP_INFO_STREAM( - this->get_logger(), "The correction has been saved in '" - << correction_file_path_from_sensor << "'"); - } - } - if(run_local) { - bool run_org = false; - if (correction_file_path_from_sensor.empty()) { - run_org = true; - } else { - auto cal_status = - correction_configuration.LoadFromFile(correction_file_path_from_sensor); - - if (cal_status != Status::OK) { - run_org = true; - }else{ - RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" - << correction_file_path_from_sensor << "'"); - } - } - if(run_org) { - if (correction_file_path.empty()) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Empty Correction File: '" << correction_file_path << "'"); - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = correction_configuration.LoadFromFile(correction_file_path); - - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Given Correction File: '" << correction_file_path << "'"); - return cal_status; - }else{ - RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" - << correction_file_path << "'"); - } - } - } - } - } // end AT128 - // Do not use outside of this location - hw_interface_.~HesaiHwInterface(); - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); - return Status::OK; -} - -RCLCPP_COMPONENTS_REGISTER_NODE(HesaiDriverRosWrapper) -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp deleted file mode 100644 index 1ac59b55b..000000000 --- a/nebula_ros/src/hesai/hesai_hw_interface_ros_wrapper.cpp +++ /dev/null @@ -1,510 +0,0 @@ -#include "nebula_ros/hesai/hesai_hw_interface_ros_wrapper.hpp" - -namespace nebula -{ -namespace ros -{ -HesaiHwInterfaceRosWrapper::HesaiHwInterfaceRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_hw_interface_ros_wrapper", options), hw_interface_() -{ - if (mtx_config_.try_lock()) { - interface_status_ = GetParameters(sensor_configuration_); - mtx_config_.unlock(); - } - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_hw_ms_)); - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); -#if not defined(TEST_PCAP) - Status rt = hw_interface_.InitializeTcpDriver(); - if(this->retry_hw_) - { - int cnt = 0; - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - while(rt == Status::ERROR_1) - { - cnt++; - std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000 - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - rt = hw_interface_.InitializeTcpDriver(); - } - } - - if(rt != Status::ERROR_1){ - try{ - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto result = hw_interface_.GetInventory(); - RCLCPP_INFO_STREAM(get_logger(), result); - hw_interface_.SetTargetModel(result.model); - }); - for (std::thread & th : thread_pool) { - th.join(); - } - - } - catch (...) - { - std::cout << "catch (...) in parent" << std::endl; - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); - } - if (this->setup_sensor) { - hw_interface_.CheckAndSetConfig(); - updateParameters(); - } - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr->sensor_model); - hw_interface_.SetTargetModel(sensor_cfg_ptr->sensor_model); - } -#endif - - hw_interface_.RegisterScanCallback( - std::bind(&HesaiHwInterfaceRosWrapper::ReceiveScanDataCallback, this, std::placeholders::_1)); - pandar_scan_pub_ = - this->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); - -#if not defined(TEST_PCAP) - if (this->setup_sensor) { - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiHwInterfaceRosWrapper::paramCallback, this, std::placeholders::_1)); - } -#endif - -#ifdef WITH_DEBUG_STDOUT_HesaiHwInterfaceRosWrapper - if (false) { - std::vector thread_pool{}; - thread_pool.emplace_back([this] { hw_interface_.SetStandbyMode(0); }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetLidarCalib(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpDiagStatus(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpDiagPort(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpDiagTime(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpDiagGrandmaster(ios); - }); - // thread_pool.emplace_back([&hw_interface_]{ - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetInventory(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetConfig(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetLidarStatus(ios); - }); - thread_pool.emplace_back([this] { hw_interface_.SetStandbyMode(1); }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetPtpConfig(ios); - }); - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - hw_interface_.GetLidarRange(ios); - }); - for (std::thread & th : thread_pool) { - // hw_interface_.IOServiceRun(); - th.join(); - } - } - if (false) { - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto ios = std::make_shared(); - std::cout << "GetLidarCalib" << std::endl; - hw_interface_.GetLidarCalib(ios); - }); - for (std::thread & th : thread_pool) { - th.join(); - } - } -#endif - - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); -} - -HesaiHwInterfaceRosWrapper::~HesaiHwInterfaceRosWrapper() { - RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); - hw_interface_.FinalizeTcpDriver(); -} - -Status HesaiHwInterfaceRosWrapper::StreamStart() -{ - if (Status::OK == interface_status_) { - interface_status_ = hw_interface_.SensorInterfaceStart(); - } - return interface_status_; -} - -Status HesaiHwInterfaceRosWrapper::StreamStop() { return Status::OK; } -Status HesaiHwInterfaceRosWrapper::Shutdown() { return Status::OK; } - -Status HesaiHwInterfaceRosWrapper::InitializeHwInterface( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) -{ - std::stringstream ss; - ss << sensor_configuration; - RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); - return Status::OK; -} - -Status HesaiHwInterfaceRosWrapper::GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { - descriptor.additional_constraints = "200, 300, 400, 500"; - range.set__from_value(200).set__to_value(500).set__step(100); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 200, descriptor); - } else { - descriptor.additional_constraints = "300, 600, 1200"; - range.set__from_value(300).set__to_value(1200).set__step(300); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 600, descriptor); - } - sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = - this->get_parameter("dual_return_distance_threshold").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("setup_sensor", true, descriptor); - this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("delay_hw_ms", 0, descriptor); - this->delay_hw_ms_ = this->get_parameter("delay_hw_ms").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("retry_hw", true, descriptor); - this->retry_hw_ = this->get_parameter("retry_hw").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("ptp_profile", ""); - sensor_configuration.ptp_profile = - nebula::drivers::PtpProfileFromString(this->get_parameter("ptp_profile").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("ptp_transport_type", ""); - sensor_configuration.ptp_transport_type = - nebula::drivers::PtpTransportTypeFromString(this->get_parameter("ptp_transport_type").as_string()); - if(static_cast(sensor_configuration.ptp_profile) > 0) { - sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; - } - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("ptp_switch_type", ""); - sensor_configuration.ptp_switch_type = - nebula::drivers::PtpSwitchTypeFromString(this->get_parameter("ptp_switch_type").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(127).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("ptp_domain", 0, descriptor); - sensor_configuration.ptp_domain = this->get_parameter("ptp_domain").as_int(); - } - - if(sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { - RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); - return Status::SENSOR_CONFIG_ERROR; - } - if(sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when using the '1588v2' PTP Profile"); - return Status::SENSOR_CONFIG_ERROR; - } - if(sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); - return Status::SENSOR_CONFIG_ERROR; - } - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { // || - return Status::SENSOR_CONFIG_ERROR; - } - - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); - return Status::OK; -} - -void HesaiHwInterfaceRosWrapper::ReceiveScanDataCallback( - std::unique_ptr scan_buffer) -{ - // Publish - scan_buffer->header.frame_id = sensor_configuration_.frame_id; - scan_buffer->header.stamp = scan_buffer->packets.front().stamp; - pandar_scan_pub_->publish(std::move(scan_buffer)); -} - -rcl_interfaces::msg::SetParametersResult HesaiHwInterfaceRosWrapper::paramCallback( - const std::vector & p) -{ - std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback"); - RCLCPP_DEBUG_STREAM(this->get_logger(), p); - RCLCPP_DEBUG_STREAM(this->get_logger(), sensor_configuration_); - RCLCPP_INFO_STREAM(this->get_logger(), p); - - drivers::HesaiSensorConfiguration new_param{sensor_configuration_}; - RCLCPP_INFO_STREAM(this->get_logger(), new_param); - std::string sensor_model_str; - std::string return_mode_str; - if ( - get_param(p, "sensor_model", sensor_model_str) || - get_param(p, "return_mode", return_mode_str) || get_param(p, "host_ip", new_param.host_ip) || - get_param(p, "sensor_ip", new_param.sensor_ip) || - get_param(p, "frame_id", new_param.frame_id) || - get_param(p, "data_port", new_param.data_port) || - get_param(p, "gnss_port", new_param.gnss_port) || - get_param(p, "scan_phase", new_param.scan_phase) || - get_param(p, "packet_mtu_size", new_param.packet_mtu_size) || - get_param(p, "rotation_speed", new_param.rotation_speed) || - get_param(p, "cloud_min_angle", new_param.cloud_min_angle) || - get_param(p, "cloud_max_angle", new_param.cloud_max_angle) || - get_param(p, "dual_return_distance_threshold", new_param.dual_return_distance_threshold)) { - if (0 < sensor_model_str.length()) - new_param.sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); - if (0 < return_mode_str.length()) - new_param.return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); - - sensor_configuration_ = new_param; - RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - hw_interface_.CheckAndSetConfig(); - } - - auto result = std::make_shared(); - result->successful = true; - result->reason = "success"; - - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback success"); - - return *result; -} - -std::vector HesaiHwInterfaceRosWrapper::updateParameters() -{ - std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters start"); - std::ostringstream os_sensor_model; - os_sensor_model << sensor_configuration_.sensor_model; - std::ostringstream os_return_mode; - os_return_mode << sensor_configuration_.return_mode; - RCLCPP_INFO_STREAM(this->get_logger(), "set_parameters"); - auto results = set_parameters( - {rclcpp::Parameter("sensor_model", os_sensor_model.str()), - rclcpp::Parameter("return_mode", os_return_mode.str()), - rclcpp::Parameter("host_ip", sensor_configuration_.host_ip), - rclcpp::Parameter("sensor_ip", sensor_configuration_.sensor_ip), - rclcpp::Parameter("frame_id", sensor_configuration_.frame_id), - rclcpp::Parameter("data_port", sensor_configuration_.data_port), - rclcpp::Parameter("gnss_port", sensor_configuration_.gnss_port), - rclcpp::Parameter("scan_phase", sensor_configuration_.scan_phase), - rclcpp::Parameter("packet_mtu_size", sensor_configuration_.packet_mtu_size), - rclcpp::Parameter("rotation_speed", sensor_configuration_.rotation_speed), - rclcpp::Parameter("cloud_min_angle", sensor_configuration_.cloud_min_angle), - rclcpp::Parameter("cloud_max_angle", sensor_configuration_.cloud_max_angle), - rclcpp::Parameter( - "dual_return_distance_threshold", sensor_configuration_.dual_return_distance_threshold)}); - RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters end"); - return results; -} - -RCLCPP_COMPONENTS_REGISTER_NODE(HesaiHwInterfaceRosWrapper) -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp deleted file mode 100644 index e64bf443b..000000000 --- a/nebula_ros/src/hesai/hesai_hw_monitor_ros_wrapper.cpp +++ /dev/null @@ -1,620 +0,0 @@ -#include "nebula_ros/hesai/hesai_hw_monitor_ros_wrapper.hpp" - -namespace nebula -{ -namespace ros -{ -HesaiHwMonitorRosWrapper::HesaiHwMonitorRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_hw_monitor_ros_wrapper", options), hw_interface_(), diagnostics_updater_(this) -{ - cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); - cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - if (mtx_config_.try_lock()) { - interface_status_ = GetParameters(sensor_configuration_); - mtx_config_.unlock(); - } - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_monitor_ms_)); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - - message_sep = ": "; - not_supported_message = "Not supported"; - error_message = "Error"; - - switch (sensor_cfg_ptr->sensor_model) { - case nebula::drivers::SensorModel::HESAI_PANDARXT32: - case nebula::drivers::SensorModel::HESAI_PANDARXT32M: - case nebula::drivers::SensorModel::HESAI_PANDARAT128: - temperature_names.emplace_back("Bottom circuit board T1"); - temperature_names.emplace_back("Bottom circuit board T2"); - temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); - temperature_names.emplace_back("Laser emitting board RT_L2"); - temperature_names.emplace_back("Receiving board RT_R"); - temperature_names.emplace_back("Receiving board RT2"); - temperature_names.emplace_back("Top circuit RT3"); - temperature_names.emplace_back("Not used"); - break; - case nebula::drivers::SensorModel::HESAI_PANDAR64: - case nebula::drivers::SensorModel::HESAI_PANDAR40P: - case nebula::drivers::SensorModel::HESAI_PANDAR40M: - case nebula::drivers::SensorModel::HESAI_PANDARQT64: - case nebula::drivers::SensorModel::HESAI_PANDARQT128: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: - default: - temperature_names.emplace_back("Bottom circuit RT1"); - temperature_names.emplace_back("Bottom circuit RT2"); - temperature_names.emplace_back("Internal Temperature"); - temperature_names.emplace_back("Laser emitting board RT1"); - temperature_names.emplace_back("Laser emitting board RT2"); - temperature_names.emplace_back("Receiving board RT1"); - temperature_names.emplace_back("Top circuit RT1"); - temperature_names.emplace_back("Top circuit RT2"); - break; - } - - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); - while(hw_interface_.InitializeTcpDriver() == Status::ERROR_1) - { - RCLCPP_WARN(this->get_logger(), "Could not initialize TCP driver, retrying in 8s..."); - std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000 - } - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto result = hw_interface_.GetInventory(); - current_inventory.reset(new HesaiInventory(result)); - current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); - RCLCPP_INFO_STREAM(this->get_logger(), "HesaiInventory"); - RCLCPP_INFO_STREAM(this->get_logger(), result); - info_model = result.get_str_model(); - info_serial = std::string(std::begin(result.sn), std::end(result.sn)); - hw_interface_.SetTargetModel(result.model); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); - InitializeHesaiDiagnostics(); - }); - for (std::thread & th : thread_pool) { - th.join(); - } - - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiHwMonitorRosWrapper::paramCallback, this, std::placeholders::_1)); -} - -Status HesaiHwMonitorRosWrapper::MonitorStart() { return interface_status_; } - -Status HesaiHwMonitorRosWrapper::MonitorStop() { return Status::OK; } -Status HesaiHwMonitorRosWrapper::Shutdown() { return Status::OK; } - -Status HesaiHwMonitorRosWrapper::InitializeHwMonitor( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) -{ - std::stringstream ss; - ss << sensor_configuration; - RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); - return Status::OK; -} - -Status HesaiHwMonitorRosWrapper::GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration) -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { - descriptor.additional_constraints = "200, 300, 400, 500"; - range.set__from_value(200).set__to_value(500).set__step(100); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 200, descriptor); - } else { - descriptor.additional_constraints = "300, 600, 1200"; - range.set__from_value(300).set__to_value(1200).set__step(300); - descriptor.integer_range = {range}; - this->declare_parameter("rotation_speed", 600, descriptor); - } - sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = - this->get_parameter("dual_return_distance_threshold").as_double(); - } - - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - return Status::INVALID_SENSOR_MODEL; - } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - return Status::INVALID_ECHO_MODE; - } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { // || - return Status::SENSOR_CONFIG_ERROR; - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("diag_span", 1000, descriptor); - this->diag_span_ = this->get_parameter("diag_span").as_int(); - } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("delay_monitor_ms", 0, descriptor); - this->delay_monitor_ms_ = this->get_parameter("delay_monitor_ms").as_int(); - } - - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); - return Status::OK; -} - -void HesaiHwMonitorRosWrapper::InitializeHesaiDiagnostics() -{ - RCLCPP_INFO_STREAM(this->get_logger(), "InitializeHesaiDiagnostics"); - using std::chrono_literals::operator""s; - std::ostringstream os; - auto hardware_id = info_model + ": " + info_serial; - diagnostics_updater_.setHardwareID(hardware_id); - RCLCPP_INFO_STREAM(this->get_logger(), "hardware_id: " + hardware_id); - - diagnostics_updater_.add("hesai_status", this, &HesaiHwMonitorRosWrapper::HesaiCheckStatus); - diagnostics_updater_.add("hesai_ptp", this, &HesaiHwMonitorRosWrapper::HesaiCheckPtp); - diagnostics_updater_.add( - "hesai_temperature", this, &HesaiHwMonitorRosWrapper::HesaiCheckTemperature); - diagnostics_updater_.add("hesai_rpm", this, &HesaiHwMonitorRosWrapper::HesaiCheckRpm); - - current_status.reset(); - current_monitor.reset(); - current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - - auto fetch_diag_from_sensor = [this](){ - OnHesaiStatusTimer(); - if (hw_interface_.UseHttpGetLidarMonitor()) { - OnHesaiLidarMonitorTimerHttp(); - } else { - OnHesaiLidarMonitorTimer(); - } - }; - - fetch_diagnostics_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); - - if (hw_interface_.UseHttpGetLidarMonitor()) { - diagnostics_updater_.add( - "hesai_voltage", this, &HesaiHwMonitorRosWrapper::HesaiCheckVoltageHttp); - } else { - diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorRosWrapper::HesaiCheckVoltage); - } - - auto on_timer_update = [this] { - RCLCPP_DEBUG_STREAM(get_logger(), "OnUpdateTimer"); - auto now = this->get_clock()->now(); - auto dif = (now - *current_status_time).seconds(); - - RCLCPP_DEBUG_STREAM(get_logger(), "dif(status): " << dif); - - if (diag_span_ * 2.0 < dif * 1000) { - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); - } else { - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); - } - dif = (now - *current_lidar_monitor_time).seconds(); - RCLCPP_DEBUG_STREAM(get_logger(), "dif(monitor): " << dif); - if (diag_span_ * 2.0 < dif * 1000) { - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); - } else { - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); - } - diagnostics_updater_.force_update(); - }; - diagnostics_update_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(1000), std::move(on_timer_update), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(diagnostics_update_timer_, cbg_r_); - - RCLCPP_DEBUG_STREAM(get_logger(), "add_timer"); -} - -std::string HesaiHwMonitorRosWrapper::GetPtreeValue( - boost::property_tree::ptree * pt, const std::string & key) -{ - boost::optional value = pt->get_optional(key); - if (value) { - return value.get(); - } else { - return not_supported_message; - } -} -std::string HesaiHwMonitorRosWrapper::GetFixedPrecisionString(double val, int pre) -{ - std::stringstream ss; - ss << std::fixed << std::setprecision(pre) << val; - return ss.str(); -} - -rcl_interfaces::msg::SetParametersResult HesaiHwMonitorRosWrapper::paramCallback( - const std::vector & p) -{ - std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback"); - RCLCPP_DEBUG_STREAM(get_logger(), p); - RCLCPP_DEBUG_STREAM(get_logger(), sensor_configuration_); - RCLCPP_INFO_STREAM(this->get_logger(), p); - - drivers::HesaiSensorConfiguration new_param{sensor_configuration_}; - RCLCPP_INFO_STREAM(this->get_logger(), new_param); - uint16_t new_diag_span = 0; - if (get_param(p, "diag_span", new_diag_span)) { - sensor_configuration_ = new_param; - RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); - } - - auto result = std::make_shared(); - result->successful = true; - result->reason = "success"; - - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback success"); - return *result; -} - -void HesaiHwMonitorRosWrapper::OnHesaiStatusTimer() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer" << std::endl); - try { - auto ios = std::make_shared(); - auto result = hw_interface_.GetLidarStatus(); - std::scoped_lock lock(mtx_status); - current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_status.reset(new HesaiLidarStatus(result)); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiHwMonitorRosWrapper::OnHesaiStatusTimer(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiHwMonitorRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), - error.what()); - } - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl); -} - -void HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp"); - try { - hw_interface_.GetLidarMonitorAsyncHttp([this](const std::string & str) { - std::scoped_lock lock(mtx_lidar_monitor); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_tree = - std::make_unique(hw_interface_.ParseJson(str)); - }); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_error)"), - error.what()); - } - - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp END"); -} - -void HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer"); - try { - auto ios = std::make_shared(); - auto result = hw_interface_.GetLidarMonitor(); - std::scoped_lock lock(mtx_lidar_monitor); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_monitor.reset(new HesaiLidarMonitor(result)); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiHwMonitorRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), - error.what()); - } - - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END"); -} - -void HesaiHwMonitorRosWrapper::HesaiCheckStatus( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_status); - if (current_status) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - - diagnostics.add("system_uptime", std::to_string(current_status->system_uptime.value())); - diagnostics.add("startup_times", std::to_string(current_status->startup_times.value())); - diagnostics.add("total_operation_time", std::to_string(current_status->total_operation_time.value())); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckPtp( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_status); - if (current_status) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - auto gps_status = current_status->get_str_gps_pps_lock(); - auto gprmc_status = current_status->get_str_gps_gprmc_status(); - auto ptp_status = current_status->get_str_ptp_clock_status(); - std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); - std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); - std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); - diagnostics.add("gps_pps_lock", gps_status); - diagnostics.add("gps_gprmc_status", gprmc_status); - diagnostics.add("ptp_clock_status", ptp_status); - if (gps_status != "UNKNOWN") { - msg.emplace_back("gps_pps_lock: " + gps_status); - } - if (gprmc_status != "UNKNOWN") { - msg.emplace_back("gprmc_status: " + gprmc_status); - } - if (ptp_status != "UNKNOWN") { - msg.emplace_back("ptp_status: " + ptp_status); - } - if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") { - level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - } - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckTemperature( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_status); - if (current_status) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - for (size_t i = 0; i < std::size(current_status->temperature); i++) { - diagnostics.add( - temperature_names[i], GetFixedPrecisionString(current_status->temperature[i].value() * 0.01)); - } - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckRpm( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_status); - if (current_status) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - diagnostics.add("motor_speed", std::to_string(current_status->motor_speed.value())); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckVoltageHttp( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_monitor); - if (current_lidar_monitor_tree) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - std::string key = ""; - - std::string mes; - key = "lidarInCur"; - try { - mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); - } catch (boost::bad_lexical_cast & ex) { - level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = error_message + std::string(ex.what()); - } - diagnostics.add(key, mes); - key = "lidarInVol"; - try { - mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); - } catch (boost::bad_lexical_cast & ex) { - level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = error_message + std::string(ex.what()); - } - diagnostics.add(key, mes); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiHwMonitorRosWrapper::HesaiCheckVoltage( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_monitor); - if (current_monitor) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - diagnostics.add( - "input_voltage", GetFixedPrecisionString(current_monitor->input_voltage.value() * 0.01) + " V"); - diagnostics.add( - "input_current", GetFixedPrecisionString(current_monitor->input_current.value() * 0.01) + " mA"); - diagnostics.add( - "input_power", GetFixedPrecisionString(current_monitor->input_power.value() * 0.01) + " W"); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - - HesaiHwMonitorRosWrapper::~HesaiHwMonitorRosWrapper() { - RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); - hw_interface_.FinalizeTcpDriver(); - } - - RCLCPP_COMPONENTS_REGISTER_NODE(HesaiHwMonitorRosWrapper) -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp new file mode 100644 index 000000000..4fc2a12df --- /dev/null +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -0,0 +1,1234 @@ +#include "nebula_ros/hesai/hesai_ros_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ +HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) +: rclcpp::Node("hesai_ros_wrapper", options), hw_interface_(), diagnostics_updater_(this) +{ + setvbuf(stdout, NULL, _IONBF, BUFSIZ); + + drivers::HesaiSensorConfiguration sensor_configuration; + wrapper_status_ = GetParameters(sensor_configuration); + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + + // hwiface +{ + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return; + } + std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_hw_ms_)); + hw_interface_.SetLogger(std::make_shared(this->get_logger())); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); +#if not defined(TEST_PCAP) + Status rt = hw_interface_.InitializeTcpDriver(); + if(this->retry_hw_) + { + int cnt = 0; + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); + while(rt == Status::ERROR_1) + { + cnt++; + std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000 + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); + rt = hw_interface_.InitializeTcpDriver(); + } + } + + if(rt != Status::ERROR_1){ + try{ + std::vector thread_pool{}; + thread_pool.emplace_back([this] { + auto result = hw_interface_.GetInventory(); + RCLCPP_INFO_STREAM(get_logger(), result); + hw_interface_.SetTargetModel(result.model); + }); + for (std::thread & th : thread_pool) { + th.join(); + } + + } + catch (...) + { + std::cout << "catch (...) in parent" << std::endl; + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); + } + if (this->setup_sensor) { + hw_interface_.CheckAndSetConfig(); + updateParameters(); + } + } + else + { + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); + hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); + } +#endif + + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveScanDataCallback, this, std::placeholders::_1)); + pandar_scan_pub_ = + this->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); + +#if not defined(TEST_PCAP) + if (this->setup_sensor) { + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); + } +#endif + + RCLCPP_DEBUG(this->get_logger(), "Starting stream"); + StreamStart(); +} + // decoder + { + drivers::HesaiCalibrationConfiguration calibration_configuration; + drivers::HesaiCorrection correction_configuration; + + wrapper_status_ = + GetCalibrationData(calibration_configuration, correction_configuration); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return; + } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + + calibration_cfg_ptr_ = + std::make_shared(calibration_configuration); + + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { + correction_cfg_ptr_ = std::make_shared(correction_configuration); + wrapper_status_ = InitializeCloudDriver( + std::static_pointer_cast(sensor_cfg_ptr_), + std::static_pointer_cast(calibration_cfg_ptr_), + std::static_pointer_cast(correction_cfg_ptr_)); + } else { + wrapper_status_ = InitializeCloudDriver( + std::static_pointer_cast(sensor_cfg_ptr_), + std::static_pointer_cast(calibration_cfg_ptr_)); + } + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); + rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; + auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), + qos_profile); + pandar_scan_sub_ = create_subscription( + "pandar_packets", qos, + std::bind(&HesaiRosWrapper::ReceiveScanMsgCallback, this, std::placeholders::_1)); + nebula_points_pub_ = + this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); + aw_points_base_pub_ = + this->create_publisher("aw_points", rclcpp::SensorDataQoS()); + aw_points_ex_pub_ = + this->create_publisher("aw_points_ex", rclcpp::SensorDataQoS()); +} + +//hwmon +{ +cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); + cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return; + } + std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_monitor_ms_)); + + message_sep = ": "; + not_supported_message = "Not supported"; + error_message = "Error"; + + switch (sensor_cfg_ptr_->sensor_model) { + case nebula::drivers::SensorModel::HESAI_PANDARXT32: + case nebula::drivers::SensorModel::HESAI_PANDARXT32M: + case nebula::drivers::SensorModel::HESAI_PANDARAT128: + temperature_names.emplace_back("Bottom circuit board T1"); + temperature_names.emplace_back("Bottom circuit board T2"); + temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names.emplace_back("Laser emitting board RT_L2"); + temperature_names.emplace_back("Receiving board RT_R"); + temperature_names.emplace_back("Receiving board RT2"); + temperature_names.emplace_back("Top circuit RT3"); + temperature_names.emplace_back("Not used"); + break; + case nebula::drivers::SensorModel::HESAI_PANDAR64: + case nebula::drivers::SensorModel::HESAI_PANDAR40P: + case nebula::drivers::SensorModel::HESAI_PANDAR40M: + case nebula::drivers::SensorModel::HESAI_PANDARQT64: + case nebula::drivers::SensorModel::HESAI_PANDARQT128: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: + default: + temperature_names.emplace_back("Bottom circuit RT1"); + temperature_names.emplace_back("Bottom circuit RT2"); + temperature_names.emplace_back("Internal Temperature"); + temperature_names.emplace_back("Laser emitting board RT1"); + temperature_names.emplace_back("Laser emitting board RT2"); + temperature_names.emplace_back("Receiving board RT1"); + temperature_names.emplace_back("Top circuit RT1"); + temperature_names.emplace_back("Top circuit RT2"); + break; + } + + std::vector thread_pool{}; + thread_pool.emplace_back([this] { + auto result = hw_interface_.GetInventory(); + current_inventory.reset(new HesaiInventory(result)); + current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); + RCLCPP_INFO_STREAM(this->get_logger(), "HesaiInventory"); + RCLCPP_INFO_STREAM(this->get_logger(), result); + info_model = result.get_str_model(); + info_serial = std::string(result.sn.begin(), result.sn.end()); + hw_interface_.SetTargetModel(result.model); + RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); + RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); + InitializeHesaiDiagnostics(); + }); + for (std::thread & th : thread_pool) { + th.join(); + } + + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); +} +} + +void HesaiRosWrapper::ReceiveScanMsgCallback( + const pandar_msgs::msg::PandarScan::SharedPtr scan_msg) +{ + auto t_start = std::chrono::high_resolution_clock::now(); + std::tuple pointcloud_ts = + driver_ptr_->ConvertScanToPointcloud(scan_msg); + nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + + if (pointcloud == nullptr) { + RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); + return; + }; + if ( + nebula_points_pub_->get_subscription_count() > 0 || + nebula_points_pub_->get_intra_process_subscription_count() > 0) { + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); + } + if ( + aw_points_base_pub_->get_subscription_count() > 0 || + aw_points_base_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_cloud_xyzi = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); + } + if ( + aw_points_ex_pub_->get_subscription_count() > 0 || + aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_ex_cloud = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); + } + + auto runtime = std::chrono::high_resolution_clock::now() - t_start; + RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); +} + +void HesaiRosWrapper::PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher) +{ + if (pointcloud->header.stamp.sec < 0) { + RCLCPP_WARN_STREAM(this->get_logger(), "Timestamp error, verify clock source."); + } + pointcloud->header.frame_id = sensor_cfg_ptr_->frame_id; + publisher->publish(std::move(pointcloud)); +} + +Status HesaiRosWrapper::InitializeCloudDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) +{ + driver_ptr_ = std::make_shared( + std::static_pointer_cast(sensor_configuration), + std::static_pointer_cast(calibration_configuration)); + return driver_ptr_->GetStatus(); +} + +Status HesaiRosWrapper::InitializeCloudDriver( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration, + const std::shared_ptr & correction_configuration) +{ + // driver should be initialized here with proper decoder + driver_ptr_ = std::make_shared( + std::static_pointer_cast(sensor_configuration), + std::static_pointer_cast(calibration_configuration), + std::static_pointer_cast(correction_configuration)); + return driver_ptr_->GetStatus(); +} + +Status HesaiRosWrapper::GetStatus() { return wrapper_status_; } + +/// decoder +Status HesaiRosWrapper::GetParameters( + drivers::HesaiSensorConfiguration & sensor_configuration) +{ + /////////////////////////////////////////////// + // Define and get ROS parameters + /////////////////////////////////////////////// + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_model", ""); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("return_mode", "", descriptor); + sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( + this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("host_ip", "255.255.255.255", descriptor); + sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); + sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("data_port", 2368, descriptor); + sensor_configuration.data_port = this->get_parameter("data_port").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("gnss_port", 2369, descriptor); + sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("frame_id", "pandar", descriptor); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; + rcl_interfaces::msg::FloatingPointRange range; + range.set__from_value(0).set__to_value(360).set__step(0.01); + descriptor.floating_point_range = {range}; + this->declare_parameter("scan_phase", 0., descriptor); + sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("calibration_file", "", descriptor); + calibration_file_path = + this->get_parameter("calibration_file").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("min_range", 0.3, descriptor); + sensor_configuration.min_range = this->get_parameter("min_range").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("max_range", 300., descriptor); + sensor_configuration.max_range = this->get_parameter("max_range").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("packet_mtu_size", 1500, descriptor); + sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); + } + + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + rcl_interfaces::msg::IntegerRange range; + RCLCPP_DEBUG_STREAM(get_logger(), sensor_configuration.sensor_model); + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { + descriptor.additional_constraints = "200, 300, 400, 500"; + // range.set__from_value(200).set__to_value(500).set__step(100); + // descriptor.integer_range = {range}; //todo + this->declare_parameter("rotation_speed", 200, descriptor); + } else { + descriptor.additional_constraints = "300, 600, 1200"; + // range.set__from_value(300).set__to_value(1200).set__step(300); + // descriptor.integer_range = {range}; //todo + this->declare_parameter("rotation_speed", 600, descriptor); + } + sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + rcl_interfaces::msg::IntegerRange range; + range.set__from_value(0).set__to_value(360).set__step(1); + descriptor.integer_range = {range}; + this->declare_parameter("cloud_min_angle", 0, descriptor); + sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + rcl_interfaces::msg::IntegerRange range; + range.set__from_value(0).set__to_value(360).set__step(1); + descriptor.integer_range = {range}; + this->declare_parameter("cloud_max_angle", 360, descriptor); + sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); + } + if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("correction_file", "", descriptor); + correction_file_path = this->get_parameter("correction_file").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; + rcl_interfaces::msg::FloatingPointRange range; + range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); + descriptor.floating_point_range = {range}; + this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); + sensor_configuration.dual_return_distance_threshold = + this->get_parameter("dual_return_distance_threshold").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("launch_hw", "", descriptor); + launch_hw_ = this->get_parameter("launch_hw").as_bool(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("setup_sensor", true, descriptor); + this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); + } + + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + this->declare_parameter("delay_hw_ms", 0, descriptor); + this->delay_hw_ms_ = this->get_parameter("delay_hw_ms").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("retry_hw", true, descriptor); + this->retry_hw_ = this->get_parameter("retry_hw").as_bool(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("ptp_profile", ""); + sensor_configuration.ptp_profile = + nebula::drivers::PtpProfileFromString(this->get_parameter("ptp_profile").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("ptp_transport_type", ""); + sensor_configuration.ptp_transport_type = + nebula::drivers::PtpTransportTypeFromString(this->get_parameter("ptp_transport_type").as_string()); + if(static_cast(sensor_configuration.ptp_profile) > 0) { + sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; + } + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("ptp_switch_type", ""); + sensor_configuration.ptp_switch_type = + nebula::drivers::PtpSwitchTypeFromString(this->get_parameter("ptp_switch_type").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + rcl_interfaces::msg::IntegerRange range; + range.set__from_value(0).set__to_value(127).set__step(1); + descriptor.integer_range = {range}; + this->declare_parameter("ptp_domain", 0, descriptor); + sensor_configuration.ptp_domain = this->get_parameter("ptp_domain").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + this->declare_parameter("diag_span", 1000, descriptor); + this->diag_span_ = this->get_parameter("diag_span").as_int(); + } + + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + this->declare_parameter("delay_monitor_ms", 0, descriptor); + this->delay_monitor_ms_ = this->get_parameter("delay_monitor_ms").as_int(); + } + + /////////////////////////////////////////////// + // Validate ROS parameters + /////////////////////////////////////////////// + + if(sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { + RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); + return Status::SENSOR_CONFIG_ERROR; + } + if(sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { + RCLCPP_ERROR_STREAM(get_logger(), + "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when using the '1588v2' PTP Profile"); + return Status::SENSOR_CONFIG_ERROR; + } + if(sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { + RCLCPP_ERROR_STREAM(get_logger(), + "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); + return Status::SENSOR_CONFIG_ERROR; + } + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + return Status::INVALID_SENSOR_MODEL; + } + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + return Status::INVALID_ECHO_MODE; + } + if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { + return Status::SENSOR_CONFIG_ERROR; + } + + /////////////////////////////////////////////// + // Decoder-specific setup + /////////////////////////////////////////////// + + std::shared_ptr sensor_cfg_ptr = + std::make_shared(sensor_configuration); + + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr)); + + /////////////////////////////////////////////// + // HW Interface specific setup + /////////////////////////////////////////////// + + /////////////////////////////////////////////// + // HW Monitor specific setup + /////////////////////////////////////////////// + + RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + return Status::OK; +} + +Status HesaiRosWrapper::GetCalibrationData( + drivers::HesaiCalibrationConfiguration & calibration_configuration, + drivers::HesaiCorrection & correction_configuration) { + calibration_configuration.calibration_file = calibration_file_path; //todo + + bool run_local = !launch_hw_; + if (sensor_cfg_ptr_->sensor_model != drivers::SensorModel::HESAI_PANDARAT128) { + std::string calibration_file_path_from_sensor; + if (launch_hw_ && !calibration_configuration.calibration_file.empty()) { + int ext_pos = calibration_configuration.calibration_file.find_last_of('.'); + calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(0, ext_pos); + calibration_file_path_from_sensor += "_from_sensor"; + calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(ext_pos, calibration_configuration.calibration_file.size() - ext_pos); + } + if(launch_hw_) { + run_local = false; + RCLCPP_INFO_STREAM( + this->get_logger(), "Trying to acquire calibration data from sensor: '" + << sensor_cfg_ptr_->sensor_ip << "'"); + std::future future = std::async(std::launch::async, + [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { + auto str = hw_interface_.GetLidarCalibrationString(); + auto rt = calibration_configuration.SaveFileFromString( + calibration_file_path_from_sensor, str); + RCLCPP_ERROR_STREAM(get_logger(), str); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromString success:" + << calibration_file_path_from_sensor << "\n"); + } else { + RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromString failed:" + << calibration_file_path_from_sensor << "\n"); + } + rt = calibration_configuration.LoadFromString(str); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM(get_logger(), + "LoadFromString success:" << str << "\n"); + } else { + RCLCPP_ERROR_STREAM(get_logger(), + "LoadFromString failed:" << str << "\n"); + } + }); + std::future_status status; + status = future.wait_for(std::chrono::milliseconds(5000)); + if (status == std::future_status::timeout) { + std::cerr << "# std::future_status::timeout\n"; + RCLCPP_ERROR_STREAM(get_logger(), "GetCalibration Timeout"); + run_local = true; + } else if (status == std::future_status::ready && !run_local) { + RCLCPP_INFO_STREAM( + this->get_logger(), "Acquired calibration data from sensor: '" + << sensor_cfg_ptr_->sensor_ip << "'"); + RCLCPP_INFO_STREAM( + this->get_logger(), "The calibration has been saved in '" + << calibration_file_path_from_sensor << "'"); + } + } + if(run_local) { + RCLCPP_WARN_STREAM(get_logger(), "Running locally"); + bool run_org = false; + if (calibration_file_path_from_sensor.empty()) { + run_org = true; + } else { + RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_file_path_from_sensor); + auto cal_status = + calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); + + if (cal_status != Status::OK) { + run_org = true; + }else{ + RCLCPP_INFO_STREAM( + this->get_logger(), "Load calibration data from: '" + << calibration_file_path_from_sensor << "'"); + } + } + if(run_org) { + RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_configuration.calibration_file); + if (calibration_configuration.calibration_file.empty()) { + RCLCPP_ERROR_STREAM( + this->get_logger(), "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); + return Status::INVALID_CALIBRATION_FILE; + } else { + auto cal_status = + calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); + + if (cal_status != Status::OK) { + RCLCPP_ERROR_STREAM( + this->get_logger(), + "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); + return cal_status; + }else{ + RCLCPP_INFO_STREAM( + this->get_logger(), "Load calibration data from: '" + << calibration_configuration.calibration_file << "'"); + } + } + } + } + } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 + std::string correction_file_path_from_sensor; + if (launch_hw_ && !correction_file_path.empty()) { + int ext_pos = correction_file_path.find_last_of('.'); + correction_file_path_from_sensor += correction_file_path.substr(0, ext_pos); + correction_file_path_from_sensor += "_from_sensor"; + correction_file_path_from_sensor += correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); + } + std::future future = std::async(std::launch::async, [this, &correction_configuration, &correction_file_path_from_sensor, &run_local]() { + if (launch_hw_) { + RCLCPP_INFO_STREAM( + this->get_logger(), "Trying to acquire calibration data from sensor"); + auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); + RCLCPP_INFO_STREAM(get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); + auto rt = correction_configuration.SaveFileFromBinary(correction_file_path_from_sensor, received_bytes); + if(rt == Status::OK) + { + RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); + } + else + { + RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromBinary failed:" << correction_file_path_from_sensor << ". Falling back to offline calibration file."); + run_local = true; + } + rt = correction_configuration.LoadFromBinary(received_bytes); + if(rt == Status::OK) + { + RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); + run_local = false; + } + else + { + RCLCPP_ERROR_STREAM(get_logger(), "LoadFromBinary failed" << ". Falling back to offline calibration file."); + run_local = true; + } + }else{ + RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); + run_local = true; + } + }); + if (!run_local) { + std::future_status status; + status = future.wait_for(std::chrono::milliseconds(8000)); + if (status == std::future_status::timeout) { + std::cerr << "# std::future_status::timeout\n"; + run_local = true; + } else if (status == std::future_status::ready && !run_local) { + RCLCPP_INFO_STREAM( + this->get_logger(), "Acquired correction data from sensor: '" + << sensor_cfg_ptr_->sensor_ip << "'"); + RCLCPP_INFO_STREAM( + this->get_logger(), "The correction has been saved in '" + << correction_file_path_from_sensor << "'"); + } + } + if(run_local) { + bool run_org = false; + if (correction_file_path_from_sensor.empty()) { + run_org = true; + } else { + auto cal_status = + correction_configuration.LoadFromFile(correction_file_path_from_sensor); + + if (cal_status != Status::OK) { + run_org = true; + }else{ + RCLCPP_INFO_STREAM( + this->get_logger(), "Load correction data from: '" + << correction_file_path_from_sensor << "'"); + } + } + if(run_org) { + if (correction_file_path.empty()) { + RCLCPP_ERROR_STREAM( + this->get_logger(), "Empty Correction File: '" << correction_file_path << "'"); + return Status::INVALID_CALIBRATION_FILE; + } else { + auto cal_status = correction_configuration.LoadFromFile(correction_file_path); + + if (cal_status != Status::OK) { + RCLCPP_ERROR_STREAM( + this->get_logger(), "Given Correction File: '" << correction_file_path << "'"); + return cal_status; + }else{ + RCLCPP_INFO_STREAM( + this->get_logger(), "Load correction data from: '" + << correction_file_path << "'"); + } + } + } + } + } // end AT128 + + return Status::OK; + } + +HesaiRosWrapper::~HesaiRosWrapper() { + RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); + hw_interface_.FinalizeTcpDriver(); +} + +Status HesaiRosWrapper::StreamStart() +{ + if (Status::OK == interface_status_) { + interface_status_ = hw_interface_.CloudInterfaceStart(); + } + return interface_status_; +} + +Status HesaiRosWrapper::StreamStop() { return Status::OK; } +Status HesaiRosWrapper::Shutdown() { return Status::OK; } + +Status HesaiRosWrapper::InitializeHwInterface( // todo: don't think this is needed + const drivers::SensorConfigurationBase & sensor_configuration) +{ + std::stringstream ss; + ss << sensor_configuration; + RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); + return Status::OK; +} + +Status HesaiRosWrapper::InitializeHwMonitor( // todo: don't think this is needed + const drivers::SensorConfigurationBase & sensor_configuration) +{ + return Status::OK; +} + +void HesaiRosWrapper::ReceiveScanDataCallback( + std::unique_ptr scan_buffer) +{ + // Publish + scan_buffer->header.frame_id = sensor_cfg_ptr_->frame_id; + scan_buffer->header.stamp = scan_buffer->packets.front().stamp; + pandar_scan_pub_->publish(std::move(scan_buffer)); +} + +rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( + const std::vector & p) +{ + std::scoped_lock lock(mtx_config_); + RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback"); + RCLCPP_DEBUG_STREAM(this->get_logger(), p); + RCLCPP_DEBUG_STREAM(this->get_logger(), *sensor_cfg_ptr_); + RCLCPP_INFO_STREAM(this->get_logger(), p); + + std::shared_ptr new_param = + std::make_shared(*sensor_cfg_ptr_); + RCLCPP_INFO_STREAM(this->get_logger(), new_param); + std::string sensor_model_str; + std::string return_mode_str; + if ( + get_param(p, "sensor_model", sensor_model_str) | + get_param(p, "return_mode", return_mode_str) | + get_param(p, "host_ip", new_param->host_ip) | + get_param(p, "sensor_ip", new_param->sensor_ip) | + get_param(p, "frame_id", new_param->frame_id) | + get_param(p, "data_port", new_param->data_port) | + get_param(p, "gnss_port", new_param->gnss_port) | + get_param(p, "scan_phase", new_param->scan_phase) | + get_param(p, "packet_mtu_size", new_param->packet_mtu_size) | + get_param(p, "rotation_speed", new_param->rotation_speed) | + get_param(p, "cloud_min_angle", new_param->cloud_min_angle) | + get_param(p, "cloud_max_angle", new_param->cloud_max_angle) | + get_param(p, "dual_return_distance_threshold", new_param->dual_return_distance_threshold)) { + if (0 < sensor_model_str.length()) + new_param->sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); + if (0 < return_mode_str.length()) + new_param->return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); + + sensor_cfg_ptr_.swap(new_param); + RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); + RCLCPP_DEBUG_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); + hw_interface_.CheckAndSetConfig(); + } + + auto result = std::make_shared(); + result->successful = true; + result->reason = "success"; + + RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback success"); + + return *result; +} + +std::vector HesaiRosWrapper::updateParameters() +{ + std::scoped_lock lock(mtx_config_); + RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters start"); + std::ostringstream os_sensor_model; + os_sensor_model << sensor_cfg_ptr_->sensor_model; + std::ostringstream os_return_mode; + os_return_mode << sensor_cfg_ptr_->return_mode; + RCLCPP_INFO_STREAM(this->get_logger(), "set_parameters"); + auto results = set_parameters( + {rclcpp::Parameter("sensor_model", os_sensor_model.str()), + rclcpp::Parameter("return_mode", os_return_mode.str()), + rclcpp::Parameter("host_ip", sensor_cfg_ptr_->host_ip), + rclcpp::Parameter("sensor_ip", sensor_cfg_ptr_->sensor_ip), + rclcpp::Parameter("frame_id", sensor_cfg_ptr_->frame_id), + rclcpp::Parameter("data_port", sensor_cfg_ptr_->data_port), + rclcpp::Parameter("gnss_port", sensor_cfg_ptr_->gnss_port), + rclcpp::Parameter("scan_phase", sensor_cfg_ptr_->scan_phase), + rclcpp::Parameter("packet_mtu_size", sensor_cfg_ptr_->packet_mtu_size), + rclcpp::Parameter("rotation_speed", sensor_cfg_ptr_->rotation_speed), + rclcpp::Parameter("cloud_min_angle", sensor_cfg_ptr_->cloud_min_angle), + rclcpp::Parameter("cloud_max_angle", sensor_cfg_ptr_->cloud_max_angle), + rclcpp::Parameter( + "dual_return_distance_threshold", sensor_cfg_ptr_->dual_return_distance_threshold)}); + RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters end"); + return results; +} + +void HesaiRosWrapper::InitializeHesaiDiagnostics() +{ + RCLCPP_INFO_STREAM(this->get_logger(), "InitializeHesaiDiagnostics"); + using std::chrono_literals::operator""s; + std::ostringstream os; + auto hardware_id = info_model + ": " + info_serial; + diagnostics_updater_.setHardwareID(hardware_id); + RCLCPP_INFO_STREAM(this->get_logger(), "hardware_id: " + hardware_id); + + diagnostics_updater_.add("hesai_status", this, &HesaiRosWrapper::HesaiCheckStatus); + diagnostics_updater_.add("hesai_ptp", this, &HesaiRosWrapper::HesaiCheckPtp); + diagnostics_updater_.add( + "hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); + diagnostics_updater_.add("hesai_rpm", this, &HesaiRosWrapper::HesaiCheckRpm); + + current_status.reset(); + current_monitor.reset(); + current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + + auto fetch_diag_from_sensor = [this](){ + OnHesaiStatusTimer(); + if (hw_interface_.UseHttpGetLidarMonitor()) { + OnHesaiLidarMonitorTimerHttp(); + } else { + OnHesaiLidarMonitorTimer(); + } + }; + + fetch_diagnostics_timer_ = std::make_shared>( + this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); + + if (hw_interface_.UseHttpGetLidarMonitor()) { + diagnostics_updater_.add( + "hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); + } else { + diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltage); + } + + auto on_timer_update = [this] { + RCLCPP_DEBUG_STREAM(get_logger(), "OnUpdateTimer"); + auto now = this->get_clock()->now(); + auto dif = (now - *current_status_time).seconds(); + + RCLCPP_DEBUG_STREAM(get_logger(), "dif(status): " << dif); + + if (diag_span_ * 2.0 < dif * 1000) { + current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); + } else { + current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(get_logger(), "OK"); + } + dif = (now - *current_lidar_monitor_time).seconds(); + RCLCPP_DEBUG_STREAM(get_logger(), "dif(monitor): " << dif); + if (diag_span_ * 2.0 < dif * 1000) { + current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); + } else { + current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(get_logger(), "OK"); + } + diagnostics_updater_.force_update(); + }; + diagnostics_update_timer_ = std::make_shared>( + this->get_clock(), std::chrono::milliseconds(1000), std::move(on_timer_update), + this->get_node_base_interface()->get_context()); + this->get_node_timers_interface()->add_timer(diagnostics_update_timer_, cbg_r_); + + RCLCPP_DEBUG_STREAM(get_logger(), "add_timer"); +} + +std::string HesaiRosWrapper::GetPtreeValue( + boost::property_tree::ptree * pt, const std::string & key) +{ + boost::optional value = pt->get_optional(key); + if (value) { + return value.get(); + } else { + return not_supported_message; + } +} +std::string HesaiRosWrapper::GetFixedPrecisionString(double val, int pre) +{ + std::stringstream ss; + ss << std::fixed << std::setprecision(pre) << val; + return ss.str(); +} + +void HesaiRosWrapper::OnHesaiStatusTimer() +{ + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer" << std::endl); + try { + auto result = hw_interface_.GetLidarStatus(); + std::scoped_lock lock(mtx_status); + current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_status.reset(new HesaiLidarStatus(result)); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl); +} + +void HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp() +{ + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp"); + try { + hw_interface_.GetLidarMonitorAsyncHttp([this](const std::string & str) { + std::scoped_lock lock(mtx_lidar_monitor); + current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_lidar_monitor_tree = + std::make_unique(hw_interface_.ParseJson(str)); + }); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp END"); +} + +void HesaiRosWrapper::OnHesaiLidarMonitorTimer() +{ + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer"); + try { + auto ios = std::make_shared(); + auto result = hw_interface_.GetLidarMonitor(); + std::scoped_lock lock(mtx_lidar_monitor); + current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); + current_monitor.reset(new HesaiLidarMonitor(result)); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END"); +} + +void HesaiRosWrapper::HesaiCheckStatus( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_status); + if (current_status) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + + diagnostics.add("system_uptime", std::to_string(current_status->system_uptime)); + diagnostics.add("startup_times", std::to_string(current_status->startup_times)); + diagnostics.add("total_operation_time", std::to_string(current_status->total_operation_time)); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckPtp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_status); + if (current_status) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + auto gps_status = current_status->get_str_gps_pps_lock(); + auto gprmc_status = current_status->get_str_gps_gprmc_status(); + auto ptp_status = current_status->get_str_ptp_clock_status(); + std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); + std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); + std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); + diagnostics.add("gps_pps_lock", gps_status); + diagnostics.add("gps_gprmc_status", gprmc_status); + diagnostics.add("ptp_clock_status", ptp_status); + if (gps_status != "UNKNOWN") { + msg.emplace_back("gps_pps_lock: " + gps_status); + } + if (gprmc_status != "UNKNOWN") { + msg.emplace_back("gprmc_status: " + gprmc_status); + } + if (ptp_status != "UNKNOWN") { + msg.emplace_back("ptp_status: " + ptp_status); + } + if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") { + level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + } + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckTemperature( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_status); + if (current_status) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + for (size_t i = 0; i < current_status->temperature.size(); i++) { + diagnostics.add( + temperature_names[i], GetFixedPrecisionString(current_status->temperature[i] * 0.01)); + } + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckRpm( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_status); + if (current_status) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + diagnostics.add("motor_speed", std::to_string(current_status->motor_speed)); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckVoltageHttp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_lidar_monitor); + if (current_lidar_monitor_tree) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + std::string key = ""; + + std::string mes; + key = "lidarInCur"; + try { + mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); + } catch (boost::bad_lexical_cast & ex) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = error_message + std::string(ex.what()); + } + diagnostics.add(key, mes); + key = "lidarInVol"; + try { + mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); + } catch (boost::bad_lexical_cast & ex) { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = error_message + std::string(ex.what()); + } + diagnostics.add(key, mes); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiRosWrapper::HesaiCheckVoltage( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +{ + std::scoped_lock lock(mtx_lidar_monitor); + if (current_monitor) { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + diagnostics.add( + "input_voltage", GetFixedPrecisionString(current_monitor->input_voltage * 0.01) + " V"); + diagnostics.add( + "input_current", GetFixedPrecisionString(current_monitor->input_current * 0.01) + " mA"); + diagnostics.add( + "input_power", GetFixedPrecisionString(current_monitor->input_power * 0.01) + " W"); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } else { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + + RCLCPP_COMPONENTS_REGISTER_NODE(HesaiRosWrapper) +} // namespace ros +} // namespace nebula From 6baee804fa35f3325f69d0bdb710d597a20e7bac Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Thu, 21 Mar 2024 18:34:02 +0900 Subject: [PATCH 068/122] refactor: remove pandarScan pub/sub, decode one packet at a time --- .../decoders/hesai_decoder.hpp | 14 +++--- .../decoders/hesai_scan_decoder.hpp | 4 +- .../nebula_decoders_hesai/hesai_driver.hpp | 4 +- .../nebula_decoders_hesai/hesai_driver.cpp | 25 +++++----- .../hesai_hw_interface.hpp | 6 +-- .../hesai_hw_interface.cpp | 48 ++----------------- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 6 +-- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 29 +++++------ 8 files changed, 41 insertions(+), 95 deletions(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index b81b45d44..8f28856e8 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -52,17 +52,17 @@ class HesaiDecoder : public HesaiScanDecoder block_firing_offset_ns_; /// @brief Validates and parse PandarPacket. Currently only checks size, not checksums etc. - /// @param pandar_packet The incoming PandarPacket + /// @param packet The incoming PandarPacket /// @return Whether the packet was parsed successfully - bool parsePacket(const pandar_msgs::msg::PandarPacket & pandar_packet) + bool parsePacket(const std::vector & packet) { - if (pandar_packet.size < sizeof(typename SensorT::packet_t)) { + if (packet.size() < sizeof(typename SensorT::packet_t)) { RCLCPP_ERROR_STREAM( - logger_, "Packet size mismatch:" << pandar_packet.size << " | Expected at least:" + logger_, "Packet size mismatch:" << packet.size() << " | Expected at least:" << sizeof(typename SensorT::packet_t)); return false; } - if (std::memcpy(&packet_, pandar_packet.data.data(), sizeof(typename SensorT::packet_t))) { + if (std::memcpy(&packet_, packet.data(), sizeof(typename SensorT::packet_t))) { // FIXME(mojomex) do validation? // RCLCPP_DEBUG(logger_, "Packet parsed successfully"); return true; @@ -222,9 +222,9 @@ class HesaiDecoder : public HesaiScanDecoder output_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); } - int unpack(const pandar_msgs::msg::PandarPacket & pandar_packet) override + int unpack(const std::vector & packet) override { - if (!parsePacket(pandar_packet)) { + if (!parsePacket(packet)) { return -1; } diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp index f0b4e3f8b..9d06c2702 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp @@ -26,9 +26,9 @@ class HesaiScanDecoder HesaiScanDecoder() = default; /// @brief Parses PandarPacket and add its points to the point cloud - /// @param pandar_packet The incoming PandarPacket + /// @param packet The incoming PandarPacket /// @return The last azimuth processed - virtual int unpack(const pandar_msgs::msg::PandarPacket & pandar_packet) = 0; + virtual int unpack(const std::vector & packet) = 0; /// @brief Indicates whether one full scan is ready /// @return Whether a scan is ready diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index c83788965..a3f37cd32 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -54,8 +54,8 @@ class HesaiDriver : NebulaDriverBase /// @brief Convert PandarScan message to point cloud /// @param pandar_scan Message /// @return tuple of Point cloud and timestamp - std::tuple ConvertScanToPointcloud( - const std::shared_ptr & pandar_scan); + std::tuple ParseCloudPacket( + const std::vector & packet); }; } // namespace drivers diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index 49be4adac..61b969ed7 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -72,8 +72,8 @@ HesaiDriver::HesaiDriver( } } -std::tuple HesaiDriver::ConvertScanToPointcloud( - const std::shared_ptr & pandar_scan) +std::tuple HesaiDriver::ParseCloudPacket( + const std::vector & packet) { std::tuple pointcloud; auto logger = rclcpp::get_logger("HesaiDriver"); @@ -83,20 +83,17 @@ std::tuple HesaiDriver::ConvertScanToPoint return pointcloud; } - int cnt = 0, last_azimuth = 0; - for (auto & packet : pandar_scan->packets) { - last_azimuth = scan_decoder_->unpack(packet); - if (scan_decoder_->hasScanned()) { - pointcloud = scan_decoder_->getPointcloud(); - cnt++; - } + scan_decoder_->unpack(packet); + if (scan_decoder_->hasScanned()) { + pointcloud = scan_decoder_->getPointcloud(); } - if (cnt == 0) { - RCLCPP_ERROR_STREAM( - logger, "Scanned " << pandar_scan->packets.size() << " packets, but no " - << "pointclouds were generated. Last azimuth: " << last_azimuth); - } + // todo + // if (cnt == 0) { + // RCLCPP_ERROR_STREAM( + // logger, "Scanned " << pandar_scan->packets.size() << " packets, but no " + // << "pointclouds were generated. Last azimuth: " << last_azimuth); + // } return pointcloud; } diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index 1b21ddae2..34c5208ee 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -127,8 +127,8 @@ class HesaiHwInterface : NebulaHwInterfaceBase std::unique_ptr scan_cloud_ptr_; std::function is_valid_packet_; /*Lambda Function Array to verify proper packet size*/ - std::function buffer)> - scan_reception_callback_; /**This function pointer is called when the scan is complete*/ + std::function & buffer)> + cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ int prev_phase_{}; @@ -222,7 +222,7 @@ class HesaiHwInterface : NebulaHwInterfaceBase /// @param scan_callback Callback function /// @return Resulting status Status RegisterScanCallback( - std::function)> scan_callback); + std::function &)> scan_callback); /// @brief Getting data with PTC_COMMAND_GET_LIDAR_CALIBRATION /// @return Resulting status std::string GetLidarCalibrationString(); diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index fccb2a622..4fbb020b0 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -239,61 +239,19 @@ Status HesaiHwInterface::SensorInterfaceStart() } Status HesaiHwInterface::RegisterScanCallback( - std::function)> scan_callback) + std::function &)> scan_callback) { - scan_reception_callback_ = std::move(scan_callback); + cloud_packet_callback_ = std::move(scan_callback); return Status::OK; } void HesaiHwInterface::ReceiveSensorPacketCallback(const std::vector & buffer) { - int scan_phase = static_cast(sensor_configuration_->scan_phase * 100.0); if (!is_valid_packet_(buffer.size())) { PrintDebug("Invalid Packet: " + std::to_string(buffer.size())); return; } - const uint32_t buffer_size = buffer.size(); - pandar_msgs::msg::PandarPacket pandar_packet; - std::copy_n(std::make_move_iterator(buffer.begin()), buffer_size, pandar_packet.data.begin()); - pandar_packet.size = buffer_size; - auto now = std::chrono::system_clock::now(); - auto now_secs = std::chrono::duration_cast(now.time_since_epoch()).count(); - auto now_nanosecs = - std::chrono::duration_cast(now.time_since_epoch()).count(); - pandar_packet.stamp.sec = static_cast(now_secs); - pandar_packet.stamp.nanosec = static_cast(now_nanosecs % 1'000'000'000); - scan_cloud_ptr_->packets.emplace_back(pandar_packet); - - int current_phase = 0; - bool comp_flg = false; - - const auto & data = scan_cloud_ptr_->packets.back().data; - current_phase = (data[azimuth_index_] & 0xff) + ((data[azimuth_index_ + 1] & 0xff) << 8); - if (is_solid_state) { - current_phase = (static_cast(current_phase) + 36000 - 0) % 12000; - if (current_phase >= prev_phase_ || scan_cloud_ptr_->packets.size() < 2) { - prev_phase_ = current_phase; - } else { - comp_flg = true; - } - } else { - current_phase = (static_cast(current_phase) + 36000 - scan_phase) % 36000; - - if (current_phase >= prev_phase_ || scan_cloud_ptr_->packets.size() < 2) { - prev_phase_ = current_phase; - } else { - comp_flg = true; - } - } - - if (comp_flg) { // Scan complete - if (scan_reception_callback_) { - scan_cloud_ptr_->header.stamp = scan_cloud_ptr_->packets.front().stamp; - // Callback - scan_reception_callback_(std::move(scan_cloud_ptr_)); - scan_cloud_ptr_ = std::make_unique(); - } - } + cloud_packet_callback_(buffer); } Status HesaiHwInterface::SensorInterfaceStop() { diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 283f63c68..e3b1cc8e8 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -58,10 +58,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); ~HesaiRosWrapper(); - /// @brief Callback for PandarScan subscriber - /// @param scan_msg Received PandarScan - void ReceiveScanMsgCallback(const pandar_msgs::msg::PandarScan::SharedPtr scan_msg); - /// @brief Get current status of this driver /// @return Current status Status GetStatus(); @@ -134,7 +130,7 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase const drivers::SensorConfigurationBase & sensor_configuration) override; /// @brief Callback for receiving PandarScan /// @param scan_buffer Received PandarScan - void ReceiveScanDataCallback(std::unique_ptr scan_buffer); + void ReceiveCloudPacketCallback(const std::vector & scan_buffer); /// @brief rclcpp parameter callback /// @param parameters Received parameters diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 4fc2a12df..b809bccf8 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -69,7 +69,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) #endif hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveScanDataCallback, this, std::placeholders::_1)); + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); pandar_scan_pub_ = this->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); @@ -117,9 +117,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - pandar_scan_sub_ = create_subscription( - "pandar_packets", qos, - std::bind(&HesaiRosWrapper::ReceiveScanMsgCallback, this, std::placeholders::_1)); + nebula_points_pub_ = this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); aw_points_base_pub_ = @@ -198,16 +196,22 @@ cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); } } -void HesaiRosWrapper::ReceiveScanMsgCallback( - const pandar_msgs::msg::PandarScan::SharedPtr scan_msg) +void HesaiRosWrapper::ReceiveCloudPacketCallback( + const std::vector & packet) { + // Driver is not initialized yet + if (!driver_ptr_) { + return; + } + auto t_start = std::chrono::high_resolution_clock::now(); std::tuple pointcloud_ts = - driver_ptr_->ConvertScanToPointcloud(scan_msg); + driver_ptr_->ParseCloudPacket(packet); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); if (pointcloud == nullptr) { - RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); + // todo + // RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); return; }; if ( @@ -845,15 +849,6 @@ Status HesaiRosWrapper::InitializeHwMonitor( // todo: don't think this is neede return Status::OK; } -void HesaiRosWrapper::ReceiveScanDataCallback( - std::unique_ptr scan_buffer) -{ - // Publish - scan_buffer->header.frame_id = sensor_cfg_ptr_->frame_id; - scan_buffer->header.stamp = scan_buffer->packets.front().stamp; - pandar_scan_pub_->publish(std::move(scan_buffer)); -} - rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( const std::vector & p) { From cbd15d32d4921f3aceadaf08fcc0d51d121d90d3 Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Tue, 26 Mar 2024 16:31:25 +0900 Subject: [PATCH 069/122] reword later --- nebula_ros/CMakeLists.txt | 1 + .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 28 +- nebula_ros/launch/hesai_launch_all_hw.xml | 4 - nebula_ros/package.xml | 1 + nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 557 +++++++++--------- scripts/plot_times.py | 7 +- 6 files changed, 309 insertions(+), 289 deletions(-) diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index 18ce06aad..1bd697624 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -23,6 +23,7 @@ find_package(nebula_decoders REQUIRED) find_package(nebula_hw_interfaces REQUIRED) find_package(yaml-cpp REQUIRED) find_package(robosense_msgs REQUIRED) +find_package(nebula_msgs REQUIRED) include_directories( include diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index e3b1cc8e8..e91d7fcaf 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -15,8 +15,7 @@ #include #include -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" +#include "nebula_msgs/msg/nebula_packet.hpp" #include #include @@ -73,23 +72,21 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase Status Shutdown() override; private: - /// @brief Initializing ros wrapper + /// @brief Initialize pointcloud decoder /// @param sensor_configuration SensorConfiguration for this driver /// @param calibration_configuration CalibrationConfiguration for this driver - /// @return Resulting status - Status InitializeCloudDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Initializing ros wrapper for AT - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver + /// @param correction_configuration CorrectionConfiguration for this driver (only for AT128, ignored otherwise) /// @return Resulting status Status InitializeCloudDriver( const std::shared_ptr & sensor_configuration, const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration); + const std::shared_ptr & correction_configuration = nullptr); + + Status InitializeCloudDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) { + return InitializeCloudDriver(sensor_configuration, calibration_configuration, nullptr); + } /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration @@ -189,7 +186,10 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::shared_ptr driver_ptr_; Status wrapper_status_; - rclcpp::Subscription::SharedPtr pandar_scan_sub_; + + rclcpp::Publisher::SharedPtr packet_pub_; + rclcpp::Subscription::SharedPtr packet_sub_; + rclcpp::Publisher::SharedPtr nebula_points_pub_; rclcpp::Publisher::SharedPtr aw_points_ex_pub_; rclcpp::Publisher::SharedPtr aw_points_base_pub_; diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index 579852fb8..a74eb9813 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -27,8 +27,6 @@ - - @@ -55,7 +53,6 @@ - @@ -63,6 +60,5 @@ - diff --git a/nebula_ros/package.xml b/nebula_ros/package.xml index 87bc000c9..54df70ea9 100644 --- a/nebula_ros/package.xml +++ b/nebula_ros/package.xml @@ -31,6 +31,7 @@ velodyne_msgs visualization_msgs yaml-cpp + nebula_msgs ament_cmake_gtest ament_lint_auto diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index b809bccf8..ce81d6b3e 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -5,7 +5,9 @@ namespace nebula namespace ros { HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_ros_wrapper", options), hw_interface_(), diagnostics_updater_(this) +: rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), + hw_interface_(), + diagnostics_updater_(this) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); @@ -14,33 +16,29 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) sensor_cfg_ptr_ = std::make_shared(sensor_configuration); // hwiface -{ - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_hw_ms_)); - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); -#if not defined(TEST_PCAP) - Status rt = hw_interface_.InitializeTcpDriver(); - if(this->retry_hw_) { - int cnt = 0; - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - while(rt == Status::ERROR_1) - { - cnt++; - std::this_thread::sleep_for(std::chrono::milliseconds(8000));// >5000 - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - rt = hw_interface_.InitializeTcpDriver(); + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return; + } + hw_interface_.SetLogger(std::make_shared(this->get_logger())); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); + Status rt = hw_interface_.InitializeTcpDriver(); + if (this->retry_hw_) { + int cnt = 0; + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); + while (rt == Status::ERROR_1) { + cnt++; + std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); + rt = hw_interface_.InitializeTcpDriver(); + } } - } - if(rt != Status::ERROR_1){ - try{ - std::vector thread_pool{}; + if (rt != Status::ERROR_1) { + try { + std::vector thread_pool{}; thread_pool.emplace_back([this] { auto result = hw_interface_.GetInventory(); RCLCPP_INFO_STREAM(get_logger(), result); @@ -50,74 +48,60 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) th.join(); } + } catch (...) { + std::cout << "catch (...) in parent" << std::endl; + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); + } + if (this->setup_sensor) { + hw_interface_.CheckAndSetConfig(); + updateParameters(); + } + } else { + RCLCPP_ERROR_STREAM( + get_logger(), + "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); + hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); } - catch (...) - { - std::cout << "catch (...) in parent" << std::endl; - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); - } - if (this->setup_sensor) { - hw_interface_.CheckAndSetConfig(); - updateParameters(); - } - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); - hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); - } -#endif - - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - pandar_scan_pub_ = - this->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); - -#if not defined(TEST_PCAP) - if (this->setup_sensor) { - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); } -#endif - - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); -} // decoder { - drivers::HesaiCalibrationConfiguration calibration_configuration; - drivers::HesaiCorrection correction_configuration; - - wrapper_status_ = - GetCalibrationData(calibration_configuration, correction_configuration); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return; - } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - - calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); + drivers::HesaiCalibrationConfiguration calibration_configuration; + drivers::HesaiCorrection correction_configuration; + wrapper_status_ = GetCalibrationData(calibration_configuration, correction_configuration); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return; + } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { + calibration_cfg_ptr_ = + std::make_shared(calibration_configuration); + // Will be left empty for AT128, and ignored by all decoders except AT128 correction_cfg_ptr_ = std::make_shared(correction_configuration); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); wrapper_status_ = InitializeCloudDriver( std::static_pointer_cast(sensor_cfg_ptr_), std::static_pointer_cast(calibration_cfg_ptr_), std::static_pointer_cast(correction_cfg_ptr_)); - } else { - wrapper_status_ = InitializeCloudDriver( - std::static_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); - } + + RCLCPP_DEBUG(this->get_logger(), "Starting stream"); + StreamStart(); + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + packet_pub_ = create_publisher( + "hesai_packets", rclcpp::SensorDataQoS()); + + packet_sub_ = create_subscription( + "hesai_packets", rclcpp::SensorDataQoS(), [](nebula_msgs::msg::NebulaPacket::UniquePtr){}); + nebula_points_pub_ = this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); aw_points_base_pub_ = @@ -194,11 +178,18 @@ cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); set_param_res_ = this->add_on_set_parameters_callback( std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); } -} -void HesaiRosWrapper::ReceiveCloudPacketCallback( - const std::vector & packet) +void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) { + auto t_received = std::chrono::high_resolution_clock::now().time_since_epoch().count(); + auto msg_ptr = std::make_unique(packet.size()); + msg_ptr->stamp.sec = t_received / 1'000'000'000; + msg_ptr->stamp.nanosec = t_received % 1'000'000'000; + // TODO(mojomex) this copy could be avoided if transport_drivers would give us a non-const vector + std::copy(packet.begin(), packet.end(), msg_ptr->data.begin()); + packet_pub_->publish(std::move(msg_ptr)); + + //todo // Driver is not initialized yet if (!driver_ptr_) { return; @@ -209,6 +200,12 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback( driver_ptr_->ParseCloudPacket(packet); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + auto t_end = std::chrono::high_resolution_clock::now(); + auto runtime = t_end - t_start; + t_start = t_end; + RCLCPP_DEBUG( + get_logger(), "PROFILING {'d_decode_packet': %lu}", runtime.count()); + if (pointcloud == nullptr) { // todo // RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); @@ -237,8 +234,8 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback( if ( aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - const auto autoware_ex_cloud = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( + pointcloud, std::get<1>(pointcloud_ts)); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = @@ -246,8 +243,9 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback( PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); } - auto runtime = std::chrono::high_resolution_clock::now() - t_start; - RCLCPP_DEBUG(get_logger(), "PROFILING {'d_total': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); + runtime = std::chrono::high_resolution_clock::now() - t_start; + RCLCPP_DEBUG( + get_logger(), "PROFILING {'d_convert_pc': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); } void HesaiRosWrapper::PublishCloud( @@ -261,22 +259,11 @@ void HesaiRosWrapper::PublishCloud( publisher->publish(std::move(pointcloud)); } -Status HesaiRosWrapper::InitializeCloudDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) -{ - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - Status HesaiRosWrapper::InitializeCloudDriver( const std::shared_ptr & sensor_configuration, const std::shared_ptr & calibration_configuration, const std::shared_ptr & correction_configuration) { - // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), std::static_pointer_cast(calibration_configuration), @@ -284,11 +271,12 @@ Status HesaiRosWrapper::InitializeCloudDriver( return driver_ptr_->GetStatus(); } -Status HesaiRosWrapper::GetStatus() { return wrapper_status_; } +Status HesaiRosWrapper::GetStatus() +{ + return wrapper_status_; +} -/// decoder -Status HesaiRosWrapper::GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration) +Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration) { /////////////////////////////////////////////// // Define and get ROS parameters @@ -377,8 +365,7 @@ Status HesaiRosWrapper::GetParameters( descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; this->declare_parameter("calibration_file", "", descriptor); - calibration_file_path = - this->get_parameter("calibration_file").as_string(); + calibration_file_path = this->get_parameter("calibration_file").as_string(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -492,16 +479,6 @@ Status HesaiRosWrapper::GetParameters( this->declare_parameter("setup_sensor", true, descriptor); this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); } - - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("delay_hw_ms", 0, descriptor); - this->delay_hw_ms_ = this->get_parameter("delay_hw_ms").as_int(); - } { rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; @@ -528,9 +505,9 @@ Status HesaiRosWrapper::GetParameters( descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; this->declare_parameter("ptp_transport_type", ""); - sensor_configuration.ptp_transport_type = - nebula::drivers::PtpTransportTypeFromString(this->get_parameter("ptp_transport_type").as_string()); - if(static_cast(sensor_configuration.ptp_profile) > 0) { + sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportTypeFromString( + this->get_parameter("ptp_transport_type").as_string()); + if (static_cast(sensor_configuration.ptp_profile) > 0) { sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; } } @@ -565,32 +542,27 @@ Status HesaiRosWrapper::GetParameters( this->diag_span_ = this->get_parameter("diag_span").as_int(); } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("delay_monitor_ms", 0, descriptor); - this->delay_monitor_ms_ = this->get_parameter("delay_monitor_ms").as_int(); - } - /////////////////////////////////////////////// // Validate ROS parameters /////////////////////////////////////////////// - if(sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { - RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); + if (sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { + RCLCPP_ERROR_STREAM( + get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); return Status::SENSOR_CONFIG_ERROR; } - if(sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when using the '1588v2' PTP Profile"); + if ( + sensor_configuration.ptp_transport_type == + nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { + RCLCPP_ERROR_STREAM( + get_logger(), + "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " + "using the '1588v2' PTP Profile"); return Status::SENSOR_CONFIG_ERROR; } - if(sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); + if (sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { + RCLCPP_ERROR_STREAM( + get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); return Status::SENSOR_CONFIG_ERROR; } if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { @@ -603,69 +575,61 @@ Status HesaiRosWrapper::GetParameters( return Status::SENSOR_CONFIG_ERROR; } - /////////////////////////////////////////////// - // Decoder-specific setup - /////////////////////////////////////////////// - std::shared_ptr sensor_cfg_ptr = std::make_shared(sensor_configuration); hw_interface_.SetSensorConfiguration( std::static_pointer_cast(sensor_cfg_ptr)); - /////////////////////////////////////////////// - // HW Interface specific setup - /////////////////////////////////////////////// - - /////////////////////////////////////////////// - // HW Monitor specific setup - /////////////////////////////////////////////// - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); return Status::OK; } Status HesaiRosWrapper::GetCalibrationData( drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration) { - calibration_configuration.calibration_file = calibration_file_path; //todo + drivers::HesaiCorrection & correction_configuration) +{ + calibration_configuration.calibration_file = calibration_file_path; // todo - bool run_local = !launch_hw_; + bool run_local = !launch_hw_; if (sensor_cfg_ptr_->sensor_model != drivers::SensorModel::HESAI_PANDARAT128) { std::string calibration_file_path_from_sensor; if (launch_hw_ && !calibration_configuration.calibration_file.empty()) { int ext_pos = calibration_configuration.calibration_file.find_last_of('.'); - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(0, ext_pos); + calibration_file_path_from_sensor += + calibration_configuration.calibration_file.substr(0, ext_pos); calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr(ext_pos, calibration_configuration.calibration_file.size() - ext_pos); + calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr( + ext_pos, calibration_configuration.calibration_file.size() - ext_pos); } - if(launch_hw_) { + if (launch_hw_) { run_local = false; RCLCPP_INFO_STREAM( - this->get_logger(), "Trying to acquire calibration data from sensor: '" - << sensor_cfg_ptr_->sensor_ip << "'"); - std::future future = std::async(std::launch::async, - [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { - auto str = hw_interface_.GetLidarCalibrationString(); - auto rt = calibration_configuration.SaveFileFromString( - calibration_file_path_from_sensor, str); - RCLCPP_ERROR_STREAM(get_logger(), str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromString success:" - << calibration_file_path_from_sensor << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromString failed:" - << calibration_file_path_from_sensor << "\n"); - } - rt = calibration_configuration.LoadFromString(str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), - "LoadFromString success:" << str << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), - "LoadFromString failed:" << str << "\n"); - } - }); + this->get_logger(), + "Trying to acquire calibration data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); + std::future future = std::async( + std::launch::async, + [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { + auto str = hw_interface_.GetLidarCalibrationString(); + auto rt = + calibration_configuration.SaveFileFromString(calibration_file_path_from_sensor, str); + RCLCPP_ERROR_STREAM(get_logger(), str); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM( + get_logger(), + "SaveFileFromString success:" << calibration_file_path_from_sensor << "\n"); + } else { + RCLCPP_ERROR_STREAM( + get_logger(), + "SaveFileFromString failed:" << calibration_file_path_from_sensor << "\n"); + } + rt = calibration_configuration.LoadFromString(str); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM(get_logger(), "LoadFromString success:" << str << "\n"); + } else { + RCLCPP_ERROR_STREAM(get_logger(), "LoadFromString failed:" << str << "\n"); + } + }); std::future_status status; status = future.wait_for(std::chrono::milliseconds(5000)); if (status == std::future_status::timeout) { @@ -674,36 +638,38 @@ Status HesaiRosWrapper::GetCalibrationData( run_local = true; } else if (status == std::future_status::ready && !run_local) { RCLCPP_INFO_STREAM( - this->get_logger(), "Acquired calibration data from sensor: '" - << sensor_cfg_ptr_->sensor_ip << "'"); + this->get_logger(), + "Acquired calibration data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); RCLCPP_INFO_STREAM( - this->get_logger(), "The calibration has been saved in '" - << calibration_file_path_from_sensor << "'"); + this->get_logger(), + "The calibration has been saved in '" << calibration_file_path_from_sensor << "'"); } } - if(run_local) { + if (run_local) { RCLCPP_WARN_STREAM(get_logger(), "Running locally"); bool run_org = false; if (calibration_file_path_from_sensor.empty()) { run_org = true; } else { - RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_file_path_from_sensor); - auto cal_status = - calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); + RCLCPP_INFO_STREAM( + get_logger(), "Trying to load file: " << calibration_file_path_from_sensor); + auto cal_status = calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); if (cal_status != Status::OK) { run_org = true; - }else{ + } else { RCLCPP_INFO_STREAM( - this->get_logger(), "Load calibration data from: '" - << calibration_file_path_from_sensor << "'"); + this->get_logger(), + "Load calibration data from: '" << calibration_file_path_from_sensor << "'"); } } - if(run_org) { - RCLCPP_INFO_STREAM(get_logger(),"Trying to load file: " << calibration_configuration.calibration_file); + if (run_org) { + RCLCPP_INFO_STREAM( + get_logger(), "Trying to load file: " << calibration_configuration.calibration_file); if (calibration_configuration.calibration_file.empty()) { RCLCPP_ERROR_STREAM( - this->get_logger(), "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); + this->get_logger(), + "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); return Status::INVALID_CALIBRATION_FILE; } else { auto cal_status = @@ -714,54 +680,61 @@ Status HesaiRosWrapper::GetCalibrationData( this->get_logger(), "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); return cal_status; - }else{ + } else { RCLCPP_INFO_STREAM( - this->get_logger(), "Load calibration data from: '" - << calibration_configuration.calibration_file << "'"); + this->get_logger(), + "Load calibration data from: '" << calibration_configuration.calibration_file << "'"); } } } } - } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 + } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 std::string correction_file_path_from_sensor; if (launch_hw_ && !correction_file_path.empty()) { int ext_pos = correction_file_path.find_last_of('.'); correction_file_path_from_sensor += correction_file_path.substr(0, ext_pos); correction_file_path_from_sensor += "_from_sensor"; - correction_file_path_from_sensor += correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); + correction_file_path_from_sensor += + correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); } - std::future future = std::async(std::launch::async, [this, &correction_configuration, &correction_file_path_from_sensor, &run_local]() { - if (launch_hw_) { - RCLCPP_INFO_STREAM( - this->get_logger(), "Trying to acquire calibration data from sensor"); - auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); - RCLCPP_INFO_STREAM(get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); - auto rt = correction_configuration.SaveFileFromBinary(correction_file_path_from_sensor, received_bytes); - if(rt == Status::OK) - { - RCLCPP_INFO_STREAM(get_logger(), "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "SaveFileFromBinary failed:" << correction_file_path_from_sensor << ". Falling back to offline calibration file."); - run_local = true; - } - rt = correction_configuration.LoadFromBinary(received_bytes); - if(rt == Status::OK) - { - RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); - run_local = false; - } - else - { - RCLCPP_ERROR_STREAM(get_logger(), "LoadFromBinary failed" << ". Falling back to offline calibration file."); + std::future future = std::async( + std::launch::async, + [this, &correction_configuration, &correction_file_path_from_sensor, &run_local]() { + if (launch_hw_) { + RCLCPP_INFO_STREAM(this->get_logger(), "Trying to acquire calibration data from sensor"); + auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); + RCLCPP_INFO_STREAM( + get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); + auto rt = correction_configuration.SaveFileFromBinary( + correction_file_path_from_sensor, received_bytes); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM( + get_logger(), + "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); + } else { + RCLCPP_ERROR_STREAM( + get_logger(), + "SaveFileFromBinary failed:" << correction_file_path_from_sensor + << ". Falling back to offline calibration file."); + run_local = true; + } + rt = correction_configuration.LoadFromBinary(received_bytes); + if (rt == Status::OK) { + RCLCPP_INFO_STREAM( + get_logger(), "LoadFromBinary success" + << "\n"); + run_local = false; + } else { + RCLCPP_ERROR_STREAM( + get_logger(), "LoadFromBinary failed" + << ". Falling back to offline calibration file."); + run_local = true; + } + } else { + RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); run_local = true; } - }else{ - RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); - run_local = true; - } - }); + }); if (!run_local) { std::future_status status; status = future.wait_for(std::chrono::milliseconds(8000)); @@ -770,30 +743,29 @@ Status HesaiRosWrapper::GetCalibrationData( run_local = true; } else if (status == std::future_status::ready && !run_local) { RCLCPP_INFO_STREAM( - this->get_logger(), "Acquired correction data from sensor: '" - << sensor_cfg_ptr_->sensor_ip << "'"); + this->get_logger(), + "Acquired correction data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); RCLCPP_INFO_STREAM( - this->get_logger(), "The correction has been saved in '" - << correction_file_path_from_sensor << "'"); + this->get_logger(), + "The correction has been saved in '" << correction_file_path_from_sensor << "'"); } } - if(run_local) { + if (run_local) { bool run_org = false; if (correction_file_path_from_sensor.empty()) { run_org = true; } else { - auto cal_status = - correction_configuration.LoadFromFile(correction_file_path_from_sensor); + auto cal_status = correction_configuration.LoadFromFile(correction_file_path_from_sensor); if (cal_status != Status::OK) { run_org = true; - }else{ + } else { RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" - << correction_file_path_from_sensor << "'"); + this->get_logger(), + "Load correction data from: '" << correction_file_path_from_sensor << "'"); } } - if(run_org) { + if (run_org) { if (correction_file_path.empty()) { RCLCPP_ERROR_STREAM( this->get_logger(), "Empty Correction File: '" << correction_file_path << "'"); @@ -805,20 +777,20 @@ Status HesaiRosWrapper::GetCalibrationData( RCLCPP_ERROR_STREAM( this->get_logger(), "Given Correction File: '" << correction_file_path << "'"); return cal_status; - }else{ + } else { RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" - << correction_file_path << "'"); + this->get_logger(), "Load correction data from: '" << correction_file_path << "'"); } } } } - } // end AT128 + } // end AT128 return Status::OK; - } +} -HesaiRosWrapper::~HesaiRosWrapper() { +HesaiRosWrapper::~HesaiRosWrapper() +{ RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); hw_interface_.FinalizeTcpDriver(); } @@ -831,8 +803,14 @@ Status HesaiRosWrapper::StreamStart() return interface_status_; } -Status HesaiRosWrapper::StreamStop() { return Status::OK; } -Status HesaiRosWrapper::Shutdown() { return Status::OK; } +Status HesaiRosWrapper::StreamStop() +{ + return Status::OK; +} +Status HesaiRosWrapper::Shutdown() +{ + return Status::OK; +} Status HesaiRosWrapper::InitializeHwInterface( // todo: don't think this is needed const drivers::SensorConfigurationBase & sensor_configuration) @@ -844,8 +822,63 @@ Status HesaiRosWrapper::InitializeHwInterface( // todo: don't think this is nee } Status HesaiRosWrapper::InitializeHwMonitor( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) + const drivers::SensorConfigurationBase & /* sensor_configuration */) { + cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); + cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return Status::ERROR_1; + } + + message_sep = ": "; + not_supported_message = "Not supported"; + error_message = "Error"; + + switch (sensor_cfg_ptr_->sensor_model) { + case nebula::drivers::SensorModel::HESAI_PANDARXT32: + case nebula::drivers::SensorModel::HESAI_PANDARXT32M: + case nebula::drivers::SensorModel::HESAI_PANDARAT128: + temperature_names.emplace_back("Bottom circuit board T1"); + temperature_names.emplace_back("Bottom circuit board T2"); + temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names.emplace_back("Laser emitting board RT_L2"); + temperature_names.emplace_back("Receiving board RT_R"); + temperature_names.emplace_back("Receiving board RT2"); + temperature_names.emplace_back("Top circuit RT3"); + temperature_names.emplace_back("Not used"); + break; + case nebula::drivers::SensorModel::HESAI_PANDAR64: + case nebula::drivers::SensorModel::HESAI_PANDAR40P: + case nebula::drivers::SensorModel::HESAI_PANDAR40M: + case nebula::drivers::SensorModel::HESAI_PANDARQT64: + case nebula::drivers::SensorModel::HESAI_PANDARQT128: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: + default: + temperature_names.emplace_back("Bottom circuit RT1"); + temperature_names.emplace_back("Bottom circuit RT2"); + temperature_names.emplace_back("Internal Temperature"); + temperature_names.emplace_back("Laser emitting board RT1"); + temperature_names.emplace_back("Laser emitting board RT2"); + temperature_names.emplace_back("Receiving board RT1"); + temperature_names.emplace_back("Top circuit RT1"); + temperature_names.emplace_back("Top circuit RT2"); + break; + } + + auto result = hw_interface_.GetInventory(); + current_inventory.reset(new HesaiInventory(result)); + current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); + std::cout << "HesaiInventory" << std::endl; + std::cout << result << std::endl; + info_model = result.get_str_model(); + info_serial = std::string(result.sn.begin(), result.sn.end()); + hw_interface_.SetTargetModel(result.model); + RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); + RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); + InitializeHesaiDiagnostics(); return Status::OK; } @@ -858,16 +891,14 @@ rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( RCLCPP_DEBUG_STREAM(this->get_logger(), *sensor_cfg_ptr_); RCLCPP_INFO_STREAM(this->get_logger(), p); - std::shared_ptr new_param = + std::shared_ptr new_param = std::make_shared(*sensor_cfg_ptr_); RCLCPP_INFO_STREAM(this->get_logger(), new_param); std::string sensor_model_str; std::string return_mode_str; if ( - get_param(p, "sensor_model", sensor_model_str) | - get_param(p, "return_mode", return_mode_str) | - get_param(p, "host_ip", new_param->host_ip) | - get_param(p, "sensor_ip", new_param->sensor_ip) | + get_param(p, "sensor_model", sensor_model_str) | get_param(p, "return_mode", return_mode_str) | + get_param(p, "host_ip", new_param->host_ip) | get_param(p, "sensor_ip", new_param->sensor_ip) | get_param(p, "frame_id", new_param->frame_id) | get_param(p, "data_port", new_param->data_port) | get_param(p, "gnss_port", new_param->gnss_port) | @@ -938,8 +969,7 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() diagnostics_updater_.add("hesai_status", this, &HesaiRosWrapper::HesaiCheckStatus); diagnostics_updater_.add("hesai_ptp", this, &HesaiRosWrapper::HesaiCheckPtp); - diagnostics_updater_.add( - "hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); + diagnostics_updater_.add("hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); diagnostics_updater_.add("hesai_rpm", this, &HesaiRosWrapper::HesaiCheckRpm); current_status.reset(); @@ -964,8 +994,7 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); if (hw_interface_.UseHttpGetLidarMonitor()) { - diagnostics_updater_.add( - "hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); + diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); } else { diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltage); } @@ -1030,12 +1059,10 @@ void HesaiRosWrapper::OnHesaiStatusTimer() current_status.reset(new HesaiLidarStatus(result)); } catch (const std::system_error & error) { RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), - error.what()); + rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), error.what()); } catch (const boost::system::system_error & error) { RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), + rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), error.what()); } RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl); @@ -1053,8 +1080,7 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp() }); } catch (const std::system_error & error) { RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), + rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), error.what()); } catch (const boost::system::system_error & error) { RCLCPP_ERROR_STREAM( @@ -1080,15 +1106,13 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimer() error.what()); } catch (const boost::system::system_error & error) { RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), + rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), error.what()); } RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END"); } -void HesaiRosWrapper::HesaiCheckStatus( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_status); if (current_status) { @@ -1105,8 +1129,7 @@ void HesaiRosWrapper::HesaiCheckStatus( } } -void HesaiRosWrapper::HesaiCheckPtp( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_status); if (current_status) { @@ -1156,8 +1179,7 @@ void HesaiRosWrapper::HesaiCheckTemperature( } } -void HesaiRosWrapper::HesaiCheckRpm( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_status); if (current_status) { @@ -1204,8 +1226,7 @@ void HesaiRosWrapper::HesaiCheckVoltageHttp( } } -void HesaiRosWrapper::HesaiCheckVoltage( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_lidar_monitor); if (current_monitor) { @@ -1224,6 +1245,6 @@ void HesaiRosWrapper::HesaiCheckVoltage( } } - RCLCPP_COMPONENTS_REGISTER_NODE(HesaiRosWrapper) +RCLCPP_COMPONENTS_REGISTER_NODE(HesaiRosWrapper) } // namespace ros } // namespace nebula diff --git a/scripts/plot_times.py b/scripts/plot_times.py index 521dfd347..3cbf93f61 100644 --- a/scripts/plot_times.py +++ b/scripts/plot_times.py @@ -24,7 +24,6 @@ def parse_logs(run_name): for col in [c for c in df.columns if c.startswith("d_")]: df[col] /= 1e6 # ns to ms - df['d_total'] = sum([df[c] for c in df.columns if c.startswith("d_")]) # type: ignore return df def plot_timing_comparison(run_names): @@ -41,11 +40,13 @@ def plot_timing_comparison(run_names): boxes = axs[1:] for i, (label, df) in enumerate(scenario_dfs.items()): - durations = df['d_total'] + # durations = df['d_total'] - ax_d.plot(durations.index, durations, label=label, linestyle='', marker='.') + # ax_d.plot(durations.index, durations, label=label, linestyle='', marker='.') for col in filter(lambda col: col.startswith("n_"), df.columns): ax_n.plot(df.index, df[col], label=f"{label}::{col}", linestyle='', marker='.', color='black') + for col in filter(lambda col: col.startswith("d_"), df.columns): + ax_d.plot(df.index, df[col], label=f"{label}::{col}", linestyle='', marker='.') d_columns = [col for col in df.columns if col.startswith("d_")] n_cols = len(d_columns) From 892a48b0e1daa1fe3c8cf5a085578fd5ed132b0d Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 26 Mar 2024 22:02:51 +0900 Subject: [PATCH 070/122] temporary progress --- nebula_messages/nebula_msgs/CMakeLists.txt | 2 +- .../nebula_msgs/msg/NebulaPacket.msg | 2 +- nebula_messages/nebula_msgs/package.xml | 2 +- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 6 +- nebula_ros/launch/hesai_launch_all_hw.xml | 59 ++++---- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 134 +++++------------- 6 files changed, 78 insertions(+), 127 deletions(-) diff --git a/nebula_messages/nebula_msgs/CMakeLists.txt b/nebula_messages/nebula_msgs/CMakeLists.txt index 2ffa068a5..e2b798d9d 100644 --- a/nebula_messages/nebula_msgs/CMakeLists.txt +++ b/nebula_messages/nebula_msgs/CMakeLists.txt @@ -21,4 +21,4 @@ rosidl_generate_interfaces(${PROJECT_NAME} std_msgs ) -ament_package() +ament_package() \ No newline at end of file diff --git a/nebula_messages/nebula_msgs/msg/NebulaPacket.msg b/nebula_messages/nebula_msgs/msg/NebulaPacket.msg index f6ba285d8..be5898eb1 100644 --- a/nebula_messages/nebula_msgs/msg/NebulaPacket.msg +++ b/nebula_messages/nebula_msgs/msg/NebulaPacket.msg @@ -1,2 +1,2 @@ builtin_interfaces/Time stamp -uint8[] data +uint8[] data \ No newline at end of file diff --git a/nebula_messages/nebula_msgs/package.xml b/nebula_messages/nebula_msgs/package.xml index cdd135c37..3eb05e603 100644 --- a/nebula_messages/nebula_msgs/package.xml +++ b/nebula_messages/nebula_msgs/package.xml @@ -22,4 +22,4 @@ ament_cmake - + \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index e91d7fcaf..0681f9455 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -125,10 +125,14 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase /// @return Resulting status Status InitializeHwInterface( const drivers::SensorConfigurationBase & sensor_configuration) override; - /// @brief Callback for receiving PandarScan + /// @brief Callback for receiving a raw UDP packet /// @param scan_buffer Received PandarScan void ReceiveCloudPacketCallback(const std::vector & scan_buffer); + /// @brief Decodes a nebula packet and, if it completes the scan, publishes the pointcloud. + /// @param packet_msg The received packet message + void ProcessCloudPacket(std::unique_ptr packet_msg); + /// @brief rclcpp parameter callback /// @param parameters Received parameters /// @return SetParametersResult diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index a74eb9813..b7c1459ec 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -33,32 +33,35 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index ce81d6b3e..8957a30d2 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -86,94 +86,31 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) std::static_pointer_cast(calibration_cfg_ptr_), std::static_pointer_cast(correction_cfg_ptr_)); - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), - qos_profile); - - packet_pub_ = create_publisher( - "hesai_packets", rclcpp::SensorDataQoS()); - - packet_sub_ = create_subscription( - "hesai_packets", rclcpp::SensorDataQoS(), [](nebula_msgs::msg::NebulaPacket::UniquePtr){}); - - nebula_points_pub_ = - this->create_publisher("pandar_points", rclcpp::SensorDataQoS()); - aw_points_base_pub_ = - this->create_publisher("aw_points", rclcpp::SensorDataQoS()); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", rclcpp::SensorDataQoS()); -} - -//hwmon -{ -cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); - cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); + rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; + auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), + qos_profile); + + packet_pub_ = create_publisher( + "hesai_packets", rclcpp::SensorDataQoS()); + + packet_sub_ = create_subscription( + "hesai_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); + + nebula_points_pub_ = this->create_publisher( + "pandar_points", rclcpp::SensorDataQoS()); + aw_points_base_pub_ = + this->create_publisher("aw_points", rclcpp::SensorDataQoS()); + aw_points_ex_pub_ = this->create_publisher( + "aw_points_ex", rclcpp::SensorDataQoS()); } - std::this_thread::sleep_for(std::chrono::milliseconds(this->delay_monitor_ms_)); - message_sep = ": "; - not_supported_message = "Not supported"; - error_message = "Error"; + RCLCPP_DEBUG(this->get_logger(), "Starting stream"); + StreamStart(); + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - switch (sensor_cfg_ptr_->sensor_model) { - case nebula::drivers::SensorModel::HESAI_PANDARXT32: - case nebula::drivers::SensorModel::HESAI_PANDARXT32M: - case nebula::drivers::SensorModel::HESAI_PANDARAT128: - temperature_names.emplace_back("Bottom circuit board T1"); - temperature_names.emplace_back("Bottom circuit board T2"); - temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); - temperature_names.emplace_back("Laser emitting board RT_L2"); - temperature_names.emplace_back("Receiving board RT_R"); - temperature_names.emplace_back("Receiving board RT2"); - temperature_names.emplace_back("Top circuit RT3"); - temperature_names.emplace_back("Not used"); - break; - case nebula::drivers::SensorModel::HESAI_PANDAR64: - case nebula::drivers::SensorModel::HESAI_PANDAR40P: - case nebula::drivers::SensorModel::HESAI_PANDAR40M: - case nebula::drivers::SensorModel::HESAI_PANDARQT64: - case nebula::drivers::SensorModel::HESAI_PANDARQT128: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: - default: - temperature_names.emplace_back("Bottom circuit RT1"); - temperature_names.emplace_back("Bottom circuit RT2"); - temperature_names.emplace_back("Internal Temperature"); - temperature_names.emplace_back("Laser emitting board RT1"); - temperature_names.emplace_back("Laser emitting board RT2"); - temperature_names.emplace_back("Receiving board RT1"); - temperature_names.emplace_back("Top circuit RT1"); - temperature_names.emplace_back("Top circuit RT2"); - break; - } - - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto result = hw_interface_.GetInventory(); - current_inventory.reset(new HesaiInventory(result)); - current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); - RCLCPP_INFO_STREAM(this->get_logger(), "HesaiInventory"); - RCLCPP_INFO_STREAM(this->get_logger(), result); - info_model = result.get_str_model(); - info_serial = std::string(result.sn.begin(), result.sn.end()); - hw_interface_.SetTargetModel(result.model); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); - InitializeHesaiDiagnostics(); - }); - for (std::thread & th : thread_pool) { - th.join(); - } + InitializeHwMonitor(*sensor_cfg_ptr_); set_param_res_ = this->add_on_set_parameters_callback( std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); @@ -181,23 +118,30 @@ cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) { - auto t_received = std::chrono::high_resolution_clock::now().time_since_epoch().count(); - auto msg_ptr = std::make_unique(packet.size()); - msg_ptr->stamp.sec = t_received / 1'000'000'000; - msg_ptr->stamp.nanosec = t_received % 1'000'000'000; - // TODO(mojomex) this copy could be avoided if transport_drivers would give us a non-const vector - std::copy(packet.begin(), packet.end(), msg_ptr->data.begin()); - packet_pub_->publish(std::move(msg_ptr)); - - //todo // Driver is not initialized yet if (!driver_ptr_) { return; } + const auto now = std::chrono::system_clock::now(); + const auto timestamp_ns = + std::chrono::duration_cast(now.time_since_epoch()).count(); + + auto msg_ptr = std::make_unique(); + msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); + msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); + std::copy(packet.begin(), packet.end(), std::back_inserter(msg_ptr->data)); + + packet_pub_->publish(std::move(msg_ptr)); +} + +void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) +{ + std::lock_guard lock(mtx_decode_); + auto t_start = std::chrono::high_resolution_clock::now(); std::tuple pointcloud_ts = - driver_ptr_->ParseCloudPacket(packet); + driver_ptr_->ParseCloudPacket(packet_msg->data); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); auto t_end = std::chrono::high_resolution_clock::now(); From 21486763772063d8702bbdf6e2233d6ff81097e9 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 19:35:25 +0900 Subject: [PATCH 071/122] fix(hesai_ros_wrapper): remove changes wrongly merged during rebase --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 8957a30d2..9aef30110 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -91,6 +91,8 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + //TODO(mojomex): create high-frequency QoS with large buffer to prevent packet loss + packet_pub_ = create_publisher( "hesai_packets", rclcpp::SensorDataQoS()); @@ -137,8 +139,6 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { - std::lock_guard lock(mtx_decode_); - auto t_start = std::chrono::high_resolution_clock::now(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); @@ -742,7 +742,7 @@ HesaiRosWrapper::~HesaiRosWrapper() Status HesaiRosWrapper::StreamStart() { if (Status::OK == interface_status_) { - interface_status_ = hw_interface_.CloudInterfaceStart(); + interface_status_ = hw_interface_.SensorInterfaceStart(); } return interface_status_; } From 4923a469748087fbb5f939382009527a758f1aa6 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 20:16:36 +0900 Subject: [PATCH 072/122] fix(hesai_ros_wrapper): increase packet buffering to stop internal packet loss --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 43 +++++++++++----------- 1 file changed, 21 insertions(+), 22 deletions(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 9aef30110..15f7eca09 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -88,23 +88,23 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), - qos_profile); + auto pointcloud_qos = + rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - //TODO(mojomex): create high-frequency QoS with large buffer to prevent packet loss - - packet_pub_ = create_publisher( - "hesai_packets", rclcpp::SensorDataQoS()); + auto packet_qos = + rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 1000), qos_profile); + packet_pub_ = create_publisher("hesai_packets", packet_qos); packet_sub_ = create_subscription( - "hesai_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); + "hesai_packets", packet_qos, + std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); - nebula_points_pub_ = this->create_publisher( - "pandar_points", rclcpp::SensorDataQoS()); + nebula_points_pub_ = + this->create_publisher("pandar_points", pointcloud_qos); aw_points_base_pub_ = - this->create_publisher("aw_points", rclcpp::SensorDataQoS()); - aw_points_ex_pub_ = this->create_publisher( - "aw_points_ex", rclcpp::SensorDataQoS()); + this->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = + this->create_publisher("aw_points_ex", pointcloud_qos); } RCLCPP_DEBUG(this->get_logger(), "Starting stream"); @@ -664,14 +664,12 @@ Status HesaiRosWrapper::GetCalibrationData( } rt = correction_configuration.LoadFromBinary(received_bytes); if (rt == Status::OK) { - RCLCPP_INFO_STREAM( - get_logger(), "LoadFromBinary success" - << "\n"); + RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); run_local = false; } else { RCLCPP_ERROR_STREAM( - get_logger(), "LoadFromBinary failed" - << ". Falling back to offline calibration file."); + get_logger(), + "LoadFromBinary failed" << ". Falling back to offline calibration file."); run_local = true; } } else { @@ -923,8 +921,8 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - auto fetch_diag_from_sensor = [this](){ - OnHesaiStatusTimer(); + auto fetch_diag_from_sensor = [this]() { + OnHesaiStatusTimer(); if (hw_interface_.UseHttpGetLidarMonitor()) { OnHesaiLidarMonitorTimerHttp(); } else { @@ -932,9 +930,10 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() } }; - fetch_diagnostics_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), - this->get_node_base_interface()->get_context()); + fetch_diagnostics_timer_ = + std::make_shared>( + this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), + this->get_node_base_interface()->get_context()); this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); if (hw_interface_.UseHttpGetLidarMonitor()) { From ff9096bbeef029baca37f083519621f1d2a59aca Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 20:17:59 +0900 Subject: [PATCH 073/122] feat(nebula_common): add instrumentation tools --- .../nebula_common/util/instrumentation.hpp | 109 ++++++++++++++++++ 1 file changed, 109 insertions(+) create mode 100644 nebula_common/include/nebula_common/util/instrumentation.hpp diff --git a/nebula_common/include/nebula_common/util/instrumentation.hpp b/nebula_common/include/nebula_common/util/instrumentation.hpp new file mode 100644 index 000000000..ab9357286 --- /dev/null +++ b/nebula_common/include/nebula_common/util/instrumentation.hpp @@ -0,0 +1,109 @@ +#pragma once + +#include +#include +#include + +namespace nebula +{ +namespace util +{ + +using namespace std::chrono_literals; + +class Instrumentation +{ + using clock = std::chrono::high_resolution_clock; + using time_point = clock::time_point; + using duration = std::chrono::nanoseconds; + +public: + Instrumentation(std::string tag) : tag(tag), last_print(clock::now()) {} + + void tick() + { + auto now = clock::now(); + + if (last_tick != time_point::min()) { + auto rtt = now - last_tick; + rtts_.update(rtt); + } + + last_tick = now; + } + + void tock() + { + auto now = clock::now(); + auto delay = now - last_tick; + delays_.update(delay); + + if (now - last_print >= PRINT_INTERVAL) { + auto del = delays_.reset(); + auto rtt = rtts_.reset(); + + last_print = now; + + std::cout << "{\"tag\": \"" << tag << "\", \"del_min\": " << del.min.count() * 1e-9 + << ", \"del_avg\": " << del.avg.count() * 1e-9 + << ", \"del_max\": " << del.max.count() * 1e-9 + << ", \"rtt_min\": " << rtt.min.count() * 1e-9 + << ", \"rtt_avg\": " << rtt.avg.count() * 1e-9 + << ", \"rtt_max\": " << rtt.max.count() * 1e-9 << ", \"window\": " << rtt.count + << '}' << std::endl; + } + } + +private: + class Counter + { + public: + struct Stats + { + duration min; + duration avg; + duration max; + uint64_t count; + }; + + Stats reset() + { + auto avg_measurement = sum_measurements / num_measurements; + + Stats result{min_measurement, avg_measurement, max_measurement, num_measurements}; + + sum_measurements = duration::zero(); + num_measurements = 0; + min_measurement = duration::zero(); + max_measurement = duration::max(); + } + + void update(duration measurement) + { + sum_measurements += measurement; + num_measurements++; + + min_measurement = std::min(min_measurement, measurement); + max_measurement = std::max(max_measurement, measurement); + } + + private: + duration sum_measurements{duration::zero()}; + uint64_t num_measurements{0}; + duration min_measurement{duration::max()}; + duration max_measurement{duration::zero()}; + }; + + std::string tag; + + time_point last_tick{time_point::min()}; + time_point last_print{time_point::min()}; + + Counter delays_; + Counter rtts_; + + const duration PRINT_INTERVAL = 1s; +}; + +} // namespace util +} // namespace nebula \ No newline at end of file From fc168523bbac0cbc78d5d88a4e96ca239d70dac0 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 4 Apr 2024 20:18:20 +0900 Subject: [PATCH 074/122] feat(hesai_ros_wrapper): instrument code on critical path --- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 1 + nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 37 +++++++++++++------ 2 files changed, 27 insertions(+), 11 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 0681f9455..781b64198 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -4,6 +4,7 @@ #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" +#include "nebula_common/util/instrumentation.hpp" #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" #include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 15f7eca09..1835e1de6 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -120,11 +120,14 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) { + static nebula::util::Instrumentation convert{"ReceiveCloudPacketCallback.convert"}; + static nebula::util::Instrumentation publish{"ReceiveCloudPacketCallback.publish"}; // Driver is not initialized yet if (!driver_ptr_) { return; } + convert.tick(); const auto now = std::chrono::system_clock::now(); const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); @@ -133,22 +136,24 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); std::copy(packet.begin(), packet.end(), std::back_inserter(msg_ptr->data)); + convert.tock(); + publish.tick(); packet_pub_->publish(std::move(msg_ptr)); + publish.tock(); } void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { - auto t_start = std::chrono::high_resolution_clock::now(); + static nebula::util::Instrumentation parse{"ProcessCloudPacket.parse"}; + static nebula::util::Instrumentation convert{"ProcessCloudPacket.convert"}; + static nebula::util::Instrumentation publish{"ProcessCloudPacket.publish"}; + + parse.tick(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - - auto t_end = std::chrono::high_resolution_clock::now(); - auto runtime = t_end - t_start; - t_start = t_end; - RCLCPP_DEBUG( - get_logger(), "PROFILING {'d_decode_packet': %lu}", runtime.count()); + parse.tock(); if (pointcloud == nullptr) { // todo @@ -158,38 +163,48 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrget_subscription_count() > 0 || nebula_points_pub_->get_intra_process_subscription_count() > 0) { + convert.tick(); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + convert.tock(); + publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); + publish.tock(); } if ( aw_points_base_pub_->get_subscription_count() > 0 || aw_points_base_pub_->get_intra_process_subscription_count() > 0) { + convert.tick(); + const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + convert.tock(); + publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); + publish.tock(); } if ( aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { + convert.tick(); + const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( pointcloud, std::get<1>(pointcloud_ts)); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + convert.tock(); + publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); + publish.tock(); } - - runtime = std::chrono::high_resolution_clock::now() - t_start; - RCLCPP_DEBUG( - get_logger(), "PROFILING {'d_convert_pc': %lu, 'n_out': %lu}", runtime.count(), pointcloud->size()); } void HesaiRosWrapper::PublishCloud( From b7a5a89e2acabc5bec764f846d618b504e09a5be Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:18:57 +0900 Subject: [PATCH 075/122] disable instrumentation --- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 3 +- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 55 ++++++++++--------- 2 files changed, 32 insertions(+), 26 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 781b64198..149232e98 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -4,7 +4,8 @@ #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" -#include "nebula_common/util/instrumentation.hpp" +// #include "nebula_common/util/instrumentation.hpp" +// #include "nebula_common/util/topic_delay.hpp" #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" #include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 1835e1de6..533c3cf49 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -120,14 +120,15 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) { - static nebula::util::Instrumentation convert{"ReceiveCloudPacketCallback.convert"}; - static nebula::util::Instrumentation publish{"ReceiveCloudPacketCallback.publish"}; + // static auto convert = nebula::util::Instrumentation("ReceiveCloudPacketCallback.convert"); + // static auto publish = nebula::util::Instrumentation("ReceiveCloudPacketCallback.publish"); + // static auto delay = nebula::util::TopicDelay("ReceiveCloudPacketCallback"); // Driver is not initialized yet if (!driver_ptr_) { return; } - convert.tick(); + // convert.tick(); const auto now = std::chrono::system_clock::now(); const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); @@ -135,25 +136,29 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa auto msg_ptr = std::make_unique(); msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); - std::copy(packet.begin(), packet.end(), std::back_inserter(msg_ptr->data)); - convert.tock(); + msg_ptr->data.swap(packet); + // convert.tock(); - publish.tick(); - packet_pub_->publish(std::move(msg_ptr)); - publish.tock(); + // delay.tick(msg_ptr->stamp); + + // publish.tick(); + // publish.tock(); } void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { - static nebula::util::Instrumentation parse{"ProcessCloudPacket.parse"}; - static nebula::util::Instrumentation convert{"ProcessCloudPacket.convert"}; - static nebula::util::Instrumentation publish{"ProcessCloudPacket.publish"}; + // static auto parse = nebula::util::Instrumentation("ProcessCloudPacket.parse"); + // static auto convert = nebula::util::Instrumentation("ProcessCloudPacket.convert"); + // static auto publish = nebula::util::Instrumentation("ProcessCloudPacket.publish"); + // static auto delay = nebula::util::TopicDelay("ProcessCloudPacket"); + + // delay.tick(packet_msg->stamp); - parse.tick(); + // parse.tick(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - parse.tock(); + // parse.tock(); if (pointcloud == nullptr) { // todo @@ -163,20 +168,20 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrget_subscription_count() > 0 || nebula_points_pub_->get_intra_process_subscription_count() > 0) { - convert.tick(); + // convert.tick(); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - convert.tock(); - publish.tick(); + // convert.tock(); + // publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); - publish.tock(); + // publish.tock(); } if ( aw_points_base_pub_->get_subscription_count() > 0 || aw_points_base_pub_->get_intra_process_subscription_count() > 0) { - convert.tick(); + // convert.tick(); const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); @@ -184,15 +189,15 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrheader.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - convert.tock(); - publish.tick(); + // convert.tock(); + // publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); - publish.tock(); + // publish.tock(); } if ( aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - convert.tick(); + // convert.tick(); const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( pointcloud, std::get<1>(pointcloud_ts)); @@ -200,10 +205,10 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrheader.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - convert.tock(); - publish.tick(); + // convert.tock(); + // publish.tick(); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); - publish.tock(); + // publish.tock(); } } From d04af0e724a19ff0756ff0e169ac7003f948f266 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:20:44 +0900 Subject: [PATCH 076/122] feat(hesai): move received buffer into ros message instead of copy --- .../hesai_hw_interface.hpp | 6 +++--- .../hesai_hw_interface.cpp | 12 ++++++------ .../include/nebula_ros/hesai/hesai_ros_wrapper.hpp | 2 +- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 3 ++- 4 files changed, 12 insertions(+), 11 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index 34c5208ee..d71a26998 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -127,7 +127,7 @@ class HesaiHwInterface : NebulaHwInterfaceBase std::unique_ptr scan_cloud_ptr_; std::function is_valid_packet_; /*Lambda Function Array to verify proper packet size*/ - std::function & buffer)> + std::function & buffer)> cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ int prev_phase_{}; @@ -198,7 +198,7 @@ class HesaiHwInterface : NebulaHwInterfaceBase /// @brief Callback function to receive the Cloud Packet data from the UDP Driver /// @param buffer Buffer containing the data received from the UDP socket - void ReceiveSensorPacketCallback(const std::vector & buffer) final; + void ReceiveSensorPacketCallback(std::vector & buffer); /// @brief Starting the interface that handles UDP streams /// @return Resulting status Status SensorInterfaceStart() final; @@ -222,7 +222,7 @@ class HesaiHwInterface : NebulaHwInterfaceBase /// @param scan_callback Callback function /// @return Resulting status Status RegisterScanCallback( - std::function &)> scan_callback); + std::function &)> scan_callback); /// @brief Getting data with PTC_COMMAND_GET_LIDAR_CALIBRATION /// @return Resulting status std::string GetLidarCalibrationString(); diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 4fbb020b0..e37d42a43 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -239,18 +239,18 @@ Status HesaiHwInterface::SensorInterfaceStart() } Status HesaiHwInterface::RegisterScanCallback( - std::function &)> scan_callback) + std::function &)> scan_callback) { cloud_packet_callback_ = std::move(scan_callback); return Status::OK; } -void HesaiHwInterface::ReceiveSensorPacketCallback(const std::vector & buffer) +void HesaiHwInterface::ReceiveSensorPacketCallback(std::vector & buffer) { - if (!is_valid_packet_(buffer.size())) { - PrintDebug("Invalid Packet: " + std::to_string(buffer.size())); - return; - } + // if (!is_valid_packet_(buffer.size())) { + // PrintDebug("Invalid Packet: " + std::to_string(buffer.size())); + // return; + // } TODO cloud_packet_callback_(buffer); } Status HesaiHwInterface::SensorInterfaceStop() diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 149232e98..3190b3b97 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -129,7 +129,7 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase const drivers::SensorConfigurationBase & sensor_configuration) override; /// @brief Callback for receiving a raw UDP packet /// @param scan_buffer Received PandarScan - void ReceiveCloudPacketCallback(const std::vector & scan_buffer); + void ReceiveCloudPacketCallback(std::vector & scan_buffer); /// @brief Decodes a nebula packet and, if it completes the scan, publishes the pointcloud. /// @param packet_msg The received packet message diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 533c3cf49..c113f1f04 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -118,7 +118,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); } -void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & packet) +void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) { // static auto convert = nebula::util::Instrumentation("ReceiveCloudPacketCallback.convert"); // static auto publish = nebula::util::Instrumentation("ReceiveCloudPacketCallback.publish"); @@ -142,6 +142,7 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(const std::vector & pa // delay.tick(msg_ptr->stamp); // publish.tick(); + packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); } From bc8813a2c11586b28cb87c6406c659467afc0168 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:21:46 +0900 Subject: [PATCH 077/122] feat(hesai_ros_wrapper: add thread-safe queue between udp receiver and decoder, decode in separate thread --- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 5 +++ .../include/nebula_ros/hesai/mt_queue.hpp | 41 +++++++++++++++++++ nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 27 ++++++++---- 3 files changed, 65 insertions(+), 8 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/hesai/mt_queue.hpp diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 3190b3b97..4e1a6be7d 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -28,6 +28,8 @@ #include #include +#include "nebula_ros/hesai/mt_queue.hpp" + namespace nebula { namespace ros @@ -204,6 +206,9 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::shared_ptr sensor_cfg_ptr_; std::shared_ptr correction_cfg_ptr_; + mt_queue> packet_queue_; + std::thread decoder_thread_; + Status interface_status_; //todo: temporary class member during single node refactoring diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp new file mode 100644 index 000000000..49c08b957 --- /dev/null +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -0,0 +1,41 @@ +#pragma once + +#include +#include +#include + +template +class mt_queue +{ +private: + std::mutex d_mutex; + std::condition_variable d_condition; + std::deque d_queue; + + size_t capacity_; + +public: + mt_queue(size_t capacity) : capacity_(capacity) {} + + bool push(T && value) + { + { + std::unique_lock lock(this->d_mutex); + if (d_queue.size() == capacity_) { + return false; + } + + d_queue.push_front(std::move(value)); + } + this->d_condition.notify_one(); + return true; + } + T pop() + { + std::unique_lock lock(this->d_mutex); + this->d_condition.wait(lock, [=] { return !this->d_queue.empty(); }); + T rc(std::move(this->d_queue.back())); + this->d_queue.pop_back(); + return rc; + } +}; \ No newline at end of file diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index c113f1f04..b86c05199 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -7,7 +7,8 @@ namespace ros HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), hw_interface_(), - diagnostics_updater_(this) + diagnostics_updater_(this), + packet_queue_(300) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); @@ -91,13 +92,20 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - auto packet_qos = - rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 1000), qos_profile); + // auto packet_qos = + // rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 300), qos_profile); - packet_pub_ = create_publisher("hesai_packets", packet_qos); - packet_sub_ = create_subscription( - "hesai_packets", packet_qos, - std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); + // packet_pub_ = create_publisher("hesai_packets", packet_qos); + // packet_sub_ = create_subscription( + // "hesai_packets", packet_qos, + // std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); + + decoder_thread_ = std::thread([this](){ + while(true) { + auto pkt = packet_queue_.pop(); + this->ProcessCloudPacket(std::move(pkt)); + } + }); nebula_points_pub_ = this->create_publisher("pandar_points", pointcloud_qos); @@ -142,7 +150,10 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) // delay.tick(msg_ptr->stamp); // publish.tick(); - packet_pub_->publish(std::move(msg_ptr)); + if (!packet_queue_.push(std::move(msg_ptr))) { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packets dropped"); + } + // packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); } From 232afae5c96bf53ec011a88887995dc5e5e129cd Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:22:12 +0900 Subject: [PATCH 078/122] feat(nebula_common): more instrumentation tools --- .../nebula_common/util/instrumentation.hpp | 87 +++++++------------ .../util/performance_counter.hpp | 43 +++++++++ .../nebula_common/util/topic_delay.hpp | 68 +++++++++++++++ scripts/plot_instrumentation.py | 77 ++++++++++++++++ 4 files changed, 220 insertions(+), 55 deletions(-) create mode 100644 nebula_common/include/nebula_common/util/performance_counter.hpp create mode 100644 nebula_common/include/nebula_common/util/topic_delay.hpp create mode 100755 scripts/plot_instrumentation.py diff --git a/nebula_common/include/nebula_common/util/instrumentation.hpp b/nebula_common/include/nebula_common/util/instrumentation.hpp index ab9357286..ccce705d8 100644 --- a/nebula_common/include/nebula_common/util/instrumentation.hpp +++ b/nebula_common/include/nebula_common/util/instrumentation.hpp @@ -1,5 +1,7 @@ #pragma once +#include "nebula_common/util/performance_counter.hpp" + #include #include #include @@ -18,86 +20,61 @@ class Instrumentation using duration = std::chrono::nanoseconds; public: - Instrumentation(std::string tag) : tag(tag), last_print(clock::now()) {} + Instrumentation(std::string tag) + : tag_(std::move(tag)), last_print_(clock::now()), delays_(), rtts_() + { + } void tick() { auto now = clock::now(); - if (last_tick != time_point::min()) { - auto rtt = now - last_tick; + if (last_tick_ != time_point::min()) { + auto rtt = now - last_tick_; rtts_.update(rtt); } - last_tick = now; + last_tick_ = now; } void tock() { auto now = clock::now(); - auto delay = now - last_tick; + auto delay = now - last_tick_; delays_.update(delay); - if (now - last_print >= PRINT_INTERVAL) { + if (now - last_print_ >= PRINT_INTERVAL) { auto del = delays_.reset(); auto rtt = rtts_.reset(); - last_print = now; + last_print_ = now; - std::cout << "{\"tag\": \"" << tag << "\", \"del_min\": " << del.min.count() * 1e-9 - << ", \"del_avg\": " << del.avg.count() * 1e-9 - << ", \"del_max\": " << del.max.count() * 1e-9 - << ", \"rtt_min\": " << rtt.min.count() * 1e-9 - << ", \"rtt_avg\": " << rtt.avg.count() * 1e-9 - << ", \"rtt_max\": " << rtt.max.count() * 1e-9 << ", \"window\": " << rtt.count - << '}' << std::endl; - } - } + std::stringstream ss; -private: - class Counter - { - public: - struct Stats - { - duration min; - duration avg; - duration max; - uint64_t count; - }; - - Stats reset() - { - auto avg_measurement = sum_measurements / num_measurements; - - Stats result{min_measurement, avg_measurement, max_measurement, num_measurements}; - - sum_measurements = duration::zero(); - num_measurements = 0; - min_measurement = duration::zero(); - max_measurement = duration::max(); - } + ss << "{\"type\": \"instrumentation\", \"tag\": \"" << tag_ + << "\", \"del\": ["; + + for (duration & dt : *del) { + ss << dt.count() << ','; + } - void update(duration measurement) - { - sum_measurements += measurement; - num_measurements++; + ss <<"null], \"rtt\": ["; - min_measurement = std::min(min_measurement, measurement); - max_measurement = std::max(max_measurement, measurement); - } + for (duration & dt : *rtt) { + ss << dt.count() << ','; + } + + ss << "null]}" << std::endl; - private: - duration sum_measurements{duration::zero()}; - uint64_t num_measurements{0}; - duration min_measurement{duration::max()}; - duration max_measurement{duration::zero()}; - }; + std::cout << ss.str(); + } + } - std::string tag; +private: + std::string tag_; - time_point last_tick{time_point::min()}; - time_point last_print{time_point::min()}; + time_point last_tick_{time_point::min()}; + time_point last_print_{time_point::min()}; Counter delays_; Counter rtts_; diff --git a/nebula_common/include/nebula_common/util/performance_counter.hpp b/nebula_common/include/nebula_common/util/performance_counter.hpp new file mode 100644 index 000000000..cd6b618f1 --- /dev/null +++ b/nebula_common/include/nebula_common/util/performance_counter.hpp @@ -0,0 +1,43 @@ +#pragma once + +#include +#include +#include + +namespace nebula +{ +namespace util +{ + +class Counter +{ + using clock = std::chrono::high_resolution_clock; + using time_point = clock::time_point; + using duration = std::chrono::nanoseconds; + +public: + Counter() + : buf_record_(), buf_output_() + { + buf_record_.resize(100000); + buf_output_.resize(100000); + } + + std::vector * reset() + { + buf_record_.swap(buf_output_); + buf_record_.clear(); + return &buf_output_; + } + + void update(duration measurement) + { + buf_record_.push_back(measurement); + } + +private: + std::vector buf_record_; + std::vector buf_output_; +}; +} // namespace util +} // namespace nebula \ No newline at end of file diff --git a/nebula_common/include/nebula_common/util/topic_delay.hpp b/nebula_common/include/nebula_common/util/topic_delay.hpp new file mode 100644 index 000000000..a92ce29a2 --- /dev/null +++ b/nebula_common/include/nebula_common/util/topic_delay.hpp @@ -0,0 +1,68 @@ +#pragma once + +#include + +#include "nebula_common/util/performance_counter.hpp" + + +#include +#include +#include + +namespace nebula +{ +namespace util +{ + +using namespace std::chrono_literals; + +class TopicDelay +{ + using clock = std::chrono::high_resolution_clock; + using time_point = clock::time_point; + using duration = std::chrono::nanoseconds; + +public: + TopicDelay(std::string tag) : tag_(std::move(tag)), last_print_(clock::now()), delays_() {} + + void tick(builtin_interfaces::msg::Time & stamp) + { + auto now = clock::now(); + + time_point t_msg = time_point(duration(static_cast(stamp.sec) * 1'000'000'000ULL + stamp.nanosec)); + auto delay = now - t_msg; + + delays_.update(delay); + + if (now - last_print_ >= PRINT_INTERVAL) { + auto del = delays_.reset(); + + last_print_ = now; + + std::stringstream ss; + + ss << "{\"type\": \"topic_delay\", \"tag\": \"" << tag_ + << "\", \"del\": ["; + + for (duration & dt : *del) { + ss << dt.count() << ','; + } + + ss << "null]}" << std::endl; + + std::cout << ss.str(); + } + } + +private: + std::string tag_; + + time_point last_print_{time_point::min()}; + + Counter delays_; + + const duration PRINT_INTERVAL = 1s; +}; + +} // namespace util +} // namespace nebula \ No newline at end of file diff --git a/scripts/plot_instrumentation.py b/scripts/plot_instrumentation.py new file mode 100755 index 000000000..fe9c12fda --- /dev/null +++ b/scripts/plot_instrumentation.py @@ -0,0 +1,77 @@ +#!/usr/bin/python3 + +import argparse +from matplotlib import pyplot as plt +import numpy as np +import pandas as pd +import re +import json +import os +from collections import defaultdict + +def condition_data(log_file: str): + with open(log_file, 'r') as f: + lines = f.readlines() + lines = [re.search(r'(\{"type":.*?"tag":.*?\})', l) for l in lines] + lines = [re.sub(r'([0-9])"', r'\1', l[1]) for l in lines if l] + lines = [json.loads(l) for l in lines if l] + + cols = defaultdict(list) + + for record in lines: + for key in record.keys(): + if key in ["tag", "type"]: + continue + + colname = f"{record['type']}.{key}.{record['tag']}" + cols[colname] += [num for num in record[key] if num is not None] + + def quantile_filter(series, quantile): + q = series.quantile(quantile) + return series[series <= q] + + cols = {k: pd.Series(v, name=k) / 1e3 for k, v in cols.items()} + cols = {k: quantile_filter(v, .999) for k, v in cols.items()} + + for v in cols.values(): + v: pd.Series + v.attrs['file'] = os.path.basename(os.path.splitext(log_file)[0]) + + return cols + +def plot(conditioned_logs): + + conditioned_logs = {k: [dic[k] for dic in conditioned_logs] for k in conditioned_logs[0]} + + fig, axs = plt.subplots(1, len(conditioned_logs), figsize=(15, 8), dpi=120) + + handles, labels = [], [] + + for i, k in enumerate(sorted(conditioned_logs.keys())): + k: str + v = conditioned_logs[k] + ax: plt.Axes = axs[i] + art = ax.boxplot(v) + handles.append(art) + labels.append(k) + ax.set_ylabel("dt [µs]") + ax.set_title(k.replace(".", "\n")) + ax.set_xticks([1 + i for i in range(len(v))], [ser.attrs['file'] for ser in v]) + ax.tick_params(axis='x', labelrotation=90) + + + + fig.tight_layout() + plt.savefig("instrumentation.png") + plt.show() + +def main(args): + conditioned_logs = [condition_data(f) for f in args.log_files] + plot(conditioned_logs) + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("log_files", nargs="+") + args = parser.parse_args() + + main(args) \ No newline at end of file From e9afe522b492a0a55ad1e9d2727015fbee4cac76 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 5 Apr 2024 17:23:02 +0900 Subject: [PATCH 079/122] fix: update link to transport_drivers fork --- build_depends.repos | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/build_depends.repos b/build_depends.repos index e28379f1a..e9278685a 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -2,5 +2,5 @@ repositories: # TCP version of transport drivers transport_drivers: type: git - url: https://github.com/MapIV/transport_drivers - version: boost + url: https://github.com/mojomex/transport_drivers + version: mutable-buffer-in-udp-callback From 1f1e92e22913ff94b5bfe010c1ac3b77cbe8df6a Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 15:36:49 +0900 Subject: [PATCH 080/122] update GitHub PR view From 617373a38fccec1326c77d6da1b9df78295d39df Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 16:43:51 +0900 Subject: [PATCH 081/122] refactor(mt_queue): make variables more readable --- .../include/nebula_ros/hesai/mt_queue.hpp | 25 +++++++++---------- 1 file changed, 12 insertions(+), 13 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp index 49c08b957..730b54f7c 100644 --- a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -8,10 +8,9 @@ template class mt_queue { private: - std::mutex d_mutex; - std::condition_variable d_condition; - std::deque d_queue; - + std::mutex mutex_; + std::condition_variable condition_variable_; + std::deque queue_; size_t capacity_; public: @@ -20,22 +19,22 @@ class mt_queue bool push(T && value) { { - std::unique_lock lock(this->d_mutex); - if (d_queue.size() == capacity_) { + std::unique_lock lock(this->mutex_); + if (queue_.size() == capacity_) { return false; } - d_queue.push_front(std::move(value)); + queue_.push_front(std::move(value)); } - this->d_condition.notify_one(); + this->condition_variable_.notify_one(); return true; } T pop() { - std::unique_lock lock(this->d_mutex); - this->d_condition.wait(lock, [=] { return !this->d_queue.empty(); }); - T rc(std::move(this->d_queue.back())); - this->d_queue.pop_back(); - return rc; + std::unique_lock lock(this->mutex_); + this->condition_variable_.wait(lock, [=] { return !this->queue_.empty(); }); + T return_value(std::move(this->queue_.back())); + this->queue_.pop_back(); + return return_value; } }; \ No newline at end of file From b81f2a9eaf77b2098320a70948cf810dc194b467 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 16:45:48 +0900 Subject: [PATCH 082/122] perf(hesai_ros_wrapper): update queue capacity to alleviate packet drops on ECU --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index b86c05199..f84371a36 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -8,7 +8,7 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), hw_interface_(), diagnostics_updater_(this), - packet_queue_(300) + packet_queue_(3000) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); From 18cb87537741320a2c5edbb868b53d819cfa032c Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 16:46:11 +0900 Subject: [PATCH 083/122] chore(hesai_ros_wrapper): remove unused pub/sub --- .../include/nebula_ros/hesai/hesai_ros_wrapper.hpp | 3 --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 11 ----------- 2 files changed, 14 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 4e1a6be7d..b2cbd04dc 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -195,9 +195,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::shared_ptr driver_ptr_; Status wrapper_status_; - rclcpp::Publisher::SharedPtr packet_pub_; - rclcpp::Subscription::SharedPtr packet_sub_; - rclcpp::Publisher::SharedPtr nebula_points_pub_; rclcpp::Publisher::SharedPtr aw_points_ex_pub_; rclcpp::Publisher::SharedPtr aw_points_base_pub_; diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index f84371a36..1540df3fa 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -92,14 +92,6 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - // auto packet_qos = - // rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 300), qos_profile); - - // packet_pub_ = create_publisher("hesai_packets", packet_qos); - // packet_sub_ = create_subscription( - // "hesai_packets", packet_qos, - // std::bind(&HesaiRosWrapper::ProcessCloudPacket, this, std::placeholders::_1)); - decoder_thread_ = std::thread([this](){ while(true) { auto pkt = packet_queue_.pop(); @@ -254,9 +246,6 @@ Status HesaiRosWrapper::GetStatus() Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration) { - /////////////////////////////////////////////// - // Define and get ROS parameters - /////////////////////////////////////////////// { rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; From 0cdcd802724c9622bc21a7bc85033099c8568fe9 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 18:07:03 +0900 Subject: [PATCH 084/122] refactor(hesai_ros_wrapper): clean up control flow, member variables --- .../common/nebula_ros_wrapper_base.hpp | 68 --- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 110 ++--- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 436 ++++++++---------- 3 files changed, 230 insertions(+), 384 deletions(-) delete mode 100644 nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp diff --git a/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp b/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp deleted file mode 100644 index 5aaeb634b..000000000 --- a/nebula_ros/include/nebula_ros/common/nebula_ros_wrapper_base.hpp +++ /dev/null @@ -1,68 +0,0 @@ -#pragma once - -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" - -#include -#include -#include - -#include - -#include -#include - -namespace nebula -{ -namespace ros -{ -/// @brief Base class for ros wrapper of each sensor driver -class NebulaRosWrapperBase -{ -public: - NebulaRosWrapperBase() = default; - - NebulaRosWrapperBase(NebulaRosWrapperBase && c) = delete; - NebulaRosWrapperBase & operator=(NebulaRosWrapperBase && c) = delete; - NebulaRosWrapperBase(const NebulaRosWrapperBase & c) = delete; - NebulaRosWrapperBase & operator=(const NebulaRosWrapperBase & c) = delete; - - /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) - /// @return Resulting status - virtual Status StreamStart() = 0; - - /// @brief Stop point cloud streaming (not used) - /// @return Resulting status - virtual Status StreamStop() = 0; - - /// @brief Shutdown (not used) - /// @return Resulting status - virtual Status Shutdown() = 0; - -private: - /// @brief Virtual function for initializing hardware interface ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - virtual Status InitializeHwInterface( - const drivers::SensorConfigurationBase & sensor_configuration) = 0; - - /// @brief Virtual function for initializing hardware monitor ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - virtual Status InitializeHwMonitor( - const drivers::SensorConfigurationBase & sensor_configuration) = 0; - - /// @brief Virtual function for initializing ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @return Resulting status - virtual Status InitializeCloudDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) = 0; - - /// @brief Point cloud publisher - rclcpp::Publisher::SharedPtr cloud_pub_; -}; - -} // namespace ros -} // namespace nebula diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index b2cbd04dc..2ba2e2407 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -8,9 +8,7 @@ // #include "nebula_common/util/topic_delay.hpp" #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" -#include "nebula_ros/common/nebula_hw_interface_ros_wrapper_base.hpp" -#include "nebula_ros/common/nebula_hw_monitor_ros_wrapper_base.hpp" -#include "nebula_ros/common/nebula_ros_wrapper_base.hpp" +#include "nebula_ros/hesai/mt_queue.hpp" #include #include @@ -28,8 +26,6 @@ #include #include -#include "nebula_ros/hesai/mt_queue.hpp" - namespace nebula { namespace ros @@ -55,7 +51,7 @@ bool get_param(const std::vector & p, const std::string & nam } /// @brief Ros wrapper of hesai driver -class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase +class HesaiRosWrapper final : public rclcpp::Node { public: explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); @@ -67,36 +63,17 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase /// @brief Start point cloud streaming (Call CloudInterfaceStart of HwInterface) /// @return Resulting status - Status StreamStart() override; - /// @brief Stop point cloud streaming (not used) - /// @return Resulting status - Status StreamStop() override; - /// @brief Shutdown (not used) - /// @return Resulting status - Status Shutdown() override; + Status StreamStart(); private: - /// @brief Initialize pointcloud decoder - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver (only for AT128, ignored otherwise) - /// @return Resulting status - Status InitializeCloudDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration = nullptr); - - Status InitializeCloudDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) { - return InitializeCloudDriver(sensor_configuration, calibration_configuration, nullptr); - } + Status InitializeHwInterface(); + Status InitializeDecoder(); + Status InitializeHwMonitor(); /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration /// @return Resulting status - Status GetParameters( - drivers::HesaiSensorConfiguration & sensor_configuration); + Status GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration); /// @brief Get calibration data from the sensor /// @param calibration_configuration Output of CalibrationConfiguration @@ -124,11 +101,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::unique_ptr pointcloud, const rclcpp::Publisher::SharedPtr & publisher); - /// @brief Initializing hardware interface ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - Status InitializeHwInterface( - const drivers::SensorConfigurationBase & sensor_configuration) override; /// @brief Callback for receiving a raw UDP packet /// @param scan_buffer Received PandarScan void ReceiveCloudPacketCallback(std::vector & scan_buffer); @@ -146,12 +118,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase /// @return SetParametersResult std::vector updateParameters(); - /// @brief Initializing hardware monitor ros wrapper - /// @param sensor_configuration SensorConfiguration for this driver - /// @return Resulting status - Status InitializeHwMonitor( - const drivers::SensorConfigurationBase & sensor_configuration) override; - /// @brief Initializing diagnostics void InitializeHesaiDiagnostics(); /// @brief Callback of the timer for getting the current lidar status @@ -193,7 +159,10 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::string GetFixedPrecisionString(double val, int pre = 2); std::shared_ptr driver_ptr_; + drivers::HesaiHwInterface hw_interface_; + Status wrapper_status_; + Status interface_status_; rclcpp::Publisher::SharedPtr nebula_points_pub_; rclcpp::Publisher::SharedPtr aw_points_ex_pub_; @@ -203,15 +172,15 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase std::shared_ptr sensor_cfg_ptr_; std::shared_ptr correction_cfg_ptr_; + /// @brief Stores received packets that have not been processed yet by the decoder thread mt_queue> packet_queue_; + /// @brief Thread to isolate decoding from receiving std::thread decoder_thread_; - Status interface_status_; - - //todo: temporary class member during single node refactoring + // todo: temporary class member during single node refactoring bool launch_hw_; - //todo: temporary class member during single node refactoring + // todo: temporary class member during single node refactoring std::string calibration_file_path; /// @brief File path of Correction data (Only required only for AT) std::string correction_file_path; @@ -219,9 +188,6 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase /// @brief Received Hesai message publisher rclcpp::Publisher::SharedPtr pandar_scan_pub_; - drivers::HesaiHwInterface hw_interface_; - - uint16_t delay_hw_ms_; bool retry_hw_; std::mutex mtx_config_; OnSetParametersCallbackHandle::SharedPtr set_param_res_; @@ -229,39 +195,35 @@ class HesaiRosWrapper final : public rclcpp::Node, NebulaRosWrapperBase diagnostic_updater::Updater diagnostics_updater_; rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; - rclcpp::TimerBase::SharedPtr diagnostics_update_monitor_timer_; rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_; - std::unique_ptr current_status; - std::unique_ptr current_monitor; - std::unique_ptr current_config; - std::unique_ptr current_inventory; - std::unique_ptr current_lidar_monitor_tree; - std::unique_ptr current_status_time; - std::unique_ptr current_config_time; - std::unique_ptr current_inventory_time; - std::unique_ptr current_lidar_monitor_time; - uint8_t current_diag_status; - uint8_t current_monitor_status; - uint16_t diag_span_; - uint16_t delay_monitor_ms_; - std::mutex mtx_diag; - std::mutex mtx_status; - std::mutex mtx_lidar_monitor; + std::unique_ptr current_status_; + std::unique_ptr current_monitor_; + std::unique_ptr current_config_; + std::unique_ptr current_inventory_; + std::unique_ptr current_lidar_monitor_tree_; + + std::unique_ptr current_status_time_; + std::unique_ptr current_config_time_; + std::unique_ptr current_inventory_time_; + std::unique_ptr current_lidar_monitor_time_; - std::string info_model; - std::string info_serial; - rclcpp::CallbackGroup::SharedPtr cbg_r_; - rclcpp::CallbackGroup::SharedPtr cbg_m_; - rclcpp::CallbackGroup::SharedPtr cbg_m2_; + uint8_t current_diag_status_; + uint8_t current_monitor_status_; + + uint16_t diag_span_; + std::mutex mtx_lidar_status_; + std::mutex mtx_lidar_monitor_; - const char * not_supported_message; - const char * error_message; - std::string message_sep; + std::string info_model_; + std::string info_serial_; - std::vector temperature_names; + std::vector temperature_names_; bool setup_sensor; + const std::string MSG_NOT_SUPPORTED = "Not supported"; + const std::string MSG_ERROR = "Error"; + const std::string MSG_SEP = ": "; }; } // namespace ros diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 1540df3fa..f0e6c121a 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -7,115 +7,164 @@ namespace ros HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), hw_interface_(), - diagnostics_updater_(this), - packet_queue_(3000) + packet_queue_(3000), + diagnostics_updater_(this) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); drivers::HesaiSensorConfiguration sensor_configuration; wrapper_status_ = GetParameters(sensor_configuration); sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + // DeclareRosParameters(); + // auto sensor_cfg_ptr = GetRosParameters(); + InitializeHwInterface(); + InitializeDecoder(); + InitializeHwMonitor(); + // StreamStart(); - // hwiface - { - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return; - } - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - Status rt = hw_interface_.InitializeTcpDriver(); - if (this->retry_hw_) { - int cnt = 0; - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - while (rt == Status::ERROR_1) { - cnt++; - std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << cnt); - rt = hw_interface_.InitializeTcpDriver(); - } + + RCLCPP_DEBUG(this->get_logger(), "Starting stream"); + StreamStart(); + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + + set_param_res_ = this->add_on_set_parameters_callback( + std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); +} + +Status HesaiRosWrapper::InitializeHwInterface() +{ + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return interface_status_; + } + hw_interface_.SetLogger(std::make_shared(this->get_logger())); + hw_interface_.SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); + + Status status; + int retry_count = 0; + + while (true) { + status = hw_interface_.InitializeTcpDriver(); + if (status == Status::OK || !retry_hw_) { + break; } - if (rt != Status::ERROR_1) { - try { - std::vector thread_pool{}; - thread_pool.emplace_back([this] { - auto result = hw_interface_.GetInventory(); - RCLCPP_INFO_STREAM(get_logger(), result); - hw_interface_.SetTargetModel(result.model); - }); - for (std::thread & th : thread_pool) { - th.join(); - } + retry_count++; + std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << retry_count); + }; - } catch (...) { - std::cout << "catch (...) in parent" << std::endl; - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); - } - if (this->setup_sensor) { - hw_interface_.CheckAndSetConfig(); - updateParameters(); - } - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); - hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); + if (status == Status::OK) { + try { + auto inventory = hw_interface_.GetInventory(); + RCLCPP_INFO_STREAM(get_logger(), inventory); + hw_interface_.SetTargetModel(inventory.model); + } catch (...) { + RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); } + if (this->setup_sensor) { + hw_interface_.CheckAndSetConfig(); + updateParameters(); + } + } else { + RCLCPP_ERROR_STREAM( + get_logger(), + "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); + hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); } - // decoder - { - drivers::HesaiCalibrationConfiguration calibration_configuration; - drivers::HesaiCorrection correction_configuration; - wrapper_status_ = GetCalibrationData(calibration_configuration, correction_configuration); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return; - } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - - calibration_cfg_ptr_ = - std::make_shared(calibration_configuration); - // Will be left empty for AT128, and ignored by all decoders except AT128 - correction_cfg_ptr_ = std::make_shared(correction_configuration); - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - wrapper_status_ = InitializeCloudDriver( - std::static_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); - - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto pointcloud_qos = - rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - - decoder_thread_ = std::thread([this](){ - while(true) { - auto pkt = packet_queue_.pop(); - this->ProcessCloudPacket(std::move(pkt)); - } - }); + return Status::OK; +} + +Status HesaiRosWrapper::InitializeDecoder() +{ + calibration_cfg_ptr_ = std::make_shared(); + correction_cfg_ptr_ = std::make_shared(); - nebula_points_pub_ = - this->create_publisher("pandar_points", pointcloud_qos); - aw_points_base_pub_ = - this->create_publisher("aw_points", pointcloud_qos); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", pointcloud_qos); + wrapper_status_ = GetCalibrationData(*calibration_cfg_ptr_, *correction_cfg_ptr_); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return wrapper_status_; } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); + rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; + auto pointcloud_qos = + rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + + decoder_thread_ = std::thread([this]() { + while (true) { + auto pkt = packet_queue_.pop(); + this->ProcessCloudPacket(std::move(pkt)); + } + }); - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + nebula_points_pub_ = + this->create_publisher("pandar_points", pointcloud_qos); + aw_points_base_pub_ = + this->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = + this->create_publisher("aw_points_ex", pointcloud_qos); - InitializeHwMonitor(*sensor_cfg_ptr_); + driver_ptr_ = std::make_shared( + sensor_cfg_ptr_, calibration_cfg_ptr_, correction_cfg_ptr_); + return driver_ptr_->GetStatus(); +} - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); +Status HesaiRosWrapper::InitializeHwMonitor() +{ + if (Status::OK != interface_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); + return Status::ERROR_1; + } + + switch (sensor_cfg_ptr_->sensor_model) { + case nebula::drivers::SensorModel::HESAI_PANDARXT32: + case nebula::drivers::SensorModel::HESAI_PANDARXT32M: + case nebula::drivers::SensorModel::HESAI_PANDARAT128: + temperature_names_.emplace_back("Bottom circuit board T1"); + temperature_names_.emplace_back("Bottom circuit board T2"); + temperature_names_.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names_.emplace_back("Laser emitting board RT_L2"); + temperature_names_.emplace_back("Receiving board RT_R"); + temperature_names_.emplace_back("Receiving board RT2"); + temperature_names_.emplace_back("Top circuit RT3"); + temperature_names_.emplace_back("Not used"); + break; + case nebula::drivers::SensorModel::HESAI_PANDAR64: + case nebula::drivers::SensorModel::HESAI_PANDAR40P: + case nebula::drivers::SensorModel::HESAI_PANDAR40M: + case nebula::drivers::SensorModel::HESAI_PANDARQT64: + case nebula::drivers::SensorModel::HESAI_PANDARQT128: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: + default: + temperature_names_.emplace_back("Bottom circuit RT1"); + temperature_names_.emplace_back("Bottom circuit RT2"); + temperature_names_.emplace_back("Internal Temperature"); + temperature_names_.emplace_back("Laser emitting board RT1"); + temperature_names_.emplace_back("Laser emitting board RT2"); + temperature_names_.emplace_back("Receiving board RT1"); + temperature_names_.emplace_back("Top circuit RT1"); + temperature_names_.emplace_back("Top circuit RT2"); + break; + } + + auto result = hw_interface_.GetInventory(); + current_inventory_.reset(new HesaiInventory(result)); + current_inventory_time_.reset(new rclcpp::Time(this->get_clock()->now())); + std::cout << "HesaiInventory" << std::endl; + std::cout << result << std::endl; + info_model_ = result.get_str_model(); + info_serial_ = std::string(result.sn.begin(), result.sn.end()); + hw_interface_.SetTargetModel(result.model); + RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model_); + RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial_); + InitializeHesaiDiagnostics(); + return Status::OK; } void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) @@ -227,18 +276,6 @@ void HesaiRosWrapper::PublishCloud( publisher->publish(std::move(pointcloud)); } -Status HesaiRosWrapper::InitializeCloudDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) -{ - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration), - std::static_pointer_cast(correction_configuration)); - return driver_ptr_->GetStatus(); -} - Status HesaiRosWrapper::GetStatus() { return wrapper_status_; @@ -766,85 +803,6 @@ Status HesaiRosWrapper::StreamStart() return interface_status_; } -Status HesaiRosWrapper::StreamStop() -{ - return Status::OK; -} -Status HesaiRosWrapper::Shutdown() -{ - return Status::OK; -} - -Status HesaiRosWrapper::InitializeHwInterface( // todo: don't think this is needed - const drivers::SensorConfigurationBase & sensor_configuration) -{ - std::stringstream ss; - ss << sensor_configuration; - RCLCPP_DEBUG_STREAM(this->get_logger(), ss.str()); - return Status::OK; -} - -Status HesaiRosWrapper::InitializeHwMonitor( // todo: don't think this is needed - const drivers::SensorConfigurationBase & /* sensor_configuration */) -{ - cbg_r_ = create_callback_group(rclcpp::CallbackGroupType::Reentrant); - cbg_m_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - cbg_m2_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return Status::ERROR_1; - } - - message_sep = ": "; - not_supported_message = "Not supported"; - error_message = "Error"; - - switch (sensor_cfg_ptr_->sensor_model) { - case nebula::drivers::SensorModel::HESAI_PANDARXT32: - case nebula::drivers::SensorModel::HESAI_PANDARXT32M: - case nebula::drivers::SensorModel::HESAI_PANDARAT128: - temperature_names.emplace_back("Bottom circuit board T1"); - temperature_names.emplace_back("Bottom circuit board T2"); - temperature_names.emplace_back("Laser emitting board RT_L1(Internal)"); - temperature_names.emplace_back("Laser emitting board RT_L2"); - temperature_names.emplace_back("Receiving board RT_R"); - temperature_names.emplace_back("Receiving board RT2"); - temperature_names.emplace_back("Top circuit RT3"); - temperature_names.emplace_back("Not used"); - break; - case nebula::drivers::SensorModel::HESAI_PANDAR64: - case nebula::drivers::SensorModel::HESAI_PANDAR40P: - case nebula::drivers::SensorModel::HESAI_PANDAR40M: - case nebula::drivers::SensorModel::HESAI_PANDARQT64: - case nebula::drivers::SensorModel::HESAI_PANDARQT128: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: - default: - temperature_names.emplace_back("Bottom circuit RT1"); - temperature_names.emplace_back("Bottom circuit RT2"); - temperature_names.emplace_back("Internal Temperature"); - temperature_names.emplace_back("Laser emitting board RT1"); - temperature_names.emplace_back("Laser emitting board RT2"); - temperature_names.emplace_back("Receiving board RT1"); - temperature_names.emplace_back("Top circuit RT1"); - temperature_names.emplace_back("Top circuit RT2"); - break; - } - - auto result = hw_interface_.GetInventory(); - current_inventory.reset(new HesaiInventory(result)); - current_inventory_time.reset(new rclcpp::Time(this->get_clock()->now())); - std::cout << "HesaiInventory" << std::endl; - std::cout << result << std::endl; - info_model = result.get_str_model(); - info_serial = std::string(result.sn.begin(), result.sn.end()); - hw_interface_.SetTargetModel(result.model); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial); - InitializeHesaiDiagnostics(); - return Status::OK; -} - rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( const std::vector & p) { @@ -926,7 +884,7 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() RCLCPP_INFO_STREAM(this->get_logger(), "InitializeHesaiDiagnostics"); using std::chrono_literals::operator""s; std::ostringstream os; - auto hardware_id = info_model + ": " + info_serial; + auto hardware_id = info_model_ + ": " + info_serial_; diagnostics_updater_.setHardwareID(hardware_id); RCLCPP_INFO_STREAM(this->get_logger(), "hardware_id: " + hardware_id); @@ -935,12 +893,12 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() diagnostics_updater_.add("hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); diagnostics_updater_.add("hesai_rpm", this, &HesaiRosWrapper::HesaiCheckRpm); - current_status.reset(); - current_monitor.reset(); - current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_status_.reset(); + current_monitor_.reset(); + current_status_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; auto fetch_diag_from_sensor = [this]() { OnHesaiStatusTimer(); @@ -952,10 +910,7 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() }; fetch_diagnostics_timer_ = - std::make_shared>( - this->get_clock(), std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(fetch_diagnostics_timer_, cbg_m_); + create_wall_timer(std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor)); if (hw_interface_.UseHttpGetLidarMonitor()) { diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); @@ -966,32 +921,30 @@ void HesaiRosWrapper::InitializeHesaiDiagnostics() auto on_timer_update = [this] { RCLCPP_DEBUG_STREAM(get_logger(), "OnUpdateTimer"); auto now = this->get_clock()->now(); - auto dif = (now - *current_status_time).seconds(); + auto dif = (now - *current_status_time_).seconds(); RCLCPP_DEBUG_STREAM(get_logger(), "dif(status): " << dif); if (diag_span_ * 2.0 < dif * 1000) { - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); } else { - current_diag_status = diagnostic_msgs::msg::DiagnosticStatus::OK; + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; RCLCPP_DEBUG_STREAM(get_logger(), "OK"); } - dif = (now - *current_lidar_monitor_time).seconds(); + dif = (now - *current_lidar_monitor_time_).seconds(); RCLCPP_DEBUG_STREAM(get_logger(), "dif(monitor): " << dif); if (diag_span_ * 2.0 < dif * 1000) { - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); } else { - current_monitor_status = diagnostic_msgs::msg::DiagnosticStatus::OK; + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; RCLCPP_DEBUG_STREAM(get_logger(), "OK"); } diagnostics_updater_.force_update(); }; - diagnostics_update_timer_ = std::make_shared>( - this->get_clock(), std::chrono::milliseconds(1000), std::move(on_timer_update), - this->get_node_base_interface()->get_context()); - this->get_node_timers_interface()->add_timer(diagnostics_update_timer_, cbg_r_); + diagnostics_update_timer_ = + create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); RCLCPP_DEBUG_STREAM(get_logger(), "add_timer"); } @@ -1003,7 +956,7 @@ std::string HesaiRosWrapper::GetPtreeValue( if (value) { return value.get(); } else { - return not_supported_message; + return MSG_NOT_SUPPORTED; } } std::string HesaiRosWrapper::GetFixedPrecisionString(double val, int pre) @@ -1018,9 +971,9 @@ void HesaiRosWrapper::OnHesaiStatusTimer() RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer" << std::endl); try { auto result = hw_interface_.GetLidarStatus(); - std::scoped_lock lock(mtx_status); - current_status_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_status.reset(new HesaiLidarStatus(result)); + std::scoped_lock lock(mtx_lidar_status_); + current_status_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_status_.reset(new HesaiLidarStatus(result)); } catch (const std::system_error & error) { RCLCPP_ERROR_STREAM( rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), error.what()); @@ -1037,9 +990,9 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp() RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp"); try { hw_interface_.GetLidarMonitorAsyncHttp([this](const std::string & str) { - std::scoped_lock lock(mtx_lidar_monitor); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_tree = + std::scoped_lock lock(mtx_lidar_monitor_); + current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_lidar_monitor_tree_ = std::make_unique(hw_interface_.ParseJson(str)); }); } catch (const std::system_error & error) { @@ -1059,11 +1012,10 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimer() { RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer"); try { - auto ios = std::make_shared(); auto result = hw_interface_.GetLidarMonitor(); - std::scoped_lock lock(mtx_lidar_monitor); - current_lidar_monitor_time.reset(new rclcpp::Time(this->get_clock()->now())); - current_monitor.reset(new HesaiLidarMonitor(result)); + std::scoped_lock lock(mtx_lidar_monitor_); + current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); + current_monitor_.reset(new HesaiLidarMonitor(result)); } catch (const std::system_error & error) { RCLCPP_ERROR_STREAM( rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), @@ -1078,14 +1030,14 @@ void HesaiRosWrapper::OnHesaiLidarMonitorTimer() void HesaiRosWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_status); - if (current_status) { + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - diagnostics.add("system_uptime", std::to_string(current_status->system_uptime)); - diagnostics.add("startup_times", std::to_string(current_status->startup_times)); - diagnostics.add("total_operation_time", std::to_string(current_status->total_operation_time)); + diagnostics.add("system_uptime", std::to_string(current_status_->system_uptime)); + diagnostics.add("startup_times", std::to_string(current_status_->startup_times)); + diagnostics.add("total_operation_time", std::to_string(current_status_->total_operation_time)); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -1095,13 +1047,13 @@ void HesaiRosWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapp void HesaiRosWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_status); - if (current_status) { + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - auto gps_status = current_status->get_str_gps_pps_lock(); - auto gprmc_status = current_status->get_str_gps_gprmc_status(); - auto ptp_status = current_status->get_str_ptp_clock_status(); + auto gps_status = current_status_->get_str_gps_pps_lock(); + auto gprmc_status = current_status_->get_str_gps_gprmc_status(); + auto ptp_status = current_status_->get_str_ptp_clock_status(); std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); @@ -1129,13 +1081,13 @@ void HesaiRosWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper void HesaiRosWrapper::HesaiCheckTemperature( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_status); - if (current_status) { + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - for (size_t i = 0; i < current_status->temperature.size(); i++) { + for (size_t i = 0; i < current_status_->temperature.size(); i++) { diagnostics.add( - temperature_names[i], GetFixedPrecisionString(current_status->temperature[i] * 0.01)); + temperature_names_[i], GetFixedPrecisionString(current_status_->temperature[i] * 0.01)); } diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -1145,11 +1097,11 @@ void HesaiRosWrapper::HesaiCheckTemperature( void HesaiRosWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_status); - if (current_status) { + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - diagnostics.add("motor_speed", std::to_string(current_status->motor_speed)); + diagnostics.add("motor_speed", std::to_string(current_status_->motor_speed)); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { @@ -1160,8 +1112,8 @@ void HesaiRosWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper void HesaiRosWrapper::HesaiCheckVoltageHttp( diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_lidar_monitor); - if (current_lidar_monitor_tree) { + std::scoped_lock lock(mtx_lidar_monitor_); + if (current_lidar_monitor_tree_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; std::string key = ""; @@ -1169,18 +1121,18 @@ void HesaiRosWrapper::HesaiCheckVoltageHttp( std::string mes; key = "lidarInCur"; try { - mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); + mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); } catch (boost::bad_lexical_cast & ex) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = error_message + std::string(ex.what()); + mes = MSG_ERROR + std::string(ex.what()); } diagnostics.add(key, mes); key = "lidarInVol"; try { - mes = GetPtreeValue(current_lidar_monitor_tree.get(), "Body." + key); + mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); } catch (boost::bad_lexical_cast & ex) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = error_message + std::string(ex.what()); + mes = MSG_ERROR + std::string(ex.what()); } diagnostics.add(key, mes); @@ -1192,16 +1144,16 @@ void HesaiRosWrapper::HesaiCheckVoltageHttp( void HesaiRosWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { - std::scoped_lock lock(mtx_lidar_monitor); - if (current_monitor) { + std::scoped_lock lock(mtx_lidar_monitor_); + if (current_monitor_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; diagnostics.add( - "input_voltage", GetFixedPrecisionString(current_monitor->input_voltage * 0.01) + " V"); + "input_voltage", GetFixedPrecisionString(current_monitor_->input_voltage * 0.01) + " V"); diagnostics.add( - "input_current", GetFixedPrecisionString(current_monitor->input_current * 0.01) + " mA"); + "input_current", GetFixedPrecisionString(current_monitor_->input_current * 0.01) + " mA"); diagnostics.add( - "input_power", GetFixedPrecisionString(current_monitor->input_power * 0.01) + " W"); + "input_power", GetFixedPrecisionString(current_monitor_->input_power * 0.01) + " W"); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); } else { From 162e7546359f8d35074762bca2a26f16d0930dd0 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 28 Mar 2024 20:10:51 +0900 Subject: [PATCH 085/122] fix(hesai_hw_interface): add error handling * check PTC command error codes, throw exception if necessary * perform size checks before parsing responses * emit errors on too-large payload size --- .../nebula_hw_interfaces_hesai/hesai_cmd_response.hpp | 2 +- .../nebula_hw_interfaces_hesai/hesai_hw_interface.hpp | 1 + .../src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp | 1 - 3 files changed, 2 insertions(+), 2 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp index a6d78c45e..2691def33 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp @@ -124,7 +124,7 @@ struct HesaiPtpDiagGrandmaster { os << "clockQuality: " << arg.clockQuality; os << ", "; - os << "utc_offset: " << arg.utc_offset; + os << "utc_offset: " << static_cast(arg.utc_offset.value()); os << ", "; os << "time_flags: " << +arg.time_flags; os << ", "; diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index d71a26998..84750bcb2 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -102,6 +102,7 @@ const int PTP_LOG_MIN_DELAY_INTERVAL = 0; const int HESAI_LIDAR_GPS_CLOCK_SOURCE = 0; const int HESAI_LIDAR_PTP_CLOCK_SOURCE = 1; + /// @brief Hardware interface of hesai driver class HesaiHwInterface : NebulaHwInterfaceBase { diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index e37d42a43..c70bd4400 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -68,7 +68,6 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( auto recv_buf = std::make_shared>(); auto response_complete = std::make_shared(false); - // Low byte is for PTC error code, the rest is nebula-specific auto error_code = std::make_shared(); std::stringstream ss; From 9bdadd2736e23903a6119f78e2649786116a844a Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 15:14:44 +0900 Subject: [PATCH 086/122] fix(hesai_hw_monitor_ros_wrapper): fixed wrong range given for S/N copy --- ros2_socketcan | 1 + transport_drivers | 1 + 2 files changed, 2 insertions(+) create mode 160000 ros2_socketcan create mode 160000 transport_drivers diff --git a/ros2_socketcan b/ros2_socketcan new file mode 160000 index 000000000..4ced5284f --- /dev/null +++ b/ros2_socketcan @@ -0,0 +1 @@ +Subproject commit 4ced5284fdd080274b04530406d887e8330a0cdb diff --git a/transport_drivers b/transport_drivers new file mode 160000 index 000000000..abf8aa8e1 --- /dev/null +++ b/transport_drivers @@ -0,0 +1 @@ +Subproject commit abf8aa8e171f33e0acd6d845c3d795192c964e9c From 49e03d4b046801dd32fe29fedab2138ae4820456 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 8 Apr 2024 16:26:42 +0900 Subject: [PATCH 087/122] fix(hesai): print uint8, uint16 as numbers --- .../nebula_hw_interfaces_hesai/hesai_cmd_response.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp index 2691def33..a6d78c45e 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp @@ -124,7 +124,7 @@ struct HesaiPtpDiagGrandmaster { os << "clockQuality: " << arg.clockQuality; os << ", "; - os << "utc_offset: " << static_cast(arg.utc_offset.value()); + os << "utc_offset: " << arg.utc_offset; os << ", "; os << "time_flags: " << +arg.time_flags; os << ", "; From bc718eff835aa9741ff1ed5f309d0ed83823d938 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 9 Apr 2024 18:45:41 +0900 Subject: [PATCH 088/122] feat(hesai_ros_wrapper): publish/subscribe to legacy pandar_packets on demand --- .../hesai_hw_interface.hpp | 8 +- .../hesai_hw_interface.cpp | 70 ++---------- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 52 +++++---- .../include/nebula_ros/hesai/mt_queue.hpp | 13 ++- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 101 +++++++++++++----- 5 files changed, 124 insertions(+), 120 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index 84750bcb2..0bf3a864b 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -104,7 +104,7 @@ const int HESAI_LIDAR_PTP_CLOCK_SOURCE = 1; /// @brief Hardware interface of hesai driver -class HesaiHwInterface : NebulaHwInterfaceBase +class HesaiHwInterface : public NebulaHwInterfaceBase { private: struct ptc_error_t @@ -122,12 +122,6 @@ class HesaiHwInterface : NebulaHwInterfaceBase std::unique_ptr<::drivers::udp_driver::UdpDriver> cloud_udp_driver_; std::shared_ptr<::drivers::tcp_driver::TcpDriver> tcp_driver_; std::shared_ptr sensor_configuration_; - std::shared_ptr calibration_configuration_; - size_t azimuth_index_{}; - size_t mtu_size_{}; - std::unique_ptr scan_cloud_ptr_; - std::function - is_valid_packet_; /*Lambda Function Array to verify proper packet size*/ std::function & buffer)> cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index c70bd4400..451b2a9d3 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -17,8 +17,7 @@ HesaiHwInterface::HesaiHwInterface() : cloud_io_context_{new ::drivers::common::IoContext(1)}, m_owned_ctx{new boost::asio::io_context(1)}, cloud_udp_driver_{new ::drivers::udp_driver::UdpDriver(*cloud_io_context_)}, - tcp_driver_{new ::drivers::tcp_driver::TcpDriver(m_owned_ctx)}, - scan_cloud_ptr_{std::make_unique()} + tcp_driver_{new ::drivers::tcp_driver::TcpDriver(m_owned_ctx)} { } HesaiHwInterface::~HesaiHwInterface() @@ -145,63 +144,8 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( Status HesaiHwInterface::SetSensorConfiguration( std::shared_ptr sensor_configuration) { - HesaiStatus status = Status::OK; - mtu_size_ = MTU_SIZE; - is_solid_state = false; - try { - sensor_configuration_ = - std::static_pointer_cast(sensor_configuration); - if ( - sensor_configuration_->sensor_model == SensorModel::HESAI_PANDAR40P || - sensor_configuration_->sensor_model == SensorModel::HESAI_PANDAR40P) { - azimuth_index_ = 2; - is_valid_packet_ = [](size_t packet_size) { - return ( - packet_size == PANDAR40_PACKET_SIZE || packet_size == PANDAR40P_EXTENDED_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARQT64) { - azimuth_index_ = 12; // 12 + 258 * [0-3] - is_valid_packet_ = [](size_t packet_size) { return (packet_size == PANDARQT64_PACKET_SIZE); }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARQT128) { - azimuth_index_ = 12; // 12 + 514 * [0-1] - is_valid_packet_ = [](size_t packet_size) { - return (packet_size == PANDARQT128_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARXT32) { - azimuth_index_ = 12; // 12 + 130 * [0-7] - is_valid_packet_ = [](size_t packet_size) { return (packet_size == PANDARXT32_PACKET_SIZE); }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARXT32M) { - azimuth_index_ = 12; // 12 + 130 * [0-7] - is_valid_packet_ = [](size_t packet_size) { - return (packet_size == PANDARXT32M_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDARAT128) { - azimuth_index_ = 12; // 12 + 4 * 128 * [0-1] - is_solid_state = true; - is_valid_packet_ = [](size_t packet_size) { - return (packet_size == PANDARAT128_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDAR64) { - azimuth_index_ = 8; // 8 + 192 * [0-5] - is_valid_packet_ = [](size_t packet_size) { - return ( - packet_size == PANDAR64_PACKET_SIZE || packet_size == PANDAR64_EXTENDED_PACKET_SIZE); - }; - } else if (sensor_configuration_->sensor_model == SensorModel::HESAI_PANDAR128_E4X) { - azimuth_index_ = 12; // 12 - is_valid_packet_ = [](size_t packet_size) { - return ( - packet_size == PANDAR128_E4X_EXTENDED_PACKET_SIZE || - packet_size == PANDAR128_E4X_PACKET_SIZE); - }; - } else { - status = Status::INVALID_SENSOR_MODEL; - } - } catch (const std::exception & ex) { - status = Status::SENSOR_CONFIG_ERROR; - std::cerr << status << std::endl; - return status; - } + sensor_configuration_ = + std::static_pointer_cast(sensor_configuration); return Status::OK; } @@ -246,10 +190,6 @@ Status HesaiHwInterface::RegisterScanCallback( void HesaiHwInterface::ReceiveSensorPacketCallback(std::vector & buffer) { - // if (!is_valid_packet_(buffer.size())) { - // PrintDebug("Invalid Packet: " + std::to_string(buffer.size())); - // return; - // } TODO cloud_packet_callback_(buffer); } Status HesaiHwInterface::SensorInterfaceStop() @@ -301,7 +241,9 @@ Status HesaiHwInterface::InitializeTcpDriver() Status HesaiHwInterface::FinalizeTcpDriver() { try { - tcp_driver_->close(); + if (tcp_driver_) { + tcp_driver_->close(); + } } catch (std::exception & e) { PrintError("Error while finalizing the TcpDriver"); return Status::UDP_CONNECTION_ERROR; diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 2ba2e2407..9c50e20eb 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -16,6 +16,8 @@ #include #include "nebula_msgs/msg/nebula_packet.hpp" +#include "pandar_msgs/msg/pandar_packet.hpp" +#include "pandar_msgs/msg/pandar_scan.hpp" #include #include @@ -105,6 +107,10 @@ class HesaiRosWrapper final : public rclcpp::Node /// @param scan_buffer Received PandarScan void ReceiveCloudPacketCallback(std::vector & scan_buffer); + /// @brief Callback for receiving replayed, aggregated packets (= scan messages) + /// @param scan_msg + void ReceiveScanMessageCallback(std::unique_ptr scan_msg); + /// @brief Decodes a nebula packet and, if it completes the scan, publishes the pointcloud. /// @param packet_msg The received packet message void ProcessCloudPacket(std::unique_ptr packet_msg); @@ -158,19 +164,23 @@ class HesaiRosWrapper final : public rclcpp::Node /// @return Created string std::string GetFixedPrecisionString(double val, int pre = 2); - std::shared_ptr driver_ptr_; - drivers::HesaiHwInterface hw_interface_; + std::shared_ptr driver_ptr_{}; + drivers::HesaiHwInterface hw_interface_{}; Status wrapper_status_; Status interface_status_; - rclcpp::Publisher::SharedPtr nebula_points_pub_; - rclcpp::Publisher::SharedPtr aw_points_ex_pub_; - rclcpp::Publisher::SharedPtr aw_points_base_pub_; + rclcpp::Subscription::SharedPtr packets_sub_{}; + rclcpp::Publisher::SharedPtr packets_pub_{}; + pandar_msgs::msg::PandarScan::UniquePtr current_scan_msg_{}; + + rclcpp::Publisher::SharedPtr nebula_points_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; - std::shared_ptr calibration_cfg_ptr_; - std::shared_ptr sensor_cfg_ptr_; - std::shared_ptr correction_cfg_ptr_; + std::shared_ptr calibration_cfg_ptr_{}; + std::shared_ptr sensor_cfg_ptr_{}; + std::shared_ptr correction_cfg_ptr_{}; /// @brief Stores received packets that have not been processed yet by the decoder thread mt_queue> packet_queue_; @@ -186,27 +196,27 @@ class HesaiRosWrapper final : public rclcpp::Node std::string correction_file_path; /// @brief Received Hesai message publisher - rclcpp::Publisher::SharedPtr pandar_scan_pub_; + rclcpp::Publisher::SharedPtr pandar_scan_pub_{}; bool retry_hw_; std::mutex mtx_config_; - OnSetParametersCallbackHandle::SharedPtr set_param_res_; + OnSetParametersCallbackHandle::SharedPtr set_param_res_{}; diagnostic_updater::Updater diagnostics_updater_; - rclcpp::TimerBase::SharedPtr diagnostics_update_timer_; - rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_; + rclcpp::TimerBase::SharedPtr diagnostics_update_timer_{}; + rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_{}; - std::unique_ptr current_status_; - std::unique_ptr current_monitor_; - std::unique_ptr current_config_; - std::unique_ptr current_inventory_; - std::unique_ptr current_lidar_monitor_tree_; + std::unique_ptr current_status_{}; + std::unique_ptr current_monitor_{}; + std::unique_ptr current_config_{}; + std::unique_ptr current_inventory_{}; + std::unique_ptr current_lidar_monitor_tree_{}; - std::unique_ptr current_status_time_; - std::unique_ptr current_config_time_; - std::unique_ptr current_inventory_time_; - std::unique_ptr current_lidar_monitor_time_; + std::unique_ptr current_status_time_{}; + std::unique_ptr current_config_time_{}; + std::unique_ptr current_inventory_time_{}; + std::unique_ptr current_lidar_monitor_time_{}; uint8_t current_diag_status_; uint8_t current_monitor_status_; diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp index 730b54f7c..67b287ddc 100644 --- a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -16,7 +16,7 @@ class mt_queue public: mt_queue(size_t capacity) : capacity_(capacity) {} - bool push(T && value) + bool try_push(T && value) { { std::unique_lock lock(this->mutex_); @@ -29,6 +29,17 @@ class mt_queue this->condition_variable_.notify_one(); return true; } + + void push(T && value) + { + { + std::unique_lock lock(this->mutex_); + this->condition_variable_.wait(lock, [=] { return this->queue_.size() < this->capacity_; }); + queue_.push_front(std::move(value)); + } + this->condition_variable_.notify_one(); + } + T pop() { std::unique_lock lock(this->mutex_); diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index f0e6c121a..0fe4e7bd3 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -7,26 +7,29 @@ namespace ros HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), hw_interface_(), + wrapper_status_(Status::NOT_INITIALIZED), + interface_status_(Status::NOT_INITIALIZED), packet_queue_(3000), diagnostics_updater_(this) { setvbuf(stdout, NULL, _IONBF, BUFSIZ); - drivers::HesaiSensorConfiguration sensor_configuration; - wrapper_status_ = GetParameters(sensor_configuration); - sensor_cfg_ptr_ = std::make_shared(sensor_configuration); - // DeclareRosParameters(); - // auto sensor_cfg_ptr = GetRosParameters(); + sensor_cfg_ptr_ = std::make_shared(); + wrapper_status_ = GetParameters(*sensor_cfg_ptr_); + InitializeHwInterface(); InitializeDecoder(); - InitializeHwMonitor(); - // StreamStart(); - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - StreamStart(); - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + + if (launch_hw_) { + InitializeHwMonitor(); + StreamStart(); + hw_interface_.RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + } else { + packets_sub_ = create_subscription("pandar_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); + } set_param_res_ = this->add_on_set_parameters_callback( std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); @@ -34,29 +37,31 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) Status HesaiRosWrapper::InitializeHwInterface() { - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return interface_status_; - } + interface_status_ = Status::OK; + hw_interface_.SetLogger(std::make_shared(this->get_logger())); hw_interface_.SetSensorConfiguration( std::static_pointer_cast(sensor_cfg_ptr_)); - - Status status; + hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); + + if (!launch_hw_) { + return interface_status_; + } + int retry_count = 0; while (true) { - status = hw_interface_.InitializeTcpDriver(); - if (status == Status::OK || !retry_hw_) { + interface_status_ = hw_interface_.InitializeTcpDriver(); + if (interface_status_ == Status::OK || !retry_hw_) { break; } retry_count++; std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << retry_count); - }; + } - if (status == Status::OK) { + if (interface_status_ == Status::OK) { try { auto inventory = hw_interface_.GetInventory(); RCLCPP_INFO_STREAM(get_logger(), inventory); @@ -72,9 +77,12 @@ Status HesaiRosWrapper::InitializeHwInterface() RCLCPP_ERROR_STREAM( get_logger(), "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); - hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); } + pandar_scan_pub_ = + create_publisher("pandar_packets", rclcpp::SensorDataQoS()); + current_scan_msg_ = std::make_unique(); + return Status::OK; } @@ -191,13 +199,32 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) // delay.tick(msg_ptr->stamp); // publish.tick(); - if (!packet_queue_.push(std::move(msg_ptr))) { + if (!packet_queue_.try_push(std::move(msg_ptr))) { RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packets dropped"); } // packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); } +void HesaiRosWrapper::ReceiveScanMessageCallback( + std::unique_ptr scan_msg) +{ + if (launch_hw_) { + RCLCPP_ERROR_THROTTLE( + get_logger(), *get_clock(), 1000, + "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); + return; + } + + for (auto & pkt : scan_msg->packets) { + auto nebula_pkt_ptr = std::make_unique(); + nebula_pkt_ptr->stamp = pkt.stamp; + std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); + + packet_queue_.push(std::move(nebula_pkt_ptr)); + } +} + void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) { // static auto parse = nebula::util::Instrumentation("ProcessCloudPacket.parse"); @@ -207,6 +234,22 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrstamp); + // Accumulate packets for recording only if someone is subscribed to the topic (for performance) + if ( + pandar_scan_pub_ && + (pandar_scan_pub_->get_subscription_count() > 0 || + pandar_scan_pub_->get_intra_process_subscription_count() > 0)) { + if (current_scan_msg_->packets.size() == 0) { + current_scan_msg_->header.stamp = packet_msg->stamp; + } + + pandar_msgs::msg::PandarPacket pandar_packet_msg{}; + pandar_packet_msg.stamp = packet_msg->stamp; + pandar_packet_msg.size = packet_msg->data.size(); + std::copy(packet_msg->data.begin(), packet_msg->data.end(), pandar_packet_msg.data.begin()); + current_scan_msg_->packets.emplace_back(std::move(pandar_packet_msg)); + } + // parse.tick(); std::tuple pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); @@ -218,6 +261,13 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrpackets.empty()) { + pandar_scan_pub_->publish(std::move(current_scan_msg_)); + current_scan_msg_ = std::make_unique(); + } + if ( nebula_points_pub_->get_subscription_count() > 0 || nebula_points_pub_->get_intra_process_subscription_count() > 0) { @@ -577,11 +627,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor return Status::SENSOR_CONFIG_ERROR; } - std::shared_ptr sensor_cfg_ptr = - std::make_shared(sensor_configuration); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr)); + std::static_pointer_cast(sensor_cfg_ptr_)); RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); return Status::OK; From 4ff887850963d5b070c944e015bece66d9eb3311 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 9 Apr 2024 18:46:05 +0900 Subject: [PATCH 089/122] change launch file back to single-threaded container --- nebula_ros/launch/hesai_launch_all_hw.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index b7c1459ec..1bd285766 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -33,7 +33,7 @@ - From 8fb516e2443338bb786d2a6f7b15239efc3c2b98 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 10 Apr 2024 12:23:36 +0900 Subject: [PATCH 090/122] attempt to make queue contention less bad --- .../include/nebula_ros/hesai/mt_queue.hpp | 37 +++++++++++-------- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 12 ++++-- 2 files changed, 30 insertions(+), 19 deletions(-) diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp index 67b287ddc..a259a80ba 100644 --- a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -9,7 +9,7 @@ class mt_queue { private: std::mutex mutex_; - std::condition_variable condition_variable_; + std::condition_variable cv_not_empty_, cv_not_full_; std::deque queue_; size_t capacity_; @@ -18,34 +18,39 @@ class mt_queue bool try_push(T && value) { - { - std::unique_lock lock(this->mutex_); - if (queue_.size() == capacity_) { - return false; - } - + std::unique_lock lock(this->mutex_); + bool can_push = queue_.size() < capacity_; + if (can_push) { queue_.push_front(std::move(value)); } - this->condition_variable_.notify_one(); - return true; + this->cv_not_empty_.notify_all(); + return can_push; } void push(T && value) { - { - std::unique_lock lock(this->mutex_); - this->condition_variable_.wait(lock, [=] { return this->queue_.size() < this->capacity_; }); - queue_.push_front(std::move(value)); - } - this->condition_variable_.notify_one(); + std::unique_lock lock(this->mutex_); + this->cv_not_full_.wait(lock, [=] { return this->queue_.size() < this->capacity_; }); + queue_.push_front(std::move(value)); + this->cv_not_empty_.notify_all(); } T pop() { std::unique_lock lock(this->mutex_); - this->condition_variable_.wait(lock, [=] { return !this->queue_.empty(); }); + this->cv_not_empty_.wait(lock, [=] { return !this->queue_.empty(); }); T return_value(std::move(this->queue_.back())); this->queue_.pop_back(); + this->cv_not_full_.notify_all(); + return return_value; } + + void pop_all(std::deque & dest) { + std::unique_lock lock(this->mutex_); + this->cv_not_empty_.wait(lock, [=] { return !this->queue_.empty(); }); + dest.insert(dest.end(), std::make_move_iterator(queue_.begin()), std::make_move_iterator(queue_.end())); + this->queue_.clear(); + this->cv_not_full_.notify_all(); + } }; \ No newline at end of file diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 0fe4e7bd3..6fdc46a1a 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -104,9 +104,15 @@ Status HesaiRosWrapper::InitializeDecoder() rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); decoder_thread_ = std::thread([this]() { + std::deque> received{}; while (true) { - auto pkt = packet_queue_.pop(); - this->ProcessCloudPacket(std::move(pkt)); + packet_queue_.pop_all(received); + + while (!received.empty()) { + auto pkt = std::move(received.back()); + received.pop_back(); + this->ProcessCloudPacket(std::move(pkt)); + } } }); @@ -200,7 +206,7 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) // publish.tick(); if (!packet_queue_.try_push(std::move(msg_ptr))) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packets dropped"); + RCLCPP_ERROR(get_logger(), "Packet dropped"); } // packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); From a0631bdf053ffbc40464020e69d4566bf7ab6319 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 11 Apr 2024 19:00:25 +0900 Subject: [PATCH 091/122] chore(hesai_ros_wrapper): reduce logging output --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 6fdc46a1a..7a0bf34f0 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -206,7 +206,7 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) // publish.tick(); if (!packet_queue_.try_push(std::move(msg_ptr))) { - RCLCPP_ERROR(get_logger(), "Packet dropped"); + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); } // packet_pub_->publish(std::move(msg_ptr)); // publish.tock(); From 43fad4659989351b439a19f2d65d1edf18c09895 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 11 Apr 2024 19:18:35 +0900 Subject: [PATCH 092/122] feat(hesai_ros_wrapper): print warning when connected to HW and receiving /pandar_packets --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 16 +++++----------- 1 file changed, 5 insertions(+), 11 deletions(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 7a0bf34f0..23205ea64 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -27,10 +27,11 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) StreamStart(); hw_interface_.RegisterScanCallback( std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - } else { - packets_sub_ = create_subscription("pandar_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); } + packets_sub_ = create_subscription("pandar_packets", rclcpp::SensorDataQoS(), + std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); + set_param_res_ = this->add_on_set_parameters_callback( std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); } @@ -104,15 +105,8 @@ Status HesaiRosWrapper::InitializeDecoder() rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); decoder_thread_ = std::thread([this]() { - std::deque> received{}; while (true) { - packet_queue_.pop_all(received); - - while (!received.empty()) { - auto pkt = std::move(received.back()); - received.pop_back(); - this->ProcessCloudPacket(std::move(pkt)); - } + this->ProcessCloudPacket(std::move(packet_queue_.pop())); } }); @@ -242,7 +236,7 @@ void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptrget_subscription_count() > 0 || pandar_scan_pub_->get_intra_process_subscription_count() > 0)) { if (current_scan_msg_->packets.size() == 0) { From 243fc7528f194693cd9d5521c4273e5296ca4f77 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Fri, 12 Apr 2024 14:43:27 +0900 Subject: [PATCH 093/122] feat(nebula_launch.py): throw error when trying to launch Hesai sensor and refer to hesai_launch_all_hw.xml --- nebula_ros/launch/nebula_launch.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/nebula_ros/launch/nebula_launch.py b/nebula_ros/launch/nebula_launch.py index b394498fb..74d3eb475 100644 --- a/nebula_ros/launch/nebula_launch.py +++ b/nebula_ros/launch/nebula_launch.py @@ -41,8 +41,11 @@ def launch_setup(context, *args, **kwargs): # Model and make sensor_model = LaunchConfiguration("sensor_model").perform(context) calibration_file = LaunchConfiguration("calibration_file").perform(context) - correction_file = LaunchConfiguration("correction_file").perform(context) sensor_make, sensor_extension = get_sensor_make(sensor_model) + + if sensor_make.lower() == "hesai": + raise ValueError("\n `nebula_launch.py` is deprecated. For Hesai sensors, use `hesai_launch_all_hw.xml` instead.") + nebula_decoders_share_dir = get_package_share_directory("nebula_decoders") nebula_ros_share_dir = get_package_share_directory("nebula_ros") @@ -84,7 +87,6 @@ def launch_setup(context, *args, **kwargs): "sensor_ip": LaunchConfiguration("sensor_ip"), "return_mode": LaunchConfiguration("return_mode"), "calibration_file": calibration_file or sensor_calib_fp, - "correction_file": correction_file or sensor_corr_fp, "setup_sensor": LaunchConfiguration("setup_sensor"), "ptp_profile": LaunchConfiguration("ptp_profile"), "ptp_domain": LaunchConfiguration("ptp_domain"), @@ -110,7 +112,6 @@ def launch_setup(context, *args, **kwargs): "sensor_ip": LaunchConfiguration("sensor_ip"), "return_mode": LaunchConfiguration("return_mode"), "calibration_file": calibration_file or sensor_calib_fp, - "correction_file": correction_file or sensor_corr_fp, }, ], ) @@ -127,7 +128,6 @@ def launch_setup(context, *args, **kwargs): "sensor_ip": LaunchConfiguration("sensor_ip"), "return_mode": LaunchConfiguration("return_mode"), "calibration_file": calibration_file or sensor_calib_fp, - "correction_file": correction_file or sensor_corr_fp, "launch_hw": LaunchConfiguration("launch_hw"), "ptp_profile": LaunchConfiguration("ptp_profile"), "ptp_domain": LaunchConfiguration("ptp_domain"), From 2c14f48ce91459857bce080c3c6ee1b58772d521 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 16:38:39 +0900 Subject: [PATCH 094/122] refactor(nebula_ros): split single wrapper file into 3 sub-wrappers --- .cspell.json | 27 +- .../nebula_common/hesai/hesai_common.hpp | 35 +- .../include/nebula_common/util/expected.hpp | 5 +- .../decoders/hesai_packet.hpp | 2 +- .../nebula_decoders_hesai/hesai_driver.hpp | 15 +- .../nebula_decoders_hesai/hesai_driver.cpp | 55 +- .../hesai_hw_interface.cpp | 24 +- nebula_ros/CMakeLists.txt | 4 + .../nebula_ros/hesai/decoder_wrapper.hpp | 66 + .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 181 +-- .../nebula_ros/hesai/hw_interface_wrapper.hpp | 32 + .../nebula_ros/hesai/hw_monitor_wrapper.hpp | 95 ++ .../include/nebula_ros/hesai/mt_queue.hpp | 9 +- nebula_ros/package.xml | 1 + nebula_ros/src/hesai/decoder_wrapper.cpp | 255 ++++ nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 1159 +++-------------- nebula_ros/src/hesai/hw_interface_wrapper.cpp | 94 ++ nebula_ros/src/hesai/hw_monitor_wrapper.cpp | 412 ++++++ 18 files changed, 1268 insertions(+), 1203 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp create mode 100644 nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp create mode 100644 nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp create mode 100644 nebula_ros/src/hesai/decoder_wrapper.cpp create mode 100644 nebula_ros/src/hesai/hw_interface_wrapper.cpp create mode 100644 nebula_ros/src/hesai/hw_monitor_wrapper.cpp diff --git a/.cspell.json b/.cspell.json index 75b26f454..5265d4bf1 100644 --- a/.cspell.json +++ b/.cspell.json @@ -6,14 +6,26 @@ "adctp", "Adctp", "AT", + "autosar", "block_id", + "Bpearl", + "calib", + "DHAVE", + "Difop", "extrinsics", "gprmc", + "gptp", + "Helios", "Hesai", + "Idat", + "ipaddr", + "manc", "memcpy", "mkdoxy", + "Msop", "nohup", "nproc", + "ntoa", "pandar", "PANDAR", "PANDARAT", @@ -23,6 +35,7 @@ "QT", "rclcpp", "schedutil", + "srvs", "STD_COUT", "stds", "struct", @@ -30,21 +43,9 @@ "UDP_SEQ", "vccint", "Vccint", + "Vdat", "XT", "XTM", - "DHAVE", - "Bpearl", - "Helios", - "Msop", - "Difop", - "gptp", - "Idat", - "Vdat", - "autosar", - "srvs", - "manc", - "ipaddr", - "ntoa", "piyushk", "Piyush", "fout" diff --git a/nebula_common/include/nebula_common/hesai/hesai_common.hpp b/nebula_common/include/nebula_common/hesai/hesai_common.hpp index 9c6e5d555..0c7ae1c1b 100644 --- a/nebula_common/include/nebula_common/hesai/hesai_common.hpp +++ b/nebula_common/include/nebula_common/hesai/hesai_common.hpp @@ -14,7 +14,7 @@ namespace nebula namespace drivers { /// @brief struct for Hesai sensor configuration -struct HesaiSensorConfiguration : LidarConfigurationBase +struct HesaiSensorConfiguration : public LidarConfigurationBase { uint16_t gnss_port{}; double scan_phase{}; @@ -43,13 +43,20 @@ inline std::ostream & operator<<(std::ostream & os, HesaiSensorConfiguration con return os; } +struct HesaiCalibrationConfigurationBase : public CalibrationConfigurationBase +{ + virtual nebula::Status LoadFromBytes(const std::vector & buf) = 0; + virtual nebula::Status LoadFromFile(const std::string & calibration_file) = 0; + virtual nebula::Status SaveToFileFromBytes(const std::string & calibration_file, const std::vector & buf) = 0; +}; + /// @brief struct for Hesai calibration configuration -struct HesaiCalibrationConfiguration : CalibrationConfigurationBase +struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase { std::map elev_angle_map; std::map azimuth_offset_map; - inline nebula::Status LoadFromFile(const std::string & calibration_file) + inline nebula::Status LoadFromFile(const std::string & calibration_file) override { std::ifstream ifs(calibration_file); if (!ifs) { @@ -61,6 +68,11 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase return LoadFromString(ss.str()); } + nebula::Status LoadFromBytes(const std::vector & buf) { + std::string calibration_string = std::string(buf.begin(), buf.end()); + return LoadFromString(calibration_string); + } + /// @brief Loading calibration data /// @param calibration_content /// @return Resulting status @@ -99,7 +111,7 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase /// @brief Saving calibration data (not used) /// @param calibration_file /// @return Resulting status - inline nebula::Status SaveFile(const std::string & calibration_file) + inline nebula::Status SaveToFile(const std::string & calibration_file) { std::ofstream ofs(calibration_file); if (!ofs) { @@ -117,6 +129,11 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase return Status::OK; } + nebula::Status SaveToFileFromBytes(const std::string & calibration_file, const std::vector & buf) override { + std::string calibration_string = std::string(buf.begin(), buf.end()); + return SaveFileFromString(calibration_file, calibration_string); + } + /// @brief Saving calibration data from string /// @param calibration_file path /// @param calibration_string calibration string @@ -134,7 +151,7 @@ struct HesaiCalibrationConfiguration : CalibrationConfigurationBase }; /// @brief struct for Hesai correction configuration (for AT) -struct HesaiCorrection +struct HesaiCorrection : public HesaiCalibrationConfigurationBase { uint16_t delimiter; uint8_t versionMajor; @@ -156,7 +173,7 @@ struct HesaiCorrection /// @brief Load correction data from file /// @param buf Binary buffer /// @return Resulting status - inline nebula::Status LoadFromBinary(const std::vector & buf) + inline nebula::Status LoadFromBytes(const std::vector & buf) override { size_t index; for (index = 0; index < buf.size()-1; index++) { @@ -258,7 +275,7 @@ struct HesaiCorrection /// @brief Load correction data from file /// @param correction_file path /// @return Resulting status - inline nebula::Status LoadFromFile(const std::string & correction_file) + inline nebula::Status LoadFromFile(const std::string & correction_file) override { std::ifstream ifs(correction_file, std::ios::in | std::ios::binary); if (!ifs) { @@ -271,7 +288,7 @@ struct HesaiCorrection ifs.read((char *)&c, sizeof(unsigned char)); buf.emplace_back(c); } - LoadFromBinary(buf); + LoadFromBytes(buf); ifs.close(); return Status::OK; @@ -281,7 +298,7 @@ struct HesaiCorrection /// @param correction_file path /// @param buf correction binary /// @return Resulting status - inline nebula::Status SaveFileFromBinary(const std::string & correction_file, const std::vector & buf) + inline nebula::Status SaveToFileFromBytes(const std::string & correction_file, const std::vector & buf) override { std::cerr << "Saving in:" << correction_file << "\n"; std::ofstream ofs(correction_file, std::ios::trunc | std::ios::binary); diff --git a/nebula_common/include/nebula_common/util/expected.hpp b/nebula_common/include/nebula_common/util/expected.hpp index d3643cfb4..0f47e9de1 100644 --- a/nebula_common/include/nebula_common/util/expected.hpp +++ b/nebula_common/include/nebula_common/util/expected.hpp @@ -54,8 +54,9 @@ struct expected return default_; } - /// @brief Return the contained value, or, if an error is contained, throw `runtime_error(error_msg)`. - /// @return The contained value if no error is thrown + /// @brief If the instance has a value, return the value, else throw std::runtime_error(error_msg) + /// @param error_msg The message to be included in the thrown exception + /// @return The value T value_or_throw(const std::string & error_msg) { if (has_value()) return value(); throw std::runtime_error(error_msg); diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp index 730888c91..0280f1ff7 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp @@ -190,7 +190,7 @@ struct PacketBase /// @brief Get the number of returns for a given return mode /// @param return_mode The return mode /// @return The number of returns -int get_n_returns(uint8_t return_mode) +inline int get_n_returns(uint8_t return_mode) { switch (return_mode) { case return_mode::SINGLE_FIRST: diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index a3f37cd32..5ee9892d4 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -34,12 +34,11 @@ class HesaiDriver : NebulaDriverBase HesaiDriver() = delete; /// @brief Constructor /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver (for AT) + /// @param calibration_configuration CalibrationConfiguration for this driver (either HesaiCalibrationConfiguration + /// for sensors other than AT128 or HesaiCorrection for AT128) explicit HesaiDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration = nullptr); + const std::shared_ptr& sensor_configuration, + const std::shared_ptr& calibration_configuration = nullptr); /// @brief Get current status of this driver /// @return Current status @@ -48,14 +47,12 @@ class HesaiDriver : NebulaDriverBase /// @brief Setting CalibrationConfiguration (not used) /// @param calibration_configuration /// @return Resulting status - Status SetCalibrationConfiguration( - const CalibrationConfigurationBase & calibration_configuration) override; + Status SetCalibrationConfiguration(const CalibrationConfigurationBase& calibration_configuration) override; /// @brief Convert PandarScan message to point cloud /// @param pandar_scan Message /// @return tuple of Point cloud and timestamp - std::tuple ParseCloudPacket( - const std::vector & packet); + std::tuple ParseCloudPacket(const std::vector& packet); }; } // namespace drivers diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index 61b969ed7..27624a469 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -17,53 +17,56 @@ namespace nebula { namespace drivers { -HesaiDriver::HesaiDriver( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) +HesaiDriver::HesaiDriver(const std::shared_ptr& sensor_configuration, + const std::shared_ptr& calibration_configuration) { // initialize proper parser from cloud config's model and echo mode driver_status_ = nebula::Status::OK; - switch (sensor_configuration->sensor_model) { + + std::shared_ptr calibration = nullptr; + std::shared_ptr correction = nullptr; + + if (sensor_configuration->sensor_model == SensorModel::HESAI_PANDARAT128) + { + correction = std::static_pointer_cast(calibration_configuration); + } + else + { + calibration = std::static_pointer_cast(calibration_configuration); + } + + switch (sensor_configuration->sensor_model) + { case SensorModel::UNKNOWN: driver_status_ = nebula::Status::INVALID_SENSOR_MODEL; break; case SensorModel::HESAI_PANDAR64: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDAR40P: case SensorModel::HESAI_PANDAR40M: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARQT64: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARQT128: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARXT32: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARXT32M: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDARAT128: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDAR128_E3X: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; case SensorModel::HESAI_PANDAR128_E4X: - scan_decoder_.reset(new HesaiDecoder( - sensor_configuration, calibration_configuration, correction_configuration)); + scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); break; default: driver_status_ = nebula::Status::NOT_INITIALIZED; @@ -78,13 +81,15 @@ std::tuple HesaiDriver::ParseCloudPacket( std::tuple pointcloud; auto logger = rclcpp::get_logger("HesaiDriver"); - if (driver_status_ != nebula::Status::OK) { + if (driver_status_ != nebula::Status::OK) + { RCLCPP_ERROR(logger, "Driver not OK."); return pointcloud; } scan_decoder_->unpack(packet); - if (scan_decoder_->hasScanned()) { + if (scan_decoder_->hasScanned()) + { pointcloud = scan_decoder_->getPointcloud(); } diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 451b2a9d3..5a40b6b60 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -22,29 +22,7 @@ HesaiHwInterface::HesaiHwInterface() } HesaiHwInterface::~HesaiHwInterface() { -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................st: HesaiHwInterface::~HesaiHwInterface()" << std::endl; -#endif - if (tcp_driver_) { -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................tcp_driver_ is available" << std::endl; -#endif - if (tcp_driver_ && tcp_driver_->isOpen()) { -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................st: tcp_driver_->close();" << std::endl; -#endif - tcp_driver_->close(); -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................ed: tcp_driver_->close();" << std::endl; -#endif - } -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................ed: if(tcp_driver_)" << std::endl; -#endif - } -#ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE - std::cout << ".......................ed: HesaiHwInterface::~HesaiHwInterface()" << std::endl; -#endif + FinalizeTcpDriver(); } HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index 1bd697624..b11339765 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -24,6 +24,7 @@ find_package(nebula_hw_interfaces REQUIRED) find_package(yaml-cpp REQUIRED) find_package(robosense_msgs REQUIRED) find_package(nebula_msgs REQUIRED) +find_package(pandar_msgs REQUIRED) include_directories( include @@ -36,6 +37,9 @@ link_libraries(${YAML_CPP_LIBRARIES} ${PCL_LIBRARIES}) ## Hesai ament_auto_add_library(hesai_ros_wrapper SHARED src/hesai/hesai_ros_wrapper.cpp + src/hesai/decoder_wrapper.cpp + src/hesai/hw_interface_wrapper.cpp + src/hesai/hw_monitor_wrapper.cpp ) rclcpp_components_register_node(hesai_ros_wrapper diff --git a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp new file mode 100644 index 000000000..262c16839 --- /dev/null +++ b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp @@ -0,0 +1,66 @@ +#pragma once + +#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" +#include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" + +#include +#include +#include + +#include "nebula_msgs/msg/nebula_packet.hpp" +#include "pandar_msgs/msg/pandar_packet.hpp" +#include "pandar_msgs/msg/pandar_scan.hpp" + +#include +#include + +namespace nebula +{ +namespace ros +{ +class HesaiDecoderWrapper +{ +public: + HesaiDecoderWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config); + + nebula::util::expected, nebula::Status> + GetCalibrationData(); + + void ProcessCloudPacket(std::unique_ptr packet_msg); + + void PublishCloud(std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr& publisher); + + nebula::Status Status(); + +private: + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast(std::chrono::duration(seconds)); + } + + nebula::Status status_; + rclcpp::Logger logger_; + + const std::shared_ptr hw_interface_; + std::shared_ptr sensor_cfg_; + + std::string calibration_file_path_{}; + std::shared_ptr calibration_cfg_ptr_{}; + + std::shared_ptr driver_ptr_; + + rclcpp::Publisher::SharedPtr packets_pub_{}; + pandar_msgs::msg::PandarScan::UniquePtr current_scan_msg_{}; + + rclcpp::Publisher::SharedPtr nebula_points_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; + rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 9c50e20eb..e037bce40 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -4,29 +4,27 @@ #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" -// #include "nebula_common/util/instrumentation.hpp" -// #include "nebula_common/util/topic_delay.hpp" -#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" +#include "nebula_ros/hesai/decoder_wrapper.hpp" +#include "nebula_ros/hesai/hw_interface_wrapper.hpp" +#include "nebula_ros/hesai/hw_monitor_wrapper.hpp" #include "nebula_ros/hesai/mt_queue.hpp" #include -#include #include #include #include "nebula_msgs/msg/nebula_packet.hpp" -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" #include #include #include +#include #include #include +#include #include -#include namespace nebula { @@ -40,12 +38,12 @@ namespace ros /// @param value Corresponding value /// @return Whether the target name existed template -bool get_param(const std::vector & p, const std::string & name, T & value) +bool get_param(const std::vector& p, const std::string& name, T& value) { - auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { - return parameter.get_name() == name; - }); - if (it != p.cend()) { + auto it = std::find_if(p.cbegin(), p.cend(), + [&name](const rclcpp::Parameter& parameter) { return parameter.get_name() == name; }); + if (it != p.cend()) + { value = it->template get_value(); return true; } @@ -56,8 +54,8 @@ bool get_param(const std::vector & p, const std::string & nam class HesaiRosWrapper final : public rclcpp::Node { public: - explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); - ~HesaiRosWrapper(); + explicit HesaiRosWrapper(const rclcpp::NodeOptions& options); + ~HesaiRosWrapper() noexcept; /// @brief Get current status of this driver /// @return Current status @@ -68,172 +66,45 @@ class HesaiRosWrapper final : public rclcpp::Node Status StreamStart(); private: - Status InitializeHwInterface(); - Status InitializeDecoder(); - Status InitializeHwMonitor(); + void ReceiveCloudPacketCallback(std::vector& packet); + + void ReceiveScanMessageCallback(std::unique_ptr scan_msg); + + Status DeclareAndGetSensorConfigParams(); /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration /// @return Resulting status - Status GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration); - - /// @brief Get calibration data from the sensor - /// @param calibration_configuration Output of CalibrationConfiguration - /// @param correction_configuration Output of CorrectionConfiguration (for AT) - /// @return Resulting status - Status GetCalibrationData( - drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration); - - /// @brief Convert seconds to chrono::nanoseconds - /// @param seconds - /// @return chrono::nanoseconds - static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) - { - return std::chrono::duration_cast( - std::chrono::duration(seconds)); - } - - /*** - * Publishes a sensor_msgs::msg::PointCloud2 to the specified publisher - * @param pointcloud unique pointer containing the point cloud to publish - * @param publisher - */ - void PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher); - - /// @brief Callback for receiving a raw UDP packet - /// @param scan_buffer Received PandarScan - void ReceiveCloudPacketCallback(std::vector & scan_buffer); - - /// @brief Callback for receiving replayed, aggregated packets (= scan messages) - /// @param scan_msg - void ReceiveScanMessageCallback(std::unique_ptr scan_msg); - - /// @brief Decodes a nebula packet and, if it completes the scan, publishes the pointcloud. - /// @param packet_msg The received packet message - void ProcessCloudPacket(std::unique_ptr packet_msg); + Status DeclareAndGetWrapperParams(); /// @brief rclcpp parameter callback /// @param parameters Received parameters /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback( - const std::vector & parameters); + rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector& parameters); + /// @brief Updating rclcpp parameter /// @return SetParametersResult std::vector updateParameters(); - /// @brief Initializing diagnostics - void InitializeHesaiDiagnostics(); - /// @brief Callback of the timer for getting the current lidar status - void OnHesaiStatusTimer(); - /// @brief Callback of the timer for getting the current lidar monitor via http - void OnHesaiLidarMonitorTimerHttp(); - /// @brief Callback of the timer for getting the current lidar monitor via tcp - void OnHesaiLidarMonitorTimer(); - // void OnHesaiDiagnosticsTimer(); - // void OnHesaiStatusTimer(); - - /// @brief Check status information from HesaiLidarStatus for diagnostic_updater - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check ptp information from HesaiLidarStatus for diagnostic_updater - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check temperature information from HesaiLidarStatus for diagnostic_updater - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check rpm information from HesaiLidarStatus for diagnostic_updater - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check voltage information from HesaiLidarStatus for diagnostic_updater via http - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Check voltage information from HesaiLidarStatus for diagnostic_updater via tcp - /// @param diagnostics DiagnosticStatusWrapper - void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - /// @brief Get value from property_tree - /// @param pt property_tree - /// @param key Pey string - /// @return Value - std::string GetPtreeValue(boost::property_tree::ptree * pt, const std::string & key); - /// @brief Making fixed precision string - /// @param val Target value - /// @param pre Precision - /// @return Created string - std::string GetFixedPrecisionString(double val, int pre = 2); - - std::shared_ptr driver_ptr_{}; - drivers::HesaiHwInterface hw_interface_{}; - Status wrapper_status_; - Status interface_status_; - rclcpp::Subscription::SharedPtr packets_sub_{}; - rclcpp::Publisher::SharedPtr packets_pub_{}; - pandar_msgs::msg::PandarScan::UniquePtr current_scan_msg_{}; - - rclcpp::Publisher::SharedPtr nebula_points_pub_{}; - rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; - rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; - - std::shared_ptr calibration_cfg_ptr_{}; - std::shared_ptr sensor_cfg_ptr_{}; - std::shared_ptr correction_cfg_ptr_{}; + std::shared_ptr sensor_cfg_ptr_{}; /// @brief Stores received packets that have not been processed yet by the decoder thread mt_queue> packet_queue_; /// @brief Thread to isolate decoding from receiving std::thread decoder_thread_; - // todo: temporary class member during single node refactoring - bool launch_hw_; + rclcpp::Subscription::SharedPtr packets_sub_{}; - // todo: temporary class member during single node refactoring - std::string calibration_file_path; - /// @brief File path of Correction data (Only required only for AT) - std::string correction_file_path; + bool launch_hw_; - /// @brief Received Hesai message publisher - rclcpp::Publisher::SharedPtr pandar_scan_pub_{}; + std::optional hw_interface_wrapper_; + std::optional hw_monitor_wrapper_; + std::optional decoder_wrapper_; - bool retry_hw_; std::mutex mtx_config_; OnSetParametersCallbackHandle::SharedPtr set_param_res_{}; - - diagnostic_updater::Updater diagnostics_updater_; - - rclcpp::TimerBase::SharedPtr diagnostics_update_timer_{}; - rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_{}; - - std::unique_ptr current_status_{}; - std::unique_ptr current_monitor_{}; - std::unique_ptr current_config_{}; - std::unique_ptr current_inventory_{}; - std::unique_ptr current_lidar_monitor_tree_{}; - - std::unique_ptr current_status_time_{}; - std::unique_ptr current_config_time_{}; - std::unique_ptr current_inventory_time_{}; - std::unique_ptr current_lidar_monitor_time_{}; - - uint8_t current_diag_status_; - uint8_t current_monitor_status_; - - uint16_t diag_span_; - std::mutex mtx_lidar_status_; - std::mutex mtx_lidar_monitor_; - - std::string info_model_; - std::string info_serial_; - - std::vector temperature_names_; - - bool setup_sensor; - const std::string MSG_NOT_SUPPORTED = "Not supported"; - const std::string MSG_ERROR = "Error"; - const std::string MSG_SEP = ": "; }; } // namespace ros diff --git a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp new file mode 100644 index 000000000..30f069c99 --- /dev/null +++ b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp @@ -0,0 +1,32 @@ +#pragma once + +#include +#include + +#include + +#include + +namespace nebula +{ +namespace ros +{ +class HesaiHwInterfaceWrapper +{ +public: + HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, + std::shared_ptr& config); + + nebula::Status InitializeHwInterface(); + + nebula::Status Status(); + + std::shared_ptr HwInterface() const; + +private: + std::shared_ptr hw_interface_; + rclcpp::Logger logger_; + nebula::Status status_; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp new file mode 100644 index 000000000..5ddfc9e79 --- /dev/null +++ b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp @@ -0,0 +1,95 @@ +#pragma once + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +namespace nebula +{ +namespace ros +{ +class HesaiHwMonitorWrapper +{ +public: + HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config); + + nebula::Status InitializeHwMonitor(); + + void InitializeHesaiDiagnostics(); + + std::string GetPtreeValue(boost::property_tree::ptree* pt, const std::string& key); + + std::string GetFixedPrecisionString(double val, int pre); + + void OnHesaiStatusTimer(); + + void OnHesaiLidarMonitorTimerHttp(); + + void OnHesaiLidarMonitorTimer(); + + void HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + + nebula::Status Status(); + +private: + rclcpp::Logger logger_; + diagnostic_updater::Updater diagnostics_updater_; + nebula::Status status_; + + const std::shared_ptr hw_interface_; + rclcpp::Node* const parent_node_; + + uint16_t diag_span_; + rclcpp::TimerBase::SharedPtr diagnostics_update_timer_{}; + rclcpp::TimerBase::SharedPtr fetch_diagnostics_timer_{}; + + std::unique_ptr current_status_{}; + std::unique_ptr current_monitor_{}; + std::unique_ptr current_config_{}; + std::unique_ptr current_inventory_{}; + std::unique_ptr current_lidar_monitor_tree_{}; + + std::unique_ptr current_status_time_{}; + std::unique_ptr current_config_time_{}; + std::unique_ptr current_inventory_time_{}; + std::unique_ptr current_lidar_monitor_time_{}; + + uint8_t current_diag_status_; + uint8_t current_monitor_status_; + + std::mutex mtx_lidar_status_; + std::mutex mtx_lidar_monitor_; + + std::string info_model_; + std::string info_serial_; + + std::vector temperature_names_; + + bool setup_sensor; + const std::string MSG_NOT_SUPPORTED = "Not supported"; + const std::string MSG_ERROR = "Error"; + const std::string MSG_SEP = ": "; +}; +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp index a259a80ba..d60b7b4db 100644 --- a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp @@ -3,6 +3,7 @@ #include #include #include +#include template class mt_queue @@ -45,12 +46,4 @@ class mt_queue return return_value; } - - void pop_all(std::deque & dest) { - std::unique_lock lock(this->mutex_); - this->cv_not_empty_.wait(lock, [=] { return !this->queue_.empty(); }); - dest.insert(dest.end(), std::make_move_iterator(queue_.begin()), std::make_move_iterator(queue_.end())); - this->queue_.clear(); - this->cv_not_full_.notify_all(); - } }; \ No newline at end of file diff --git a/nebula_ros/package.xml b/nebula_ros/package.xml index 54df70ea9..e918afdc7 100644 --- a/nebula_ros/package.xml +++ b/nebula_ros/package.xml @@ -32,6 +32,7 @@ visualization_msgs yaml-cpp nebula_msgs + pandar_msgs ament_cmake_gtest ament_lint_auto diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp new file mode 100644 index 000000000..1ae6d2837 --- /dev/null +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -0,0 +1,255 @@ +#include "nebula_ros/hesai/decoder_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ + +HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config) + : status_(nebula::Status::NOT_INITIALIZED) + , logger_(parent_node->get_logger().get_child("HesaiDecoder")) + , hw_interface_(hw_interface) + , sensor_cfg_(config) +{ + if (!config) + { + throw std::runtime_error("HesaiDecoderWrapper cannot be instantiated without a valid config!"); + } + + if (config->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + parent_node->declare_parameter("correction_file", "", descriptor); + calibration_file_path_ = parent_node->get_parameter("correction_file").as_string(); + } + else + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + parent_node->declare_parameter("calibration_file", "", descriptor); + calibration_file_path_ = parent_node->get_parameter("calibration_file").as_string(); + } + + auto calibration_result = GetCalibrationData(); + + if (!calibration_result.has_value()) + { + throw std::runtime_error( + (std::stringstream() << "No valid calibration found: " << calibration_result.error()).str()); + } + + calibration_cfg_ptr_ = calibration_result.value(); + RCLCPP_INFO_STREAM(logger_, "Using calibration data from " << calibration_cfg_ptr_->calibration_file); + + RCLCPP_INFO(logger_, "Starting Decoder"); + + driver_ptr_ = std::make_shared(config, calibration_cfg_ptr_); + status_ = driver_ptr_->GetStatus(); + + if (Status::OK != status_) + { + throw std::runtime_error((std::stringstream() << "Error instantiating decoder: " << status_).str()); + } + + // Publish packets only if HW interface is connected + if (hw_interface_) + { + current_scan_msg_ = std::make_unique(); + packets_pub_ = + parent_node->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); + } + + auto qos_profile = rmw_qos_profile_sensor_data; + auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + + nebula_points_pub_ = parent_node->create_publisher("pandar_points", pointcloud_qos); + aw_points_base_pub_ = parent_node->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = parent_node->create_publisher("aw_points_ex", pointcloud_qos); + + RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); +} + +nebula::util::expected, nebula::Status> +HesaiDecoderWrapper::GetCalibrationData() +{ + std::shared_ptr calib; + + if (sensor_cfg_->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) + { + calib = std::make_shared(); + } + else + { + calib = std::make_shared(); + } + + bool hw_connected = hw_interface_ != nullptr; + std::string calibration_file_path_from_sensor; + + { + int ext_pos = calibration_file_path_.find_last_of('.'); + calibration_file_path_from_sensor = calibration_file_path_.substr(0, ext_pos); + // TODO: if multiple different sensors of the same type are used, this will mix up their calibration data + calibration_file_path_from_sensor += "_from_sensor"; + calibration_file_path_from_sensor += + calibration_file_path_.substr(ext_pos, calibration_file_path_.size() - ext_pos); + } + + // If a sensor is connected, try to download and save its calibration data + if (hw_connected) + { + try + { + auto raw_data = hw_interface_->GetLidarCalibrationBytes(); + RCLCPP_INFO(logger_, "Downloaded calibration data from sensor."); + auto status = calib->SaveToFileFromBytes(calibration_file_path_from_sensor, raw_data); + if (status != Status::OK) + { + RCLCPP_ERROR_STREAM(logger_, "Could not save calibration data: " << status); + } + else + { + RCLCPP_INFO_STREAM(logger_, "Saved downloaded data to " << calibration_file_path_from_sensor); + } + } + catch (std::runtime_error& e) + { + RCLCPP_ERROR_STREAM(logger_, "Could not download calibration data: " << e.what()); + } + } + + // If saved calibration data from a sensor exists (either just downloaded above, or previously), try to load it + if (std::filesystem::exists(calibration_file_path_from_sensor)) + { + auto status = calib->LoadFromFile(calibration_file_path_from_sensor); + if (status == Status::OK) + { + calib->calibration_file = calibration_file_path_from_sensor; + return calib; + } + + RCLCPP_ERROR_STREAM(logger_, "Could not load downloaded calibration data: " << status); + } + else + { + RCLCPP_ERROR(logger_, "No downloaded calibration data found."); + } + + RCLCPP_WARN(logger_, "Falling back to generic calibration file."); + + // If downloaded data did not exist or could not be loaded, fall back to a generic file. + // If that file does not exist either, return an error code + if (!std::filesystem::exists(calibration_file_path_)) + { + RCLCPP_ERROR(logger_, "No calibration data found."); + return nebula::Status(Status::INVALID_CALIBRATION_FILE); + } + + // Try to load the existing fallback calibration file. Return an error if this fails + auto status = calib->LoadFromFile(calibration_file_path_); + if (status != Status::OK) + { + RCLCPP_ERROR(logger_, "Could not load fallback calibration file."); + return status; + } + + // Return the fallback calibration file + calib->calibration_file = calibration_file_path_; + return calib; +} + +void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) +{ + // Accumulate packets for recording only if someone is subscribed to the topic (for performance) + if (hw_interface_ && + (packets_pub_->get_subscription_count() > 0 || packets_pub_->get_intra_process_subscription_count() > 0)) + { + if (current_scan_msg_->packets.size() == 0) + { + current_scan_msg_->header.stamp = packet_msg->stamp; + } + + pandar_msgs::msg::PandarPacket pandar_packet_msg{}; + pandar_packet_msg.stamp = packet_msg->stamp; + pandar_packet_msg.size = packet_msg->data.size(); + std::copy(packet_msg->data.begin(), packet_msg->data.end(), pandar_packet_msg.data.begin()); + current_scan_msg_->packets.emplace_back(std::move(pandar_packet_msg)); + } + + std::tuple pointcloud_ts = + driver_ptr_->ParseCloudPacket(packet_msg->data); + nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + + if (pointcloud == nullptr) + { + // todo + // RCLCPP_WARN_STREAM(logger_, "Empty cloud parsed."); + return; + }; + + // Publish scan message only if it has been written to + if (current_scan_msg_ && !current_scan_msg_->packets.empty()) + { + packets_pub_->publish(std::move(current_scan_msg_)); + current_scan_msg_ = std::make_unique(); + } + + if (nebula_points_pub_->get_subscription_count() > 0 || + nebula_points_pub_->get_intra_process_subscription_count() > 0) + { + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); + } + if (aw_points_base_pub_->get_subscription_count() > 0 || + aw_points_base_pub_->get_intra_process_subscription_count() > 0) + { + const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); + } + if (aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) + { + const auto autoware_ex_cloud = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + auto ros_pc_msg_ptr = std::make_unique(); + pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); + ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); + } +} + +void HesaiDecoderWrapper::PublishCloud(std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr& publisher) +{ + if (pointcloud->header.stamp.sec < 0) + { + RCLCPP_WARN_STREAM(logger_, "Timestamp error, verify clock source."); + } + pointcloud->header.frame_id = sensor_cfg_->frame_id; + publisher->publish(std::move(pointcloud)); +} + +nebula::Status HesaiDecoderWrapper::Status() +{ + if (!driver_ptr_) + { + return nebula::Status::NOT_INITIALIZED; + } + + return driver_ptr_->GetStatus(); +} +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 23205ea64..e99e5c6d9 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -4,344 +4,70 @@ namespace nebula { namespace ros { -HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) -: rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), - hw_interface_(), - wrapper_status_(Status::NOT_INITIALIZED), - interface_status_(Status::NOT_INITIALIZED), - packet_queue_(3000), - diagnostics_updater_(this) +HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions& options) + : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)) + , wrapper_status_(Status::NOT_INITIALIZED) + , sensor_cfg_ptr_(nullptr) + , packet_queue_(3000) + , hw_interface_wrapper_() + , hw_monitor_wrapper_() + , decoder_wrapper_() { setvbuf(stdout, NULL, _IONBF, BUFSIZ); - sensor_cfg_ptr_ = std::make_shared(); - wrapper_status_ = GetParameters(*sensor_cfg_ptr_); + wrapper_status_ = DeclareAndGetSensorConfigParams(); + wrapper_status_ = DeclareAndGetWrapperParams(); - InitializeHwInterface(); - InitializeDecoder(); - - RCLCPP_DEBUG(this->get_logger(), "Starting stream"); - - if (launch_hw_) { - InitializeHwMonitor(); - StreamStart(); - hw_interface_.RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); - } - - packets_sub_ = create_subscription("pandar_packets", rclcpp::SensorDataQoS(), - std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); - - set_param_res_ = this->add_on_set_parameters_callback( - std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); -} - -Status HesaiRosWrapper::InitializeHwInterface() -{ - interface_status_ = Status::OK; - - hw_interface_.SetLogger(std::make_shared(this->get_logger())); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - hw_interface_.SetTargetModel(sensor_cfg_ptr_->sensor_model); - - if (!launch_hw_) { - return interface_status_; - } - - int retry_count = 0; - - while (true) { - interface_status_ = hw_interface_.InitializeTcpDriver(); - if (interface_status_ == Status::OK || !retry_hw_) { - break; - } - - retry_count++; - std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Retry: " << retry_count); - } - - if (interface_status_ == Status::OK) { - try { - auto inventory = hw_interface_.GetInventory(); - RCLCPP_INFO_STREAM(get_logger(), inventory); - hw_interface_.SetTargetModel(inventory.model); - } catch (...) { - RCLCPP_ERROR_STREAM(get_logger(), "Failed to get model from sensor..."); - } - if (this->setup_sensor) { - hw_interface_.CheckAndSetConfig(); - updateParameters(); - } - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "Failed to get model from sensor... Set from config: " << sensor_cfg_ptr_->sensor_model); + if (launch_hw_) + { + hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_); + hw_monitor_wrapper_.emplace(this, hw_interface_wrapper_->HwInterface(), sensor_cfg_ptr_); } - pandar_scan_pub_ = - create_publisher("pandar_packets", rclcpp::SensorDataQoS()); - current_scan_msg_ = std::make_unique(); - - return Status::OK; -} + decoder_wrapper_.emplace(this, hw_interface_wrapper_ ? hw_interface_wrapper_->HwInterface() : nullptr, + sensor_cfg_ptr_); -Status HesaiRosWrapper::InitializeDecoder() -{ - calibration_cfg_ptr_ = std::make_shared(); - correction_cfg_ptr_ = std::make_shared(); + RCLCPP_INFO_STREAM(get_logger(), "SensorConfig:" << *sensor_cfg_ptr_); + set_param_res_ = + add_on_set_parameters_callback(std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); - wrapper_status_ = GetCalibrationData(*calibration_cfg_ptr_, *correction_cfg_ptr_); - if (Status::OK != wrapper_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); - return wrapper_status_; - } - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); - RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Wrapper=" << wrapper_status_); - rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data; - auto pointcloud_qos = - rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + RCLCPP_DEBUG(get_logger(), "Starting stream"); decoder_thread_ = std::thread([this]() { - while (true) { - this->ProcessCloudPacket(std::move(packet_queue_.pop())); + while (true) + { + decoder_wrapper_->ProcessCloudPacket(std::move(packet_queue_.pop())); } }); - nebula_points_pub_ = - this->create_publisher("pandar_points", pointcloud_qos); - aw_points_base_pub_ = - this->create_publisher("aw_points", pointcloud_qos); - aw_points_ex_pub_ = - this->create_publisher("aw_points_ex", pointcloud_qos); - - driver_ptr_ = std::make_shared( - sensor_cfg_ptr_, calibration_cfg_ptr_, correction_cfg_ptr_); - return driver_ptr_->GetStatus(); -} - -Status HesaiRosWrapper::InitializeHwMonitor() -{ - if (Status::OK != interface_status_) { - RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << interface_status_); - return Status::ERROR_1; - } - - switch (sensor_cfg_ptr_->sensor_model) { - case nebula::drivers::SensorModel::HESAI_PANDARXT32: - case nebula::drivers::SensorModel::HESAI_PANDARXT32M: - case nebula::drivers::SensorModel::HESAI_PANDARAT128: - temperature_names_.emplace_back("Bottom circuit board T1"); - temperature_names_.emplace_back("Bottom circuit board T2"); - temperature_names_.emplace_back("Laser emitting board RT_L1(Internal)"); - temperature_names_.emplace_back("Laser emitting board RT_L2"); - temperature_names_.emplace_back("Receiving board RT_R"); - temperature_names_.emplace_back("Receiving board RT2"); - temperature_names_.emplace_back("Top circuit RT3"); - temperature_names_.emplace_back("Not used"); - break; - case nebula::drivers::SensorModel::HESAI_PANDAR64: - case nebula::drivers::SensorModel::HESAI_PANDAR40P: - case nebula::drivers::SensorModel::HESAI_PANDAR40M: - case nebula::drivers::SensorModel::HESAI_PANDARQT64: - case nebula::drivers::SensorModel::HESAI_PANDARQT128: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: - case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: - default: - temperature_names_.emplace_back("Bottom circuit RT1"); - temperature_names_.emplace_back("Bottom circuit RT2"); - temperature_names_.emplace_back("Internal Temperature"); - temperature_names_.emplace_back("Laser emitting board RT1"); - temperature_names_.emplace_back("Laser emitting board RT2"); - temperature_names_.emplace_back("Receiving board RT1"); - temperature_names_.emplace_back("Top circuit RT1"); - temperature_names_.emplace_back("Top circuit RT2"); - break; - } - - auto result = hw_interface_.GetInventory(); - current_inventory_.reset(new HesaiInventory(result)); - current_inventory_time_.reset(new rclcpp::Time(this->get_clock()->now())); - std::cout << "HesaiInventory" << std::endl; - std::cout << result << std::endl; - info_model_ = result.get_str_model(); - info_serial_ = std::string(result.sn.begin(), result.sn.end()); - hw_interface_.SetTargetModel(result.model); - RCLCPP_INFO_STREAM(this->get_logger(), "Model:" << info_model_); - RCLCPP_INFO_STREAM(this->get_logger(), "Serial:" << info_serial_); - InitializeHesaiDiagnostics(); - return Status::OK; -} - -void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) -{ - // static auto convert = nebula::util::Instrumentation("ReceiveCloudPacketCallback.convert"); - // static auto publish = nebula::util::Instrumentation("ReceiveCloudPacketCallback.publish"); - // static auto delay = nebula::util::TopicDelay("ReceiveCloudPacketCallback"); - // Driver is not initialized yet - if (!driver_ptr_) { - return; - } - - // convert.tick(); - const auto now = std::chrono::system_clock::now(); - const auto timestamp_ns = - std::chrono::duration_cast(now.time_since_epoch()).count(); - - auto msg_ptr = std::make_unique(); - msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); - msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); - msg_ptr->data.swap(packet); - // convert.tock(); - - // delay.tick(msg_ptr->stamp); - - // publish.tick(); - if (!packet_queue_.try_push(std::move(msg_ptr))) { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); - } - // packet_pub_->publish(std::move(msg_ptr)); - // publish.tock(); -} - -void HesaiRosWrapper::ReceiveScanMessageCallback( - std::unique_ptr scan_msg) -{ - if (launch_hw_) { - RCLCPP_ERROR_THROTTLE( - get_logger(), *get_clock(), 1000, - "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); - return; - } - - for (auto & pkt : scan_msg->packets) { - auto nebula_pkt_ptr = std::make_unique(); - nebula_pkt_ptr->stamp = pkt.stamp; - std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); - - packet_queue_.push(std::move(nebula_pkt_ptr)); - } -} - -void HesaiRosWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) -{ - // static auto parse = nebula::util::Instrumentation("ProcessCloudPacket.parse"); - // static auto convert = nebula::util::Instrumentation("ProcessCloudPacket.convert"); - // static auto publish = nebula::util::Instrumentation("ProcessCloudPacket.publish"); - // static auto delay = nebula::util::TopicDelay("ProcessCloudPacket"); - - // delay.tick(packet_msg->stamp); - - // Accumulate packets for recording only if someone is subscribed to the topic (for performance) - if ( - launch_hw_ && - (pandar_scan_pub_->get_subscription_count() > 0 || - pandar_scan_pub_->get_intra_process_subscription_count() > 0)) { - if (current_scan_msg_->packets.size() == 0) { - current_scan_msg_->header.stamp = packet_msg->stamp; - } - - pandar_msgs::msg::PandarPacket pandar_packet_msg{}; - pandar_packet_msg.stamp = packet_msg->stamp; - pandar_packet_msg.size = packet_msg->data.size(); - std::copy(packet_msg->data.begin(), packet_msg->data.end(), pandar_packet_msg.data.begin()); - current_scan_msg_->packets.emplace_back(std::move(pandar_packet_msg)); - } - - // parse.tick(); - std::tuple pointcloud_ts = - driver_ptr_->ParseCloudPacket(packet_msg->data); - nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); - // parse.tock(); - - if (pointcloud == nullptr) { - // todo - // RCLCPP_WARN_STREAM(get_logger(), "Empty cloud parsed."); - return; - }; - - // Publish scan message only if it has been written to - if (current_scan_msg_ && !current_scan_msg_->packets.empty()) { - pandar_scan_pub_->publish(std::move(current_scan_msg_)); - current_scan_msg_ = std::make_unique(); - } - - if ( - nebula_points_pub_->get_subscription_count() > 0 || - nebula_points_pub_->get_intra_process_subscription_count() > 0) { - // convert.tick(); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - // convert.tock(); - // publish.tick(); - PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); - // publish.tock(); - } - if ( - aw_points_base_pub_->get_subscription_count() > 0 || - aw_points_base_pub_->get_intra_process_subscription_count() > 0) { - // convert.tick(); - - const auto autoware_cloud_xyzi = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - // convert.tock(); - // publish.tick(); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); - // publish.tock(); + if (launch_hw_) + { + StreamStart(); + hw_interface_wrapper_->HwInterface()->RegisterScanCallback( + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); } - if ( - aw_points_ex_pub_->get_subscription_count() > 0 || - aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { - // convert.tick(); - - const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( - pointcloud, std::get<1>(pointcloud_ts)); - auto ros_pc_msg_ptr = std::make_unique(); - pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = - rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); - // convert.tock(); - // publish.tick(); - PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); - // publish.tock(); + else + { + packets_sub_ = create_subscription( + "pandar_packets", rclcpp::SensorDataQoS(), + std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); + RCLCPP_INFO_STREAM(get_logger(), "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); } } -void HesaiRosWrapper::PublishCloud( - std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr & publisher) +nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() { - if (pointcloud->header.stamp.sec < 0) { - RCLCPP_WARN_STREAM(this->get_logger(), "Timestamp error, verify clock source."); - } - pointcloud->header.frame_id = sensor_cfg_ptr_->frame_id; - publisher->publish(std::move(pointcloud)); -} + nebula::drivers::HesaiSensorConfiguration sensor_configuration; -Status HesaiRosWrapper::GetStatus() -{ - return wrapper_status_; -} - -Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor_configuration) -{ { rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); + declare_parameter("sensor_model", ""); sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + nebula::drivers::SensorModelFromString(get_parameter("sensor_model").as_string()); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -349,9 +75,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); + declare_parameter("return_mode", "", descriptor); sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); + get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -359,8 +85,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = this->get_parameter("host_ip").as_string(); + declare_parameter("host_ip", "255.255.255.255", descriptor); + sensor_configuration.host_ip = get_parameter("host_ip").as_string(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -368,8 +94,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = this->get_parameter("sensor_ip").as_string(); + declare_parameter("sensor_ip", "192.168.1.201", descriptor); + sensor_configuration.sensor_ip = get_parameter("sensor_ip").as_string(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -377,8 +103,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = this->get_parameter("data_port").as_int(); + declare_parameter("data_port", 2368, descriptor); + sensor_configuration.data_port = get_parameter("data_port").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -386,8 +112,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = this->get_parameter("gnss_port").as_int(); + declare_parameter("gnss_port", 2369, descriptor); + sensor_configuration.gnss_port = get_parameter("gnss_port").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -395,8 +121,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + declare_parameter("frame_id", "pandar", descriptor); + sensor_configuration.frame_id = get_parameter("frame_id").as_string(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -406,18 +132,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; rcl_interfaces::msg::FloatingPointRange range; range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("calibration_file", "", descriptor); - calibration_file_path = this->get_parameter("calibration_file").as_string(); + descriptor.floating_point_range = { range }; + declare_parameter("scan_phase", 0., descriptor); + sensor_configuration.scan_phase = get_parameter("scan_phase").as_double(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -425,8 +142,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("min_range", 0.3, descriptor); - sensor_configuration.min_range = this->get_parameter("min_range").as_double(); + declare_parameter("min_range", 0.3, descriptor); + sensor_configuration.min_range = get_parameter("min_range").as_double(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -434,8 +151,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("max_range", 300., descriptor); - sensor_configuration.max_range = this->get_parameter("max_range").as_double(); + declare_parameter("max_range", 300., descriptor); + sensor_configuration.max_range = get_parameter("max_range").as_double(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -443,10 +160,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = this->get_parameter("packet_mtu_size").as_int(); + declare_parameter("packet_mtu_size", 1500, descriptor); + sensor_configuration.packet_mtu_size = get_parameter("packet_mtu_size").as_int(); } - { rcl_interfaces::msg::ParameterDescriptor descriptor; descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; @@ -454,18 +170,21 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.dynamic_typing = false; rcl_interfaces::msg::IntegerRange range; RCLCPP_DEBUG_STREAM(get_logger(), sensor_configuration.sensor_model); - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) + { descriptor.additional_constraints = "200, 300, 400, 500"; // range.set__from_value(200).set__to_value(500).set__step(100); // descriptor.integer_range = {range}; //todo - this->declare_parameter("rotation_speed", 200, descriptor); - } else { + declare_parameter("rotation_speed", 200, descriptor); + } + else + { descriptor.additional_constraints = "300, 600, 1200"; // range.set__from_value(300).set__to_value(1200).set__step(300); // descriptor.integer_range = {range}; //todo - this->declare_parameter("rotation_speed", 600, descriptor); + declare_parameter("rotation_speed", 600, descriptor); } - sensor_configuration.rotation_speed = this->get_parameter("rotation_speed").as_int(); + sensor_configuration.rotation_speed = get_parameter("rotation_speed").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -475,9 +194,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.additional_constraints = ""; rcl_interfaces::msg::IntegerRange range; range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); + descriptor.integer_range = { range }; + declare_parameter("cloud_min_angle", 0, descriptor); + sensor_configuration.cloud_min_angle = get_parameter("cloud_min_angle").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -487,18 +206,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.additional_constraints = ""; rcl_interfaces::msg::IntegerRange range; range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); - } - if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("correction_file", "", descriptor); - correction_file_path = this->get_parameter("correction_file").as_string(); + descriptor.integer_range = { range }; + declare_parameter("cloud_max_angle", 360, descriptor); + sensor_configuration.cloud_max_angle = get_parameter("cloud_max_angle").as_int(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -508,37 +218,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; rcl_interfaces::msg::FloatingPointRange range; range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = - this->get_parameter("dual_return_distance_threshold").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("launch_hw", "", descriptor); - launch_hw_ = this->get_parameter("launch_hw").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("setup_sensor", true, descriptor); - this->setup_sensor = this->get_parameter("setup_sensor").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("retry_hw", true, descriptor); - this->retry_hw_ = this->get_parameter("retry_hw").as_bool(); + descriptor.floating_point_range = { range }; + declare_parameter("dual_return_distance_threshold", 0.1, descriptor); + sensor_configuration.dual_return_distance_threshold = get_parameter("dual_return_distance_threshold").as_double(); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -546,9 +228,8 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("ptp_profile", ""); - sensor_configuration.ptp_profile = - nebula::drivers::PtpProfileFromString(this->get_parameter("ptp_profile").as_string()); + declare_parameter("ptp_profile", ""); + sensor_configuration.ptp_profile = nebula::drivers::PtpProfileFromString(get_parameter("ptp_profile").as_string()); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -556,10 +237,11 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("ptp_transport_type", ""); - sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportTypeFromString( - this->get_parameter("ptp_transport_type").as_string()); - if (static_cast(sensor_configuration.ptp_profile) > 0) { + declare_parameter("ptp_transport_type", ""); + sensor_configuration.ptp_transport_type = + nebula::drivers::PtpTransportTypeFromString(get_parameter("ptp_transport_type").as_string()); + if (static_cast(sensor_configuration.ptp_profile) > 0) + { sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; } } @@ -569,9 +251,9 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.read_only = true; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("ptp_switch_type", ""); + declare_parameter("ptp_switch_type", ""); sensor_configuration.ptp_switch_type = - nebula::drivers::PtpSwitchTypeFromString(this->get_parameter("ptp_switch_type").as_string()); + nebula::drivers::PtpSwitchTypeFromString(get_parameter("ptp_switch_type").as_string()); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -580,320 +262,144 @@ Status HesaiRosWrapper::GetParameters(drivers::HesaiSensorConfiguration & sensor descriptor.dynamic_typing = false; rcl_interfaces::msg::IntegerRange range; range.set__from_value(0).set__to_value(127).set__step(1); - descriptor.integer_range = {range}; - this->declare_parameter("ptp_domain", 0, descriptor); - sensor_configuration.ptp_domain = this->get_parameter("ptp_domain").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - this->declare_parameter("diag_span", 1000, descriptor); - this->diag_span_ = this->get_parameter("diag_span").as_int(); + descriptor.integer_range = { range }; + declare_parameter("ptp_domain", 0, descriptor); + sensor_configuration.ptp_domain = get_parameter("ptp_domain").as_int(); } - /////////////////////////////////////////////// - // Validate ROS parameters - /////////////////////////////////////////////// - - if (sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) { - RCLCPP_ERROR_STREAM( - get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); + if (sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) + { + RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); return Status::SENSOR_CONFIG_ERROR; } - if ( - sensor_configuration.ptp_transport_type == - nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { - RCLCPP_ERROR_STREAM( - get_logger(), - "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " - "using the '1588v2' PTP Profile"); + if (sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) + { + RCLCPP_ERROR_STREAM(get_logger(), + "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " + "using the '1588v2' PTP Profile"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { - RCLCPP_ERROR_STREAM( - get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); + if (sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) + { + RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) + { return Status::INVALID_SENSOR_MODEL; } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) + { return Status::INVALID_ECHO_MODE; } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { + if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) + { return Status::SENSOR_CONFIG_ERROR; } - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - - RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + auto new_cfg_ptr_ = std::make_shared(sensor_configuration); + sensor_cfg_ptr_.swap(new_cfg_ptr_); return Status::OK; } -Status HesaiRosWrapper::GetCalibrationData( - drivers::HesaiCalibrationConfiguration & calibration_configuration, - drivers::HesaiCorrection & correction_configuration) +void HesaiRosWrapper::ReceiveScanMessageCallback(std::unique_ptr scan_msg) { - calibration_configuration.calibration_file = calibration_file_path; // todo - - bool run_local = !launch_hw_; - if (sensor_cfg_ptr_->sensor_model != drivers::SensorModel::HESAI_PANDARAT128) { - std::string calibration_file_path_from_sensor; - if (launch_hw_ && !calibration_configuration.calibration_file.empty()) { - int ext_pos = calibration_configuration.calibration_file.find_last_of('.'); - calibration_file_path_from_sensor += - calibration_configuration.calibration_file.substr(0, ext_pos); - calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += calibration_configuration.calibration_file.substr( - ext_pos, calibration_configuration.calibration_file.size() - ext_pos); - } - if (launch_hw_) { - run_local = false; - RCLCPP_INFO_STREAM( - this->get_logger(), - "Trying to acquire calibration data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); - std::future future = std::async( - std::launch::async, - [this, &calibration_configuration, &calibration_file_path_from_sensor, &run_local]() { - auto str = hw_interface_.GetLidarCalibrationString(); - auto rt = - calibration_configuration.SaveFileFromString(calibration_file_path_from_sensor, str); - RCLCPP_ERROR_STREAM(get_logger(), str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM( - get_logger(), - "SaveFileFromString success:" << calibration_file_path_from_sensor << "\n"); - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "SaveFileFromString failed:" << calibration_file_path_from_sensor << "\n"); - } - rt = calibration_configuration.LoadFromString(str); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "LoadFromString success:" << str << "\n"); - } else { - RCLCPP_ERROR_STREAM(get_logger(), "LoadFromString failed:" << str << "\n"); - } - }); - std::future_status status; - status = future.wait_for(std::chrono::milliseconds(5000)); - if (status == std::future_status::timeout) { - std::cerr << "# std::future_status::timeout\n"; - RCLCPP_ERROR_STREAM(get_logger(), "GetCalibration Timeout"); - run_local = true; - } else if (status == std::future_status::ready && !run_local) { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Acquired calibration data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); - RCLCPP_INFO_STREAM( - this->get_logger(), - "The calibration has been saved in '" << calibration_file_path_from_sensor << "'"); - } - } - if (run_local) { - RCLCPP_WARN_STREAM(get_logger(), "Running locally"); - bool run_org = false; - if (calibration_file_path_from_sensor.empty()) { - run_org = true; - } else { - RCLCPP_INFO_STREAM( - get_logger(), "Trying to load file: " << calibration_file_path_from_sensor); - auto cal_status = calibration_configuration.LoadFromFile(calibration_file_path_from_sensor); + if (hw_interface_wrapper_) + { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 1000, + "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); + return; + } - if (cal_status != Status::OK) { - run_org = true; - } else { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Load calibration data from: '" << calibration_file_path_from_sensor << "'"); - } - } - if (run_org) { - RCLCPP_INFO_STREAM( - get_logger(), "Trying to load file: " << calibration_configuration.calibration_file); - if (calibration_configuration.calibration_file.empty()) { - RCLCPP_ERROR_STREAM( - this->get_logger(), - "Empty Calibration_file File: '" << calibration_configuration.calibration_file << "'"); - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = - calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); + for (auto& pkt : scan_msg->packets) + { + auto nebula_pkt_ptr = std::make_unique(); + nebula_pkt_ptr->stamp = pkt.stamp; + std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), - "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); - return cal_status; - } else { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Load calibration data from: '" << calibration_configuration.calibration_file << "'"); - } - } - } - } - } else { // sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128 - std::string correction_file_path_from_sensor; - if (launch_hw_ && !correction_file_path.empty()) { - int ext_pos = correction_file_path.find_last_of('.'); - correction_file_path_from_sensor += correction_file_path.substr(0, ext_pos); - correction_file_path_from_sensor += "_from_sensor"; - correction_file_path_from_sensor += - correction_file_path.substr(ext_pos, correction_file_path.size() - ext_pos); - } - std::future future = std::async( - std::launch::async, - [this, &correction_configuration, &correction_file_path_from_sensor, &run_local]() { - if (launch_hw_) { - RCLCPP_INFO_STREAM(this->get_logger(), "Trying to acquire calibration data from sensor"); - auto received_bytes = hw_interface_.GetLidarCalibrationBytes(); - RCLCPP_INFO_STREAM( - get_logger(), "AT128 calibration size:" << received_bytes.size() << "\n"); - auto rt = correction_configuration.SaveFileFromBinary( - correction_file_path_from_sensor, received_bytes); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM( - get_logger(), - "SaveFileFromBinary success:" << correction_file_path_from_sensor << "\n"); - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "SaveFileFromBinary failed:" << correction_file_path_from_sensor - << ". Falling back to offline calibration file."); - run_local = true; - } - rt = correction_configuration.LoadFromBinary(received_bytes); - if (rt == Status::OK) { - RCLCPP_INFO_STREAM(get_logger(), "LoadFromBinary success" << "\n"); - run_local = false; - } else { - RCLCPP_ERROR_STREAM( - get_logger(), - "LoadFromBinary failed" << ". Falling back to offline calibration file."); - run_local = true; - } - } else { - RCLCPP_ERROR_STREAM(get_logger(), "Falling back to offline calibration file."); - run_local = true; - } - }); - if (!run_local) { - std::future_status status; - status = future.wait_for(std::chrono::milliseconds(8000)); - if (status == std::future_status::timeout) { - std::cerr << "# std::future_status::timeout\n"; - run_local = true; - } else if (status == std::future_status::ready && !run_local) { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Acquired correction data from sensor: '" << sensor_cfg_ptr_->sensor_ip << "'"); - RCLCPP_INFO_STREAM( - this->get_logger(), - "The correction has been saved in '" << correction_file_path_from_sensor << "'"); - } - } - if (run_local) { - bool run_org = false; - if (correction_file_path_from_sensor.empty()) { - run_org = true; - } else { - auto cal_status = correction_configuration.LoadFromFile(correction_file_path_from_sensor); + packet_queue_.push(std::move(nebula_pkt_ptr)); + } +} - if (cal_status != Status::OK) { - run_org = true; - } else { - RCLCPP_INFO_STREAM( - this->get_logger(), - "Load correction data from: '" << correction_file_path_from_sensor << "'"); - } - } - if (run_org) { - if (correction_file_path.empty()) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Empty Correction File: '" << correction_file_path << "'"); - return Status::INVALID_CALIBRATION_FILE; - } else { - auto cal_status = correction_configuration.LoadFromFile(correction_file_path); +Status HesaiRosWrapper::GetStatus() +{ + return wrapper_status_; +} - if (cal_status != Status::OK) { - RCLCPP_ERROR_STREAM( - this->get_logger(), "Given Correction File: '" << correction_file_path << "'"); - return cal_status; - } else { - RCLCPP_INFO_STREAM( - this->get_logger(), "Load correction data from: '" << correction_file_path << "'"); - } - } - } - } - } // end AT128 +Status HesaiRosWrapper::DeclareAndGetWrapperParams() +{ + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + declare_parameter("launch_hw", "", descriptor); + launch_hw_ = get_parameter("launch_hw").as_bool(); + } return Status::OK; } HesaiRosWrapper::~HesaiRosWrapper() { - RCLCPP_INFO_STREAM(get_logger(), "Closing TcpDriver"); - hw_interface_.FinalizeTcpDriver(); } Status HesaiRosWrapper::StreamStart() { - if (Status::OK == interface_status_) { - interface_status_ = hw_interface_.SensorInterfaceStart(); + if (!hw_interface_wrapper_) + { + return Status::UDP_CONNECTION_ERROR; } - return interface_status_; + + if (hw_interface_wrapper_->Status() != Status::OK) + { + return hw_interface_wrapper_->Status(); + } + + return hw_interface_wrapper_->HwInterface()->SensorInterfaceStart(); } -rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( - const std::vector & p) +rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback(const std::vector& p) { std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback"); - RCLCPP_DEBUG_STREAM(this->get_logger(), p); - RCLCPP_DEBUG_STREAM(this->get_logger(), *sensor_cfg_ptr_); - RCLCPP_INFO_STREAM(this->get_logger(), p); + RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback"); + RCLCPP_DEBUG_STREAM(get_logger(), p); + RCLCPP_DEBUG_STREAM(get_logger(), *sensor_cfg_ptr_); + + drivers::HesaiSensorConfiguration new_cfg(*sensor_cfg_ptr_); - std::shared_ptr new_param = - std::make_shared(*sensor_cfg_ptr_); - RCLCPP_INFO_STREAM(this->get_logger(), new_param); std::string sensor_model_str; std::string return_mode_str; - if ( - get_param(p, "sensor_model", sensor_model_str) | get_param(p, "return_mode", return_mode_str) | - get_param(p, "host_ip", new_param->host_ip) | get_param(p, "sensor_ip", new_param->sensor_ip) | - get_param(p, "frame_id", new_param->frame_id) | - get_param(p, "data_port", new_param->data_port) | - get_param(p, "gnss_port", new_param->gnss_port) | - get_param(p, "scan_phase", new_param->scan_phase) | - get_param(p, "packet_mtu_size", new_param->packet_mtu_size) | - get_param(p, "rotation_speed", new_param->rotation_speed) | - get_param(p, "cloud_min_angle", new_param->cloud_min_angle) | - get_param(p, "cloud_max_angle", new_param->cloud_max_angle) | - get_param(p, "dual_return_distance_threshold", new_param->dual_return_distance_threshold)) { + if (get_param(p, "sensor_model", sensor_model_str) | get_param(p, "return_mode", return_mode_str) | + get_param(p, "host_ip", new_cfg.host_ip) | get_param(p, "sensor_ip", new_cfg.sensor_ip) | + get_param(p, "frame_id", new_cfg.frame_id) | get_param(p, "data_port", new_cfg.data_port) | + get_param(p, "gnss_port", new_cfg.gnss_port) | get_param(p, "scan_phase", new_cfg.scan_phase) | + get_param(p, "packet_mtu_size", new_cfg.packet_mtu_size) | + get_param(p, "rotation_speed", new_cfg.rotation_speed) | + get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | + get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle) | + get_param(p, "dual_return_distance_threshold", new_cfg.dual_return_distance_threshold)) + { if (0 < sensor_model_str.length()) - new_param->sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); + new_cfg.sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); if (0 < return_mode_str.length()) - new_param->return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); + new_cfg.return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); - sensor_cfg_ptr_.swap(new_param); - RCLCPP_INFO_STREAM(this->get_logger(), "Update sensor_configuration"); - RCLCPP_DEBUG_STREAM(this->get_logger(), "hw_interface_.SetSensorConfiguration"); - hw_interface_.SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - hw_interface_.CheckAndSetConfig(); + auto new_cfg_ptr = std::make_shared(new_cfg); + sensor_cfg_ptr_.swap(new_cfg_ptr); + RCLCPP_INFO_STREAM(get_logger(), "Update sensor_configuration"); + RCLCPP_DEBUG_STREAM(get_logger(), "hw_interface_.SetSensorConfiguration"); + hw_interface_wrapper_->HwInterface()->SetSensorConfiguration( + std::static_pointer_cast(sensor_cfg_ptr_)); + hw_interface_wrapper_->HwInterface()->CheckAndSetConfig(); } auto result = std::make_shared(); result->successful = true; result->reason = "success"; - RCLCPP_DEBUG_STREAM(this->get_logger(), "add_on_set_parameters_callback success"); + RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback success"); return *result; } @@ -901,310 +407,47 @@ rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback( std::vector HesaiRosWrapper::updateParameters() { std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters start"); + RCLCPP_DEBUG_STREAM(get_logger(), "updateParameters start"); std::ostringstream os_sensor_model; os_sensor_model << sensor_cfg_ptr_->sensor_model; std::ostringstream os_return_mode; os_return_mode << sensor_cfg_ptr_->return_mode; - RCLCPP_INFO_STREAM(this->get_logger(), "set_parameters"); + RCLCPP_INFO_STREAM(get_logger(), "set_parameters"); auto results = set_parameters( - {rclcpp::Parameter("sensor_model", os_sensor_model.str()), - rclcpp::Parameter("return_mode", os_return_mode.str()), - rclcpp::Parameter("host_ip", sensor_cfg_ptr_->host_ip), - rclcpp::Parameter("sensor_ip", sensor_cfg_ptr_->sensor_ip), - rclcpp::Parameter("frame_id", sensor_cfg_ptr_->frame_id), - rclcpp::Parameter("data_port", sensor_cfg_ptr_->data_port), - rclcpp::Parameter("gnss_port", sensor_cfg_ptr_->gnss_port), - rclcpp::Parameter("scan_phase", sensor_cfg_ptr_->scan_phase), - rclcpp::Parameter("packet_mtu_size", sensor_cfg_ptr_->packet_mtu_size), - rclcpp::Parameter("rotation_speed", sensor_cfg_ptr_->rotation_speed), - rclcpp::Parameter("cloud_min_angle", sensor_cfg_ptr_->cloud_min_angle), - rclcpp::Parameter("cloud_max_angle", sensor_cfg_ptr_->cloud_max_angle), - rclcpp::Parameter( - "dual_return_distance_threshold", sensor_cfg_ptr_->dual_return_distance_threshold)}); - RCLCPP_DEBUG_STREAM(this->get_logger(), "updateParameters end"); + { rclcpp::Parameter("sensor_model", os_sensor_model.str()), + rclcpp::Parameter("return_mode", os_return_mode.str()), rclcpp::Parameter("host_ip", sensor_cfg_ptr_->host_ip), + rclcpp::Parameter("sensor_ip", sensor_cfg_ptr_->sensor_ip), + rclcpp::Parameter("frame_id", sensor_cfg_ptr_->frame_id), + rclcpp::Parameter("data_port", sensor_cfg_ptr_->data_port), + rclcpp::Parameter("gnss_port", sensor_cfg_ptr_->gnss_port), + rclcpp::Parameter("scan_phase", sensor_cfg_ptr_->scan_phase), + rclcpp::Parameter("packet_mtu_size", sensor_cfg_ptr_->packet_mtu_size), + rclcpp::Parameter("rotation_speed", sensor_cfg_ptr_->rotation_speed), + rclcpp::Parameter("cloud_min_angle", sensor_cfg_ptr_->cloud_min_angle), + rclcpp::Parameter("cloud_max_angle", sensor_cfg_ptr_->cloud_max_angle), + rclcpp::Parameter("dual_return_distance_threshold", sensor_cfg_ptr_->dual_return_distance_threshold) }); + RCLCPP_DEBUG_STREAM(get_logger(), "updateParameters end"); return results; } -void HesaiRosWrapper::InitializeHesaiDiagnostics() -{ - RCLCPP_INFO_STREAM(this->get_logger(), "InitializeHesaiDiagnostics"); - using std::chrono_literals::operator""s; - std::ostringstream os; - auto hardware_id = info_model_ + ": " + info_serial_; - diagnostics_updater_.setHardwareID(hardware_id); - RCLCPP_INFO_STREAM(this->get_logger(), "hardware_id: " + hardware_id); - - diagnostics_updater_.add("hesai_status", this, &HesaiRosWrapper::HesaiCheckStatus); - diagnostics_updater_.add("hesai_ptp", this, &HesaiRosWrapper::HesaiCheckPtp); - diagnostics_updater_.add("hesai_temperature", this, &HesaiRosWrapper::HesaiCheckTemperature); - diagnostics_updater_.add("hesai_rpm", this, &HesaiRosWrapper::HesaiCheckRpm); - - current_status_.reset(); - current_monitor_.reset(); - current_status_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; - current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; - - auto fetch_diag_from_sensor = [this]() { - OnHesaiStatusTimer(); - if (hw_interface_.UseHttpGetLidarMonitor()) { - OnHesaiLidarMonitorTimerHttp(); - } else { - OnHesaiLidarMonitorTimer(); - } - }; - - fetch_diagnostics_timer_ = - create_wall_timer(std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor)); - - if (hw_interface_.UseHttpGetLidarMonitor()) { - diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltageHttp); - } else { - diagnostics_updater_.add("hesai_voltage", this, &HesaiRosWrapper::HesaiCheckVoltage); - } - - auto on_timer_update = [this] { - RCLCPP_DEBUG_STREAM(get_logger(), "OnUpdateTimer"); - auto now = this->get_clock()->now(); - auto dif = (now - *current_status_time_).seconds(); - - RCLCPP_DEBUG_STREAM(get_logger(), "dif(status): " << dif); - - if (diag_span_ * 2.0 < dif * 1000) { - current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); - } else { - current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); - } - dif = (now - *current_lidar_monitor_time_).seconds(); - RCLCPP_DEBUG_STREAM(get_logger(), "dif(monitor): " << dif); - if (diag_span_ * 2.0 < dif * 1000) { - current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; - RCLCPP_DEBUG_STREAM(get_logger(), "STALE"); - } else { - current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; - RCLCPP_DEBUG_STREAM(get_logger(), "OK"); - } - diagnostics_updater_.force_update(); - }; - diagnostics_update_timer_ = - create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); - - RCLCPP_DEBUG_STREAM(get_logger(), "add_timer"); -} - -std::string HesaiRosWrapper::GetPtreeValue( - boost::property_tree::ptree * pt, const std::string & key) -{ - boost::optional value = pt->get_optional(key); - if (value) { - return value.get(); - } else { - return MSG_NOT_SUPPORTED; - } -} -std::string HesaiRosWrapper::GetFixedPrecisionString(double val, int pre) -{ - std::stringstream ss; - ss << std::fixed << std::setprecision(pre) << val; - return ss.str(); -} - -void HesaiRosWrapper::OnHesaiStatusTimer() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer" << std::endl); - try { - auto result = hw_interface_.GetLidarStatus(); - std::scoped_lock lock(mtx_lidar_status_); - current_status_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_status_.reset(new HesaiLidarStatus(result)); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(std::system_error)"), error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiStatusTimer(boost::system::system_error)"), - error.what()); - } - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiStatusTimer END" << std::endl); -} - -void HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp"); - try { - hw_interface_.GetLidarMonitorAsyncHttp([this](const std::string & str) { - std::scoped_lock lock(mtx_lidar_monitor_); - current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_lidar_monitor_tree_ = - std::make_unique(hw_interface_.ParseJson(str)); - }); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger( - "HesaiRosWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_error)"), - error.what()); - } - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimerHttp END"); -} - -void HesaiRosWrapper::OnHesaiLidarMonitorTimer() -{ - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer"); - try { - auto result = hw_interface_.GetLidarMonitor(); - std::scoped_lock lock(mtx_lidar_monitor_); - current_lidar_monitor_time_.reset(new rclcpp::Time(this->get_clock()->now())); - current_monitor_.reset(new HesaiLidarMonitor(result)); - } catch (const std::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), - error.what()); - } catch (const boost::system::system_error & error) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("HesaiRosWrapper::OnHesaiLidarMonitorTimer(boost::system::system_error)"), - error.what()); - } - RCLCPP_DEBUG_STREAM(this->get_logger(), "OnHesaiLidarMonitorTimer END"); -} - -void HesaiRosWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - - diagnostics.add("system_uptime", std::to_string(current_status_->system_uptime)); - diagnostics.add("startup_times", std::to_string(current_status_->startup_times)); - diagnostics.add("total_operation_time", std::to_string(current_status_->total_operation_time)); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiRosWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - auto gps_status = current_status_->get_str_gps_pps_lock(); - auto gprmc_status = current_status_->get_str_gps_gprmc_status(); - auto ptp_status = current_status_->get_str_ptp_clock_status(); - std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); - std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); - std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); - diagnostics.add("gps_pps_lock", gps_status); - diagnostics.add("gps_gprmc_status", gprmc_status); - diagnostics.add("ptp_clock_status", ptp_status); - if (gps_status != "UNKNOWN") { - msg.emplace_back("gps_pps_lock: " + gps_status); - } - if (gprmc_status != "UNKNOWN") { - msg.emplace_back("gprmc_status: " + gprmc_status); - } - if (ptp_status != "UNKNOWN") { - msg.emplace_back("ptp_status: " + ptp_status); - } - if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") { - level = diagnostic_msgs::msg::DiagnosticStatus::WARN; - } - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiRosWrapper::HesaiCheckTemperature( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - for (size_t i = 0; i < current_status_->temperature.size(); i++) { - diagnostics.add( - temperature_names_[i], GetFixedPrecisionString(current_status_->temperature[i] * 0.01)); - } - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} - -void HesaiRosWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) +void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector& packet) { - std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - diagnostics.add("motor_speed", std::to_string(current_status_->motor_speed)); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + if (!decoder_wrapper_ || decoder_wrapper_->Status() != Status::OK) + { + return; } -} -void HesaiRosWrapper::HesaiCheckVoltageHttp( - diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_monitor_); - if (current_lidar_monitor_tree_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - std::string key = ""; - - std::string mes; - key = "lidarInCur"; - try { - mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); - } catch (boost::bad_lexical_cast & ex) { - level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = MSG_ERROR + std::string(ex.what()); - } - diagnostics.add(key, mes); - key = "lidarInVol"; - try { - mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); - } catch (boost::bad_lexical_cast & ex) { - level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; - mes = MSG_ERROR + std::string(ex.what()); - } - diagnostics.add(key, mes); - - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); - } -} + const auto now = std::chrono::system_clock::now(); + const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); -void HesaiRosWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) -{ - std::scoped_lock lock(mtx_lidar_monitor_); - if (current_monitor_) { - uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; - std::vector msg; - diagnostics.add( - "input_voltage", GetFixedPrecisionString(current_monitor_->input_voltage * 0.01) + " V"); - diagnostics.add( - "input_current", GetFixedPrecisionString(current_monitor_->input_current * 0.01) + " mA"); - diagnostics.add( - "input_power", GetFixedPrecisionString(current_monitor_->input_power * 0.01) + " W"); + auto msg_ptr = std::make_unique(); + msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); + msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); + msg_ptr->data.swap(packet); - diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } else { - diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + if (!packet_queue_.try_push(std::move(msg_ptr))) + { + RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); } } diff --git a/nebula_ros/src/hesai/hw_interface_wrapper.cpp b/nebula_ros/src/hesai/hw_interface_wrapper.cpp new file mode 100644 index 000000000..e38f6b181 --- /dev/null +++ b/nebula_ros/src/hesai/hw_interface_wrapper.cpp @@ -0,0 +1,94 @@ +#include "nebula_ros/hesai/hw_interface_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ + +HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, + std::shared_ptr& config) + : hw_interface_(new nebula::drivers::HesaiHwInterface()) + , logger_(parent_node->get_logger().get_child("HwInterface")) + , status_(Status::NOT_INITIALIZED) +{ + bool setup_sensor, retry_connect; + + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + parent_node->declare_parameter("setup_sensor", true, descriptor); + setup_sensor = parent_node->get_parameter("setup_sensor").as_bool(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + parent_node->declare_parameter("retry_hw", true, descriptor); + retry_connect = parent_node->get_parameter("retry_hw").as_bool(); + } + + hw_interface_->SetSensorConfiguration(std::static_pointer_cast(config)); + + status_ = Status::OK; + + hw_interface_->SetLogger(std::make_shared(parent_node->get_logger())); + hw_interface_->SetTargetModel(config->sensor_model); + + int retry_count = 0; + + while (true) + { + status_ = hw_interface_->InitializeTcpDriver(); + if (status_ == Status::OK || !retry_connect) + { + break; + } + + retry_count++; + std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 + RCLCPP_WARN_STREAM(logger_, "Retry: " << retry_count); + } + + if (status_ == Status::OK) + { + try + { + auto inventory = hw_interface_->GetInventory(); + RCLCPP_INFO_STREAM(logger_, inventory); + hw_interface_->SetTargetModel(inventory.model); + } + catch (...) + { + RCLCPP_ERROR_STREAM(logger_, "Failed to get model from sensor..."); + } + if (setup_sensor) + { + hw_interface_->CheckAndSetConfig(); + // updateParameters(); TODO + } + } + else + { + RCLCPP_ERROR_STREAM(logger_, "Failed to get model from sensor... Set from config: " << config->sensor_model); + } + + status_ = Status::OK; +} + +Status HesaiHwInterfaceWrapper::Status() +{ + return status_; +} + +std::shared_ptr HesaiHwInterfaceWrapper::HwInterface() const +{ + return hw_interface_; +} + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp new file mode 100644 index 000000000..579e32a4e --- /dev/null +++ b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp @@ -0,0 +1,412 @@ +#include "nebula_ros/hesai/hw_monitor_wrapper.hpp" + +namespace nebula +{ +namespace ros +{ +HesaiHwMonitorWrapper::HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, + const std::shared_ptr& hw_interface, + std::shared_ptr& config) + : logger_(parent_node->get_logger().get_child("HwMonitor")) + , diagnostics_updater_(parent_node) + , status_(Status::OK) + , hw_interface_(hw_interface) + , parent_node_(parent_node) +{ + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "milliseconds"; + parent_node->declare_parameter("diag_span", 1000, descriptor); + diag_span_ = parent_node->get_parameter("diag_span").as_int(); + } + + switch (config->sensor_model) + { + case nebula::drivers::SensorModel::HESAI_PANDARXT32: + case nebula::drivers::SensorModel::HESAI_PANDARXT32M: + case nebula::drivers::SensorModel::HESAI_PANDARAT128: + temperature_names_.emplace_back("Bottom circuit board T1"); + temperature_names_.emplace_back("Bottom circuit board T2"); + temperature_names_.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names_.emplace_back("Laser emitting board RT_L2"); + temperature_names_.emplace_back("Receiving board RT_R"); + temperature_names_.emplace_back("Receiving board RT2"); + temperature_names_.emplace_back("Top circuit RT3"); + temperature_names_.emplace_back("Not used"); + break; + case nebula::drivers::SensorModel::HESAI_PANDAR64: + case nebula::drivers::SensorModel::HESAI_PANDAR40P: + case nebula::drivers::SensorModel::HESAI_PANDAR40M: + case nebula::drivers::SensorModel::HESAI_PANDARQT64: + case nebula::drivers::SensorModel::HESAI_PANDARQT128: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E3X: + case nebula::drivers::SensorModel::HESAI_PANDAR128_E4X: + default: + temperature_names_.emplace_back("Bottom circuit RT1"); + temperature_names_.emplace_back("Bottom circuit RT2"); + temperature_names_.emplace_back("Internal Temperature"); + temperature_names_.emplace_back("Laser emitting board RT1"); + temperature_names_.emplace_back("Laser emitting board RT2"); + temperature_names_.emplace_back("Receiving board RT1"); + temperature_names_.emplace_back("Top circuit RT1"); + temperature_names_.emplace_back("Top circuit RT2"); + break; + } + + auto result = hw_interface->GetInventory(); + current_inventory_.reset(new HesaiInventory(result)); + current_inventory_time_.reset(new rclcpp::Time(parent_node->get_clock()->now())); + std::cout << "HesaiInventory" << std::endl; + std::cout << result << std::endl; + info_model_ = result.get_str_model(); + info_serial_ = std::string(std::begin(result.sn), std::end(result.sn)); + RCLCPP_INFO_STREAM(logger_, "Model:" << info_model_); + RCLCPP_INFO_STREAM(logger_, "Serial:" << info_serial_); + InitializeHesaiDiagnostics(); + + if (Status::OK != status_) + { + throw std::runtime_error((std::stringstream() << "Error getting calibration data: " << status_).str()); + } +} + +void HesaiHwMonitorWrapper::InitializeHesaiDiagnostics() +{ + RCLCPP_INFO_STREAM(logger_, "InitializeHesaiDiagnostics"); + using std::chrono_literals::operator""s; + std::ostringstream os; + auto hardware_id = info_model_ + ": " + info_serial_; + diagnostics_updater_.setHardwareID(hardware_id); + RCLCPP_INFO_STREAM(logger_, "hardware_id: " + hardware_id); + + diagnostics_updater_.add("hesai_status", this, &HesaiHwMonitorWrapper::HesaiCheckStatus); + diagnostics_updater_.add("hesai_ptp", this, &HesaiHwMonitorWrapper::HesaiCheckPtp); + diagnostics_updater_.add("hesai_temperature", this, &HesaiHwMonitorWrapper::HesaiCheckTemperature); + diagnostics_updater_.add("hesai_rpm", this, &HesaiHwMonitorWrapper::HesaiCheckRpm); + + current_status_.reset(); + current_monitor_.reset(); + current_status_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_lidar_monitor_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + + auto fetch_diag_from_sensor = [this]() { + OnHesaiStatusTimer(); + if (hw_interface_->UseHttpGetLidarMonitor()) + { + OnHesaiLidarMonitorTimerHttp(); + } + else + { + OnHesaiLidarMonitorTimer(); + } + }; + + fetch_diagnostics_timer_ = + parent_node_->create_wall_timer(std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor)); + + if (hw_interface_->UseHttpGetLidarMonitor()) + { + diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorWrapper::HesaiCheckVoltageHttp); + } + else + { + diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorWrapper::HesaiCheckVoltage); + } + + auto on_timer_update = [this] { + RCLCPP_DEBUG_STREAM(logger_, "OnUpdateTimer"); + auto now = parent_node_->get_clock()->now(); + auto dif = (now - *current_status_time_).seconds(); + + RCLCPP_DEBUG_STREAM(logger_, "dif(status): " << dif); + + if (diag_span_ * 2.0 < dif * 1000) + { + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(logger_, "STALE"); + } + else + { + current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(logger_, "OK"); + } + dif = (now - *current_lidar_monitor_time_).seconds(); + RCLCPP_DEBUG_STREAM(logger_, "dif(monitor): " << dif); + if (diag_span_ * 2.0 < dif * 1000) + { + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; + RCLCPP_DEBUG_STREAM(logger_, "STALE"); + } + else + { + current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; + RCLCPP_DEBUG_STREAM(logger_, "OK"); + } + diagnostics_updater_.force_update(); + }; + diagnostics_update_timer_ = + parent_node_->create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); + + RCLCPP_DEBUG_STREAM(logger_, "add_timer"); +} + +std::string HesaiHwMonitorWrapper::GetPtreeValue(boost::property_tree::ptree* pt, const std::string& key) +{ + boost::optional value = pt->get_optional(key); + if (value) + { + return value.get(); + } + else + { + return MSG_NOT_SUPPORTED; + } +} +std::string HesaiHwMonitorWrapper::GetFixedPrecisionString(double val, int pre) +{ + std::stringstream ss; + ss << std::fixed << std::setprecision(pre) << val; + return ss.str(); +} + +void HesaiHwMonitorWrapper::OnHesaiStatusTimer() +{ + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiStatusTimer" << std::endl); + try + { + auto result = hw_interface_->GetLidarStatus(); + std::scoped_lock lock(mtx_lidar_status_); + current_status_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_status_.reset(new HesaiLidarStatus(result)); + } + catch (const std::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiStatusTimer(std::system_error)"), + error.what()); + } + catch (const boost::system::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiStatusTimer(boost::system::system_error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiStatusTimer END" << std::endl); +} + +void HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp() +{ + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimerHttp"); + try + { + hw_interface_->GetLidarMonitorAsyncHttp([this](const std::string& str) { + std::scoped_lock lock(mtx_lidar_monitor_); + current_lidar_monitor_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_lidar_monitor_tree_ = std::make_unique(hw_interface_->ParseJson(str)); + }); + } + catch (const std::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), + error.what()); + } + catch (const boost::system::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_" + "error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimerHttp END"); +} + +void HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer() +{ + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimer"); + try + { + auto result = hw_interface_->GetLidarMonitor(); + std::scoped_lock lock(mtx_lidar_monitor_); + current_lidar_monitor_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); + current_monitor_.reset(new HesaiLidarMonitor(result)); + } + catch (const std::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), + error.what()); + } + catch (const boost::system::system_error& error) + { + RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer(boost::system::system_" + "error)"), + error.what()); + } + RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimer END"); +} + +void HesaiHwMonitorWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + + diagnostics.add("system_uptime", std::to_string(current_status_->system_uptime.value())); + diagnostics.add("startup_times", std::to_string(current_status_->startup_times.value())); + diagnostics.add("total_operation_time", std::to_string(current_status_->total_operation_time.value())); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + auto gps_status = current_status_->get_str_gps_pps_lock(); + auto gprmc_status = current_status_->get_str_gps_gprmc_status(); + auto ptp_status = current_status_->get_str_ptp_clock_status(); + std::transform(gps_status.cbegin(), gps_status.cend(), gps_status.begin(), toupper); + std::transform(gprmc_status.cbegin(), gprmc_status.cend(), gprmc_status.begin(), toupper); + std::transform(ptp_status.cbegin(), ptp_status.cend(), ptp_status.begin(), toupper); + diagnostics.add("gps_pps_lock", gps_status); + diagnostics.add("gps_gprmc_status", gprmc_status); + diagnostics.add("ptp_clock_status", ptp_status); + if (gps_status != "UNKNOWN") + { + msg.emplace_back("gps_pps_lock: " + gps_status); + } + if (gprmc_status != "UNKNOWN") + { + msg.emplace_back("gprmc_status: " + gprmc_status); + } + if (ptp_status != "UNKNOWN") + { + msg.emplace_back("ptp_status: " + ptp_status); + } + if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") + { + level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + } + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + for (size_t i = 0; i < std::size(current_status_->temperature); i++) + { + diagnostics.add(temperature_names_[i], + GetFixedPrecisionString(current_status_->temperature[i].value() * 0.01, 3)); + } + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_status_); + if (current_status_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + diagnostics.add("motor_speed", std::to_string(current_status_->motor_speed.value())); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_monitor_); + if (current_lidar_monitor_tree_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + std::string key = ""; + + std::string mes; + key = "lidarInCur"; + try + { + mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); + } + catch (boost::bad_lexical_cast& ex) + { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = MSG_ERROR + std::string(ex.what()); + } + diagnostics.add(key, mes); + key = "lidarInVol"; + try + { + mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); + } + catch (boost::bad_lexical_cast& ex) + { + level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + mes = MSG_ERROR + std::string(ex.what()); + } + diagnostics.add(key, mes); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +void HesaiHwMonitorWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +{ + std::scoped_lock lock(mtx_lidar_monitor_); + if (current_monitor_) + { + uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; + std::vector msg; + diagnostics.add("input_voltage", GetFixedPrecisionString(current_monitor_->input_voltage.value() * 0.01, 3) + " V"); + diagnostics.add("input_current", GetFixedPrecisionString(current_monitor_->input_current.value() * 0.01, 3) + " m" + "A"); + diagnostics.add("input_power", GetFixedPrecisionString(current_monitor_->input_power.value() * 0.01, 3) + " W"); + + diagnostics.summary(level, boost::algorithm::join(msg, ", ")); + } + else + { + diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); + } +} + +Status HesaiHwMonitorWrapper::Status() +{ + return Status::NOT_IMPLEMENTED; // TODO +} +} // namespace ros +} // namespace nebula \ No newline at end of file From 10388c9049fb7e362fd63b92c6c862c550d05fc5 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 16 Apr 2024 17:57:28 +0900 Subject: [PATCH 095/122] chore: update cspell ignore --- nebula_common/src/velodyne/velodyne_calibration_decoder.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index 0c03c3c9e..954da496b 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,3 +1,4 @@ +// cspell:ignore piyush, fout /** * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, From 7d78b847aa1af4bebfe552dbefbf34ca2668f917 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 16:40:54 +0900 Subject: [PATCH 096/122] chore(velodyne_calibration_decoder): fix spelling --- nebula_common/src/velodyne/velodyne_calibration_decoder.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index 954da496b..0016e8208 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,4 +1,3 @@ -// cspell:ignore piyush, fout /** * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, @@ -7,6 +6,8 @@ * License: Modified BSD License */ +// cspell:ignore piyush, piyushk, fout + #include #ifdef HAVE_NEW_YAMLCPP From a063a5fb2b6548cc54f2b435219e343b06fe2a47 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 16:43:32 +0900 Subject: [PATCH 097/122] chore(nebula_common): remove debug code --- .../nebula_common/util/instrumentation.hpp | 86 ------------------- .../util/performance_counter.hpp | 43 ---------- .../nebula_common/util/topic_delay.hpp | 68 --------------- 3 files changed, 197 deletions(-) delete mode 100644 nebula_common/include/nebula_common/util/instrumentation.hpp delete mode 100644 nebula_common/include/nebula_common/util/performance_counter.hpp delete mode 100644 nebula_common/include/nebula_common/util/topic_delay.hpp diff --git a/nebula_common/include/nebula_common/util/instrumentation.hpp b/nebula_common/include/nebula_common/util/instrumentation.hpp deleted file mode 100644 index ccce705d8..000000000 --- a/nebula_common/include/nebula_common/util/instrumentation.hpp +++ /dev/null @@ -1,86 +0,0 @@ -#pragma once - -#include "nebula_common/util/performance_counter.hpp" - -#include -#include -#include - -namespace nebula -{ -namespace util -{ - -using namespace std::chrono_literals; - -class Instrumentation -{ - using clock = std::chrono::high_resolution_clock; - using time_point = clock::time_point; - using duration = std::chrono::nanoseconds; - -public: - Instrumentation(std::string tag) - : tag_(std::move(tag)), last_print_(clock::now()), delays_(), rtts_() - { - } - - void tick() - { - auto now = clock::now(); - - if (last_tick_ != time_point::min()) { - auto rtt = now - last_tick_; - rtts_.update(rtt); - } - - last_tick_ = now; - } - - void tock() - { - auto now = clock::now(); - auto delay = now - last_tick_; - delays_.update(delay); - - if (now - last_print_ >= PRINT_INTERVAL) { - auto del = delays_.reset(); - auto rtt = rtts_.reset(); - - last_print_ = now; - - std::stringstream ss; - - ss << "{\"type\": \"instrumentation\", \"tag\": \"" << tag_ - << "\", \"del\": ["; - - for (duration & dt : *del) { - ss << dt.count() << ','; - } - - ss <<"null], \"rtt\": ["; - - for (duration & dt : *rtt) { - ss << dt.count() << ','; - } - - ss << "null]}" << std::endl; - - std::cout << ss.str(); - } - } - -private: - std::string tag_; - - time_point last_tick_{time_point::min()}; - time_point last_print_{time_point::min()}; - - Counter delays_; - Counter rtts_; - - const duration PRINT_INTERVAL = 1s; -}; - -} // namespace util -} // namespace nebula \ No newline at end of file diff --git a/nebula_common/include/nebula_common/util/performance_counter.hpp b/nebula_common/include/nebula_common/util/performance_counter.hpp deleted file mode 100644 index cd6b618f1..000000000 --- a/nebula_common/include/nebula_common/util/performance_counter.hpp +++ /dev/null @@ -1,43 +0,0 @@ -#pragma once - -#include -#include -#include - -namespace nebula -{ -namespace util -{ - -class Counter -{ - using clock = std::chrono::high_resolution_clock; - using time_point = clock::time_point; - using duration = std::chrono::nanoseconds; - -public: - Counter() - : buf_record_(), buf_output_() - { - buf_record_.resize(100000); - buf_output_.resize(100000); - } - - std::vector * reset() - { - buf_record_.swap(buf_output_); - buf_record_.clear(); - return &buf_output_; - } - - void update(duration measurement) - { - buf_record_.push_back(measurement); - } - -private: - std::vector buf_record_; - std::vector buf_output_; -}; -} // namespace util -} // namespace nebula \ No newline at end of file diff --git a/nebula_common/include/nebula_common/util/topic_delay.hpp b/nebula_common/include/nebula_common/util/topic_delay.hpp deleted file mode 100644 index a92ce29a2..000000000 --- a/nebula_common/include/nebula_common/util/topic_delay.hpp +++ /dev/null @@ -1,68 +0,0 @@ -#pragma once - -#include - -#include "nebula_common/util/performance_counter.hpp" - - -#include -#include -#include - -namespace nebula -{ -namespace util -{ - -using namespace std::chrono_literals; - -class TopicDelay -{ - using clock = std::chrono::high_resolution_clock; - using time_point = clock::time_point; - using duration = std::chrono::nanoseconds; - -public: - TopicDelay(std::string tag) : tag_(std::move(tag)), last_print_(clock::now()), delays_() {} - - void tick(builtin_interfaces::msg::Time & stamp) - { - auto now = clock::now(); - - time_point t_msg = time_point(duration(static_cast(stamp.sec) * 1'000'000'000ULL + stamp.nanosec)); - auto delay = now - t_msg; - - delays_.update(delay); - - if (now - last_print_ >= PRINT_INTERVAL) { - auto del = delays_.reset(); - - last_print_ = now; - - std::stringstream ss; - - ss << "{\"type\": \"topic_delay\", \"tag\": \"" << tag_ - << "\", \"del\": ["; - - for (duration & dt : *del) { - ss << dt.count() << ','; - } - - ss << "null]}" << std::endl; - - std::cout << ss.str(); - } - } - -private: - std::string tag_; - - time_point last_print_{time_point::min()}; - - Counter delays_; - - const duration PRINT_INTERVAL = 1s; -}; - -} // namespace util -} // namespace nebula \ No newline at end of file From 9ff53af3e641dd4ad57804e9870da42354bc3f34 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 16:40:54 +0900 Subject: [PATCH 098/122] chore(velodyne_calibration_decoder): fix spelling --- nebula_common/src/velodyne/velodyne_calibration_decoder.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index 0016e8208..bfea254b7 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,4 +1,5 @@ /** + * cspell:ignore piyush, piyushk, fout * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, * The University of Texas at Austin From f3f8f3c58f50eb9e819415ff88bbc8bf63fbff5b Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:25:11 +0900 Subject: [PATCH 099/122] fix(hesai_decoder): initialize last_phase to prevent empty pointcloud published on startup --- .../nebula_decoders_hesai/decoders/hesai_decoder.hpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index 8f28856e8..daf9406cc 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -174,6 +174,10 @@ class HesaiDecoder : public HesaiScanDecoder /// @return Whether the scan has completed bool checkScanCompleted(uint32_t current_phase, uint32_t sync_phase) { + if (last_phase_ == -1) { + return false; + } + return angle_corrector_.hasScanned(current_phase, last_phase_, sync_phase); } @@ -220,6 +224,8 @@ class HesaiDecoder : public HesaiScanDecoder decode_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); output_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); + + last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet } int unpack(const std::vector & packet) override @@ -247,7 +253,7 @@ class HesaiDecoder : public HesaiScanDecoder sensor_configuration_->scan_phase * SensorT::packet_t::DEGREE_SUBDIVISIONS); if (scan_completed) { - std::swap(decode_pc_, output_pc_); + std::swap(decode_pc_, output_pc_); decode_pc_->clear(); has_scanned_ = true; output_scan_timestamp_ns_ = decode_scan_timestamp_ns_; From e3b42f04f8e8560ab5ad9e4bd62a46c7a05b32a7 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:25:36 +0900 Subject: [PATCH 100/122] fix(nebula_tests): make Hesai tests compile again --- nebula_tests/hesai/hesai_ros_decoder_test.cpp | 42 ++++++++----------- nebula_tests/hesai/hesai_ros_decoder_test.hpp | 30 +++++++------ .../hesai/hesai_ros_decoder_test_main.cpp | 2 + 3 files changed, 37 insertions(+), 37 deletions(-) diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.cpp b/nebula_tests/hesai/hesai_ros_decoder_test.cpp index a07a4dabd..00f33fa1a 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.cpp @@ -46,12 +46,11 @@ HesaiRosDecoderTest::HesaiRosDecoderTest( correction_cfg_ptr_ = std::make_shared(correction_configuration); wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); + correction_cfg_ptr_); } else { wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + calibration_cfg_ptr_); } RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); @@ -59,26 +58,12 @@ HesaiRosDecoderTest::HesaiRosDecoderTest( Status HesaiRosDecoderTest::InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiRosDecoderTest::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast( - calibration_configuration), //); - std::static_pointer_cast(correction_configuration)); + calibration_configuration); return driver_ptr_->GetStatus(); } @@ -291,7 +276,6 @@ void HesaiRosDecoderTest::ReadBag( storage_options.storage_id = params_.storage_id; converter_options.output_serialization_format = params_.format; //"cdr"; rclcpp::Serialization serialization; - nebula::drivers::NebulaPointCloudPtr pointcloud(new nebula::drivers::NebulaPointCloud); rosbag2_cpp::Reader bag_reader(std::make_unique()); bag_reader.open(storage_options, converter_options); @@ -310,12 +294,20 @@ void HesaiRosDecoderTest::ReadBag( "Found data in topic " << bag_message->topic_name << ": " << bag_message->time_stamp); auto extracted_msg_ptr = std::make_shared(extracted_msg); - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud(extracted_msg_ptr); - auto scan_timestamp = std::get<1>(pointcloud_ts); - pointcloud = std::get<0>(pointcloud_ts); - scan_callback(bag_message->time_stamp, scan_timestamp, pointcloud); - pointcloud.reset(new nebula::drivers::NebulaPointCloud); + for (auto & pkt : extracted_msg_ptr->packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); + auto pointcloud = std::get<0>(pointcloud_ts); + auto scan_timestamp = std::get<1>(pointcloud_ts); + + if (!pointcloud) { + continue; + } + + std::cerr << "PC size: " << pointcloud->size() << std::endl; + + scan_callback(bag_message->time_stamp, scan_timestamp, pointcloud); + } } } } diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.hpp b/nebula_tests/hesai/hesai_ros_decoder_test.hpp index a0477a366..43996b9ac 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.hpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.hpp @@ -48,9 +48,25 @@ struct HesaiRosDecoderTestParams double dual_return_distance_threshold = 0.1; }; +inline std::ostream & operator<<(std::ostream & os, nebula::ros::HesaiRosDecoderTestParams const & arg) { + return os << "sensor_model=" << arg.sensor_model << ", " + << "return_mode=" << arg.return_mode << ", " + << "calibration_file=" << arg.calibration_file << ", " + << "bag_path=" << arg.bag_path << ", " + << "correction_file=" << arg.correction_file << ", " + << "frame_id=" << arg.frame_id << ", " + << "scan_phase=" << arg.scan_phase << ", " + << "min_range=" << arg.min_range << ", " + << "max_range=" << arg.max_range << ", " + << "storage_id=" << arg.storage_id << ", " + << "format=" << arg.format << ", " + << "target_topic=" << arg.target_topic << ", " + << "dual_return_distance_threshold=" << arg.dual_return_distance_threshold << ", "; +} + /// @brief Testing decoder of pandar 40p (Keeps HesaiDriverRosWrapper structure as much as /// possible) -class HesaiRosDecoderTest final : public rclcpp::Node, NebulaDriverRosWrapperBase //, testing::Test +class HesaiRosDecoderTest final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; @@ -65,17 +81,7 @@ class HesaiRosDecoderTest final : public rclcpp::Node, NebulaDriverRosWrapperBas /// @return Resulting status Status InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Initializing ros wrapper for AT - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration); + std::shared_ptr calibration_configuration); /// @brief Get configurations (Magic numbers for Pandar40P is described, each function can be /// integrated if the ros parameter can be passed to Google Test) diff --git a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp index 96ff00c3c..d6574ccd4 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp @@ -142,6 +142,8 @@ TEST_P(DecoderTest, TestTimezone) auto gmt = timezone; hesai_driver_->ReadBag(scan_callback); + ASSERT_GT(decoded_timestamps.size(), 0U); + // Then, reset driver and timestamps vector for the next decode run TearDown(); SetUp(); From cb6fe321f977674e46a5c1358df135a4b0d1d114 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:25:52 +0900 Subject: [PATCH 101/122] fix(nebula_examples): make Hesai examples compile again --- .../hesai_ros_offline_extract_bag_pcd.hpp | 9 +- .../hesai/hesai_ros_offline_extract_pcd.hpp | 14 +-- .../hesai_ros_offline_extract_bag_pcd.cpp | 91 +++++++++---------- .../hesai/hesai_ros_offline_extract_pcd.cpp | 41 ++++----- 4 files changed, 61 insertions(+), 94 deletions(-) diff --git a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp index a7681323c..5136cbb12 100644 --- a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp +++ b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp @@ -35,7 +35,7 @@ namespace nebula { namespace ros { -class HesaiRosOfflineExtractBag final : public rclcpp::Node, NebulaDriverRosWrapperBase +class HesaiRosOfflineExtractBag final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; @@ -46,12 +46,7 @@ class HesaiRosOfflineExtractBag final : public rclcpp::Node, NebulaDriverRosWrap Status InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration); + std::shared_ptr calibration_configuration); Status GetParameters( drivers::HesaiSensorConfiguration & sensor_configuration, diff --git a/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp b/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp index 711502e6a..8e26515bf 100644 --- a/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp +++ b/nebula_examples/include/hesai/hesai_ros_offline_extract_pcd.hpp @@ -36,7 +36,7 @@ namespace nebula namespace ros { /// @brief Offline hesai driver usage example (Output PCD data) -class HesaiRosOfflineExtractSample final : public rclcpp::Node, NebulaDriverRosWrapperBase +class HesaiRosOfflineExtractSample final : public rclcpp::Node { std::shared_ptr driver_ptr_; Status wrapper_status_; @@ -51,17 +51,7 @@ class HesaiRosOfflineExtractSample final : public rclcpp::Node, NebulaDriverRosW /// @return Resulting status Status InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) override; - - /// @brief Initializing ros wrapper for AT - /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver - /// @param correction_configuration CorrectionConfiguration for this driver - /// @return Resulting status - Status InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration); + std::shared_ptr calibration_configuration); /// @brief Get configurations from ros parameters /// @param sensor_configuration Output of SensorConfiguration diff --git a/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp b/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp index 9c1266347..02cc84c72 100644 --- a/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp +++ b/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp @@ -56,12 +56,11 @@ HesaiRosOfflineExtractBag::HesaiRosOfflineExtractBag( correction_cfg_ptr_ = std::make_shared(correction_configuration); wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); + correction_cfg_ptr_); } else { wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + calibration_cfg_ptr_); } RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); @@ -69,26 +68,12 @@ HesaiRosOfflineExtractBag::HesaiRosOfflineExtractBag( Status HesaiRosOfflineExtractBag::InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiRosOfflineExtractBag::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast( - calibration_configuration), //); - std::static_pointer_cast(correction_configuration)); + calibration_configuration); return driver_ptr_->GetStatus(); } @@ -328,39 +313,45 @@ Status HesaiRosOfflineExtractBag::ReadBag() std::cout << "Found data in topic " << bag_message->topic_name << ": " << bag_message->time_stamp << std::endl; - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud( - std::make_shared(extracted_msg)); - auto pointcloud = std::get<0>(pointcloud_ts); - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); + for (auto & pkt : extracted_msg.packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); + auto pointcloud = std::get<0>(pointcloud_ts); - if (needs_open) { - const rosbag2_storage::StorageOptions storage_options_w( - {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); - const rosbag2_cpp::ConverterOptions converter_options_w( - {rmw_get_serialization_format(), rmw_get_serialization_format()}); - writer_ = std::make_unique(); - writer_->open(storage_options_w, converter_options_w); - writer_->create_topic( - {bag_message->topic_name, "pandar_msgs/msg/PandarScan", rmw_get_serialization_format(), - ""}); - needs_open = false; - } - writer_->write(bag_message); - cnt++; - if (skip_num < cnt) { - out_cnt++; - if (only_xyz) { - pcl::PointCloud cloud_xyz; - pcl::copyPointCloud(*pointcloud, cloud_xyz); - writer.writeBinary((o_dir / fn).string(), cloud_xyz); - } else { - writer.writeBinary((o_dir / fn).string(), *pointcloud); + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); + + if (needs_open) { + const rosbag2_storage::StorageOptions storage_options_w( + {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); + const rosbag2_cpp::ConverterOptions converter_options_w( + {rmw_get_serialization_format(), rmw_get_serialization_format()}); + writer_ = std::make_unique(); + writer_->open(storage_options_w, converter_options_w); + writer_->create_topic( + {bag_message->topic_name, "pandar_msgs/msg/PandarScan", rmw_get_serialization_format(), + ""}); + needs_open = false; + } + writer_->write(bag_message); + cnt++; + if (skip_num < cnt) { + out_cnt++; + if (only_xyz) { + pcl::PointCloud cloud_xyz; + pcl::copyPointCloud(*pointcloud, cloud_xyz); + writer.writeBinary((o_dir / fn).string(), cloud_xyz); + } else { + writer.writeBinary((o_dir / fn).string(), *pointcloud); + } + // writer.writeASCII((o_dir / fn).string(), *pointcloud); + } + if (out_num <= out_cnt) { + break; } - // writer.writeASCII((o_dir / fn).string(), *pointcloud); - } - if (out_num <= out_cnt) { - break; } } } diff --git a/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp b/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp index a57d9b96e..bd992ee19 100644 --- a/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp +++ b/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp @@ -56,12 +56,11 @@ HesaiRosOfflineExtractSample::HesaiRosOfflineExtractSample( correction_cfg_ptr_ = std::make_shared(correction_configuration); wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_), - std::static_pointer_cast(correction_cfg_ptr_)); + correction_cfg_ptr_); } else { wrapper_status_ = InitializeDriver( std::const_pointer_cast(sensor_cfg_ptr_), - std::static_pointer_cast(calibration_cfg_ptr_)); + calibration_cfg_ptr_); } RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); @@ -69,26 +68,12 @@ HesaiRosOfflineExtractSample::HesaiRosOfflineExtractSample( Status HesaiRosOfflineExtractSample::InitializeDriver( std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration) + std::shared_ptr calibration_configuration) { // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast(calibration_configuration)); - return driver_ptr_->GetStatus(); -} - -Status HesaiRosOfflineExtractSample::InitializeDriver( - std::shared_ptr sensor_configuration, - std::shared_ptr calibration_configuration, - std::shared_ptr correction_configuration) -{ - // driver should be initialized here with proper decoder - driver_ptr_ = std::make_shared( - std::static_pointer_cast(sensor_configuration), - std::static_pointer_cast( - calibration_configuration), //); - std::static_pointer_cast(correction_configuration)); + calibration_configuration); return driver_ptr_->GetStatus(); } @@ -296,12 +281,18 @@ Status HesaiRosOfflineExtractSample::ReadBag() // nebula::drivers::NebulaPointCloudPtr pointcloud = // driver_ptr_->ConvertScanToPointcloud( // std::make_shared(extracted_msg)); - auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud( - std::make_shared(extracted_msg)); - auto pointcloud = std::get<0>(pointcloud_ts); - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); - writer.writeBinary((o_dir / fn).string(), *pointcloud); + for (auto & pkt : extracted_msg.packets) { + auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); + auto pointcloud = std::get<0>(pointcloud_ts); + + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); + writer.writeBinary((o_dir / fn).string(), *pointcloud); + } } } // close on scope exit From d45c0eb367bc4d71ef952155959fb4f7d294f89d Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 19:29:03 +0900 Subject: [PATCH 102/122] chore(velodyne_calibration_decoder): fix spelling once and for all --- .cspell.json | 2 +- nebula_common/src/velodyne/velodyne_calibration_decoder.cpp | 3 --- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/.cspell.json b/.cspell.json index 5265d4bf1..228d7f45e 100644 --- a/.cspell.json +++ b/.cspell.json @@ -50,4 +50,4 @@ "Piyush", "fout" ] -} +} \ No newline at end of file diff --git a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp index bfea254b7..0c03c3c9e 100644 --- a/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp +++ b/nebula_common/src/velodyne/velodyne_calibration_decoder.cpp @@ -1,5 +1,4 @@ /** - * cspell:ignore piyush, piyushk, fout * \author Piyush Khandelwal (piyushk@cs.utexas.edu) * Copyright (C) 2012, Austin Robot Technology, * The University of Texas at Austin @@ -7,8 +6,6 @@ * License: Modified BSD License */ -// cspell:ignore piyush, piyushk, fout - #include #ifdef HAVE_NEW_YAMLCPP From 012908e7656baba8fce883527fb352f6b7fef42e Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 18 Apr 2024 20:21:56 +0900 Subject: [PATCH 103/122] fix(nebula_examples): fix test failure (remove ament_lint_common) --- nebula_examples/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_examples/package.xml b/nebula_examples/package.xml index 6f1163279..f63847cca 100644 --- a/nebula_examples/package.xml +++ b/nebula_examples/package.xml @@ -28,8 +28,8 @@ velodyne_msgs yaml-cpp + ament_cmake_gtest ament_lint_auto - ament_lint_common ament_cmake From 34ff9e8a26834920be0cc7cdd0f2d582ba1f820e Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Mon, 22 Apr 2024 11:30:28 +0900 Subject: [PATCH 104/122] fix(hesai_hw_interface): add missing check for PTC error, make error type more readable --- .../nebula_hw_interfaces_hesai/hesai_hw_interface.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index 0bf3a864b..b0a443495 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -102,7 +102,6 @@ const int PTP_LOG_MIN_DELAY_INTERVAL = 0; const int HESAI_LIDAR_GPS_CLOCK_SOURCE = 0; const int HESAI_LIDAR_PTP_CLOCK_SOURCE = 1; - /// @brief Hardware interface of hesai driver class HesaiHwInterface : public NebulaHwInterfaceBase { From 3f42a2a9a821c5d702158d6f3c3be66423f63934 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 23 Apr 2024 15:35:45 +0900 Subject: [PATCH 105/122] refactor(hesai): re-introduce parameter update mechanism --- .../include/nebula_common/nebula_common.hpp | 6 +- .../decoders/angle_corrector.hpp | 8 +- .../angle_corrector_calibration_based.hpp | 8 +- .../angle_corrector_correction_based.hpp | 4 +- .../decoders/hesai_decoder.hpp | 18 +- .../nebula_decoders_hesai/hesai_driver.hpp | 8 +- .../nebula_decoders_hesai/hesai_driver.cpp | 14 +- .../hesai_hw_interface.hpp | 18 +- .../hesai_hw_interface.cpp | 16 +- nebula_ros/CMakeLists.txt | 1 + .../common/parameter_descriptors.hpp | 41 ++ .../nebula_ros/hesai/decoder_wrapper.hpp | 41 +- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 39 +- .../nebula_ros/hesai/hw_interface_wrapper.hpp | 9 +- .../nebula_ros/hesai/hw_monitor_wrapper.hpp | 13 +- .../src/common/parameter_descriptors.cpp | 29 ++ nebula_ros/src/hesai/decoder_wrapper.cpp | 118 +++-- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 428 ++++++------------ nebula_ros/src/hesai/hw_interface_wrapper.cpp | 46 +- nebula_ros/src/hesai/hw_monitor_wrapper.cpp | 17 +- 20 files changed, 430 insertions(+), 452 deletions(-) create mode 100644 nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp create mode 100644 nebula_ros/src/common/parameter_descriptors.cpp diff --git a/nebula_common/include/nebula_common/nebula_common.hpp b/nebula_common/include/nebula_common/nebula_common.hpp index 9d04a267a..cf1eb0841 100644 --- a/nebula_common/include/nebula_common/nebula_common.hpp +++ b/nebula_common/include/nebula_common/nebula_common.hpp @@ -346,7 +346,7 @@ enum class PtpProfile { IEEE_1588v2 = 0, IEEE_802_1AS, IEEE_802_1AS_AUTO, - PROFILE_UNKNOWN + UNKNOWN_PROFILE }; enum class PtpTransportType { @@ -624,7 +624,7 @@ inline PtpProfile PtpProfileFromString(const std::string & ptp_profile) if (tmp_str == "802.1as") return PtpProfile::IEEE_802_1AS; if (tmp_str == "automotive") return PtpProfile::IEEE_802_1AS_AUTO; - return PtpProfile::PROFILE_UNKNOWN; + return PtpProfile::UNKNOWN_PROFILE; } /// @brief Convert PtpProfile enum to string (Overloading the << operator) @@ -643,7 +643,7 @@ inline std::ostream & operator<<(std::ostream & os, nebula::drivers::PtpProfile case PtpProfile::IEEE_802_1AS_AUTO: os << "IEEE_802.1AS Automotive"; break; - case PtpProfile::PROFILE_UNKNOWN: + case PtpProfile::UNKNOWN_PROFILE: os << "UNKNOWN"; break; } diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp index 42fd0a008..121913c34 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp @@ -26,13 +26,13 @@ struct CorrectedAngleData class AngleCorrector { protected: - const std::shared_ptr sensor_calibration_; - const std::shared_ptr sensor_correction_; + const std::shared_ptr sensor_calibration_; + const std::shared_ptr sensor_correction_; public: AngleCorrector( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) + const std::shared_ptr & sensor_calibration, + const std::shared_ptr & sensor_correction) : sensor_calibration_(sensor_calibration), sensor_correction_(sensor_correction) { } diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp index 3e0c999b0..bee570afc 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp @@ -27,8 +27,8 @@ class AngleCorrectorCalibrationBased : public AngleCorrector public: AngleCorrectorCalibrationBased( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) + const std::shared_ptr & sensor_calibration, + const std::shared_ptr & sensor_correction) : AngleCorrector(sensor_calibration, sensor_correction) { if (sensor_calibration == nullptr) { @@ -37,8 +37,8 @@ class AngleCorrectorCalibrationBased : public AngleCorrector } for (size_t channel_id = 0; channel_id < ChannelN; ++channel_id) { - float elevation_angle_deg = sensor_calibration->elev_angle_map[channel_id]; - float azimuth_offset_deg = sensor_calibration->azimuth_offset_map[channel_id]; + float elevation_angle_deg = sensor_calibration->elev_angle_map.at(channel_id); + float azimuth_offset_deg = sensor_calibration->azimuth_offset_map.at(channel_id); elevation_angle_rad_[channel_id] = deg2rad(elevation_angle_deg); azimuth_offset_rad_[channel_id] = deg2rad(azimuth_offset_deg); diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp index be60078de..d23dfc1f2 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp @@ -43,8 +43,8 @@ class AngleCorrectorCorrectionBased : public AngleCorrector public: AngleCorrectorCorrectionBased( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) + const std::shared_ptr & sensor_calibration, + const std::shared_ptr & sensor_correction) : AngleCorrector(sensor_calibration, sensor_correction), logger_(rclcpp::get_logger("AngleCorrectorCorrectionBased")) { diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index daf9406cc..e8a9afc34 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -18,7 +18,7 @@ class HesaiDecoder : public HesaiScanDecoder { protected: /// @brief Configuration for this decoder - const std::shared_ptr sensor_configuration_; + const std::shared_ptr sensor_configuration_; /// @brief The sensor definition, used for return mode and time offset handling SensorT sensor_{}; @@ -34,13 +34,13 @@ class HesaiDecoder : public HesaiScanDecoder /// @brief The last decoded packet typename SensorT::packet_t packet_; /// @brief The last azimuth processed - int last_phase_; + int last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet /// @brief The timestamp of the last completed scan in nanoseconds - uint64_t output_scan_timestamp_ns_; + uint64_t output_scan_timestamp_ns_ = 0; /// @brief The timestamp of the scan currently in progress - uint64_t decode_scan_timestamp_ns_; + uint64_t decode_scan_timestamp_ns_ = 0; /// @brief Whether a full scan has been processed - bool has_scanned_; + bool has_scanned_ = false; rclcpp::Logger logger_; @@ -209,9 +209,9 @@ class HesaiDecoder : public HesaiScanDecoder /// @param correction_configuration Correction for this decoder (can be nullptr if /// calibration_configuration is set) explicit HesaiDecoder( - const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_configuration, + const std::shared_ptr & correction_configuration) : sensor_configuration_(sensor_configuration), angle_corrector_(calibration_configuration, correction_configuration), logger_(rclcpp::get_logger("HesaiDecoder")) @@ -224,8 +224,6 @@ class HesaiDecoder : public HesaiScanDecoder decode_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); output_pc_->reserve(SensorT::MAX_SCAN_BUFFER_POINTS); - - last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet } int unpack(const std::vector & packet) override diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index 5ee9892d4..87798dbd1 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -22,7 +22,7 @@ namespace nebula namespace drivers { /// @brief Hesai driver -class HesaiDriver : NebulaDriverBase +class HesaiDriver { private: /// @brief Current driver status @@ -37,8 +37,8 @@ class HesaiDriver : NebulaDriverBase /// @param calibration_configuration CalibrationConfiguration for this driver (either HesaiCalibrationConfiguration /// for sensors other than AT128 or HesaiCorrection for AT128) explicit HesaiDriver( - const std::shared_ptr& sensor_configuration, - const std::shared_ptr& calibration_configuration = nullptr); + const std::shared_ptr& sensor_configuration, + const std::shared_ptr& calibration_configuration = nullptr); /// @brief Get current status of this driver /// @return Current status @@ -47,7 +47,7 @@ class HesaiDriver : NebulaDriverBase /// @brief Setting CalibrationConfiguration (not used) /// @param calibration_configuration /// @return Resulting status - Status SetCalibrationConfiguration(const CalibrationConfigurationBase& calibration_configuration) override; + Status SetCalibrationConfiguration(const HesaiCalibrationConfigurationBase& calibration_configuration); /// @brief Convert PandarScan message to point cloud /// @param pandar_scan Message diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index 27624a469..beafd8e71 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -17,22 +17,22 @@ namespace nebula { namespace drivers { -HesaiDriver::HesaiDriver(const std::shared_ptr& sensor_configuration, - const std::shared_ptr& calibration_configuration) +HesaiDriver::HesaiDriver(const std::shared_ptr& sensor_configuration, + const std::shared_ptr& calibration_configuration) { // initialize proper parser from cloud config's model and echo mode driver_status_ = nebula::Status::OK; - std::shared_ptr calibration = nullptr; - std::shared_ptr correction = nullptr; + std::shared_ptr calibration = nullptr; + std::shared_ptr correction = nullptr; if (sensor_configuration->sensor_model == SensorModel::HESAI_PANDARAT128) { - correction = std::static_pointer_cast(calibration_configuration); + correction = std::static_pointer_cast(calibration_configuration); } else { - calibration = std::static_pointer_cast(calibration_configuration); + calibration = std::static_pointer_cast(calibration_configuration); } switch (sensor_configuration->sensor_model) @@ -104,7 +104,7 @@ std::tuple HesaiDriver::ParseCloudPacket( } Status HesaiDriver::SetCalibrationConfiguration( - const CalibrationConfigurationBase & calibration_configuration) + const HesaiCalibrationConfigurationBase & calibration_configuration) { throw std::runtime_error( "SetCalibrationConfiguration. Not yet implemented (" + diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index b0a443495..d3472afbe 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -103,7 +103,7 @@ const int HESAI_LIDAR_GPS_CLOCK_SOURCE = 0; const int HESAI_LIDAR_PTP_CLOCK_SOURCE = 1; /// @brief Hardware interface of hesai driver -class HesaiHwInterface : public NebulaHwInterfaceBase +class HesaiHwInterface { private: struct ptc_error_t @@ -120,10 +120,12 @@ class HesaiHwInterface : public NebulaHwInterfaceBase std::shared_ptr m_owned_ctx; std::unique_ptr<::drivers::udp_driver::UdpDriver> cloud_udp_driver_; std::shared_ptr<::drivers::tcp_driver::TcpDriver> tcp_driver_; - std::shared_ptr sensor_configuration_; + std::shared_ptr sensor_configuration_; std::function & buffer)> cloud_packet_callback_; /**This function pointer is called when the scan is complete*/ + std::mutex mtx_inflight_tcp_request_; + int prev_phase_{}; bool is_solid_state = false; @@ -195,14 +197,14 @@ class HesaiHwInterface : public NebulaHwInterfaceBase void ReceiveSensorPacketCallback(std::vector & buffer); /// @brief Starting the interface that handles UDP streams /// @return Resulting status - Status SensorInterfaceStart() final; + Status SensorInterfaceStart(); /// @brief Function for stopping the interface that handles UDP streams /// @return Resulting status - Status SensorInterfaceStop() final; + Status SensorInterfaceStop(); /// @brief Printing sensor configuration /// @param sensor_configuration SensorConfiguration for this interface /// @return Resulting status - Status GetSensorConfiguration(SensorConfigurationBase & sensor_configuration) final; + Status GetSensorConfiguration(const SensorConfigurationBase & sensor_configuration); /// @brief Printing calibration configuration /// @param calibration_configuration CalibrationConfiguration for the checking /// @return Resulting status @@ -211,7 +213,7 @@ class HesaiHwInterface : public NebulaHwInterfaceBase /// @param sensor_configuration SensorConfiguration for this interface /// @return Resulting status Status SetSensorConfiguration( - std::shared_ptr sensor_configuration) final; + std::shared_ptr sensor_configuration); /// @brief Registering callback for PandarScan /// @param scan_callback Callback function /// @return Resulting status @@ -382,13 +384,13 @@ class HesaiHwInterface : public NebulaHwInterfaceBase /// @param hesai_config Current HesaiConfig /// @return Resulting status HesaiStatus CheckAndSetConfig( - std::shared_ptr sensor_configuration, HesaiConfig hesai_config); + std::shared_ptr sensor_configuration, HesaiConfig hesai_config); /// @brief Checking the current settings and changing the difference point /// @param sensor_configuration Current SensorConfiguration /// @param hesai_lidar_range_all Current HesaiLidarRangeAll /// @return Resulting status HesaiStatus CheckAndSetConfig( - std::shared_ptr sensor_configuration, + std::shared_ptr sensor_configuration, HesaiLidarRangeAll hesai_lidar_range_all); /// @brief Checking the current settings and changing the difference point /// @return Resulting status diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 5a40b6b60..4db22ceb8 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -28,6 +28,8 @@ HesaiHwInterface::~HesaiHwInterface() HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( const uint8_t command_id, const std::vector & payload) { + std::lock_guard lock(mtx_inflight_tcp_request_); + uint32_t len = payload.size(); std::vector send_buf; @@ -120,10 +122,10 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( } Status HesaiHwInterface::SetSensorConfiguration( - std::shared_ptr sensor_configuration) + std::shared_ptr sensor_configuration) { sensor_configuration_ = - std::static_pointer_cast(sensor_configuration); + std::static_pointer_cast(sensor_configuration); return Status::OK; } @@ -175,7 +177,7 @@ Status HesaiHwInterface::SensorInterfaceStop() return Status::ERROR_1; } -Status HesaiHwInterface::GetSensorConfiguration(SensorConfigurationBase & sensor_configuration) +Status HesaiHwInterface::GetSensorConfiguration(const SensorConfigurationBase & sensor_configuration) { std::stringstream ss; ss << sensor_configuration; @@ -808,7 +810,7 @@ HesaiStatus HesaiHwInterface::GetLidarMonitorAsyncHttp( } HesaiStatus HesaiHwInterface::CheckAndSetConfig( - std::shared_ptr sensor_configuration, HesaiConfig hesai_config) + std::shared_ptr sensor_configuration, HesaiConfig hesai_config) { using namespace std::chrono_literals; #ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE @@ -967,7 +969,7 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( } HesaiStatus HesaiHwInterface::CheckAndSetConfig( - std::shared_ptr sensor_configuration, + std::shared_ptr sensor_configuration, HesaiLidarRangeAll hesai_lidar_range_all) { #ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE @@ -1031,7 +1033,7 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig() ss << result; PrintInfo(ss.str()); CheckAndSetConfig( - std::static_pointer_cast(sensor_configuration_), result); + std::static_pointer_cast(sensor_configuration_), result); }); t.join(); @@ -1041,7 +1043,7 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig() ss << result; PrintInfo(ss.str()); CheckAndSetConfig( - std::static_pointer_cast(sensor_configuration_), result); + std::static_pointer_cast(sensor_configuration_), result); }); t2.join(); #ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE diff --git a/nebula_ros/CMakeLists.txt b/nebula_ros/CMakeLists.txt index b11339765..324d38074 100644 --- a/nebula_ros/CMakeLists.txt +++ b/nebula_ros/CMakeLists.txt @@ -40,6 +40,7 @@ ament_auto_add_library(hesai_ros_wrapper SHARED src/hesai/decoder_wrapper.cpp src/hesai/hw_interface_wrapper.cpp src/hesai/hw_monitor_wrapper.cpp + src/common/parameter_descriptors.cpp ) rclcpp_components_register_node(hesai_ros_wrapper diff --git a/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp new file mode 100644 index 000000000..b54d8ad63 --- /dev/null +++ b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp @@ -0,0 +1,41 @@ +#pragma once + +#include +#include +#include + +namespace nebula +{ +namespace ros +{ + +rcl_interfaces::msg::ParameterDescriptor param_read_write(); + +rcl_interfaces::msg::ParameterDescriptor param_read_only(); + +rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range(double start, double stop, + double step); + +rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int start, int stop, int step); + +/// @brief Get a parameter's value from a list of parameters, if that parameter is in the list. +/// @tparam T The parameter's expected value type +/// @param p A vector of parameters +/// @param name Target parameter name +/// @param value (out) Parameter value. Set if parameter is found, left untouched otherwise. +/// @return Whether the target name existed +template +bool get_param(const std::vector& p, const std::string& name, T& value) +{ + auto it = std::find_if(p.cbegin(), p.cend(), + [&name](const rclcpp::Parameter & parameter) { return parameter.get_name() == name; }); + if (it != p.cend()) + { + value = it->template get_value(); + return true; + } + return false; +} + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp index 262c16839..3b2af26d4 100644 --- a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp @@ -2,17 +2,19 @@ #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" +#include "nebula_ros/common/parameter_descriptors.hpp" -#include #include +#include #include #include "nebula_msgs/msg/nebula_packet.hpp" #include "pandar_msgs/msg/pandar_packet.hpp" #include "pandar_msgs/msg/pandar_scan.hpp" -#include #include +#include +#include namespace nebula { @@ -20,22 +22,38 @@ namespace ros { class HesaiDecoderWrapper { + using get_calibration_result_t = + nebula::util::expected, nebula::Status>; + public: HesaiDecoderWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, - std::shared_ptr& config); - - nebula::util::expected, nebula::Status> - GetCalibrationData(); + std::shared_ptr& config); void ProcessCloudPacket(std::unique_ptr packet_msg); - void PublishCloud(std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr& publisher); + void OnConfigChange(const std::shared_ptr& new_config); + + void + OnCalibrationChange(const std::shared_ptr& new_calibration); + + rcl_interfaces::msg::SetParametersResult OnParameterChange(const std::vector& p); nebula::Status Status(); private: + /// @brief Load calibration data from the best available source: + /// 1. If sensor connected, download and save from sensor + /// 2. If downloaded file available, load that file + /// 3. Load the file given by `calibration_file_path` + /// @param calibration_file_path The file to use if no better option is available + /// @param ignore_others If true, skip straight so step 3 above, ignoring better calibration options + /// @return The calibration data if successful, or an error code if not + get_calibration_result_t GetCalibrationData(const std::string& calibration_file_path, bool ignore_others = false); + + void PublishCloud(std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr& publisher); + /// @brief Convert seconds to chrono::nanoseconds /// @param seconds /// @return chrono::nanoseconds @@ -48,12 +66,13 @@ class HesaiDecoderWrapper rclcpp::Logger logger_; const std::shared_ptr hw_interface_; - std::shared_ptr sensor_cfg_; + std::shared_ptr sensor_cfg_; std::string calibration_file_path_{}; - std::shared_ptr calibration_cfg_ptr_{}; + std::shared_ptr calibration_cfg_ptr_{}; - std::shared_ptr driver_ptr_; + std::shared_ptr driver_ptr_{}; + std::mutex mtx_driver_ptr_; rclcpp::Publisher::SharedPtr packets_pub_{}; pandar_msgs::msg::PandarScan::UniquePtr current_scan_msg_{}; diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index e037bce40..42d8bdc36 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -1,6 +1,7 @@ #pragma once #include "boost_tcp_driver/tcp_driver.hpp" + #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" @@ -9,6 +10,7 @@ #include "nebula_ros/hesai/hw_interface_wrapper.hpp" #include "nebula_ros/hesai/hw_monitor_wrapper.hpp" #include "nebula_ros/hesai/mt_queue.hpp" +#include "nebula_ros/common/parameter_descriptors.hpp" #include #include @@ -31,31 +33,12 @@ namespace nebula namespace ros { -/// @brief Get parameter from rclcpp::Parameter -/// @tparam T -/// @param p Parameter from rclcpp parameter callback -/// @param name Target parameter name -/// @param value Corresponding value -/// @return Whether the target name existed -template -bool get_param(const std::vector& p, const std::string& name, T& value) -{ - auto it = std::find_if(p.cbegin(), p.cend(), - [&name](const rclcpp::Parameter& parameter) { return parameter.get_name() == name; }); - if (it != p.cend()) - { - value = it->template get_value(); - return true; - } - return false; -} - /// @brief Ros wrapper of hesai driver class HesaiRosWrapper final : public rclcpp::Node { public: explicit HesaiRosWrapper(const rclcpp::NodeOptions& options); - ~HesaiRosWrapper() noexcept; + ~HesaiRosWrapper() noexcept {}; /// @brief Get current status of this driver /// @return Current status @@ -72,23 +55,16 @@ class HesaiRosWrapper final : public rclcpp::Node Status DeclareAndGetSensorConfigParams(); - /// @brief Get configurations from ros parameters - /// @param sensor_configuration Output of SensorConfiguration - /// @return Resulting status - Status DeclareAndGetWrapperParams(); - /// @brief rclcpp parameter callback /// @param parameters Received parameters /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector& parameters); + rcl_interfaces::msg::SetParametersResult OnParameterChange(const std::vector& p); - /// @brief Updating rclcpp parameter - /// @return SetParametersResult - std::vector updateParameters(); + Status ValidateAndSetConfig(std::shared_ptr& new_config); Status wrapper_status_; - std::shared_ptr sensor_cfg_ptr_{}; + std::shared_ptr sensor_cfg_ptr_{}; /// @brief Stores received packets that have not been processed yet by the decoder thread mt_queue> packet_queue_; @@ -104,7 +80,8 @@ class HesaiRosWrapper final : public rclcpp::Node std::optional decoder_wrapper_; std::mutex mtx_config_; - OnSetParametersCallbackHandle::SharedPtr set_param_res_{}; + + OnSetParametersCallbackHandle::SharedPtr parameter_event_cb_; }; } // namespace ros diff --git a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp index 30f069c99..cbf78d130 100644 --- a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp @@ -1,8 +1,10 @@ #pragma once +#include "nebula_ros/common/parameter_descriptors.hpp" + #include -#include +#include #include #include @@ -15,9 +17,9 @@ class HesaiHwInterfaceWrapper { public: HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, - std::shared_ptr& config); + std::shared_ptr& config); - nebula::Status InitializeHwInterface(); + void OnConfigChange(const std::shared_ptr & new_config); nebula::Status Status(); @@ -27,6 +29,7 @@ class HesaiHwInterfaceWrapper std::shared_ptr hw_interface_; rclcpp::Logger logger_; nebula::Status status_; + bool setup_sensor_; }; } // namespace ros } // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp index 5ddfc9e79..5209f64a2 100644 --- a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp @@ -1,7 +1,10 @@ #pragma once +#include "nebula_ros/common/parameter_descriptors.hpp" + #include #include + #include #include #include @@ -22,10 +25,13 @@ class HesaiHwMonitorWrapper public: HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, - std::shared_ptr& config); + std::shared_ptr& config); - nebula::Status InitializeHwMonitor(); + void OnConfigChange(const std::shared_ptr & /* new_config */) {} + + nebula::Status Status(); +private: void InitializeHesaiDiagnostics(); std::string GetPtreeValue(boost::property_tree::ptree* pt, const std::string& key); @@ -50,9 +56,6 @@ class HesaiHwMonitorWrapper void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); - nebula::Status Status(); - -private: rclcpp::Logger logger_; diagnostic_updater::Updater diagnostics_updater_; nebula::Status status_; diff --git a/nebula_ros/src/common/parameter_descriptors.cpp b/nebula_ros/src/common/parameter_descriptors.cpp new file mode 100644 index 000000000..ffd0fff37 --- /dev/null +++ b/nebula_ros/src/common/parameter_descriptors.cpp @@ -0,0 +1,29 @@ +#include "nebula_ros/common/parameter_descriptors.hpp" + +namespace nebula +{ +namespace ros +{ + +rcl_interfaces::msg::ParameterDescriptor param_read_write() +{ + return rcl_interfaces::msg::ParameterDescriptor{}; +}; + +rcl_interfaces::msg::ParameterDescriptor param_read_only() +{ + return rcl_interfaces::msg::ParameterDescriptor{}.set__read_only(true); +} + +rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range(double start, double stop, double step) +{ + return { rcl_interfaces::msg::FloatingPointRange().set__from_value(start).set__to_value(stop).set__step(step) }; +} + +rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int start, int stop, int step) +{ + return { rcl_interfaces::msg::IntegerRange().set__from_value(start).set__to_value(stop).set__step(step) }; +} + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp index 1ae6d2837..1b7c10582 100644 --- a/nebula_ros/src/hesai/decoder_wrapper.cpp +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -7,7 +7,7 @@ namespace ros HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, - std::shared_ptr& config) + std::shared_ptr& config) : status_(nebula::Status::NOT_INITIALIZED) , logger_(parent_node->get_logger().get_child("HesaiDecoder")) , hw_interface_(hw_interface) @@ -20,26 +20,14 @@ HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, if (config->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - parent_node->declare_parameter("correction_file", "", descriptor); - calibration_file_path_ = parent_node->get_parameter("correction_file").as_string(); + calibration_file_path_ = parent_node->declare_parameter("correction_file", "", param_read_write()); } else { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - parent_node->declare_parameter("calibration_file", "", descriptor); - calibration_file_path_ = parent_node->get_parameter("calibration_file").as_string(); + calibration_file_path_ = parent_node->declare_parameter("calibration_file", "", param_read_write()); } - auto calibration_result = GetCalibrationData(); + auto calibration_result = GetCalibrationData(calibration_file_path_, false); if (!calibration_result.has_value()) { @@ -78,8 +66,64 @@ HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); } -nebula::util::expected, nebula::Status> -HesaiDecoderWrapper::GetCalibrationData() +void HesaiDecoderWrapper::OnConfigChange( + const std::shared_ptr& new_config) +{ + std::lock_guard lock(mtx_driver_ptr_); + auto new_driver = std::make_shared(new_config, calibration_cfg_ptr_); + driver_ptr_ = new_driver; + sensor_cfg_ = new_config; +} + +void HesaiDecoderWrapper::OnCalibrationChange( + const std::shared_ptr& new_calibration) +{ + std::lock_guard lock(mtx_driver_ptr_); + auto new_driver = std::make_shared(sensor_cfg_, new_calibration); + driver_ptr_ = new_driver; + calibration_cfg_ptr_ = new_calibration; + calibration_file_path_ = calibration_cfg_ptr_->calibration_file; +} + +rcl_interfaces::msg::SetParametersResult HesaiDecoderWrapper::OnParameterChange(const std::vector& p) +{ + using namespace rcl_interfaces::msg; + + std::string calibration_path = ""; + + // Only one of the two parameters is defined, so not checking for sensor model explicitly here is fine + bool got_any = get_param(p, "calibration_file", calibration_path) | get_param(p, "correction_file", calibration_path); + if (!got_any) + { + return rcl_interfaces::build().successful(true).reason(""); + } + + if (!std::filesystem::exists(calibration_path)) + { + auto result = SetParametersResult(); + result.successful = false; + result.reason = "The given calibration path does not exist, ignoring: '" + calibration_path + "'"; + return result; + } + + auto get_calibration_result = GetCalibrationData(calibration_path, true); + if (!get_calibration_result.has_value()) + { + auto result = SetParametersResult(); + result.successful = false; + result.reason = (std::stringstream() << "Could not change calibration file to '" << calibration_path + << "': " << get_calibration_result.error()) + .str(); + return result; + } + + OnCalibrationChange(get_calibration_result.value()); + RCLCPP_INFO_STREAM(logger_, "Changed calibration to '" << calibration_cfg_ptr_->calibration_file << "'"); + return rcl_interfaces::build().successful(true).reason(""); +} + +HesaiDecoderWrapper::get_calibration_result_t +HesaiDecoderWrapper::GetCalibrationData(const std::string& calibration_file_path, bool ignore_others) { std::shared_ptr calib; @@ -96,16 +140,15 @@ HesaiDecoderWrapper::GetCalibrationData() std::string calibration_file_path_from_sensor; { - int ext_pos = calibration_file_path_.find_last_of('.'); - calibration_file_path_from_sensor = calibration_file_path_.substr(0, ext_pos); + int ext_pos = calibration_file_path.find_last_of('.'); + calibration_file_path_from_sensor = calibration_file_path.substr(0, ext_pos); // TODO: if multiple different sensors of the same type are used, this will mix up their calibration data calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += - calibration_file_path_.substr(ext_pos, calibration_file_path_.size() - ext_pos); + calibration_file_path_from_sensor += calibration_file_path.substr(ext_pos, calibration_file_path.size() - ext_pos); } // If a sensor is connected, try to download and save its calibration data - if (hw_connected) + if (!ignore_others && hw_connected) { try { @@ -128,7 +171,7 @@ HesaiDecoderWrapper::GetCalibrationData() } // If saved calibration data from a sensor exists (either just downloaded above, or previously), try to load it - if (std::filesystem::exists(calibration_file_path_from_sensor)) + if (!ignore_others && std::filesystem::exists(calibration_file_path_from_sensor)) { auto status = calib->LoadFromFile(calibration_file_path_from_sensor); if (status == Status::OK) @@ -139,31 +182,34 @@ HesaiDecoderWrapper::GetCalibrationData() RCLCPP_ERROR_STREAM(logger_, "Could not load downloaded calibration data: " << status); } - else + else if (!ignore_others) { RCLCPP_ERROR(logger_, "No downloaded calibration data found."); } - RCLCPP_WARN(logger_, "Falling back to generic calibration file."); + if (!ignore_others) + { + RCLCPP_WARN(logger_, "Falling back to generic calibration file."); + } // If downloaded data did not exist or could not be loaded, fall back to a generic file. // If that file does not exist either, return an error code - if (!std::filesystem::exists(calibration_file_path_)) + if (!std::filesystem::exists(calibration_file_path)) { RCLCPP_ERROR(logger_, "No calibration data found."); return nebula::Status(Status::INVALID_CALIBRATION_FILE); } // Try to load the existing fallback calibration file. Return an error if this fails - auto status = calib->LoadFromFile(calibration_file_path_); + auto status = calib->LoadFromFile(calibration_file_path); if (status != Status::OK) { - RCLCPP_ERROR(logger_, "Could not load fallback calibration file."); + RCLCPP_ERROR_STREAM(logger_, "Could not load calibration file at '" << calibration_file_path << "'"); return status; } // Return the fallback calibration file - calib->calibration_file = calibration_file_path_; + calib->calibration_file = calibration_file_path; return calib; } @@ -185,9 +231,13 @@ void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptrpackets.emplace_back(std::move(pandar_packet_msg)); } - std::tuple pointcloud_ts = - driver_ptr_->ParseCloudPacket(packet_msg->data); - nebula::drivers::NebulaPointCloudPtr pointcloud = std::get<0>(pointcloud_ts); + std::tuple pointcloud_ts{}; + nebula::drivers::NebulaPointCloudPtr pointcloud = nullptr; + { + std::lock_guard lock(mtx_driver_ptr_); + pointcloud_ts = driver_ptr_->ParseCloudPacket(packet_msg->data); + pointcloud = std::get<0>(pointcloud_ts); + } if (pointcloud == nullptr) { @@ -244,6 +294,8 @@ void HesaiDecoderWrapper::PublishCloud(std::unique_ptr("launch_hw", param_read_only()); if (launch_hw_) { @@ -27,10 +35,6 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions& options) decoder_wrapper_.emplace(this, hw_interface_wrapper_ ? hw_interface_wrapper_->HwInterface() : nullptr, sensor_cfg_ptr_); - RCLCPP_INFO_STREAM(get_logger(), "SensorConfig:" << *sensor_cfg_ptr_); - set_param_res_ = - add_on_set_parameters_callback(std::bind(&HesaiRosWrapper::paramCallback, this, std::placeholders::_1)); - RCLCPP_DEBUG(get_logger(), "Starting stream"); decoder_thread_ = std::thread([this]() { @@ -42,263 +46,164 @@ HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions& options) if (launch_hw_) { - StreamStart(); hw_interface_wrapper_->HwInterface()->RegisterScanCallback( std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + StreamStart(); } else { packets_sub_ = create_subscription( "pandar_packets", rclcpp::SensorDataQoS(), std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); - RCLCPP_INFO_STREAM(get_logger(), "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); + RCLCPP_INFO_STREAM(get_logger(), + "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); } + + // Register parameter callback after all params have been declared. Otherwise it would be called once for each + // declaration + parameter_event_cb_ = + add_on_set_parameters_callback(std::bind(&HesaiRosWrapper::OnParameterChange, this, std::placeholders::_1)); } nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() { - nebula::drivers::HesaiSensorConfiguration sensor_configuration; + nebula::drivers::HesaiSensorConfiguration config; + + auto _sensor_model = declare_parameter("sensor_model", "", param_read_only()); + config.sensor_model = drivers::SensorModelFromString(_sensor_model); + + auto _return_mode = declare_parameter("return_mode", "", param_read_write()); + config.return_mode = drivers::ReturnModeFromStringHesai(_return_mode, config.sensor_model); + + config.host_ip = declare_parameter("host_ip", "255.255.255.255", param_read_only()); + config.sensor_ip = declare_parameter("sensor_ip", "192.168.1.201", param_read_only()); + config.data_port = declare_parameter("data_port", 2368, param_read_only()); + config.gnss_port = declare_parameter("gnss_port", 2369, param_read_only()); + config.frame_id = declare_parameter("frame_id", "pandar", param_read_write()); { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai( - get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("host_ip", "255.255.255.255", descriptor); - sensor_configuration.host_ip = get_parameter("host_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("sensor_ip", "192.168.1.201", descriptor); - sensor_configuration.sensor_ip = get_parameter("sensor_ip").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("data_port", 2368, descriptor); - sensor_configuration.data_port = get_parameter("data_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("gnss_port", 2369, descriptor); - sensor_configuration.gnss_port = get_parameter("gnss_port").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = { range }; - declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("min_range", 0.3, descriptor); - sensor_configuration.min_range = get_parameter("min_range").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("max_range", 300., descriptor); - sensor_configuration.max_range = get_parameter("max_range").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("packet_mtu_size", 1500, descriptor); - sensor_configuration.packet_mtu_size = get_parameter("packet_mtu_size").as_int(); + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.])"; + descriptor.floating_point_range = float_range(0, 360, 0.01); + config.scan_phase = declare_parameter("scan_phase", 0., descriptor); } + + config.min_range = declare_parameter("min_range", 0.3, param_read_write()); + config.max_range = declare_parameter("max_range", 300., param_read_write()); + config.packet_mtu_size = declare_parameter("packet_mtu_size", 1500, param_read_only()); + { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - RCLCPP_DEBUG_STREAM(get_logger(), sensor_configuration.sensor_model); - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + uint16_t default_value; + RCLCPP_DEBUG_STREAM(get_logger(), config.sensor_model); + if (config.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { - descriptor.additional_constraints = "200, 300, 400, 500"; - // range.set__from_value(200).set__to_value(500).set__step(100); - // descriptor.integer_range = {range}; //todo - declare_parameter("rotation_speed", 200, descriptor); + descriptor.additional_constraints = "200, 400"; + descriptor.integer_range = int_range(200, 400, 200); + default_value = 200; } else { descriptor.additional_constraints = "300, 600, 1200"; - // range.set__from_value(300).set__to_value(1200).set__step(300); - // descriptor.integer_range = {range}; //todo - declare_parameter("rotation_speed", 600, descriptor); + descriptor.integer_range = int_range(300, 1200, 300); + default_value = 600; } - sensor_configuration.rotation_speed = get_parameter("rotation_speed").as_int(); + config.rotation_speed = declare_parameter("rotation_speed", default_value, descriptor); } { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = { range }; - declare_parameter("cloud_min_angle", 0, descriptor); - sensor_configuration.cloud_min_angle = get_parameter("cloud_min_angle").as_int(); + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.integer_range = int_range(0, 360, 1); + config.cloud_min_angle = declare_parameter("cloud_min_angle", 0, descriptor); } { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(360).set__step(1); - descriptor.integer_range = { range }; - declare_parameter("cloud_max_angle", 360, descriptor); - sensor_configuration.cloud_max_angle = get_parameter("cloud_max_angle").as_int(); + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); + descriptor.integer_range = int_range(0, 360, 1); + config.cloud_max_angle = declare_parameter("cloud_max_angle", 360, descriptor); } { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; - descriptor.read_only = false; - descriptor.dynamic_typing = false; + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0.01).set__to_value(0.5).set__step(0.01); - descriptor.floating_point_range = { range }; - declare_parameter("dual_return_distance_threshold", 0.1, descriptor); - sensor_configuration.dual_return_distance_threshold = get_parameter("dual_return_distance_threshold").as_double(); + descriptor.floating_point_range = float_range(0.01, 0.5, 0.01); + config.dual_return_distance_threshold = + declare_parameter("dual_return_distance_threshold", 0.1, descriptor); } + + auto _ptp_profile = declare_parameter("ptp_profile", "", param_read_only()); + config.ptp_profile = drivers::PtpProfileFromString(_ptp_profile); + + auto _ptp_transport = declare_parameter("ptp_transport_type", "", param_read_only()); + config.ptp_transport_type = drivers::PtpTransportTypeFromString(_ptp_transport); + + if (config.ptp_transport_type != drivers::PtpTransportType::L2 && + config.ptp_profile != drivers::PtpProfile::IEEE_1588v2 && + config.ptp_profile != drivers::PtpProfile::UNKNOWN_PROFILE) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("ptp_profile", ""); - sensor_configuration.ptp_profile = nebula::drivers::PtpProfileFromString(get_parameter("ptp_profile").as_string()); + RCLCPP_WARN_STREAM(get_logger(), "PTP transport was set to '" << _ptp_transport << "' but PTP profile '" + << _ptp_profile + << "' only supports 'L2'. Setting it to 'L2'."); + config.ptp_transport_type = drivers::PtpTransportType::L2; + set_parameter(rclcpp::Parameter("ptp_transport_type", "L2")); } + + auto _ptp_switch = declare_parameter("ptp_switch_type", "", param_read_only()); + config.ptp_switch_type = drivers::PtpSwitchTypeFromString(_ptp_switch); + { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("ptp_transport_type", ""); - sensor_configuration.ptp_transport_type = - nebula::drivers::PtpTransportTypeFromString(get_parameter("ptp_transport_type").as_string()); - if (static_cast(sensor_configuration.ptp_profile) > 0) - { - sensor_configuration.ptp_transport_type = nebula::drivers::PtpTransportType::L2; - } + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_only(); + descriptor.integer_range = int_range(0, 127, 1); + config.ptp_domain = declare_parameter("ptp_domain", 0, descriptor); } + + auto new_cfg_ptr = std::make_shared(config); + return ValidateAndSetConfig(new_cfg_ptr); +} + +Status HesaiRosWrapper::ValidateAndSetConfig(std::shared_ptr& new_config) +{ + if (new_config->sensor_model == nebula::drivers::SensorModel::UNKNOWN) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("ptp_switch_type", ""); - sensor_configuration.ptp_switch_type = - nebula::drivers::PtpSwitchTypeFromString(get_parameter("ptp_switch_type").as_string()); + return Status::INVALID_SENSOR_MODEL; } + if (new_config->return_mode == nebula::drivers::ReturnMode::UNKNOWN) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - rcl_interfaces::msg::IntegerRange range; - range.set__from_value(0).set__to_value(127).set__step(1); - descriptor.integer_range = { range }; - declare_parameter("ptp_domain", 0, descriptor); - sensor_configuration.ptp_domain = get_parameter("ptp_domain").as_int(); + return Status::INVALID_ECHO_MODE; } - - if (sensor_configuration.ptp_profile == nebula::drivers::PtpProfile::PROFILE_UNKNOWN) + if (new_config->frame_id.empty()) + { + return Status::SENSOR_CONFIG_ERROR; + } + if (new_config->ptp_profile == nebula::drivers::PtpProfile::UNKNOWN_PROFILE) { RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) + if (new_config->ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " "using the '1588v2' PTP Profile"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) + if (new_config->ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); return Status::SENSOR_CONFIG_ERROR; } - if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) + + if (hw_interface_wrapper_) { - return Status::INVALID_SENSOR_MODEL; + hw_interface_wrapper_->OnConfigChange(new_config); } - if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) + if (hw_monitor_wrapper_) { - return Status::INVALID_ECHO_MODE; + hw_monitor_wrapper_->OnConfigChange(new_config); } - if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) + if (decoder_wrapper_) { - return Status::SENSOR_CONFIG_ERROR; + decoder_wrapper_->OnConfigChange(new_config); } - auto new_cfg_ptr_ = std::make_shared(sensor_configuration); - sensor_cfg_ptr_.swap(new_cfg_ptr_); + sensor_cfg_ptr_ = new_config; return Status::OK; } @@ -326,25 +231,6 @@ Status HesaiRosWrapper::GetStatus() return wrapper_status_; } -Status HesaiRosWrapper::DeclareAndGetWrapperParams() -{ - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - declare_parameter("launch_hw", "", descriptor); - launch_hw_ = get_parameter("launch_hw").as_bool(); - } - - return Status::OK; -} - -HesaiRosWrapper::~HesaiRosWrapper() -{ -} - Status HesaiRosWrapper::StreamStart() { if (!hw_interface_wrapper_) @@ -360,74 +246,60 @@ Status HesaiRosWrapper::StreamStart() return hw_interface_wrapper_->HwInterface()->SensorInterfaceStart(); } -rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::paramCallback(const std::vector& p) +rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::OnParameterChange(const std::vector& p) { + using namespace rcl_interfaces::msg; + + if (p.empty()) + { + return rcl_interfaces::build().successful(true).reason(""); + } + std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback"); - RCLCPP_DEBUG_STREAM(get_logger(), p); - RCLCPP_DEBUG_STREAM(get_logger(), *sensor_cfg_ptr_); + + RCLCPP_INFO(get_logger(), "OnParameterChange"); drivers::HesaiSensorConfiguration new_cfg(*sensor_cfg_ptr_); - std::string sensor_model_str; - std::string return_mode_str; - if (get_param(p, "sensor_model", sensor_model_str) | get_param(p, "return_mode", return_mode_str) | - get_param(p, "host_ip", new_cfg.host_ip) | get_param(p, "sensor_ip", new_cfg.sensor_ip) | - get_param(p, "frame_id", new_cfg.frame_id) | get_param(p, "data_port", new_cfg.data_port) | - get_param(p, "gnss_port", new_cfg.gnss_port) | get_param(p, "scan_phase", new_cfg.scan_phase) | - get_param(p, "packet_mtu_size", new_cfg.packet_mtu_size) | - get_param(p, "rotation_speed", new_cfg.rotation_speed) | - get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | - get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle) | - get_param(p, "dual_return_distance_threshold", new_cfg.dual_return_distance_threshold)) + std::string _return_mode = ""; + bool got_any = get_param(p, "return_mode", _return_mode) | get_param(p, "frame_id", new_cfg.frame_id) | + get_param(p, "scan_phase", new_cfg.scan_phase) | get_param(p, "min_range", new_cfg.min_range) | + get_param(p, "max_range", new_cfg.max_range) | get_param(p, "rotation_speed", new_cfg.rotation_speed) | + get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | + get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle) | + get_param(p, "dual_return_distance_threshold", new_cfg.dual_return_distance_threshold); + + // Currently, HW interface and monitor wrappers have only read-only parameters, so their update logic is not + // implemented + if (decoder_wrapper_) + { + auto result = decoder_wrapper_->OnParameterChange(p); + if (!result.successful) { + return result; + } + } + + if (!got_any) { - if (0 < sensor_model_str.length()) - new_cfg.sensor_model = nebula::drivers::SensorModelFromString(sensor_model_str); - if (0 < return_mode_str.length()) - new_cfg.return_mode = nebula::drivers::ReturnModeFromString(return_mode_str); - - auto new_cfg_ptr = std::make_shared(new_cfg); - sensor_cfg_ptr_.swap(new_cfg_ptr); - RCLCPP_INFO_STREAM(get_logger(), "Update sensor_configuration"); - RCLCPP_DEBUG_STREAM(get_logger(), "hw_interface_.SetSensorConfiguration"); - hw_interface_wrapper_->HwInterface()->SetSensorConfiguration( - std::static_pointer_cast(sensor_cfg_ptr_)); - hw_interface_wrapper_->HwInterface()->CheckAndSetConfig(); + return rcl_interfaces::build().successful(true).reason(""); } - auto result = std::make_shared(); - result->successful = true; - result->reason = "success"; + if (_return_mode.length() > 0) + new_cfg.return_mode = nebula::drivers::ReturnModeFromString(_return_mode); - RCLCPP_DEBUG_STREAM(get_logger(), "add_on_set_parameters_callback success"); + auto new_cfg_ptr = std::make_shared(new_cfg); + auto status = ValidateAndSetConfig(new_cfg_ptr); - return *result; -} + if (status != Status::OK) + { + RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); + auto result = SetParametersResult(); + result.successful = false; + result.reason = (std::stringstream() << "Invalid configuration: " << status).str(); + return result; + } -std::vector HesaiRosWrapper::updateParameters() -{ - std::scoped_lock lock(mtx_config_); - RCLCPP_DEBUG_STREAM(get_logger(), "updateParameters start"); - std::ostringstream os_sensor_model; - os_sensor_model << sensor_cfg_ptr_->sensor_model; - std::ostringstream os_return_mode; - os_return_mode << sensor_cfg_ptr_->return_mode; - RCLCPP_INFO_STREAM(get_logger(), "set_parameters"); - auto results = set_parameters( - { rclcpp::Parameter("sensor_model", os_sensor_model.str()), - rclcpp::Parameter("return_mode", os_return_mode.str()), rclcpp::Parameter("host_ip", sensor_cfg_ptr_->host_ip), - rclcpp::Parameter("sensor_ip", sensor_cfg_ptr_->sensor_ip), - rclcpp::Parameter("frame_id", sensor_cfg_ptr_->frame_id), - rclcpp::Parameter("data_port", sensor_cfg_ptr_->data_port), - rclcpp::Parameter("gnss_port", sensor_cfg_ptr_->gnss_port), - rclcpp::Parameter("scan_phase", sensor_cfg_ptr_->scan_phase), - rclcpp::Parameter("packet_mtu_size", sensor_cfg_ptr_->packet_mtu_size), - rclcpp::Parameter("rotation_speed", sensor_cfg_ptr_->rotation_speed), - rclcpp::Parameter("cloud_min_angle", sensor_cfg_ptr_->cloud_min_angle), - rclcpp::Parameter("cloud_max_angle", sensor_cfg_ptr_->cloud_max_angle), - rclcpp::Parameter("dual_return_distance_threshold", sensor_cfg_ptr_->dual_return_distance_threshold) }); - RCLCPP_DEBUG_STREAM(get_logger(), "updateParameters end"); - return results; + return rcl_interfaces::build().successful(true).reason(""); } void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector& packet) diff --git a/nebula_ros/src/hesai/hw_interface_wrapper.cpp b/nebula_ros/src/hesai/hw_interface_wrapper.cpp index e38f6b181..c10319c1e 100644 --- a/nebula_ros/src/hesai/hw_interface_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_interface_wrapper.cpp @@ -5,36 +5,20 @@ namespace nebula namespace ros { -HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, - std::shared_ptr& config) +HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper( + rclcpp::Node* const parent_node, std::shared_ptr& config) : hw_interface_(new nebula::drivers::HesaiHwInterface()) , logger_(parent_node->get_logger().get_child("HwInterface")) , status_(Status::NOT_INITIALIZED) { - bool setup_sensor, retry_connect; + setup_sensor_ = parent_node->declare_parameter("setup_sensor", true, param_read_only()); + bool retry_connect = parent_node->declare_parameter("retry_hw", true, param_read_only()); - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - parent_node->declare_parameter("setup_sensor", true, descriptor); - setup_sensor = parent_node->get_parameter("setup_sensor").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - parent_node->declare_parameter("retry_hw", true, descriptor); - retry_connect = parent_node->get_parameter("retry_hw").as_bool(); - } - - hw_interface_->SetSensorConfiguration(std::static_pointer_cast(config)); + status_ = hw_interface_->SetSensorConfiguration(std::static_pointer_cast(config)); - status_ = Status::OK; + if (status_ != Status::OK) { + throw std::runtime_error((std::stringstream{} << "Could not initialize HW interface: " << status_).str()); + } hw_interface_->SetLogger(std::make_shared(parent_node->get_logger())); hw_interface_->SetTargetModel(config->sensor_model); @@ -51,7 +35,7 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node retry_count++; std::this_thread::sleep_for(std::chrono::milliseconds(8000)); // >5000 - RCLCPP_WARN_STREAM(logger_, "Retry: " << retry_count); + RCLCPP_WARN_STREAM(logger_, status_ << ". Retry #" << retry_count); } if (status_ == Status::OK) @@ -66,10 +50,9 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node { RCLCPP_ERROR_STREAM(logger_, "Failed to get model from sensor..."); } - if (setup_sensor) + if (setup_sensor_) { hw_interface_->CheckAndSetConfig(); - // updateParameters(); TODO } } else @@ -80,6 +63,15 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node status_ = Status::OK; } +void HesaiHwInterfaceWrapper::OnConfigChange( + const std::shared_ptr& new_config) +{ + hw_interface_->SetSensorConfiguration(std::static_pointer_cast(new_config)); + if (setup_sensor_) { + hw_interface_->CheckAndSetConfig(); + } +} + Status HesaiHwInterfaceWrapper::Status() { return status_; diff --git a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp index 579e32a4e..0a56bec57 100644 --- a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp @@ -6,22 +6,14 @@ namespace ros { HesaiHwMonitorWrapper::HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, - std::shared_ptr& config) + std::shared_ptr& config) : logger_(parent_node->get_logger().get_child("HwMonitor")) , diagnostics_updater_(parent_node) , status_(Status::OK) , hw_interface_(hw_interface) , parent_node_(parent_node) { - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; - descriptor.read_only = false; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = "milliseconds"; - parent_node->declare_parameter("diag_span", 1000, descriptor); - diag_span_ = parent_node->get_parameter("diag_span").as_int(); - } + diag_span_ = parent_node->declare_parameter("diag_span", 1000, param_read_only()); switch (config->sensor_model) { @@ -66,11 +58,6 @@ HesaiHwMonitorWrapper::HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, RCLCPP_INFO_STREAM(logger_, "Model:" << info_model_); RCLCPP_INFO_STREAM(logger_, "Serial:" << info_serial_); InitializeHesaiDiagnostics(); - - if (Status::OK != status_) - { - throw std::runtime_error((std::stringstream() << "Error getting calibration data: " << status_).str()); - } } void HesaiHwMonitorWrapper::InitializeHesaiDiagnostics() From 9d89ff1d5bacc8483570f7878d5362b8a339efef Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 23 Apr 2024 16:58:52 +0900 Subject: [PATCH 106/122] feat(hesai_ros): add watchdog timer for pointcloud output --- .../nebula_ros/common/watchdog_timer.hpp | 52 +++++++++++++++++++ .../nebula_ros/hesai/decoder_wrapper.hpp | 3 ++ nebula_ros/src/hesai/decoder_wrapper.cpp | 10 ++++ 3 files changed, 65 insertions(+) create mode 100644 nebula_ros/include/nebula_ros/common/watchdog_timer.hpp diff --git a/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp b/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp new file mode 100644 index 000000000..ae556e33e --- /dev/null +++ b/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp @@ -0,0 +1,52 @@ +#pragma once + +#include +#include +#include +#include +#include + +namespace nebula +{ +namespace ros +{ + +class WatchdogTimer +{ + using watchdog_cb_t = std::function; + +public: + WatchdogTimer(rclcpp::Node& node, const std::chrono::microseconds& expected_update_interval, const watchdog_cb_t& callback) + : node_(node) + , callback_(callback) + , expected_update_interval_ns_( + std::chrono::duration_cast(expected_update_interval).count()) + { + timer_ = node_.create_wall_timer(expected_update_interval, std::bind(&WatchdogTimer::onTimer, this)); + } + + void update() + { + last_update_ns_ = node_.get_clock()->now().nanoseconds(); + } + +private: + void onTimer() + { + uint64_t now_ns = node_.get_clock()->now().nanoseconds(); + + bool is_late = (now_ns - last_update_ns_) > expected_update_interval_ns_; + + callback_(!is_late); + } + + rclcpp::Node& node_; + rclcpp::TimerBase::SharedPtr timer_; + std::atomic last_update_ns_; + const watchdog_cb_t callback_; + + const uint64_t expected_update_interval_ns_; +}; + +} // namespace ros +} // namespace nebula \ No newline at end of file diff --git a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp index 3b2af26d4..da5e60ff0 100644 --- a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp @@ -3,6 +3,7 @@ #include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" #include "nebula_ros/common/parameter_descriptors.hpp" +#include "nebula_ros/common/watchdog_timer.hpp" #include #include @@ -80,6 +81,8 @@ class HesaiDecoderWrapper rclcpp::Publisher::SharedPtr nebula_points_pub_{}; rclcpp::Publisher::SharedPtr aw_points_ex_pub_{}; rclcpp::Publisher::SharedPtr aw_points_base_pub_{}; + + std::shared_ptr cloud_watchdog_; }; } // namespace ros } // namespace nebula \ No newline at end of file diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp index 1b7c10582..0ddfd599e 100644 --- a/nebula_ros/src/hesai/decoder_wrapper.cpp +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -5,6 +5,8 @@ namespace nebula namespace ros { +using namespace std::chrono_literals; + HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, const std::shared_ptr& hw_interface, std::shared_ptr& config) @@ -64,6 +66,12 @@ HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, aw_points_ex_pub_ = parent_node->create_publisher("aw_points_ex", pointcloud_qos); RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); + + cloud_watchdog_ = std::make_shared(*parent_node, 100'000us, [this, parent_node](bool ok) { + if (ok) + return; + RCLCPP_WARN_THROTTLE(logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline"); + }); } void HesaiDecoderWrapper::OnConfigChange( @@ -246,6 +254,8 @@ void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptrupdate(); + // Publish scan message only if it has been written to if (current_scan_msg_ && !current_scan_msg_->packets.empty()) { From df702eb073f234a26cd3694066c583582938eca6 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 25 Apr 2024 18:29:33 +0900 Subject: [PATCH 107/122] fix(hesai): change to possibly more accurate high_resolution_clock --- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 1bce59ffe..6e08c0e3b 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -309,7 +309,7 @@ void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector& packet) return; } - const auto now = std::chrono::system_clock::now(); + const auto now = std::chrono::high_resolution_clock::now(); const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); auto msg_ptr = std::make_unique(); From 54ce7ead76c75e775246eac189ee429160635844 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Thu, 25 Apr 2024 18:34:02 +0900 Subject: [PATCH 108/122] fix(hesai): fix crash on QT128 --- .../hesai_hw_interface.cpp | 47 ++++++++++++------- 1 file changed, 31 insertions(+), 16 deletions(-) diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index 4db22ceb8..ac05a5485 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -261,8 +261,10 @@ HesaiPtpDiagStatus HesaiHwInterface::GetPtpDiagStatus() auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_STATUS}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiPtpDiagStatus)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiPtpDiagStatus)) { + throw std::runtime_error("HesaiPtpDiagStatus has unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpDiagStatus)) { + PrintError("HesaiPtpDiagStatus from Sensor has unknown format. Will parse anyway."); } HesaiPtpDiagStatus hesai_ptp_diag_status; @@ -280,9 +282,12 @@ HesaiPtpDiagPort HesaiHwInterface::GetPtpDiagPort() auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_PORT_DATA_SET}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiPtpDiagPort)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiPtpDiagPort)) { + throw std::runtime_error("HesaiPtpDiagPort has unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpDiagPort)) { + PrintError("HesaiPtpDiagPort from Sensor has unknown format. Will parse anyway."); } + HesaiPtpDiagPort hesai_ptp_diag_port; memcpy(&hesai_ptp_diag_port, response.data(), sizeof(HesaiPtpDiagPort)); @@ -298,8 +303,10 @@ HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_TIME_STATUS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiPtpDiagTime)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiPtpDiagTime)) { + throw std::runtime_error("HesaiPtpDiagTime has unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpDiagTime)) { + PrintError("HesaiPtpDiagTime from Sensor has unknown format. Will parse anyway."); } HesaiPtpDiagTime hesai_ptp_diag_time; @@ -317,8 +324,10 @@ HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiPtpDiagGrandmaster)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiPtpDiagGrandmaster)) { + throw std::runtime_error("HesaiPtpDiagGrandmaster has unexpected payload size"); + } else if (response.size() > sizeof(HesaiPtpDiagGrandmaster)) { + PrintError("HesaiPtpDiagGrandmaster from Sensor has unknown format. Will parse anyway."); } HesaiPtpDiagGrandmaster hesai_ptp_diag_grandmaster; @@ -337,7 +346,7 @@ HesaiInventory HesaiHwInterface::GetInventory() auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() < sizeof(HesaiInventory)) { - throw std::runtime_error("Unexpected payload size"); + throw std::runtime_error("HesaiInventory has unexpected payload size"); } else if (response.size() > sizeof(HesaiInventory)) { PrintError("HesaiInventory from Sensor has unknown format. Will parse anyway."); } @@ -353,8 +362,10 @@ HesaiConfig HesaiHwInterface::GetConfig() auto response_or_err = SendReceive(PTC_COMMAND_GET_CONFIG_INFO); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiConfig)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiConfig)) { + throw std::runtime_error("HesaiConfig has unexpected payload size"); + } else if (response.size() > sizeof(HesaiConfig)) { + PrintError("HesaiConfig from Sensor has unknown format. Will parse anyway."); } HesaiConfig hesai_config; @@ -369,8 +380,10 @@ HesaiLidarStatus HesaiHwInterface::GetLidarStatus() auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_STATUS); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiLidarStatus)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiLidarStatus)) { + throw std::runtime_error("HesaiLidarStatus has unexpected payload size"); + } else if (response.size() > sizeof(HesaiLidarStatus)) { + PrintError("HesaiLidarStatus from Sensor has unknown format. Will parse anyway."); } HesaiLidarStatus hesai_status; @@ -589,7 +602,7 @@ HesaiPtpConfig HesaiHwInterface::GetPtpConfig() auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); if (response.size() < sizeof(HesaiPtpConfig)) { - throw std::runtime_error("Unexpected payload size"); + throw std::runtime_error("HesaiPtpConfig has unexpected payload size"); } else if (response.size() > sizeof(HesaiPtpConfig)) { PrintError("HesaiPtpConfig from Sensor has unknown format. Will parse anyway."); } @@ -629,8 +642,10 @@ HesaiLidarMonitor HesaiHwInterface::GetLidarMonitor() auto response_or_err = SendReceive(PTC_COMMAND_LIDAR_MONITOR); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - if (response.size() != sizeof(HesaiLidarMonitor)) { - throw std::runtime_error("Unexpected payload size"); + if (response.size() < sizeof(HesaiLidarMonitor)) { + throw std::runtime_error("HesaiLidarMonitor has unexpected payload size"); + } else if (response.size() > sizeof(HesaiLidarMonitor)) { + PrintError("HesaiLidarMonitor from Sensor has unknown format. Will parse anyway."); } HesaiLidarMonitor hesai_lidar_monitor; From ddab198fa26f43f15d3bc91b80a6040787af93ff Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 30 Apr 2024 11:14:00 +0900 Subject: [PATCH 109/122] refactor(hesai_hw_interface): refactor repeated error handling code --- .../hesai_hw_interface.hpp | 6 + .../hesai_hw_interface.cpp | 116 +++++------------- 2 files changed, 35 insertions(+), 87 deletions(-) diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index d3472afbe..8dc270b8e 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -168,6 +168,12 @@ class HesaiHwInterface /// @return A string description of all errors in this code std::string PrettyPrintPTCError(ptc_error_t error_code); + /// @brief Checks if the data size matches that of the struct to be parsed, and parses the struct. + /// If data is too small, a std::runtime_error is thrown. If data is too large, a warning is printed + /// and the struct is parsed with the first sizeof(T) bytes. + template + T CheckSizeAndParse(const std::vector & data); + /// @brief Send a PTC request with an optional payload, and return the full response payload. /// Blocking. /// @param command_id PTC command number. diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index ac05a5485..a28ffd7d2 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -260,117 +260,66 @@ HesaiPtpDiagStatus HesaiHwInterface::GetPtpDiagStatus() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_STATUS}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiPtpDiagStatus)) { - throw std::runtime_error("HesaiPtpDiagStatus has unexpected payload size"); - } else if (response.size() > sizeof(HesaiPtpDiagStatus)) { - PrintError("HesaiPtpDiagStatus from Sensor has unknown format. Will parse anyway."); - } - - HesaiPtpDiagStatus hesai_ptp_diag_status; - memcpy(&hesai_ptp_diag_status, response.data(), sizeof(HesaiPtpDiagStatus)); + auto diag_status = CheckSizeAndParse(response); std::stringstream ss; - ss << "HesaiHwInterface::GetPtpDiagStatus: " << hesai_ptp_diag_status; + ss << "HesaiHwInterface::GetPtpDiagStatus: " << diag_status; PrintInfo(ss.str()); - return hesai_ptp_diag_status; + return diag_status; } HesaiPtpDiagPort HesaiHwInterface::GetPtpDiagPort() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_PORT_DATA_SET}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiPtpDiagPort)) { - throw std::runtime_error("HesaiPtpDiagPort has unexpected payload size"); - } else if (response.size() > sizeof(HesaiPtpDiagPort)) { - PrintError("HesaiPtpDiagPort from Sensor has unknown format. Will parse anyway."); - } - - HesaiPtpDiagPort hesai_ptp_diag_port; - memcpy(&hesai_ptp_diag_port, response.data(), sizeof(HesaiPtpDiagPort)); + auto diag_port = CheckSizeAndParse(response); std::stringstream ss; - ss << "HesaiHwInterface::GetPtpDiagPort: " << hesai_ptp_diag_port; + ss << "HesaiHwInterface::GetPtpDiagPort: " << diag_port; PrintInfo(ss.str()); - return hesai_ptp_diag_port; + return diag_port; } HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_TIME_STATUS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiPtpDiagTime)) { - throw std::runtime_error("HesaiPtpDiagTime has unexpected payload size"); - } else if (response.size() > sizeof(HesaiPtpDiagTime)) { - PrintError("HesaiPtpDiagTime from Sensor has unknown format. Will parse anyway."); - } - - HesaiPtpDiagTime hesai_ptp_diag_time; - memcpy(&hesai_ptp_diag_time, response.data(), sizeof(HesaiPtpDiagTime)); + auto diag_time = CheckSizeAndParse(response); std::stringstream ss; - ss << "HesaiHwInterface::GetPtpDiagTime: " << hesai_ptp_diag_time; + ss << "HesaiHwInterface::GetPtpDiagTime: " << diag_time; PrintInfo(ss.str()); - return hesai_ptp_diag_time; + return diag_time; } HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() { auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiPtpDiagGrandmaster)) { - throw std::runtime_error("HesaiPtpDiagGrandmaster has unexpected payload size"); - } else if (response.size() > sizeof(HesaiPtpDiagGrandmaster)) { - PrintError("HesaiPtpDiagGrandmaster from Sensor has unknown format. Will parse anyway."); - } - - HesaiPtpDiagGrandmaster hesai_ptp_diag_grandmaster; - memcpy(&hesai_ptp_diag_grandmaster, response.data(), sizeof(HesaiPtpDiagGrandmaster)); + auto diag_grandmaster = CheckSizeAndParse(response); std::stringstream ss; - ss << "HesaiHwInterface::GetPtpDiagGrandmaster: " << hesai_ptp_diag_grandmaster; + ss << "HesaiHwInterface::GetPtpDiagGrandmaster: " << diag_grandmaster; PrintInfo(ss.str()); - return hesai_ptp_diag_grandmaster; + return diag_grandmaster; } HesaiInventory HesaiHwInterface::GetInventory() { auto response_or_err = SendReceive(PTC_COMMAND_GET_INVENTORY_INFO); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiInventory)) { - throw std::runtime_error("HesaiInventory has unexpected payload size"); - } else if (response.size() > sizeof(HesaiInventory)) { - PrintError("HesaiInventory from Sensor has unknown format. Will parse anyway."); - } - - HesaiInventory hesai_inventory; - memcpy(&hesai_inventory, response.data(), sizeof(HesaiInventory)); - - return hesai_inventory; + return CheckSizeAndParse(response); } HesaiConfig HesaiHwInterface::GetConfig() { auto response_or_err = SendReceive(PTC_COMMAND_GET_CONFIG_INFO); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiConfig)) { - throw std::runtime_error("HesaiConfig has unexpected payload size"); - } else if (response.size() > sizeof(HesaiConfig)) { - PrintError("HesaiConfig from Sensor has unknown format. Will parse anyway."); - } - - HesaiConfig hesai_config; - memcpy(&hesai_config, response.data(), sizeof(HesaiConfig)); - + auto hesai_config = CheckSizeAndParse(response); std::cout << "Config: " << hesai_config << std::endl; return hesai_config; } @@ -379,17 +328,7 @@ HesaiLidarStatus HesaiHwInterface::GetLidarStatus() { auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_STATUS); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiLidarStatus)) { - throw std::runtime_error("HesaiLidarStatus has unexpected payload size"); - } else if (response.size() > sizeof(HesaiLidarStatus)) { - PrintError("HesaiLidarStatus from Sensor has unknown format. Will parse anyway."); - } - - HesaiLidarStatus hesai_status; - memcpy(&hesai_status, response.data(), sizeof(HesaiLidarStatus)); - - return hesai_status; + return CheckSizeAndParse(response); } Status HesaiHwInterface::SetSpinRate(uint16_t rpm) @@ -641,17 +580,7 @@ HesaiLidarMonitor HesaiHwInterface::GetLidarMonitor() { auto response_or_err = SendReceive(PTC_COMMAND_LIDAR_MONITOR); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); - - if (response.size() < sizeof(HesaiLidarMonitor)) { - throw std::runtime_error("HesaiLidarMonitor has unexpected payload size"); - } else if (response.size() > sizeof(HesaiLidarMonitor)) { - PrintError("HesaiLidarMonitor from Sensor has unknown format. Will parse anyway."); - } - - HesaiLidarMonitor hesai_lidar_monitor; - memcpy(&hesai_lidar_monitor, response.data(), sizeof(HesaiLidarMonitor)); - - return hesai_lidar_monitor; + return CheckSizeAndParse(response); } void HesaiHwInterface::IOContextRun() @@ -1323,5 +1252,18 @@ std::string HesaiHwInterface::PrettyPrintPTCError(ptc_error_t error_code) { return ss.str(); } +template +T HesaiHwInterface::CheckSizeAndParse(const std::vector & data) { + if (data.size() < sizeof(T)) { + throw std::runtime_error("Attempted to parse too-small payload"); + } else if (data.size() > sizeof(T)) { + PrintError("Sensor returned longer payload than expected. Will parse anyway."); + } + + T parsed; + memcpy(&parsed, data.data(), sizeof(T)); + return parsed; +} + } // namespace drivers } // namespace nebula From 09f074af0f7e242160f5cbc7636e50ba75d63f54 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Tue, 30 Apr 2024 13:20:08 +0900 Subject: [PATCH 110/122] fix(hesai_launch_all_hw.xml): set valid RPM when AT128 is selected --- nebula_ros/launch/hesai_launch_all_hw.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index 1bd285766..b0f804441 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -33,6 +33,8 @@ + + Date: Tue, 30 Apr 2024 13:20:49 +0900 Subject: [PATCH 111/122] refactor(hesai_decoder): remove redundant arguments for correction/calibration --- .../decoders/angle_corrector.hpp | 12 +--- .../angle_corrector_calibration_based.hpp | 6 +- .../angle_corrector_correction_based.hpp | 27 +++++---- .../decoders/hesai_decoder.hpp | 10 +--- .../nebula_decoders_hesai/hesai_driver.hpp | 22 ++++++-- .../nebula_decoders_hesai/hesai_driver.cpp | 56 +++++++++---------- 6 files changed, 63 insertions(+), 70 deletions(-) diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp index 121913c34..914d2da49 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp @@ -23,19 +23,11 @@ struct CorrectedAngleData /// @brief Handles angle correction for given azimuth/channel combinations, as well as trigonometry /// lookup tables +template class AngleCorrector { -protected: - const std::shared_ptr sensor_calibration_; - const std::shared_ptr sensor_correction_; - public: - AngleCorrector( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) - : sensor_calibration_(sensor_calibration), sensor_correction_(sensor_correction) - { - } + using correction_data_t = CorrectionDataT; /// @brief Get the corrected azimuth and elevation for a given block and channel, along with their /// sin/cos values. diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp index bee570afc..d2c078e2d 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp @@ -11,7 +11,7 @@ namespace drivers { template -class AngleCorrectorCalibrationBased : public AngleCorrector +class AngleCorrectorCalibrationBased : public AngleCorrector { private: static constexpr size_t MAX_AZIMUTH_LEN = 360 * AngleUnit; @@ -27,9 +27,7 @@ class AngleCorrectorCalibrationBased : public AngleCorrector public: AngleCorrectorCalibrationBased( - const std::shared_ptr & sensor_calibration, - const std::shared_ptr & sensor_correction) - : AngleCorrector(sensor_calibration, sensor_correction) + const std::shared_ptr & sensor_calibration) { if (sensor_calibration == nullptr) { throw std::runtime_error( diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp index d23dfc1f2..52cbaf315 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_correction_based.hpp @@ -13,10 +13,11 @@ namespace drivers { template -class AngleCorrectorCorrectionBased : public AngleCorrector +class AngleCorrectorCorrectionBased : public AngleCorrector { private: static constexpr size_t MAX_AZIMUTH_LENGTH = 360 * AngleUnit; + const std::shared_ptr correction_; rclcpp::Logger logger_; std::array cos_{}; @@ -31,26 +32,25 @@ class AngleCorrectorCorrectionBased : public AngleCorrector // * none of the startFrames are defined as > 360 deg (< 0 not possible since they are unsigned) // * the fields are arranged in ascending order (e.g. field 1: 20-140deg, field 2: 140-260deg etc.) // These assumptions hold for AT128E2X. - int field = sensor_correction_->frameNumber - 1; - for (size_t i = 0; i < sensor_correction_->frameNumber; ++i) { - if (azimuth < sensor_correction_->startFrame[i]) return field; + int field = correction_->frameNumber - 1; + for (size_t i = 0; i < correction_->frameNumber; ++i) { + if (azimuth < correction_->startFrame[i]) return field; field = i; } - // This is never reached if sensor_correction_ is correct + // This is never reached if correction_ is correct return field; } public: AngleCorrectorCorrectionBased( - const std::shared_ptr & sensor_calibration, const std::shared_ptr & sensor_correction) - : AngleCorrector(sensor_calibration, sensor_correction), + : correction_(sensor_correction), logger_(rclcpp::get_logger("AngleCorrectorCorrectionBased")) { if (sensor_correction == nullptr) { throw std::runtime_error( - "Cannot instantiate AngleCorrectorCalibrationBased without calibration data"); + "Cannot instantiate AngleCorrectorCorrectionBased without correction data"); } logger_.set_level(rclcpp::Logger::Level::Debug); @@ -64,17 +64,16 @@ class AngleCorrectorCorrectionBased : public AngleCorrector CorrectedAngleData getCorrectedAngleData(uint32_t block_azimuth, uint32_t channel_id) override { - const auto & correction = AngleCorrector::sensor_correction_; int field = findField(block_azimuth); auto elevation = - correction->elevation[channel_id] + - correction->getElevationAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100); + correction_->elevation[channel_id] + + correction_->getElevationAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100); elevation = (MAX_AZIMUTH_LENGTH + elevation) % MAX_AZIMUTH_LENGTH; - auto azimuth = (block_azimuth + MAX_AZIMUTH_LENGTH - correction->startFrame[field]) * 2 - - correction->azimuth[channel_id] + - correction->getAzimuthAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100); + auto azimuth = (block_azimuth + MAX_AZIMUTH_LENGTH - correction_->startFrame[field]) * 2 - + correction_->azimuth[channel_id] + + correction_->getAzimuthAdjustV3(channel_id, block_azimuth) * (AngleUnit / 100); azimuth = (MAX_AZIMUTH_LENGTH + azimuth) % MAX_AZIMUTH_LENGTH; float azimuth_rad = 2.f * azimuth * M_PI / MAX_AZIMUTH_LENGTH; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index e8a9afc34..ea5dbe727 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -204,16 +204,12 @@ class HesaiDecoder : public HesaiScanDecoder public: /// @brief Constructor /// @param sensor_configuration SensorConfiguration for this decoder - /// @param calibration_configuration Calibration for this decoder (can be nullptr if - /// correction_configuration is set) - /// @param correction_configuration Correction for this decoder (can be nullptr if - /// calibration_configuration is set) + /// @param correction_data Calibration data for this decoder explicit HesaiDecoder( const std::shared_ptr & sensor_configuration, - const std::shared_ptr & calibration_configuration, - const std::shared_ptr & correction_configuration) + const std::shared_ptr & correction_data) : sensor_configuration_(sensor_configuration), - angle_corrector_(calibration_configuration, correction_configuration), + angle_corrector_(correction_data), logger_(rclcpp::get_logger("HesaiDecoder")) { logger_.set_level(rclcpp::Logger::Level::Debug); diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index 87798dbd1..099e022c5 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -16,6 +16,7 @@ #include #include #include +#include namespace nebula { @@ -30,15 +31,22 @@ class HesaiDriver /// @brief Decoder according to the model std::shared_ptr scan_decoder_; + template + std::shared_ptr InitializeDecoder( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & + calibration_configuration); + public: HesaiDriver() = delete; /// @brief Constructor /// @param sensor_configuration SensorConfiguration for this driver - /// @param calibration_configuration CalibrationConfiguration for this driver (either HesaiCalibrationConfiguration - /// for sensors other than AT128 or HesaiCorrection for AT128) + /// @param calibration_configuration CalibrationConfiguration for this driver (either + /// HesaiCalibrationConfiguration for sensors other than AT128 or HesaiCorrection for AT128) explicit HesaiDriver( - const std::shared_ptr& sensor_configuration, - const std::shared_ptr& calibration_configuration = nullptr); + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & + calibration_configuration); /// @brief Get current status of this driver /// @return Current status @@ -47,12 +55,14 @@ class HesaiDriver /// @brief Setting CalibrationConfiguration (not used) /// @param calibration_configuration /// @return Resulting status - Status SetCalibrationConfiguration(const HesaiCalibrationConfigurationBase& calibration_configuration); + Status SetCalibrationConfiguration( + const HesaiCalibrationConfigurationBase & calibration_configuration); /// @brief Convert PandarScan message to point cloud /// @param pandar_scan Message /// @return tuple of Point cloud and timestamp - std::tuple ParseCloudPacket(const std::vector& packet); + std::tuple ParseCloudPacket( + const std::vector & packet); }; } // namespace drivers diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index beafd8e71..c8aea2b40 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -17,64 +17,62 @@ namespace nebula { namespace drivers { -HesaiDriver::HesaiDriver(const std::shared_ptr& sensor_configuration, - const std::shared_ptr& calibration_configuration) +HesaiDriver::HesaiDriver( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & calibration_data) { // initialize proper parser from cloud config's model and echo mode driver_status_ = nebula::Status::OK; - std::shared_ptr calibration = nullptr; - std::shared_ptr correction = nullptr; - - if (sensor_configuration->sensor_model == SensorModel::HESAI_PANDARAT128) - { - correction = std::static_pointer_cast(calibration_configuration); - } - else - { - calibration = std::static_pointer_cast(calibration_configuration); - } - - switch (sensor_configuration->sensor_model) - { - case SensorModel::UNKNOWN: - driver_status_ = nebula::Status::INVALID_SENSOR_MODEL; - break; + switch (sensor_configuration->sensor_model) { case SensorModel::HESAI_PANDAR64: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDAR40P: case SensorModel::HESAI_PANDAR40M: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARQT64: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARQT128: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARXT32: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARXT32M: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDARAT128: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDAR128_E3X: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; case SensorModel::HESAI_PANDAR128_E4X: - scan_decoder_.reset(new HesaiDecoder(sensor_configuration, calibration, correction)); + scan_decoder_ = InitializeDecoder(sensor_configuration, calibration_data); break; + case SensorModel::UNKNOWN: + driver_status_ = nebula::Status::INVALID_SENSOR_MODEL; + throw std::runtime_error("Invalid sensor model."); default: driver_status_ = nebula::Status::NOT_INITIALIZED; throw std::runtime_error("Driver not Implemented for selected sensor."); - break; } } +template +std::shared_ptr HesaiDriver::InitializeDecoder( + const std::shared_ptr & sensor_configuration, + const std::shared_ptr & + calibration_configuration) +{ + using CalibT = typename SensorT::angle_corrector_t::correction_data_t; + return std::make_shared>( + sensor_configuration, std::dynamic_pointer_cast(calibration_configuration)); +} + std::tuple HesaiDriver::ParseCloudPacket( const std::vector & packet) { From 00fefb41b5c04850bc1cef6ca0f123f445c39bd3 Mon Sep 17 00:00:00 2001 From: Maximilian Schmeller Date: Sat, 11 May 2024 20:18:09 +0900 Subject: [PATCH 112/122] refactor(nebula_ros): move mt_queue to common --- nebula_ros/include/nebula_ros/{hesai => common}/mt_queue.hpp | 0 nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) rename nebula_ros/include/nebula_ros/{hesai => common}/mt_queue.hpp (100%) diff --git a/nebula_ros/include/nebula_ros/hesai/mt_queue.hpp b/nebula_ros/include/nebula_ros/common/mt_queue.hpp similarity index 100% rename from nebula_ros/include/nebula_ros/hesai/mt_queue.hpp rename to nebula_ros/include/nebula_ros/common/mt_queue.hpp diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index 42d8bdc36..ed76343c7 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -9,7 +9,7 @@ #include "nebula_ros/hesai/decoder_wrapper.hpp" #include "nebula_ros/hesai/hw_interface_wrapper.hpp" #include "nebula_ros/hesai/hw_monitor_wrapper.hpp" -#include "nebula_ros/hesai/mt_queue.hpp" +#include "nebula_ros/common/mt_queue.hpp" #include "nebula_ros/common/parameter_descriptors.hpp" #include From 4b8b9c0a460a5276a826953ae3397c933c8d7ef6 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 13:46:56 +0900 Subject: [PATCH 113/122] chore(nebula_examples): change output rosbag format to NebulaPackets, clean up code --- .../hesai_ros_offline_extract_bag_pcd.hpp | 17 +- .../hesai_ros_offline_extract_bag_pcd.cpp | 293 ++++++------------ 2 files changed, 105 insertions(+), 205 deletions(-) diff --git a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp index 5136cbb12..bbecf43b0 100644 --- a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp +++ b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp @@ -15,18 +15,21 @@ #ifndef NEBULA_HesaiRosOfflineExtractBag_H #define NEBULA_HesaiRosOfflineExtractBag_H -#include "nebula_common/hesai/hesai_common.hpp" -#include "nebula_common/nebula_common.hpp" -#include "nebula_common/nebula_status.hpp" -#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp" -#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" +#include +#include +#include +#include +#include +#include #include #include #include -#include "pandar_msgs/msg/pandar_packet.hpp" -#include "pandar_msgs/msg/pandar_scan.hpp" +#include +#include +#include +#include #include #include diff --git a/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp b/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp index 02cc84c72..51e2d028c 100644 --- a/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp +++ b/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp @@ -70,7 +70,6 @@ Status HesaiRosOfflineExtractBag::InitializeDriver( std::shared_ptr sensor_configuration, std::shared_ptr calibration_configuration) { - // driver should be initialized here with proper decoder driver_ptr_ = std::make_shared( std::static_pointer_cast(sensor_configuration), calibration_configuration); @@ -84,141 +83,37 @@ Status HesaiRosOfflineExtractBag::GetParameters( drivers::HesaiCalibrationConfiguration & calibration_configuration, drivers::HesaiCorrection & correction_configuration) { + auto sensor_model_ = this->declare_parameter("sensor_model", "", param_read_only()); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(sensor_model_); + auto return_mode_ = this->declare_parameter("return_mode", "", param_read_only()); + sensor_configuration.return_mode = + nebula::drivers::ReturnModeFromStringHesai(return_mode_, sensor_configuration.sensor_model); + this->declare_parameter("frame_id", "pandar", param_read_only()); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("sensor_model", ""); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("return_mode", "", descriptor); - sensor_configuration.return_mode = - // nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); - nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("frame_id", "pandar", descriptor); - sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 3; - descriptor.read_only = true; - descriptor.dynamic_typing = false; + rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_only(); descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; - rcl_interfaces::msg::FloatingPointRange range; - range.set__from_value(0).set__to_value(360).set__step(0.01); - descriptor.floating_point_range = {range}; - this->declare_parameter("scan_phase", 0., descriptor); - sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("calibration_file", "", descriptor); - calibration_configuration.calibration_file = - this->get_parameter("calibration_file").as_string(); + descriptor.floating_point_range = float_range(0, 360, 0.01); + sensor_configuration.scan_phase = this->declare_parameter("scan_phase", 0., descriptor); + this->get_parameter("scan_phase").as_double(); } + + calibration_configuration.calibration_file =this->declare_parameter("calibration_file", "", param_read_only()); if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("correction_file", "", descriptor); - correction_file_path = this->get_parameter("correction_file").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("bag_path", "", descriptor); - bag_path = this->get_parameter("bag_path").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("storage_id", "sqlite3", descriptor); - storage_id = this->get_parameter("storage_id").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("out_path", "", descriptor); - out_path = this->get_parameter("out_path").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("format", "cdr", descriptor); - format = this->get_parameter("format").as_string(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 2; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("out_num", 3, descriptor); - out_num = this->get_parameter("out_num").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 2; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("skip_num", 3, descriptor); - skip_num = this->get_parameter("skip_num").as_int(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 1; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("only_xyz", false, descriptor); - only_xyz = this->get_parameter("only_xyz").as_bool(); - } - { - rcl_interfaces::msg::ParameterDescriptor descriptor; - descriptor.type = 4; - descriptor.read_only = true; - descriptor.dynamic_typing = false; - descriptor.additional_constraints = ""; - this->declare_parameter("target_topic", "", descriptor); - target_topic = this->get_parameter("target_topic").as_string(); + correction_file_path = this->declare_parameter("correction_file", "", param_read_only()); } + bag_path = this->declare_parameter("bag_path", "", param_read_only()); + storage_id = this->declare_parameter("storage_id", "sqlite3", param_read_only()); + out_path = this->declare_parameter("out_path", "", param_read_only()); + format = this->declare_parameter("format", "cdr", param_read_only()); + out_num = this->declare_parameter("out_num", 3, param_read_only()); + skip_num = this->declare_parameter("skip_num", 3, param_read_only()); + only_xyz = this->declare_parameter("only_xyz", false, param_read_only()); + target_topic = this->declare_parameter("target_topic", "", param_read_only()); + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { return Status::INVALID_SENSOR_MODEL; } @@ -281,81 +176,83 @@ Status HesaiRosOfflineExtractBag::ReadBag() if (rcpputils::fs::create_directories(o_dir)) { std::cout << "created: " << o_dir << std::endl; } - // return Status::OK; - pcl::PCDWriter writer; + pcl::PCDWriter pcd_writer; - std::unique_ptr writer_; - bool needs_open = true; + std::unique_ptr bag_writer{}; storage_options.uri = bag_path; storage_options.storage_id = storage_id; - converter_options.output_serialization_format = format; // "cdr"; - { - rosbag2_cpp::Reader reader(std::make_unique()); - // reader.open(rosbag_directory.string()); - reader.open(storage_options, converter_options); - int cnt = 0; - int out_cnt = 0; - while (reader.has_next()) { - auto bag_message = reader.read_next(); - - std::cout << "Found topic name " << bag_message->topic_name << std::endl; - - if (bag_message->topic_name == target_topic) { - std::cout << (cnt + 1) << ", " << (out_cnt + 1) << "/" << out_num << std::endl; - pandar_msgs::msg::PandarScan extracted_msg; - rclcpp::Serialization serialization; - rclcpp::SerializedMessage extracted_serialized_msg(*bag_message->serialized_data); - serialization.deserialize_message(&extracted_serialized_msg, &extracted_msg); - - // std::cout<<"Found data in topic " << bag_message->topic_name << ": " << - // extracted_test_msg.data << std::endl; - std::cout << "Found data in topic " << bag_message->topic_name << ": " - << bag_message->time_stamp << std::endl; - - for (auto & pkt : extracted_msg.packets) { - auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); - auto pointcloud = std::get<0>(pointcloud_ts); - - if (!pointcloud) { - continue; - } - - auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; - // pcl::io::savePCDFileBinary((o_dir / fn).string(), *pointcloud); - - if (needs_open) { - const rosbag2_storage::StorageOptions storage_options_w( - {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); - const rosbag2_cpp::ConverterOptions converter_options_w( - {rmw_get_serialization_format(), rmw_get_serialization_format()}); - writer_ = std::make_unique(); - writer_->open(storage_options_w, converter_options_w); - writer_->create_topic( - {bag_message->topic_name, "pandar_msgs/msg/PandarScan", rmw_get_serialization_format(), - ""}); - needs_open = false; - } - writer_->write(bag_message); - cnt++; - if (skip_num < cnt) { - out_cnt++; - if (only_xyz) { - pcl::PointCloud cloud_xyz; - pcl::copyPointCloud(*pointcloud, cloud_xyz); - writer.writeBinary((o_dir / fn).string(), cloud_xyz); - } else { - writer.writeBinary((o_dir / fn).string(), *pointcloud); - } - // writer.writeASCII((o_dir / fn).string(), *pointcloud); - } - if (out_num <= out_cnt) { - break; - } + converter_options.output_serialization_format = format; + + rosbag2_cpp::Reader reader(std::make_unique()); + reader.open(storage_options, converter_options); + int cnt = 0; + int out_cnt = 0; + while (reader.has_next()) { + auto bag_message = reader.read_next(); + + std::cout << "Found topic name " << bag_message->topic_name << std::endl; + + if (bag_message->topic_name != target_topic) { + continue; + } + + std::cout << (cnt + 1) << ", " << (out_cnt + 1) << "/" << out_num << std::endl; + pandar_msgs::msg::PandarScan extracted_msg; + rclcpp::Serialization serialization; + rclcpp::SerializedMessage extracted_serialized_msg(*bag_message->serialized_data); + serialization.deserialize_message(&extracted_serialized_msg, &extracted_msg); + + std::cout << "Found data in topic " << bag_message->topic_name << ": " + << bag_message->time_stamp << std::endl; + + nebula_msgs::msg::NebulaPackets nebula_msg; + nebula_msg.header = extracted_msg.header; + for (auto & pkt : extracted_msg.packets) { + std::vector pkt_data(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size)); + auto pointcloud_ts = driver_ptr_->ParseCloudPacket(pkt_data); + auto pointcloud = std::get<0>(pointcloud_ts); + + nebula_msgs::msg::NebulaPacket nebula_pkt; + nebula_pkt.stamp = pkt.stamp; + nebula_pkt.data.swap(pkt_data); // move storage from `pkt_data` to `data` + nebula_msg.packets.push_back(nebula_pkt); + + if (!pointcloud) { + continue; + } + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + + if (!bag_writer) { + const rosbag2_storage::StorageOptions storage_options_w( + {(o_dir / std::to_string(bag_message->time_stamp)).string(), "sqlite3"}); + const rosbag2_cpp::ConverterOptions converter_options_w( + {rmw_get_serialization_format(), rmw_get_serialization_format()}); + bag_writer = std::make_unique(); + bag_writer->open(storage_options_w, converter_options_w); + bag_writer->create_topic( + {bag_message->topic_name, "nebula_msgs/msg/NebulaPackets", rmw_get_serialization_format(), + ""}); + } + + bag_writer->write(bag_message); + cnt++; + if (skip_num < cnt) { + out_cnt++; + if (only_xyz) { + pcl::PointCloud cloud_xyz; + pcl::copyPointCloud(*pointcloud, cloud_xyz); + pcd_writer.writeBinary((o_dir / fn).string(), cloud_xyz); + } else { + pcd_writer.writeBinary((o_dir / fn).string(), *pointcloud); } } + + if (out_num <= out_cnt) { + break; + } } - // close on scope exit } return Status::OK; } From 52a210caf7172c95c148c467536f5eb6d925385d Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 13:51:53 +0900 Subject: [PATCH 114/122] chore(hesai/decoder_wrapper): clarify watchdog behavior in decoder --- nebula_ros/src/hesai/decoder_wrapper.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp index 0ddfd599e..3046dc9c0 100644 --- a/nebula_ros/src/hesai/decoder_wrapper.cpp +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -247,10 +247,12 @@ void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptr(pointcloud_ts); } + // A pointcloud is only emitted when a scan completes (e.g. 3599 packets do not emit, the 3600th emits one) if (pointcloud == nullptr) { - // todo - // RCLCPP_WARN_STREAM(logger_, "Empty cloud parsed."); + // Since this ends the function early, the `cloud_watchdog_` will not be updated. + // Thus, if pointclouds are not emitted for too long (e.g. when decoder settings are wrong or no packets come in), + // the watchdog will log a warning automatically return; }; From c4d58ec488bdbdee03bb069f404553614b113dee Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 13:53:51 +0900 Subject: [PATCH 115/122] chore(hesai/hw_monitor_wrapper): fix typo in diagnostics name --- nebula_ros/src/hesai/hw_monitor_wrapper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp index 0a56bec57..b34e181fb 100644 --- a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp @@ -22,7 +22,7 @@ HesaiHwMonitorWrapper::HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, case nebula::drivers::SensorModel::HESAI_PANDARAT128: temperature_names_.emplace_back("Bottom circuit board T1"); temperature_names_.emplace_back("Bottom circuit board T2"); - temperature_names_.emplace_back("Laser emitting board RT_L1(Internal)"); + temperature_names_.emplace_back("Laser emitting board RT_L1 (Internal)"); temperature_names_.emplace_back("Laser emitting board RT_L2"); temperature_names_.emplace_back("Receiving board RT_R"); temperature_names_.emplace_back("Receiving board RT2"); From 884a85c4818464e146545cf19a1a77a6c49008da Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 13:55:49 +0900 Subject: [PATCH 116/122] chore(hesai_ros_decoder_test): fix unclear naming in console output --- nebula_tests/hesai/hesai_ros_decoder_test.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.cpp b/nebula_tests/hesai/hesai_ros_decoder_test.cpp index 00f33fa1a..f65a974cc 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.cpp @@ -304,7 +304,7 @@ void HesaiRosDecoderTest::ReadBag( continue; } - std::cerr << "PC size: " << pointcloud->size() << std::endl; + std::cerr << "Pointcloud size: " << pointcloud->size() << std::endl; scan_callback(bag_message->time_stamp, scan_timestamp, pointcloud); } From 798c9eccc9ce71733cc6babba52151fb153f35cd Mon Sep 17 00:00:00 2001 From: amadeuszsz Date: Wed, 22 May 2024 14:25:19 +0900 Subject: [PATCH 117/122] chore(nebula_ros): add schema composition for robosense Signed-off-by: amadeuszsz --- .../config/lidar/robosense/Bpearl.param.yaml | 16 ++++ .../config/lidar/robosense/Helios.param.yaml | 16 ++++ .../config/lidar/velodyne/VLP16.param.yaml | 20 ++--- nebula_ros/config/robosense/Bpearl.yaml | 11 --- nebula_ros/config/robosense/Helios.yaml | 11 --- .../common/parameter_descriptors.hpp | 4 + nebula_ros/launch/robosense_launch.all_hw.xml | 53 ++--------- nebula_ros/schema/Bpearl.schema.json | 37 ++++++++ nebula_ros/schema/Helios.schema.json | 37 ++++++++ nebula_ros/schema/sub/robosense.json | 87 +++++++++++++++++++ .../src/common/parameter_descriptors.cpp | 26 ++++++ 11 files changed, 238 insertions(+), 80 deletions(-) create mode 100644 nebula_ros/config/lidar/robosense/Bpearl.param.yaml create mode 100644 nebula_ros/config/lidar/robosense/Helios.param.yaml delete mode 100644 nebula_ros/config/robosense/Bpearl.yaml delete mode 100644 nebula_ros/config/robosense/Helios.yaml create mode 100644 nebula_ros/schema/Bpearl.schema.json create mode 100644 nebula_ros/schema/Helios.schema.json create mode 100644 nebula_ros/schema/sub/robosense.json diff --git a/nebula_ros/config/lidar/robosense/Bpearl.param.yaml b/nebula_ros/config/lidar/robosense/Bpearl.param.yaml new file mode 100644 index 000000000..1be1f64c5 --- /dev/null +++ b/nebula_ros/config/lidar/robosense/Bpearl.param.yaml @@ -0,0 +1,16 @@ +/**: + ros__parameters: + host_ip: "255.255.255.255" + sensor_ip: "192.168.1.201" + data_port: 2368 + frame_id: data_link + diag_span: 1000 + scan_phase: 0.0 + setup_sensor: true + sensor_model: Bpearl + return_mode: Dual + gnss_port: 2369 + packet_mtu_size: 1500 + cloud_min_angle: 0 + cloud_max_angle: 360 + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/robosense/Helios.param.yaml b/nebula_ros/config/lidar/robosense/Helios.param.yaml new file mode 100644 index 000000000..b745d6e93 --- /dev/null +++ b/nebula_ros/config/lidar/robosense/Helios.param.yaml @@ -0,0 +1,16 @@ +/**: + ros__parameters: + host_ip: "255.255.255.255" + sensor_ip: "192.168.1.201" + data_port: 2368 + frame_id: data_link + diag_span: 1000 + scan_phase: 0.0 + setup_sensor: true + sensor_model: Helios + return_mode: Dual + gnss_port: 2369 + packet_mtu_size: 1500 + cloud_min_angle: 0 + cloud_max_angle: 360 + dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/lidar/velodyne/VLP16.param.yaml b/nebula_ros/config/lidar/velodyne/VLP16.param.yaml index 9ce09de50..c8b49ed78 100644 --- a/nebula_ros/config/lidar/velodyne/VLP16.param.yaml +++ b/nebula_ros/config/lidar/velodyne/VLP16.param.yaml @@ -1,21 +1,21 @@ /**: ros__parameters: - calibration_file: "$(find-pkg-share nebula_decoders)/calibration/velodyne/VLP16.yaml" + calibration_file: $(find-pkg-share nebula_decoders)/calibration/velodyne/$(var sensor_model).yaml setup_sensor: true - diag_span: 1000 advanced_diagnostics: false - launch_hw: false + launch_hw: true sensor_model: VLP16 return_mode: Dual - host_ip: "255.255.255.255" - sensor_ip: "192.168.1.201" - data_port: 2368 gnss_port: 2369 - frame_id: velodyne - scan_phase: 0.0 min_range: 0.3 - max_range: 300.0 + max_range: 300 packet_mtu_size: 1500 - rotation_speed: 360 + rotation_speed: 600 cloud_min_angle: 0 cloud_max_angle: 360 + diag_span: 1000 + scan_phase: 0 + host_ip: "255.255.255.255" + sensor_ip: "192.168.1.201" + data_port: 2368 + frame_id: data_link \ No newline at end of file diff --git a/nebula_ros/config/robosense/Bpearl.yaml b/nebula_ros/config/robosense/Bpearl.yaml deleted file mode 100644 index 9ccb42e56..000000000 --- a/nebula_ros/config/robosense/Bpearl.yaml +++ /dev/null @@ -1,11 +0,0 @@ -/**: - ros__parameters: - sensor_model: "Bpearl" # See readme for supported models - sensor_ip: "192.168.1.200" # Lidar Sensor IP - host_ip: "192.168.1.102" # Broadcast IP from Sensor - frame_id: "robosense" - data_port: 6699 # LiDAR Data Port (MSOP) - gnss_port: 7788 # LiDAR GNSS Port (DIFOP) - scan_phase: 0.0 # Angle where scans begin (degrees, [0.,360.] - diag_span: 1000 # milliseconds - dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/config/robosense/Helios.yaml b/nebula_ros/config/robosense/Helios.yaml deleted file mode 100644 index 24350822d..000000000 --- a/nebula_ros/config/robosense/Helios.yaml +++ /dev/null @@ -1,11 +0,0 @@ -/**: - ros__parameters: - sensor_model: "Helios" # See readme for supported models - sensor_ip: "192.168.1.200" # Lidar Sensor IP - host_ip: "192.168.1.102" # Broadcast IP from Sensor - frame_id: "robosense" - data_port: 6699 # LiDAR Data Port (MSOP) - gnss_port: 7788 # LiDAR GNSS Port (DIFOP) - scan_phase: 0.0 # Angle where scans begin (degrees, [0.,360.] - diag_span: 1000 # milliseconds - dual_return_distance_threshold: 0.1 diff --git a/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp index b54d8ad63..bdac267e9 100644 --- a/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp +++ b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp @@ -18,6 +18,10 @@ rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int start, int stop, int step); +double declare_fp_parameter(const std::string& name, + rcl_interfaces::msg::ParameterDescriptor parameter_descriptor, + rclcpp::Node* node); + /// @brief Get a parameter's value from a list of parameters, if that parameter is in the list. /// @tparam T The parameter's expected value type /// @param p A vector of parameters diff --git a/nebula_ros/launch/robosense_launch.all_hw.xml b/nebula_ros/launch/robosense_launch.all_hw.xml index 6e2ab6dda..52a013523 100644 --- a/nebula_ros/launch/robosense_launch.all_hw.xml +++ b/nebula_ros/launch/robosense_launch.all_hw.xml @@ -1,53 +1,10 @@ - - - - + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + \ No newline at end of file diff --git a/nebula_ros/schema/Bpearl.schema.json b/nebula_ros/schema/Bpearl.schema.json new file mode 100644 index 000000000..0622e2089 --- /dev/null +++ b/nebula_ros/schema/Bpearl.schema.json @@ -0,0 +1,37 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "LiDAR Robosense Bpearl parameters.", + "type": "object", + "definitions": { + "Bpearl": { + "type": "object", + "properties": { + }, + "allOf": [ + { + "$ref": "sub/robosense.json#/definitions/robosense" + } + ], + "required": [ + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/Bpearl" + } + }, + "required": [ + "ros__parameters" + ], + "additionalProperties": false + } + }, + "required": [ + "/**" + ], + "additionalProperties": false +} \ No newline at end of file diff --git a/nebula_ros/schema/Helios.schema.json b/nebula_ros/schema/Helios.schema.json new file mode 100644 index 000000000..4485f4aad --- /dev/null +++ b/nebula_ros/schema/Helios.schema.json @@ -0,0 +1,37 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "LiDAR Robosense Helios parameters.", + "type": "object", + "definitions": { + "Helios": { + "type": "object", + "properties": { + }, + "allOf": [ + { + "$ref": "sub/robosense.json#/definitions/robosense" + } + ], + "required": [ + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/Helios" + } + }, + "required": [ + "ros__parameters" + ], + "additionalProperties": false + } + }, + "required": [ + "/**" + ], + "additionalProperties": false +} \ No newline at end of file diff --git a/nebula_ros/schema/sub/robosense.json b/nebula_ros/schema/sub/robosense.json new file mode 100644 index 000000000..0e23e8433 --- /dev/null +++ b/nebula_ros/schema/sub/robosense.json @@ -0,0 +1,87 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "LiDAR Robosense common parameters.", + "type": "object", + "definitions": { + "robosense": { + "type": "object", + "properties": { + "setup_sensor": { + "type": "boolean", + "default": true, + "readOnly": true, + "description": "Enable sensor setup on hw-driver." + }, + "sensor_model": { + "type": "string", + "readOnly": true, + "enum": [ + "Helios", + "Bpearl" + ], + "description": "LiDAR model." + }, + "return_mode": { + "type": "string", + "enum": [ + "Dual", + "Strongest", + "Last", + "First" + ], + "description": "LiDAR return mode." + }, + "gnss_port": { + "type": "integer", + "default": 2369, + "minimum": 0, + "readOnly": true, + "description": "LiDAR GNSS port." + }, + "packet_mtu_size": { + "type": "integer", + "default": 1500, + "minimum": 0, + "readOnly": true, + "description": "Packet MTU size." + }, + "cloud_min_angle": { + "type": "integer", + "default": 0, + "minimum": 0, + "maximum": 360, + "description": "Field of View, start degrees." + }, + "cloud_max_angle": { + "type": "integer", + "default": 360, + "minimum": 0, + "maximum": 360, + "description": "Field of View, end degrees." + }, + "dual_return_distance_threshold": { + "type": "number", + "default": 0.1, + "minimum": 0.01, + "maximum": 0.5, + "description": "Distance threshold between two neighboring points for dual return mode." + } + }, + "allOf": [ + { + "$ref": "lidar.json#/definitions/lidar" + } + ], + "required": [ + "setup_sensor", + "sensor_model", + "return_mode", + "gnss_port", + "packet_mtu_size", + "cloud_min_angle", + "cloud_max_angle", + "dual_return_distance_threshold" + ] + } + } +} \ No newline at end of file diff --git a/nebula_ros/src/common/parameter_descriptors.cpp b/nebula_ros/src/common/parameter_descriptors.cpp index ffd0fff37..d82b7235e 100644 --- a/nebula_ros/src/common/parameter_descriptors.cpp +++ b/nebula_ros/src/common/parameter_descriptors.cpp @@ -25,5 +25,31 @@ rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int star return { rcl_interfaces::msg::IntegerRange().set__from_value(start).set__to_value(stop).set__step(step) }; } +double declare_fp_parameter(const std::string& name, rcl_interfaces::msg::ParameterDescriptor parameter_descriptor, rclcpp::Node* node) +{ + parameter_descriptor.dynamic_typing = true; + parameter_descriptor.read_only = false; // Can't set param if read_only, force to false + auto param = node->declare_parameter(name, rclcpp::ParameterValue{}, parameter_descriptor); + double value; + + switch (param.get_type()) + { + case rclcpp::PARAMETER_INTEGER: + value = static_cast(param.get()); + RCLCPP_WARN_STREAM( + node->get_logger(), "Parameter " << name << " was set as an integer, converting to double"); + break; + case rclcpp::PARAMETER_DOUBLE: + value = param.get(); + break; + default: + throw std::runtime_error( + (std::stringstream() << "Invalid type (" << param.get_type() << + ") for floating point parameter " << name).str()); + } + node->set_parameter(rclcpp::Parameter(name, value)); + return value; +} + } // namespace ros } // namespace nebula \ No newline at end of file From 28b42fcb66ceedae689521f3fc5212f3bd3b35f0 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 14:44:09 +0900 Subject: [PATCH 118/122] chore: run pre-commit and implement suggested fixes (not including copyright yet) --- .cspell.json | 9 +- .../nebula_common/hesai/hesai_common.hpp | 48 ++-- .../include/nebula_common/nebula_common.hpp | 37 ++- .../include/nebula_common/util/expected.hpp | 47 ++-- .../decoders/angle_corrector.hpp | 5 +- .../angle_corrector_calibration_based.hpp | 5 +- .../angle_corrector_correction_based.hpp | 15 +- .../decoders/hesai_decoder.hpp | 14 +- .../decoders/hesai_packet.hpp | 3 +- .../decoders/hesai_scan_decoder.hpp | 1 + .../nebula_decoders_hesai/hesai_driver.hpp | 4 +- .../nebula_decoders_hesai/hesai_driver.cpp | 6 +- .../hesai_ros_offline_extract_bag_pcd.hpp | 7 +- .../hesai_ros_offline_extract_bag_pcd.cpp | 22 +- .../hesai/hesai_ros_offline_extract_pcd.cpp | 10 +- .../hesai_cmd_response.hpp | 38 +-- .../hesai_hw_interface.hpp | 8 +- .../hesai_hw_interface.cpp | 91 ++++--- nebula_messages/nebula_msgs/CMakeLists.txt | 2 +- .../nebula_msgs/msg/NebulaPacket.msg | 2 +- nebula_messages/nebula_msgs/package.xml | 2 +- .../include/nebula_ros/common/mt_queue.hpp | 7 +- .../common/parameter_descriptors.hpp | 23 +- .../nebula_ros/common/watchdog_timer.hpp | 27 +- .../nebula_ros/hesai/decoder_wrapper.hpp | 40 +-- .../nebula_ros/hesai/hesai_ros_wrapper.hpp | 17 +- .../nebula_ros/hesai/hw_interface_wrapper.hpp | 11 +- .../nebula_ros/hesai/hw_monitor_wrapper.hpp | 33 ++- nebula_ros/launch/hesai_launch_all_hw.xml | 6 +- nebula_ros/launch/nebula_launch.py | 47 ++-- nebula_ros/package.xml | 4 +- .../src/common/parameter_descriptors.cpp | 15 +- nebula_ros/src/hesai/decoder_wrapper.cpp | 251 +++++++++-------- nebula_ros/src/hesai/hesai_ros_wrapper.cpp | 199 +++++++------- nebula_ros/src/hesai/hw_interface_wrapper.cpp | 48 ++-- nebula_ros/src/hesai/hw_monitor_wrapper.cpp | 253 ++++++++---------- nebula_tests/hesai/hesai_ros_decoder_test.cpp | 8 +- nebula_tests/hesai/hesai_ros_decoder_test.hpp | 30 ++- .../hesai/hesai_ros_decoder_test_main.cpp | 77 +----- .../velodyne_ros_decoder_test_vls128.cpp | 10 +- ...cc0c413aef9f44cc34d45933658dcd90140bf.json | 1 + scripts/plot_instrumentation.py | 104 +++---- scripts/plot_times.py | 53 ++-- 43 files changed, 816 insertions(+), 824 deletions(-) create mode 100644 node_modules/.cache/prettier/.prettier-caches/71fcc0c413aef9f44cc34d45933658dcd90140bf.json diff --git a/.cspell.json b/.cspell.json index 228d7f45e..30dc5cda2 100644 --- a/.cspell.json +++ b/.cspell.json @@ -13,6 +13,7 @@ "DHAVE", "Difop", "extrinsics", + "fout", "gprmc", "gptp", "Helios", @@ -32,6 +33,8 @@ "PANDARQT", "PANDARXT", "Pdelay", + "Piyush", + "piyushk", "QT", "rclcpp", "schedutil", @@ -46,8 +49,6 @@ "Vdat", "XT", "XTM", - "piyushk", - "Piyush", - "fout" + "yukkysaito" ] -} \ No newline at end of file +} diff --git a/nebula_common/include/nebula_common/hesai/hesai_common.hpp b/nebula_common/include/nebula_common/hesai/hesai_common.hpp index 0c7ae1c1b..8e0600999 100644 --- a/nebula_common/include/nebula_common/hesai/hesai_common.hpp +++ b/nebula_common/include/nebula_common/hesai/hesai_common.hpp @@ -8,7 +8,10 @@ #include #include #include +#include #include +#include +#include namespace nebula { namespace drivers @@ -47,7 +50,8 @@ struct HesaiCalibrationConfigurationBase : public CalibrationConfigurationBase { virtual nebula::Status LoadFromBytes(const std::vector & buf) = 0; virtual nebula::Status LoadFromFile(const std::string & calibration_file) = 0; - virtual nebula::Status SaveToFileFromBytes(const std::string & calibration_file, const std::vector & buf) = 0; + virtual nebula::Status SaveToFileFromBytes( + const std::string & calibration_file, const std::vector & buf) = 0; }; /// @brief struct for Hesai calibration configuration @@ -63,12 +67,13 @@ struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase return Status::INVALID_CALIBRATION_FILE; } std::ostringstream ss; - ss << ifs.rdbuf(); // reading data + ss << ifs.rdbuf(); // reading data ifs.close(); return LoadFromString(ss.str()); } - nebula::Status LoadFromBytes(const std::vector & buf) { + nebula::Status LoadFromBytes(const std::vector & buf) + { std::string calibration_string = std::string(buf.begin(), buf.end()); return LoadFromString(calibration_string); } @@ -82,14 +87,12 @@ struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase ss << calibration_content; std::string line; constexpr size_t expected_cols = 3; - while(std::getline(ss, line)) { + while (std::getline(ss, line)) { boost::char_separator sep(","); boost::tokenizer> tok(line, sep); std::vector actual_tokens(tok.begin(), tok.end()); - if (actual_tokens.size() < expected_cols - || actual_tokens.size() > expected_cols - ) { + if (actual_tokens.size() < expected_cols || actual_tokens.size() > expected_cols) { std::cerr << "Ignoring line with unexpected data:" << line << std::endl; continue; } @@ -100,10 +103,9 @@ struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase float azimuth = std::stof(actual_tokens[2]); elev_angle_map[laser_id - 1] = elevation; azimuth_offset_map[laser_id - 1] = azimuth; - } catch (const std::invalid_argument& ia) { + } catch (const std::invalid_argument & ia) { continue; } - } return Status::OK; } @@ -129,7 +131,9 @@ struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase return Status::OK; } - nebula::Status SaveToFileFromBytes(const std::string & calibration_file, const std::vector & buf) override { + nebula::Status SaveToFileFromBytes( + const std::string & calibration_file, const std::vector & buf) override + { std::string calibration_string = std::string(buf.begin(), buf.end()); return SaveFileFromString(calibration_file, calibration_string); } @@ -138,7 +142,8 @@ struct HesaiCalibrationConfiguration : public HesaiCalibrationConfigurationBase /// @param calibration_file path /// @param calibration_string calibration string /// @return Resulting status - inline nebula::Status SaveFileFromString(const std::string & calibration_file, const std::string & calibration_string) + inline nebula::Status SaveFileFromString( + const std::string & calibration_file, const std::string & calibration_string) { std::ofstream ofs(calibration_file); if (!ofs) { @@ -176,9 +181,8 @@ struct HesaiCorrection : public HesaiCalibrationConfigurationBase inline nebula::Status LoadFromBytes(const std::vector & buf) override { size_t index; - for (index = 0; index < buf.size()-1; index++) { - if(buf[index]==0xee && buf[index+1]==0xff) - break; + for (index = 0; index < buf.size() - 1; index++) { + if (buf[index] == 0xee && buf[index + 1] == 0xff) break; } delimiter = (buf[index] & 0xff) << 8 | ((buf[index + 1] & 0xff)); versionMajor = buf[index + 2] & 0xff; @@ -285,7 +289,7 @@ struct HesaiCorrection : public HesaiCalibrationConfigurationBase // int cnt = 0; while (!ifs.eof()) { unsigned char c; - ifs.read((char *)&c, sizeof(unsigned char)); + ifs.read(reinterpret_cast(&c), sizeof(unsigned char)); buf.emplace_back(c); } LoadFromBytes(buf); @@ -298,7 +302,8 @@ struct HesaiCorrection : public HesaiCalibrationConfigurationBase /// @param correction_file path /// @param buf correction binary /// @return Resulting status - inline nebula::Status SaveToFileFromBytes(const std::string & correction_file, const std::vector & buf) override + inline nebula::Status SaveToFileFromBytes( + const std::string & correction_file, const std::vector & buf) override { std::cerr << "Saving in:" << correction_file << "\n"; std::ofstream ofs(correction_file, std::ios::trunc | std::ios::binary); @@ -308,21 +313,20 @@ struct HesaiCorrection : public HesaiCalibrationConfigurationBase } std::cerr << "Writing start...." << buf.size() << "\n"; bool sop_received = false; - for (const auto &byte : buf) { + for (const auto & byte : buf) { if (!sop_received) { if (byte == 0xEE) { std::cerr << "SOP received....\n"; sop_received = true; } } - if(sop_received) { + if (sop_received) { ofs << byte; } } std::cerr << "Closing file\n"; ofs.close(); - if(sop_received) - return Status::OK; + if (sop_received) return Status::OK; return Status::INVALID_CALIBRATION_FILE; } @@ -452,8 +456,8 @@ inline int IntFromReturnModeHesai(const ReturnMode return_mode, const SensorMode case SensorModel::HESAI_PANDARQT128: if (return_mode == ReturnMode::LAST) return 0; if (return_mode == ReturnMode::STRONGEST) return 1; - if (return_mode == ReturnMode::DUAL_LAST_STRONGEST - || return_mode == ReturnMode::DUAL) return 2; + if (return_mode == ReturnMode::DUAL_LAST_STRONGEST || return_mode == ReturnMode::DUAL) + return 2; if (return_mode == ReturnMode::FIRST) return 3; if (return_mode == ReturnMode::DUAL_LAST_FIRST) return 4; if (return_mode == ReturnMode::DUAL_FIRST_STRONGEST) return 5; diff --git a/nebula_common/include/nebula_common/nebula_common.hpp b/nebula_common/include/nebula_common/nebula_common.hpp index cf1eb0841..e43ab49a3 100644 --- a/nebula_common/include/nebula_common/nebula_common.hpp +++ b/nebula_common/include/nebula_common/nebula_common.hpp @@ -2,7 +2,10 @@ #define NEBULA_COMMON_H #include + #include + +#include #include #include #include @@ -342,24 +345,11 @@ enum class datatype { FLOAT64 = 8 }; -enum class PtpProfile { - IEEE_1588v2 = 0, - IEEE_802_1AS, - IEEE_802_1AS_AUTO, - UNKNOWN_PROFILE -}; +enum class PtpProfile { IEEE_1588v2 = 0, IEEE_802_1AS, IEEE_802_1AS_AUTO, UNKNOWN_PROFILE }; -enum class PtpTransportType { - UDP_IP = 0, - L2, - UNKNOWN_TRANSPORT -}; +enum class PtpTransportType { UDP_IP = 0, L2, UNKNOWN_TRANSPORT }; -enum class PtpSwitchType { - NON_TSN = 0, - TSN, - UNKNOWN_SWITCH -}; +enum class PtpSwitchType { NON_TSN = 0, TSN, UNKNOWN_SWITCH }; /// @brief not used? struct PointField @@ -618,8 +608,9 @@ inline PtpProfile PtpProfileFromString(const std::string & ptp_profile) { // Hesai auto tmp_str = ptp_profile; - std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), - [](unsigned char c){ return std::tolower(c); }); + std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), [](unsigned char c) { + return std::tolower(c); + }); if (tmp_str == "1588v2") return PtpProfile::IEEE_1588v2; if (tmp_str == "802.1as") return PtpProfile::IEEE_802_1AS; if (tmp_str == "automotive") return PtpProfile::IEEE_802_1AS_AUTO; @@ -657,8 +648,9 @@ inline PtpTransportType PtpTransportTypeFromString(const std::string & transport { // Hesai auto tmp_str = transport_type; - std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), - [](unsigned char c){ return std::tolower(c); }); + std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), [](unsigned char c) { + return std::tolower(c); + }); if (tmp_str == "udp") return PtpTransportType::UDP_IP; if (tmp_str == "l2") return PtpTransportType::L2; @@ -692,8 +684,9 @@ inline PtpSwitchType PtpSwitchTypeFromString(const std::string & switch_type) { // Hesai auto tmp_str = switch_type; - std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), - [](unsigned char c){ return std::tolower(c); }); + std::transform(tmp_str.begin(), tmp_str.end(), tmp_str.begin(), [](unsigned char c) { + return std::tolower(c); + }); if (tmp_str == "tsn") return PtpSwitchType::TSN; if (tmp_str == "non_tsn") return PtpSwitchType::NON_TSN; diff --git a/nebula_common/include/nebula_common/util/expected.hpp b/nebula_common/include/nebula_common/util/expected.hpp index 0f47e9de1..2a59122f5 100644 --- a/nebula_common/include/nebula_common/util/expected.hpp +++ b/nebula_common/include/nebula_common/util/expected.hpp @@ -1,23 +1,22 @@ #pragma once -#include -#include #include +#include +#include namespace nebula { namespace util { -struct bad_expected_access : public std::exception { - bad_expected_access(const std::string & msg) : std::exception(), msg_(msg) {} +struct bad_expected_access : public std::exception +{ + explicit bad_expected_access(const std::string & msg) : std::exception(), msg_(msg) {} - const char* what() const noexcept override { - return msg_.c_str(); - } + const char * what() const noexcept override { return msg_.c_str(); } private: - const std::string msg_; + const std::string msg_; }; /// @brief A poor man's backport of C++23's std::expected. @@ -39,14 +38,16 @@ struct expected /// @brief Retrieve the value, or throw `bad_expected_access` if an error is contained. /// @return The value of type `T` - T value() { + T value() + { if (!has_value()) { throw bad_expected_access("value() called but containing error"); } - return std::get(value_); + return std::get(value_); } - /// @brief Return the contained value, or, if an error is contained, return the given `default_` instead. + /// @brief Return the contained value, or, if an error is contained, return the given `default_` + /// instead. /// @return The contained value, if any, else `default_` T value_or(const T & default_) { @@ -57,34 +58,38 @@ struct expected /// @brief If the instance has a value, return the value, else throw std::runtime_error(error_msg) /// @param error_msg The message to be included in the thrown exception /// @return The value - T value_or_throw(const std::string & error_msg) { + T value_or_throw(const std::string & error_msg) + { if (has_value()) return value(); throw std::runtime_error(error_msg); } /// @brief Retrieve the error, or throw `bad_expected_access` if a value is contained. /// @return The error of type `E` - E error() { + E error() + { if (has_value()) { throw bad_expected_access("error() called but containing value"); } - return std::get(value_); + return std::get(value_); } - /// @brief Return the contained error, or, if a value is contained, return the given `default_` instead. + /// @brief Return the contained error, or, if a value is contained, return the given `default_` + /// instead. /// @return The contained error, if any, else `default_` - E error_or(const E & default_) { + E error_or(const E & default_) + { if (!has_value()) return error(); - return default_; - } + return default_; + } - expected(const T & value) { value_ = value; } + explicit expected(const T & value) { value_ = value; } - expected(const E & error) { value_ = error; } + explicit expected(const E & error) { value_ = error; } private: std::variant value_; }; } // namespace util -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp index 914d2da49..02d7cd535 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp @@ -44,8 +44,9 @@ class AngleCorrector /// @param sync_azimuth The azimuth set in the sensor configuration, for which the /// timestamp is aligned to the full second /// @return true if the current azimuth is in a different scan than the last one, false otherwise - virtual bool hasScanned(uint32_t current_azimuth, uint32_t last_azimuth, uint32_t sync_azimuth) = 0; + virtual bool hasScanned( + uint32_t current_azimuth, uint32_t last_azimuth, uint32_t sync_azimuth) = 0; }; } // namespace drivers -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp index d2c078e2d..da9a1b579 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector_calibration_based.hpp @@ -4,6 +4,7 @@ #include "nebula_decoders/nebula_decoders_hesai/decoders/angle_corrector.hpp" #include +#include namespace nebula { @@ -79,10 +80,10 @@ class AngleCorrectorCalibrationBased : public AngleCorrector - -#define _(x) '"' << #x << "\": " << x << ", " +#include namespace nebula { @@ -30,8 +29,8 @@ class AngleCorrectorCorrectionBased : public AngleCorrector { // Assumes that: // * none of the startFrames are defined as > 360 deg (< 0 not possible since they are unsigned) - // * the fields are arranged in ascending order (e.g. field 1: 20-140deg, field 2: 140-260deg etc.) - // These assumptions hold for AT128E2X. + // * the fields are arranged in ascending order (e.g. field 1: 20-140deg, field 2: 140-260deg + // etc.) These assumptions hold for AT128E2X. int field = correction_->frameNumber - 1; for (size_t i = 0; i < correction_->frameNumber; ++i) { if (azimuth < correction_->startFrame[i]) return field; @@ -43,10 +42,9 @@ class AngleCorrectorCorrectionBased : public AngleCorrector } public: - AngleCorrectorCorrectionBased( + explicit AngleCorrectorCorrectionBased( const std::shared_ptr & sensor_correction) - : correction_(sensor_correction), - logger_(rclcpp::get_logger("AngleCorrectorCorrectionBased")) + : correction_(sensor_correction), logger_(rclcpp::get_logger("AngleCorrectorCorrectionBased")) { if (sensor_correction == nullptr) { throw std::runtime_error( @@ -83,7 +81,8 @@ class AngleCorrectorCorrectionBased : public AngleCorrector cos_[azimuth], sin_[elevation], cos_[elevation]}; } - bool hasScanned(uint32_t current_azimuth, uint32_t last_azimuth, uint32_t /*sync_azimuth*/) override + bool hasScanned( + uint32_t current_azimuth, uint32_t last_azimuth, uint32_t /*sync_azimuth*/) override { // For AT128, the scan is always cut at the beginning of the field: // If we would cut at `sync_azimuth`, the points left of it would be diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp index ea5dbe727..a277137d2 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_decoder.hpp @@ -8,6 +8,11 @@ #include "pandar_msgs/msg/pandar_packet.hpp" #include "pandar_msgs/msg/pandar_scan.hpp" +#include +#include +#include +#include + namespace nebula { namespace drivers @@ -34,7 +39,7 @@ class HesaiDecoder : public HesaiScanDecoder /// @brief The last decoded packet typename SensorT::packet_t packet_; /// @brief The last azimuth processed - int last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet + int last_phase_ = -1; // Dummy value to signal last_phase_ has not been set yet /// @brief The timestamp of the last completed scan in nanoseconds uint64_t output_scan_timestamp_ns_ = 0; /// @brief The timestamp of the scan currently in progress @@ -177,7 +182,7 @@ class HesaiDecoder : public HesaiScanDecoder if (last_phase_ == -1) { return false; } - + return angle_corrector_.hasScanned(current_phase, last_phase_, sync_phase); } @@ -207,7 +212,8 @@ class HesaiDecoder : public HesaiScanDecoder /// @param correction_data Calibration data for this decoder explicit HesaiDecoder( const std::shared_ptr & sensor_configuration, - const std::shared_ptr & correction_data) + const std::shared_ptr & + correction_data) : sensor_configuration_(sensor_configuration), angle_corrector_(correction_data), logger_(rclcpp::get_logger("HesaiDecoder")) @@ -247,7 +253,7 @@ class HesaiDecoder : public HesaiScanDecoder sensor_configuration_->scan_phase * SensorT::packet_t::DEGREE_SUBDIVISIONS); if (scan_completed) { - std::swap(decode_pc_, output_pc_); + std::swap(decode_pc_, output_pc_); decode_pc_->clear(); has_scanned_ = true; output_scan_timestamp_ns_ = decode_scan_timestamp_ns_; diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp index 0280f1ff7..aa807e567 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_packet.hpp @@ -221,7 +221,8 @@ uint64_t get_timestamp_ns(const PacketT & packet) return packet.tail.date_time.get_seconds() * 1000000000 + packet.tail.timestamp * 1000; } -/// @brief Get the distance unit of the given packet type in meters. Distance values in the packet, multiplied by this value, yield the distance in meters. +/// @brief Get the distance unit of the given packet type in meters. Distance values in the packet, +/// multiplied by this value, yield the distance in meters. /// @tparam PacketT The packet type /// @param packet The packet to get the distance unit from /// @return The distance unit in meters diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp index 9d06c2702..153435bbe 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp @@ -8,6 +8,7 @@ #include "pandar_msgs/msg/pandar_scan.hpp" #include +#include namespace nebula { diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp index 099e022c5..4c211efcc 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp @@ -14,9 +14,11 @@ #include #include +#include #include #include -#include +#include +#include namespace nebula { diff --git a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp index c8aea2b40..b3afa886b 100644 --- a/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp +++ b/nebula_decoders/src/nebula_decoders_hesai/hesai_driver.cpp @@ -79,15 +79,13 @@ std::tuple HesaiDriver::ParseCloudPacket( std::tuple pointcloud; auto logger = rclcpp::get_logger("HesaiDriver"); - if (driver_status_ != nebula::Status::OK) - { + if (driver_status_ != nebula::Status::OK) { RCLCPP_ERROR(logger, "Driver not OK."); return pointcloud; } scan_decoder_->unpack(packet); - if (scan_decoder_->hasScanned()) - { + if (scan_decoder_->hasScanned()) { pointcloud = scan_decoder_->getPointcloud(); } diff --git a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp index bbecf43b0..b8bbe345c 100644 --- a/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp +++ b/nebula_examples/include/hesai/hesai_ros_offline_extract_bag_pcd.hpp @@ -15,21 +15,20 @@ #ifndef NEBULA_HesaiRosOfflineExtractBag_H #define NEBULA_HesaiRosOfflineExtractBag_H +#include #include #include #include #include #include #include - -#include #include #include -#include -#include #include #include +#include +#include #include #include diff --git a/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp b/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp index 51e2d028c..649085018 100644 --- a/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp +++ b/nebula_examples/src/hesai/hesai_ros_offline_extract_bag_pcd.cpp @@ -76,7 +76,10 @@ Status HesaiRosOfflineExtractBag::InitializeDriver( return driver_ptr_->GetStatus(); } -Status HesaiRosOfflineExtractBag::GetStatus() {return wrapper_status_;} +Status HesaiRosOfflineExtractBag::GetStatus() +{ + return wrapper_status_; +} Status HesaiRosOfflineExtractBag::GetParameters( drivers::HesaiSensorConfiguration & sensor_configuration, @@ -84,14 +87,13 @@ Status HesaiRosOfflineExtractBag::GetParameters( drivers::HesaiCorrection & correction_configuration) { auto sensor_model_ = this->declare_parameter("sensor_model", "", param_read_only()); - sensor_configuration.sensor_model = - nebula::drivers::SensorModelFromString(sensor_model_); + sensor_configuration.sensor_model = nebula::drivers::SensorModelFromString(sensor_model_); auto return_mode_ = this->declare_parameter("return_mode", "", param_read_only()); sensor_configuration.return_mode = nebula::drivers::ReturnModeFromStringHesai(return_mode_, sensor_configuration.sensor_model); this->declare_parameter("frame_id", "pandar", param_read_only()); sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); - + { rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_only(); descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; @@ -100,9 +102,11 @@ Status HesaiRosOfflineExtractBag::GetParameters( this->get_parameter("scan_phase").as_double(); } - calibration_configuration.calibration_file =this->declare_parameter("calibration_file", "", param_read_only()); + calibration_configuration.calibration_file = + this->declare_parameter("calibration_file", "", param_read_only()); if (sensor_configuration.sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { - correction_file_path = this->declare_parameter("correction_file", "", param_read_only()); + correction_file_path = + this->declare_parameter("correction_file", "", param_read_only()); } bag_path = this->declare_parameter("bag_path", "", param_read_only()); @@ -215,7 +219,7 @@ Status HesaiRosOfflineExtractBag::ReadBag() nebula_msgs::msg::NebulaPacket nebula_pkt; nebula_pkt.stamp = pkt.stamp; - nebula_pkt.data.swap(pkt_data); // move storage from `pkt_data` to `data` + nebula_pkt.data.swap(pkt_data); // move storage from `pkt_data` to `data` nebula_msg.packets.push_back(nebula_pkt); if (!pointcloud) { @@ -233,7 +237,7 @@ Status HesaiRosOfflineExtractBag::ReadBag() bag_writer->open(storage_options_w, converter_options_w); bag_writer->create_topic( {bag_message->topic_name, "nebula_msgs/msg/NebulaPackets", rmw_get_serialization_format(), - ""}); + ""}); } bag_writer->write(bag_message); @@ -248,7 +252,7 @@ Status HesaiRosOfflineExtractBag::ReadBag() pcd_writer.writeBinary((o_dir / fn).string(), *pointcloud); } } - + if (out_num <= out_cnt) { break; } diff --git a/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp b/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp index bd992ee19..8e134f8aa 100644 --- a/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp +++ b/nebula_examples/src/hesai/hesai_ros_offline_extract_pcd.cpp @@ -77,7 +77,10 @@ Status HesaiRosOfflineExtractSample::InitializeDriver( return driver_ptr_->GetStatus(); } -Status HesaiRosOfflineExtractSample::GetStatus() {return wrapper_status_;} +Status HesaiRosOfflineExtractSample::GetStatus() +{ + return wrapper_status_; +} Status HesaiRosOfflineExtractSample::GetParameters( drivers::HesaiSensorConfiguration & sensor_configuration, @@ -104,7 +107,7 @@ Status HesaiRosOfflineExtractSample::GetParameters( sensor_configuration.return_mode = // nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); nebula::drivers::ReturnModeFromStringHesai( - this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); + this->get_parameter("return_mode").as_string(), sensor_configuration.sensor_model); } { rcl_interfaces::msg::ParameterDescriptor descriptor; @@ -282,7 +285,8 @@ Status HesaiRosOfflineExtractSample::ReadBag() // driver_ptr_->ConvertScanToPointcloud( // std::make_shared(extracted_msg)); for (auto & pkt : extracted_msg.packets) { - auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); + auto pointcloud_ts = driver_ptr_->ParseCloudPacket( + std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); auto pointcloud = std::get<0>(pointcloud_ts); if (!pointcloud) { diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp index a6d78c45e..13ad0ed53 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_cmd_response.hpp @@ -10,7 +10,7 @@ #include #include -using namespace boost::endian; +using namespace boost::endian; // NOLINT(build/namespaces) namespace nebula { @@ -100,7 +100,7 @@ struct HesaiPtpDiagTime os << ", "; os << "gmTimeBaseIndicator: " << arg.gmTimeBaseIndicator; os << ", "; - //FIXME: lastGmPhaseChange is a binary number, displaying it as string is incorrect + // FIXME: lastGmPhaseChange is a binary number, displaying it as string is incorrect os << "lastGmPhaseChange: " << std::string(std::begin(arg.lastGmPhaseChange), std::end(arg.lastGmPhaseChange)); os << ", "; @@ -158,7 +158,9 @@ struct HesaiInventory os << "sn: " << std::string(arg.sn, strnlen(arg.sn, sizeof(arg.sn))); os << ", "; os << "date_of_manufacture: " - << std::string(arg.date_of_manufacture, strnlen(arg.date_of_manufacture, sizeof(arg.date_of_manufacture))); + << std::string( + arg.date_of_manufacture, + strnlen(arg.date_of_manufacture, sizeof(arg.date_of_manufacture))); os << ", "; os << "mac: "; @@ -256,7 +258,7 @@ struct HesaiConfig uint8_t motor_status; uint8_t vlan_flag; big_uint16_buf_t vlan_id; - uint8_t clock_data_fmt; //FIXME: labeled as gps_nmea_sentence in AT128, OT128 datasheets + uint8_t clock_data_fmt; // FIXME: labeled as gps_nmea_sentence in AT128, OT128 datasheets uint8_t noise_filtering; uint8_t reflectivity_mapping; uint8_t reserved[6]; @@ -266,29 +268,17 @@ struct HesaiConfig std::ios initial_format(nullptr); initial_format.copyfmt(os); - os << "ipaddr: " - << +arg.ipaddr[0] << "." - << +arg.ipaddr[1] << "." - << +arg.ipaddr[2] << "." + os << "ipaddr: " << +arg.ipaddr[0] << "." << +arg.ipaddr[1] << "." << +arg.ipaddr[2] << "." << +arg.ipaddr[3]; os << ", "; - os << "mask: " - << +arg.mask[0] << "." - << +arg.mask[1] << "." - << +arg.mask[2] << "." + os << "mask: " << +arg.mask[0] << "." << +arg.mask[1] << "." << +arg.mask[2] << "." << +arg.mask[3]; os << ", "; - os << "gateway: " - << +arg.gateway[0] << "." - << +arg.gateway[1] << "." - << +arg.gateway[2] << "." + os << "gateway: " << +arg.gateway[0] << "." << +arg.gateway[1] << "." << +arg.gateway[2] << "." << +arg.gateway[3]; os << ", "; - os << "dest_ipaddr: " - << +arg.dest_ipaddr[0] << "." - << +arg.dest_ipaddr[1] << "." - << +arg.dest_ipaddr[2] << "." - << +arg.dest_ipaddr[3]; + os << "dest_ipaddr: " << +arg.dest_ipaddr[0] << "." << +arg.dest_ipaddr[1] << "." + << +arg.dest_ipaddr[2] << "." << +arg.dest_ipaddr[3]; os << ", "; os << "dest_LiDAR_udp_port: " << arg.dest_LiDAR_udp_port; os << ", "; @@ -351,7 +341,7 @@ struct HesaiLidarStatus big_uint32_buf_t startup_times; big_uint32_buf_t total_operation_time; uint8_t ptp_clock_status; - uint8_t reserved[5]; // FIXME: 4 bytes labeled as humidity in OT128 datasheet + uint8_t reserved[5]; // FIXME: 4 bytes labeled as humidity in OT128 datasheet friend std::ostream & operator<<(std::ostream & os, nebula::HesaiLidarStatus const & arg) { @@ -463,7 +453,7 @@ struct HesaiPtpConfig int8_t logAnnounceInterval; int8_t logSyncInterval; int8_t logMinDelayReqInterval; - //FIXME: this format is not correct for OT128, or for AT128 on 802.1AS + // FIXME: this format is not correct for OT128, or for AT128 on 802.1AS friend std::ostream & operator<<(std::ostream & os, nebula::HesaiPtpConfig const & arg) { @@ -489,7 +479,7 @@ struct HesaiPtpConfig /// @brief struct of PTC_COMMAND_LIDAR_MONITOR struct HesaiLidarMonitor { - //FIXME: this format is not correct for OT128 + // FIXME: this format is not correct for OT128 big_int32_buf_t input_voltage; big_int32_buf_t input_current; big_int32_buf_t input_power; diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp index 8dc270b8e..10a1ec93f 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp @@ -30,6 +30,7 @@ #include #include +#include #include namespace nebula @@ -169,8 +170,8 @@ class HesaiHwInterface std::string PrettyPrintPTCError(ptc_error_t error_code); /// @brief Checks if the data size matches that of the struct to be parsed, and parses the struct. - /// If data is too small, a std::runtime_error is thrown. If data is too large, a warning is printed - /// and the struct is parsed with the first sizeof(T) bytes. + /// If data is too small, a std::runtime_error is thrown. If data is too large, a warning is + /// printed and the struct is parsed with the first sizeof(T) bytes. template T CheckSizeAndParse(const std::vector & data); @@ -223,8 +224,7 @@ class HesaiHwInterface /// @brief Registering callback for PandarScan /// @param scan_callback Callback function /// @return Resulting status - Status RegisterScanCallback( - std::function &)> scan_callback); + Status RegisterScanCallback(std::function &)> scan_callback); /// @brief Getting data with PTC_COMMAND_GET_LIDAR_CALIBRATION /// @return Resulting status std::string GetLidarCalibrationString(); diff --git a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp index a28ffd7d2..29b260098 100644 --- a/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp +++ b/nebula_hw_interfaces/src/nebula_hesai_hw_interfaces/hesai_hw_interface.cpp @@ -43,14 +43,16 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( send_buf.emplace_back(len & 0xff); send_buf.insert(send_buf.end(), payload.begin(), payload.end()); - // These are shared_ptrs so that in case of request timeout, the callback (if ever called) can access valid memory + // These are shared_ptrs so that in case of request timeout, the callback (if ever called) can + // access valid memory auto recv_buf = std::make_shared>(); auto response_complete = std::make_shared(false); auto error_code = std::make_shared(); std::stringstream ss; - ss << "0x" << std::setfill('0') << std::setw(2) << std::hex << static_cast(command_id) << " (" << len << ") "; + ss << "0x" << std::setfill('0') << std::setw(2) << std::hex << static_cast(command_id) + << " (" << len << ") "; std::string log_tag = ss.str(); PrintDebug(log_tag + "Entering lock"); @@ -66,21 +68,26 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( PrintDebug(log_tag + "Sending payload"); tcp_driver_->asyncSendReceiveHeaderPayload( send_buf, - [this, log_tag, command_id, response_complete, error_code](const std::vector & header_bytes) { + [this, log_tag, command_id, response_complete, + error_code](const std::vector & header_bytes) { error_code->ptc_error_code = header_bytes[3]; - size_t payload_len = (header_bytes[4] << 24) | (header_bytes[5] << 16) | (header_bytes[6] << 8) | header_bytes[7]; - PrintDebug(log_tag + "Received header (expecting " + std::to_string(payload_len) + "B payload)"); - // If command_id in the response does not match, we got a response for another command (or rubbish), probably as a - // result of too many simultaneous TCP connections to the sensor (e.g. from GUI, Web UI, another nebula instance, etc.) + size_t payload_len = (header_bytes[4] << 24) | (header_bytes[5] << 16) | + (header_bytes[6] << 8) | header_bytes[7]; + PrintDebug( + log_tag + "Received header (expecting " + std::to_string(payload_len) + "B payload)"); + // If command_id in the response does not match, we got a response for another command (or + // rubbish), probably as a result of too many simultaneous TCP connections to the sensor (e.g. + // from GUI, Web UI, another nebula instance, etc.) if (header_bytes[2] != command_id) { error_code->error_flags |= TCP_ERROR_UNRELATED_RESPONSE; } - if (payload_len == 0) { - *response_complete = true; + if (payload_len == 0) { + *response_complete = true; } }, - [this, log_tag, recv_buf, response_complete, error_code](const std::vector & payload_bytes) { + [this, log_tag, recv_buf, response_complete, + error_code](const std::vector & payload_bytes) { PrintDebug(log_tag + "Received payload"); // Header had payload length 0 (thus, header callback processed request successfully already), @@ -96,7 +103,7 @@ HesaiHwInterface::ptc_cmd_result_t HesaiHwInterface::SendReceive( }, [this, log_tag, &tm]() { PrintDebug(log_tag + "Unlocking mutex"); - tm.unlock(); + tm.unlock(); PrintDebug(log_tag + "Unlocked mutex"); }); this->IOContextRun(); @@ -177,7 +184,8 @@ Status HesaiHwInterface::SensorInterfaceStop() return Status::ERROR_1; } -Status HesaiHwInterface::GetSensorConfiguration(const SensorConfigurationBase & sensor_configuration) +Status HesaiHwInterface::GetSensorConfiguration( + const SensorConfigurationBase & sensor_configuration) { std::stringstream ss; ss << sensor_configuration; @@ -251,7 +259,8 @@ std::vector HesaiHwInterface::GetLidarCalibrationBytes() std::string HesaiHwInterface::GetLidarCalibrationString() { auto response_or_err = SendReceive(PTC_COMMAND_GET_LIDAR_CALIBRATION); - auto calib_data = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); + auto calib_data = + response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); std::string calib_string(calib_data.begin(), calib_data.end()); return calib_string; } @@ -297,7 +306,8 @@ HesaiPtpDiagTime HesaiHwInterface::GetPtpDiagTime() HesaiPtpDiagGrandmaster HesaiHwInterface::GetPtpDiagGrandmaster() { - auto response_or_err = SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); + auto response_or_err = + SendReceive(PTC_COMMAND_PTP_DIAGNOSTICS, {PTC_COMMAND_PTP_GRANDMASTER_SETTINGS_NP}); auto response = response_or_err.value_or_throw(PrettyPrintPTCError(response_or_err.error_or({}))); auto diag_grandmaster = CheckSizeAndParse(response); @@ -476,15 +486,15 @@ HesaiLidarRangeAll HesaiHwInterface::GetLidarRange() if (response.size() != 5) { throw std::runtime_error("Unexpected response payload"); } - + memcpy(&hesai_range_all.start, &response[1], 2); memcpy(&hesai_range_all.end, &response[3], 2); break; case 1: // for each channel - //TODO + // TODO(yukkysaito) break; case 2: // multi-section FOV - //TODO + // TODO(yukkysaito) break; } @@ -756,7 +766,7 @@ HesaiStatus HesaiHwInterface::GetLidarMonitorAsyncHttp( HesaiStatus HesaiHwInterface::CheckAndSetConfig( std::shared_ptr sensor_configuration, HesaiConfig hesai_config) { - using namespace std::chrono_literals; + using namespace std::chrono_literals; // NOLINT(build/namespaces) #ifdef WITH_DEBUG_STDOUT_HESAI_HW_INTERFACE std::cout << "Start CheckAndSetConfig(HesaiConfig)!!" << std::endl; #endif @@ -788,7 +798,9 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( auto current_rotation_speed = hesai_config.spin_rate; if (sensor_configuration->rotation_speed != current_rotation_speed.value()) { - PrintInfo("current lidar rotation_speed: " + std::to_string(static_cast(current_rotation_speed.value()))); + PrintInfo( + "current lidar rotation_speed: " + + std::to_string(static_cast(current_rotation_speed.value()))); PrintInfo( "current configuration rotation_speed: " + std::to_string(sensor_configuration->rotation_speed)); @@ -806,8 +818,10 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( bool set_flg = false; std::stringstream ss; - ss << static_cast(hesai_config.dest_ipaddr[0]) << "." << static_cast(hesai_config.dest_ipaddr[1]) << "." - << static_cast(hesai_config.dest_ipaddr[2]) << "." << static_cast(hesai_config.dest_ipaddr[3]); + ss << static_cast(hesai_config.dest_ipaddr[0]) << "." + << static_cast(hesai_config.dest_ipaddr[1]) << "." + << static_cast(hesai_config.dest_ipaddr[2]) << "." + << static_cast(hesai_config.dest_ipaddr[3]); auto current_host_addr = ss.str(); if (sensor_configuration->host_ip != current_host_addr) { set_flg = true; @@ -818,7 +832,9 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( auto current_host_dport = hesai_config.dest_LiDAR_udp_port; if (sensor_configuration->data_port != current_host_dport.value()) { set_flg = true; - PrintInfo("current lidar dest_LiDAR_udp_port: " + std::to_string(static_cast(current_host_dport.value()))); + PrintInfo( + "current lidar dest_LiDAR_udp_port: " + + std::to_string(static_cast(current_host_dport.value()))); PrintInfo( "current configuration data_port: " + std::to_string(sensor_configuration->data_port)); } @@ -826,7 +842,9 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( auto current_host_tport = hesai_config.dest_gps_udp_port; if (sensor_configuration->gnss_port != current_host_tport.value()) { set_flg = true; - PrintInfo("current lidar dest_gps_udp_port: " + std::to_string(static_cast(current_host_tport.value()))); + PrintInfo( + "current lidar dest_gps_udp_port: " + + std::to_string(static_cast(current_host_tport.value()))); PrintInfo( "current configuration gnss_port: " + std::to_string(sensor_configuration->gnss_port)); } @@ -930,18 +948,26 @@ HesaiStatus HesaiHwInterface::CheckAndSetConfig( set_flg = true; } else { auto current_cloud_min_angle = hesai_lidar_range_all.start; - if (static_cast(sensor_configuration->cloud_min_angle * 10) != current_cloud_min_angle.value()) { + if ( + static_cast(sensor_configuration->cloud_min_angle * 10) != + current_cloud_min_angle.value()) { set_flg = true; - PrintInfo("current lidar range.start: " + std::to_string(static_cast(current_cloud_min_angle.value()))); + PrintInfo( + "current lidar range.start: " + + std::to_string(static_cast(current_cloud_min_angle.value()))); PrintInfo( "current configuration cloud_min_angle: " + std::to_string(sensor_configuration->cloud_min_angle)); } auto current_cloud_max_angle = hesai_lidar_range_all.end; - if (static_cast(sensor_configuration->cloud_max_angle * 10) != current_cloud_max_angle.value()) { + if ( + static_cast(sensor_configuration->cloud_max_angle * 10) != + current_cloud_max_angle.value()) { set_flg = true; - PrintInfo("current lidar range.end: " + std::to_string(static_cast(current_cloud_max_angle.value()))); + PrintInfo( + "current lidar range.end: " + + std::to_string(static_cast(current_cloud_max_angle.value()))); PrintInfo( "current configuration cloud_max_angle: " + std::to_string(sensor_configuration->cloud_max_angle)); @@ -1181,7 +1207,8 @@ void HesaiHwInterface::PrintDebug(const std::vector & bytes) PrintDebug(ss.str()); } -std::string HesaiHwInterface::PrettyPrintPTCError(ptc_error_t error_code) { +std::string HesaiHwInterface::PrettyPrintPTCError(ptc_error_t error_code) +{ if (error_code.ok()) { return "No error"; } @@ -1191,10 +1218,11 @@ std::string HesaiHwInterface::PrettyPrintPTCError(ptc_error_t error_code) { std::stringstream ss; if (ptc_error) { - ss << "Sensor error: 0x" << std::setfill('0') << std::setw(2) << std::hex << static_cast(ptc_error) << ' '; + ss << "Sensor error: 0x" << std::setfill('0') << std::setw(2) << std::hex + << static_cast(ptc_error) << ' '; } - switch(ptc_error) { + switch (ptc_error) { case PTC_ERROR_CODE_NO_ERROR: break; case PTC_ERROR_CODE_INVALID_INPUT_PARAM: @@ -1253,7 +1281,8 @@ std::string HesaiHwInterface::PrettyPrintPTCError(ptc_error_t error_code) { } template -T HesaiHwInterface::CheckSizeAndParse(const std::vector & data) { +T HesaiHwInterface::CheckSizeAndParse(const std::vector & data) +{ if (data.size() < sizeof(T)) { throw std::runtime_error("Attempted to parse too-small payload"); } else if (data.size() > sizeof(T)) { diff --git a/nebula_messages/nebula_msgs/CMakeLists.txt b/nebula_messages/nebula_msgs/CMakeLists.txt index e2b798d9d..2ffa068a5 100644 --- a/nebula_messages/nebula_msgs/CMakeLists.txt +++ b/nebula_messages/nebula_msgs/CMakeLists.txt @@ -21,4 +21,4 @@ rosidl_generate_interfaces(${PROJECT_NAME} std_msgs ) -ament_package() \ No newline at end of file +ament_package() diff --git a/nebula_messages/nebula_msgs/msg/NebulaPacket.msg b/nebula_messages/nebula_msgs/msg/NebulaPacket.msg index be5898eb1..f6ba285d8 100644 --- a/nebula_messages/nebula_msgs/msg/NebulaPacket.msg +++ b/nebula_messages/nebula_msgs/msg/NebulaPacket.msg @@ -1,2 +1,2 @@ builtin_interfaces/Time stamp -uint8[] data \ No newline at end of file +uint8[] data diff --git a/nebula_messages/nebula_msgs/package.xml b/nebula_messages/nebula_msgs/package.xml index 3eb05e603..cdd135c37 100644 --- a/nebula_messages/nebula_msgs/package.xml +++ b/nebula_messages/nebula_msgs/package.xml @@ -22,4 +22,4 @@ ament_cmake - \ No newline at end of file + diff --git a/nebula_ros/include/nebula_ros/common/mt_queue.hpp b/nebula_ros/include/nebula_ros/common/mt_queue.hpp index d60b7b4db..aca385ce3 100644 --- a/nebula_ros/include/nebula_ros/common/mt_queue.hpp +++ b/nebula_ros/include/nebula_ros/common/mt_queue.hpp @@ -1,9 +1,10 @@ #pragma once +#include #include #include #include -#include +#include template class mt_queue @@ -15,7 +16,7 @@ class mt_queue size_t capacity_; public: - mt_queue(size_t capacity) : capacity_(capacity) {} + explicit mt_queue(size_t capacity) : capacity_(capacity) {} bool try_push(T && value) { @@ -46,4 +47,4 @@ class mt_queue return return_value; } -}; \ No newline at end of file +}; diff --git a/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp index b54d8ad63..6d4e38504 100644 --- a/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp +++ b/nebula_ros/include/nebula_ros/common/parameter_descriptors.hpp @@ -1,9 +1,11 @@ #pragma once -#include #include +#include #include +#include +#include namespace nebula { namespace ros @@ -13,10 +15,11 @@ rcl_interfaces::msg::ParameterDescriptor param_read_write(); rcl_interfaces::msg::ParameterDescriptor param_read_only(); -rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range(double start, double stop, - double step); +rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range( + double start, double stop, double step); -rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int start, int stop, int step); +rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range( + int start, int stop, int step); /// @brief Get a parameter's value from a list of parameters, if that parameter is in the list. /// @tparam T The parameter's expected value type @@ -25,12 +28,12 @@ rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int star /// @param value (out) Parameter value. Set if parameter is found, left untouched otherwise. /// @return Whether the target name existed template -bool get_param(const std::vector& p, const std::string& name, T& value) +bool get_param(const std::vector & p, const std::string & name, T & value) { - auto it = std::find_if(p.cbegin(), p.cend(), - [&name](const rclcpp::Parameter & parameter) { return parameter.get_name() == name; }); - if (it != p.cend()) - { + auto it = std::find_if(p.cbegin(), p.cend(), [&name](const rclcpp::Parameter & parameter) { + return parameter.get_name() == name; + }); + if (it != p.cend()) { value = it->template get_value(); return true; } @@ -38,4 +41,4 @@ bool get_param(const std::vector& p, const std::string& name, } } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp b/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp index ae556e33e..e6320f91e 100644 --- a/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp +++ b/nebula_ros/include/nebula_ros/common/watchdog_timer.hpp @@ -1,9 +1,10 @@ #pragma once #include -#include + #include #include +#include #include namespace nebula @@ -16,19 +17,19 @@ class WatchdogTimer using watchdog_cb_t = std::function; public: - WatchdogTimer(rclcpp::Node& node, const std::chrono::microseconds& expected_update_interval, const watchdog_cb_t& callback) - : node_(node) - , callback_(callback) - , expected_update_interval_ns_( - std::chrono::duration_cast(expected_update_interval).count()) + WatchdogTimer( + rclcpp::Node & node, const std::chrono::microseconds & expected_update_interval, + const watchdog_cb_t & callback) + : node_(node), + callback_(callback), + expected_update_interval_ns_( + std::chrono::duration_cast(expected_update_interval).count()) { - timer_ = node_.create_wall_timer(expected_update_interval, std::bind(&WatchdogTimer::onTimer, this)); + timer_ = + node_.create_wall_timer(expected_update_interval, std::bind(&WatchdogTimer::onTimer, this)); } - void update() - { - last_update_ns_ = node_.get_clock()->now().nanoseconds(); - } + void update() { last_update_ns_ = node_.get_clock()->now().nanoseconds(); } private: void onTimer() @@ -40,7 +41,7 @@ class WatchdogTimer callback_(!is_late); } - rclcpp::Node& node_; + rclcpp::Node & node_; rclcpp::TimerBase::SharedPtr timer_; std::atomic last_update_ns_; const watchdog_cb_t callback_; @@ -49,4 +50,4 @@ class WatchdogTimer }; } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp index da5e60ff0..b2bdf856c 100644 --- a/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/decoder_wrapper.hpp @@ -16,6 +16,8 @@ #include #include #include +#include +#include namespace nebula { @@ -23,22 +25,26 @@ namespace ros { class HesaiDecoderWrapper { - using get_calibration_result_t = - nebula::util::expected, nebula::Status>; + using get_calibration_result_t = nebula::util::expected< + std::shared_ptr, nebula::Status>; public: - HesaiDecoderWrapper(rclcpp::Node* const parent_node, - const std::shared_ptr& hw_interface, - std::shared_ptr& config); + HesaiDecoderWrapper( + rclcpp::Node * const parent_node, + const std::shared_ptr & hw_interface, + std::shared_ptr & config); void ProcessCloudPacket(std::unique_ptr packet_msg); - void OnConfigChange(const std::shared_ptr& new_config); + void OnConfigChange( + const std::shared_ptr & new_config); - void - OnCalibrationChange(const std::shared_ptr& new_calibration); + void OnCalibrationChange( + const std::shared_ptr & + new_calibration); - rcl_interfaces::msg::SetParametersResult OnParameterChange(const std::vector& p); + rcl_interfaces::msg::SetParametersResult OnParameterChange( + const std::vector & p); nebula::Status Status(); @@ -48,19 +54,23 @@ class HesaiDecoderWrapper /// 2. If downloaded file available, load that file /// 3. Load the file given by `calibration_file_path` /// @param calibration_file_path The file to use if no better option is available - /// @param ignore_others If true, skip straight so step 3 above, ignoring better calibration options + /// @param ignore_others If true, skip straight so step 3 above, ignoring better calibration + /// options /// @return The calibration data if successful, or an error code if not - get_calibration_result_t GetCalibrationData(const std::string& calibration_file_path, bool ignore_others = false); + get_calibration_result_t GetCalibrationData( + const std::string & calibration_file_path, bool ignore_others = false); - void PublishCloud(std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr& publisher); + void PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher); /// @brief Convert seconds to chrono::nanoseconds /// @param seconds /// @return chrono::nanoseconds static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) { - return std::chrono::duration_cast(std::chrono::duration(seconds)); + return std::chrono::duration_cast( + std::chrono::duration(seconds)); } nebula::Status status_; @@ -85,4 +95,4 @@ class HesaiDecoderWrapper std::shared_ptr cloud_watchdog_; }; } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp index ed76343c7..0a60d3e8e 100644 --- a/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hesai_ros_wrapper.hpp @@ -1,16 +1,15 @@ #pragma once #include "boost_tcp_driver/tcp_driver.hpp" - #include "nebula_common/hesai/hesai_common.hpp" #include "nebula_common/nebula_common.hpp" #include "nebula_common/nebula_status.hpp" #include "nebula_hw_interfaces/nebula_hw_interfaces_hesai/hesai_hw_interface.hpp" +#include "nebula_ros/common/mt_queue.hpp" +#include "nebula_ros/common/parameter_descriptors.hpp" #include "nebula_ros/hesai/decoder_wrapper.hpp" #include "nebula_ros/hesai/hw_interface_wrapper.hpp" #include "nebula_ros/hesai/hw_monitor_wrapper.hpp" -#include "nebula_ros/common/mt_queue.hpp" -#include "nebula_ros/common/parameter_descriptors.hpp" #include #include @@ -24,9 +23,11 @@ #include #include +#include #include #include #include +#include namespace nebula { @@ -37,7 +38,7 @@ namespace ros class HesaiRosWrapper final : public rclcpp::Node { public: - explicit HesaiRosWrapper(const rclcpp::NodeOptions& options); + explicit HesaiRosWrapper(const rclcpp::NodeOptions & options); ~HesaiRosWrapper() noexcept {}; /// @brief Get current status of this driver @@ -49,7 +50,7 @@ class HesaiRosWrapper final : public rclcpp::Node Status StreamStart(); private: - void ReceiveCloudPacketCallback(std::vector& packet); + void ReceiveCloudPacketCallback(std::vector & packet); void ReceiveScanMessageCallback(std::unique_ptr scan_msg); @@ -58,9 +59,11 @@ class HesaiRosWrapper final : public rclcpp::Node /// @brief rclcpp parameter callback /// @param parameters Received parameters /// @return SetParametersResult - rcl_interfaces::msg::SetParametersResult OnParameterChange(const std::vector& p); + rcl_interfaces::msg::SetParametersResult OnParameterChange( + const std::vector & p); - Status ValidateAndSetConfig(std::shared_ptr& new_config); + Status ValidateAndSetConfig( + std::shared_ptr & new_config); Status wrapper_status_; diff --git a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp index cbf78d130..0791af5e2 100644 --- a/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hw_interface_wrapper.hpp @@ -3,7 +3,6 @@ #include "nebula_ros/common/parameter_descriptors.hpp" #include - #include #include @@ -16,10 +15,12 @@ namespace ros class HesaiHwInterfaceWrapper { public: - HesaiHwInterfaceWrapper(rclcpp::Node* const parent_node, - std::shared_ptr& config); + HesaiHwInterfaceWrapper( + rclcpp::Node * const parent_node, + std::shared_ptr & config); - void OnConfigChange(const std::shared_ptr & new_config); + void OnConfigChange( + const std::shared_ptr & new_config); nebula::Status Status(); @@ -32,4 +33,4 @@ class HesaiHwInterfaceWrapper bool setup_sensor_; }; } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp index 5209f64a2..0b270623f 100644 --- a/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/hesai/hw_monitor_wrapper.hpp @@ -4,7 +4,6 @@ #include #include - #include #include #include @@ -15,6 +14,8 @@ #include #include +#include +#include namespace nebula { @@ -23,18 +24,22 @@ namespace ros class HesaiHwMonitorWrapper { public: - HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, - const std::shared_ptr& hw_interface, - std::shared_ptr& config); + HesaiHwMonitorWrapper( + rclcpp::Node * const parent_node, + const std::shared_ptr & hw_interface, + std::shared_ptr & config); - void OnConfigChange(const std::shared_ptr & /* new_config */) {} + void OnConfigChange( + const std::shared_ptr & /* new_config */) + { + } nebula::Status Status(); private: void InitializeHesaiDiagnostics(); - std::string GetPtreeValue(boost::property_tree::ptree* pt, const std::string& key); + std::string GetPtreeValue(boost::property_tree::ptree * pt, const std::string & key); std::string GetFixedPrecisionString(double val, int pre); @@ -44,24 +49,24 @@ class HesaiHwMonitorWrapper void OnHesaiLidarMonitorTimer(); - void HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + void HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + void HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + void HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + void HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + void HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); - void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper& diagnostics); + void HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper & diagnostics); rclcpp::Logger logger_; diagnostic_updater::Updater diagnostics_updater_; nebula::Status status_; const std::shared_ptr hw_interface_; - rclcpp::Node* const parent_node_; + rclcpp::Node * const parent_node_; uint16_t diag_span_; rclcpp::TimerBase::SharedPtr diagnostics_update_timer_{}; @@ -95,4 +100,4 @@ class HesaiHwMonitorWrapper const std::string MSG_SEP = ": "; }; } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_ros/launch/hesai_launch_all_hw.xml b/nebula_ros/launch/hesai_launch_all_hw.xml index b0f804441..10c7aa218 100644 --- a/nebula_ros/launch/hesai_launch_all_hw.xml +++ b/nebula_ros/launch/hesai_launch_all_hw.xml @@ -35,7 +35,7 @@ - @@ -47,7 +47,7 @@ - + @@ -62,7 +62,7 @@ - + diff --git a/nebula_ros/launch/nebula_launch.py b/nebula_ros/launch/nebula_launch.py index 74d3eb475..6eee53443 100644 --- a/nebula_ros/launch/nebula_launch.py +++ b/nebula_ros/launch/nebula_launch.py @@ -26,6 +26,7 @@ def get_sensor_make(sensor_name): return "Continental", None return "unrecognized_sensor_model", None + def get_plugin_name(sensor_make, sensor_model): if sensor_make.lower() != "continental": return sensor_make @@ -34,9 +35,11 @@ def get_plugin_name(sensor_make, sensor_model): else: return "invalid_plugin" + def is_hw_monitor_available(sensor_make): return sensor_make.lower() != "continental" + def launch_setup(context, *args, **kwargs): # Model and make sensor_model = LaunchConfiguration("sensor_model").perform(context) @@ -44,7 +47,9 @@ def launch_setup(context, *args, **kwargs): sensor_make, sensor_extension = get_sensor_make(sensor_model) if sensor_make.lower() == "hesai": - raise ValueError("\n `nebula_launch.py` is deprecated. For Hesai sensors, use `hesai_launch_all_hw.xml` instead.") + raise ValueError( + "\n `nebula_launch.py` is deprecated. For Hesai sensors, use `hesai_launch_all_hw.xml` instead." + ) nebula_decoders_share_dir = get_package_share_directory("nebula_decoders") nebula_ros_share_dir = get_package_share_directory("nebula_ros") @@ -53,23 +58,36 @@ def launch_setup(context, *args, **kwargs): sensor_params_fp = LaunchConfiguration("config_file").perform(context) if sensor_params_fp == "": warnings.warn("No config file provided, using sensor model default", RuntimeWarning) - sensor_params_fp = os.path.join(nebula_ros_share_dir, "config", sensor_make.lower(), sensor_model + ".yaml") + sensor_params_fp = os.path.join( + nebula_ros_share_dir, "config", sensor_make.lower(), sensor_model + ".yaml" + ) if not os.path.exists(sensor_params_fp): sensor_params_fp = os.path.join(nebula_ros_share_dir, "config", "BaseParams.yaml") - assert os.path.exists(sensor_params_fp), "Sensor params yaml file under config/ was not found: {}".format(sensor_params_fp) + assert os.path.exists( + sensor_params_fp + ), "Sensor params yaml file under config/ was not found: {}".format(sensor_params_fp) sensor_calib_fp = sensor_corr_fp = "" if sensor_extension is not None: # Velodyne and Hesai - sensor_calib_fp = os.path.join(nebula_decoders_share_dir, "calibration", sensor_make.lower(), sensor_model + sensor_extension) - assert os.path.exists(sensor_calib_fp), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp) + sensor_calib_fp = os.path.join( + nebula_decoders_share_dir, + "calibration", + sensor_make.lower(), + sensor_model + sensor_extension, + ) + assert os.path.exists( + sensor_calib_fp + ), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp) if sensor_model.lower() == "pandarat128": sensor_corr_fp = os.path.splitext(sensor_calib_fp)[0] + ".dat" - assert os.path.exists(sensor_corr_fp), "Sensor corr file under calibration/ was not found: {}".format(sensor_corr_fp) + assert os.path.exists( + sensor_corr_fp + ), "Sensor corr file under calibration/ was not found: {}".format(sensor_corr_fp) with open(sensor_params_fp, "r") as f: - sensor_params = yaml.safe_load(f)["/**"]["ros__parameters"] + sensor_params = yaml.safe_load(f)["/**"]["ros__parameters"] nodes = [] launch_hw = LaunchConfiguration("launch_hw").perform(context) == "true" @@ -78,8 +96,8 @@ def launch_setup(context, *args, **kwargs): # HwInterface ComposableNode( package="nebula_ros", - plugin=get_plugin_name(sensor_make, sensor_model)+"HwInterfaceRosWrapper", - name=sensor_make.lower()+"_hw_interface_ros_wrapper_node", + plugin=get_plugin_name(sensor_make, sensor_model) + "HwInterfaceRosWrapper", + name=sensor_make.lower() + "_hw_interface_ros_wrapper_node", parameters=[ sensor_params, { @@ -97,14 +115,13 @@ def launch_setup(context, *args, **kwargs): ), ) - if launch_hw and is_hw_monitor_available(sensor_make): nodes.append( # HwMonitor ComposableNode( package="nebula_ros", - plugin=sensor_make+"HwMonitorRosWrapper", - name=sensor_make.lower()+"_hw_monitor_ros_wrapper_node", + plugin=sensor_make + "HwMonitorRosWrapper", + name=sensor_make.lower() + "_hw_monitor_ros_wrapper_node", parameters=[ sensor_params, { @@ -119,8 +136,8 @@ def launch_setup(context, *args, **kwargs): nodes.append( ComposableNode( package="nebula_ros", - plugin=get_plugin_name(sensor_make, sensor_model)+"DriverRosWrapper", - name=sensor_make.lower()+"_driver_ros_wrapper_node", + plugin=get_plugin_name(sensor_make, sensor_model) + "DriverRosWrapper", + name=sensor_make.lower() + "_driver_ros_wrapper_node", parameters=[ sensor_params, { @@ -146,7 +163,7 @@ def launch_setup(context, *args, **kwargs): container_kwargs = {} if LaunchConfiguration("debug_logging").perform(context) == "true": - container_kwargs["ros_arguments"] = ['--log-level', 'debug'] + container_kwargs["ros_arguments"] = ["--log-level", "debug"] container = ComposableNodeContainer( name="nebula_ros_node", diff --git a/nebula_ros/package.xml b/nebula_ros/package.xml index e918afdc7..a0bdec51f 100644 --- a/nebula_ros/package.xml +++ b/nebula_ros/package.xml @@ -21,6 +21,8 @@ nebula_common nebula_decoders nebula_hw_interfaces + nebula_msgs + pandar_msgs pcl_conversions rclcpp rclcpp_components @@ -31,8 +33,6 @@ velodyne_msgs visualization_msgs yaml-cpp - nebula_msgs - pandar_msgs ament_cmake_gtest ament_lint_auto diff --git a/nebula_ros/src/common/parameter_descriptors.cpp b/nebula_ros/src/common/parameter_descriptors.cpp index ffd0fff37..b62cb8a9e 100644 --- a/nebula_ros/src/common/parameter_descriptors.cpp +++ b/nebula_ros/src/common/parameter_descriptors.cpp @@ -15,15 +15,20 @@ rcl_interfaces::msg::ParameterDescriptor param_read_only() return rcl_interfaces::msg::ParameterDescriptor{}.set__read_only(true); } -rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range(double start, double stop, double step) +rcl_interfaces::msg::ParameterDescriptor::_floating_point_range_type float_range( + double start, double stop, double step) { - return { rcl_interfaces::msg::FloatingPointRange().set__from_value(start).set__to_value(stop).set__step(step) }; + return { + rcl_interfaces::msg::FloatingPointRange().set__from_value(start).set__to_value(stop).set__step( + step)}; } -rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range(int start, int stop, int step) +rcl_interfaces::msg::ParameterDescriptor::_integer_range_type int_range( + int start, int stop, int step) { - return { rcl_interfaces::msg::IntegerRange().set__from_value(start).set__to_value(stop).set__step(step) }; + return { + rcl_interfaces::msg::IntegerRange().set__from_value(start).set__to_value(stop).set__step(step)}; } } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_ros/src/hesai/decoder_wrapper.cpp b/nebula_ros/src/hesai/decoder_wrapper.cpp index 3046dc9c0..f51378e47 100644 --- a/nebula_ros/src/hesai/decoder_wrapper.cpp +++ b/nebula_ros/src/hesai/decoder_wrapper.cpp @@ -5,77 +5,80 @@ namespace nebula namespace ros { -using namespace std::chrono_literals; - -HesaiDecoderWrapper::HesaiDecoderWrapper(rclcpp::Node* const parent_node, - const std::shared_ptr& hw_interface, - std::shared_ptr& config) - : status_(nebula::Status::NOT_INITIALIZED) - , logger_(parent_node->get_logger().get_child("HesaiDecoder")) - , hw_interface_(hw_interface) - , sensor_cfg_(config) +using namespace std::chrono_literals; // NOLINT(build/namespaces) + +HesaiDecoderWrapper::HesaiDecoderWrapper( + rclcpp::Node * const parent_node, + const std::shared_ptr & hw_interface, + std::shared_ptr & config) +: status_(nebula::Status::NOT_INITIALIZED), + logger_(parent_node->get_logger().get_child("HesaiDecoder")), + hw_interface_(hw_interface), + sensor_cfg_(config) { - if (!config) - { + if (!config) { throw std::runtime_error("HesaiDecoderWrapper cannot be instantiated without a valid config!"); } - if (config->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) - { - calibration_file_path_ = parent_node->declare_parameter("correction_file", "", param_read_write()); - } - else - { - calibration_file_path_ = parent_node->declare_parameter("calibration_file", "", param_read_write()); + if (config->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { + calibration_file_path_ = + parent_node->declare_parameter("correction_file", "", param_read_write()); + } else { + calibration_file_path_ = + parent_node->declare_parameter("calibration_file", "", param_read_write()); } auto calibration_result = GetCalibrationData(calibration_file_path_, false); - if (!calibration_result.has_value()) - { + if (!calibration_result.has_value()) { throw std::runtime_error( - (std::stringstream() << "No valid calibration found: " << calibration_result.error()).str()); + (std::stringstream() << "No valid calibration found: " << calibration_result.error()).str()); } calibration_cfg_ptr_ = calibration_result.value(); - RCLCPP_INFO_STREAM(logger_, "Using calibration data from " << calibration_cfg_ptr_->calibration_file); + RCLCPP_INFO_STREAM( + logger_, "Using calibration data from " << calibration_cfg_ptr_->calibration_file); RCLCPP_INFO(logger_, "Starting Decoder"); driver_ptr_ = std::make_shared(config, calibration_cfg_ptr_); status_ = driver_ptr_->GetStatus(); - if (Status::OK != status_) - { - throw std::runtime_error((std::stringstream() << "Error instantiating decoder: " << status_).str()); + if (Status::OK != status_) { + throw std::runtime_error( + (std::stringstream() << "Error instantiating decoder: " << status_).str()); } // Publish packets only if HW interface is connected - if (hw_interface_) - { + if (hw_interface_) { current_scan_msg_ = std::make_unique(); - packets_pub_ = - parent_node->create_publisher("pandar_packets", rclcpp::SensorDataQoS()); + packets_pub_ = parent_node->create_publisher( + "pandar_packets", rclcpp::SensorDataQoS()); } auto qos_profile = rmw_qos_profile_sensor_data; - auto pointcloud_qos = rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); + auto pointcloud_qos = + rclcpp::QoS(rclcpp::QoSInitialization(qos_profile.history, 10), qos_profile); - nebula_points_pub_ = parent_node->create_publisher("pandar_points", pointcloud_qos); - aw_points_base_pub_ = parent_node->create_publisher("aw_points", pointcloud_qos); - aw_points_ex_pub_ = parent_node->create_publisher("aw_points_ex", pointcloud_qos); + nebula_points_pub_ = + parent_node->create_publisher("pandar_points", pointcloud_qos); + aw_points_base_pub_ = + parent_node->create_publisher("aw_points", pointcloud_qos); + aw_points_ex_pub_ = + parent_node->create_publisher("aw_points_ex", pointcloud_qos); RCLCPP_INFO_STREAM(logger_, ". Wrapper=" << status_); - cloud_watchdog_ = std::make_shared(*parent_node, 100'000us, [this, parent_node](bool ok) { - if (ok) - return; - RCLCPP_WARN_THROTTLE(logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline"); - }); + cloud_watchdog_ = + std::make_shared(*parent_node, 100'000us, [this, parent_node](bool ok) { + if (ok) return; + RCLCPP_WARN_THROTTLE( + logger_, *parent_node->get_clock(), 5000, "Missed pointcloud output deadline"); + }); } void HesaiDecoderWrapper::OnConfigChange( - const std::shared_ptr& new_config) + const std::shared_ptr & new_config) { std::lock_guard lock(mtx_driver_ptr_); auto new_driver = std::make_shared(new_config, calibration_cfg_ptr_); @@ -84,7 +87,7 @@ void HesaiDecoderWrapper::OnConfigChange( } void HesaiDecoderWrapper::OnCalibrationChange( - const std::shared_ptr& new_calibration) + const std::shared_ptr & new_calibration) { std::lock_guard lock(mtx_driver_ptr_); auto new_driver = std::make_shared(sensor_cfg_, new_calibration); @@ -93,54 +96,54 @@ void HesaiDecoderWrapper::OnCalibrationChange( calibration_file_path_ = calibration_cfg_ptr_->calibration_file; } -rcl_interfaces::msg::SetParametersResult HesaiDecoderWrapper::OnParameterChange(const std::vector& p) +rcl_interfaces::msg::SetParametersResult HesaiDecoderWrapper::OnParameterChange( + const std::vector & p) { - using namespace rcl_interfaces::msg; + using rcl_interfaces::msg::SetParametersResult; std::string calibration_path = ""; - // Only one of the two parameters is defined, so not checking for sensor model explicitly here is fine - bool got_any = get_param(p, "calibration_file", calibration_path) | get_param(p, "correction_file", calibration_path); - if (!got_any) - { + // Only one of the two parameters is defined, so not checking for sensor model explicitly here is + // fine + bool got_any = get_param(p, "calibration_file", calibration_path) | + get_param(p, "correction_file", calibration_path); + if (!got_any) { return rcl_interfaces::build().successful(true).reason(""); } - if (!std::filesystem::exists(calibration_path)) - { + if (!std::filesystem::exists(calibration_path)) { auto result = SetParametersResult(); result.successful = false; - result.reason = "The given calibration path does not exist, ignoring: '" + calibration_path + "'"; + result.reason = + "The given calibration path does not exist, ignoring: '" + calibration_path + "'"; return result; } auto get_calibration_result = GetCalibrationData(calibration_path, true); - if (!get_calibration_result.has_value()) - { + if (!get_calibration_result.has_value()) { auto result = SetParametersResult(); result.successful = false; - result.reason = (std::stringstream() << "Could not change calibration file to '" << calibration_path - << "': " << get_calibration_result.error()) - .str(); + result.reason = + (std::stringstream() << "Could not change calibration file to '" << calibration_path + << "': " << get_calibration_result.error()) + .str(); return result; } OnCalibrationChange(get_calibration_result.value()); - RCLCPP_INFO_STREAM(logger_, "Changed calibration to '" << calibration_cfg_ptr_->calibration_file << "'"); + RCLCPP_INFO_STREAM( + logger_, "Changed calibration to '" << calibration_cfg_ptr_->calibration_file << "'"); return rcl_interfaces::build().successful(true).reason(""); } -HesaiDecoderWrapper::get_calibration_result_t -HesaiDecoderWrapper::GetCalibrationData(const std::string& calibration_file_path, bool ignore_others) +HesaiDecoderWrapper::get_calibration_result_t HesaiDecoderWrapper::GetCalibrationData( + const std::string & calibration_file_path, bool ignore_others) { std::shared_ptr calib; - if (sensor_cfg_->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) - { + if (sensor_cfg_->sensor_model == drivers::SensorModel::HESAI_PANDARAT128) { calib = std::make_shared(); - } - else - { + } else { calib = std::make_shared(); } @@ -150,69 +153,60 @@ HesaiDecoderWrapper::GetCalibrationData(const std::string& calibration_file_path { int ext_pos = calibration_file_path.find_last_of('.'); calibration_file_path_from_sensor = calibration_file_path.substr(0, ext_pos); - // TODO: if multiple different sensors of the same type are used, this will mix up their calibration data + // TODO(mojomex): if multiple different sensors of the same type are used, this will mix up + // their calibration data calibration_file_path_from_sensor += "_from_sensor"; - calibration_file_path_from_sensor += calibration_file_path.substr(ext_pos, calibration_file_path.size() - ext_pos); + calibration_file_path_from_sensor += + calibration_file_path.substr(ext_pos, calibration_file_path.size() - ext_pos); } // If a sensor is connected, try to download and save its calibration data - if (!ignore_others && hw_connected) - { - try - { + if (!ignore_others && hw_connected) { + try { auto raw_data = hw_interface_->GetLidarCalibrationBytes(); RCLCPP_INFO(logger_, "Downloaded calibration data from sensor."); auto status = calib->SaveToFileFromBytes(calibration_file_path_from_sensor, raw_data); - if (status != Status::OK) - { + if (status != Status::OK) { RCLCPP_ERROR_STREAM(logger_, "Could not save calibration data: " << status); + } else { + RCLCPP_INFO_STREAM( + logger_, "Saved downloaded data to " << calibration_file_path_from_sensor); } - else - { - RCLCPP_INFO_STREAM(logger_, "Saved downloaded data to " << calibration_file_path_from_sensor); - } - } - catch (std::runtime_error& e) - { + } catch (std::runtime_error & e) { RCLCPP_ERROR_STREAM(logger_, "Could not download calibration data: " << e.what()); } } - // If saved calibration data from a sensor exists (either just downloaded above, or previously), try to load it - if (!ignore_others && std::filesystem::exists(calibration_file_path_from_sensor)) - { + // If saved calibration data from a sensor exists (either just downloaded above, or previously), + // try to load it + if (!ignore_others && std::filesystem::exists(calibration_file_path_from_sensor)) { auto status = calib->LoadFromFile(calibration_file_path_from_sensor); - if (status == Status::OK) - { + if (status == Status::OK) { calib->calibration_file = calibration_file_path_from_sensor; return calib; } RCLCPP_ERROR_STREAM(logger_, "Could not load downloaded calibration data: " << status); - } - else if (!ignore_others) - { + } else if (!ignore_others) { RCLCPP_ERROR(logger_, "No downloaded calibration data found."); } - if (!ignore_others) - { + if (!ignore_others) { RCLCPP_WARN(logger_, "Falling back to generic calibration file."); } // If downloaded data did not exist or could not be loaded, fall back to a generic file. // If that file does not exist either, return an error code - if (!std::filesystem::exists(calibration_file_path)) - { + if (!std::filesystem::exists(calibration_file_path)) { RCLCPP_ERROR(logger_, "No calibration data found."); return nebula::Status(Status::INVALID_CALIBRATION_FILE); } // Try to load the existing fallback calibration file. Return an error if this fails auto status = calib->LoadFromFile(calibration_file_path); - if (status != Status::OK) - { - RCLCPP_ERROR_STREAM(logger_, "Could not load calibration file at '" << calibration_file_path << "'"); + if (status != Status::OK) { + RCLCPP_ERROR_STREAM( + logger_, "Could not load calibration file at '" << calibration_file_path << "'"); return status; } @@ -221,14 +215,14 @@ HesaiDecoderWrapper::GetCalibrationData(const std::string& calibration_file_path return calib; } -void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptr packet_msg) +void HesaiDecoderWrapper::ProcessCloudPacket( + std::unique_ptr packet_msg) { // Accumulate packets for recording only if someone is subscribed to the topic (for performance) - if (hw_interface_ && - (packets_pub_->get_subscription_count() > 0 || packets_pub_->get_intra_process_subscription_count() > 0)) - { - if (current_scan_msg_->packets.size() == 0) - { + if ( + hw_interface_ && (packets_pub_->get_subscription_count() > 0 || + packets_pub_->get_intra_process_subscription_count() > 0)) { + if (current_scan_msg_->packets.size() == 0) { current_scan_msg_->header.stamp = packet_msg->stamp; } @@ -247,57 +241,61 @@ void HesaiDecoderWrapper::ProcessCloudPacket(std::unique_ptr(pointcloud_ts); } - // A pointcloud is only emitted when a scan completes (e.g. 3599 packets do not emit, the 3600th emits one) - if (pointcloud == nullptr) - { + // A pointcloud is only emitted when a scan completes (e.g. 3599 packets do not emit, the 3600th + // emits one) + if (pointcloud == nullptr) { // Since this ends the function early, the `cloud_watchdog_` will not be updated. - // Thus, if pointclouds are not emitted for too long (e.g. when decoder settings are wrong or no packets come in), - // the watchdog will log a warning automatically + // Thus, if pointclouds are not emitted for too long (e.g. when decoder settings are wrong or no + // packets come in), the watchdog will log a warning automatically return; - }; + } cloud_watchdog_->update(); // Publish scan message only if it has been written to - if (current_scan_msg_ && !current_scan_msg_->packets.empty()) - { + if (current_scan_msg_ && !current_scan_msg_->packets.empty()) { packets_pub_->publish(std::move(current_scan_msg_)); current_scan_msg_ = std::make_unique(); } - if (nebula_points_pub_->get_subscription_count() > 0 || - nebula_points_pub_->get_intra_process_subscription_count() > 0) - { + if ( + nebula_points_pub_->get_subscription_count() > 0 || + nebula_points_pub_->get_intra_process_subscription_count() > 0) { auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*pointcloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); PublishCloud(std::move(ros_pc_msg_ptr), nebula_points_pub_); } - if (aw_points_base_pub_->get_subscription_count() > 0 || - aw_points_base_pub_->get_intra_process_subscription_count() > 0) - { - const auto autoware_cloud_xyzi = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); + if ( + aw_points_base_pub_->get_subscription_count() > 0 || + aw_points_base_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_cloud_xyzi = + nebula::drivers::convertPointXYZIRCAEDTToPointXYZIR(pointcloud); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_cloud_xyzi, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_base_pub_); } - if (aw_points_ex_pub_->get_subscription_count() > 0 || aw_points_ex_pub_->get_intra_process_subscription_count() > 0) - { - const auto autoware_ex_cloud = - nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT(pointcloud, std::get<1>(pointcloud_ts)); + if ( + aw_points_ex_pub_->get_subscription_count() > 0 || + aw_points_ex_pub_->get_intra_process_subscription_count() > 0) { + const auto autoware_ex_cloud = nebula::drivers::convertPointXYZIRCAEDTToPointXYZIRADT( + pointcloud, std::get<1>(pointcloud_ts)); auto ros_pc_msg_ptr = std::make_unique(); pcl::toROSMsg(*autoware_ex_cloud, *ros_pc_msg_ptr); - ros_pc_msg_ptr->header.stamp = rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); + ros_pc_msg_ptr->header.stamp = + rclcpp::Time(SecondsToChronoNanoSeconds(std::get<1>(pointcloud_ts)).count()); PublishCloud(std::move(ros_pc_msg_ptr), aw_points_ex_pub_); } } -void HesaiDecoderWrapper::PublishCloud(std::unique_ptr pointcloud, - const rclcpp::Publisher::SharedPtr& publisher) +void HesaiDecoderWrapper::PublishCloud( + std::unique_ptr pointcloud, + const rclcpp::Publisher::SharedPtr & publisher) { - if (pointcloud->header.stamp.sec < 0) - { + if (pointcloud->header.stamp.sec < 0) { RCLCPP_WARN_STREAM(logger_, "Timestamp error, verify clock source."); } pointcloud->header.frame_id = sensor_cfg_->frame_id; @@ -308,12 +306,11 @@ nebula::Status HesaiDecoderWrapper::Status() { std::lock_guard lock(mtx_driver_ptr_); - if (!driver_ptr_) - { + if (!driver_ptr_) { return nebula::Status::NOT_INITIALIZED; } return driver_ptr_->GetStatus(); } } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp index 6e08c0e3b..8449bdfe5 100644 --- a/nebula_ros/src/hesai/hesai_ros_wrapper.cpp +++ b/nebula_ros/src/hesai/hesai_ros_wrapper.cpp @@ -4,65 +4,61 @@ namespace nebula { namespace ros { -HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions& options) - : rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)) - , wrapper_status_(Status::NOT_INITIALIZED) - , sensor_cfg_ptr_(nullptr) - , packet_queue_(3000) - , hw_interface_wrapper_() - , hw_monitor_wrapper_() - , decoder_wrapper_() +HesaiRosWrapper::HesaiRosWrapper(const rclcpp::NodeOptions & options) +: rclcpp::Node("hesai_ros_wrapper", rclcpp::NodeOptions(options).use_intra_process_comms(true)), + wrapper_status_(Status::NOT_INITIALIZED), + sensor_cfg_ptr_(nullptr), + packet_queue_(3000), + hw_interface_wrapper_(), + hw_monitor_wrapper_(), + decoder_wrapper_() { setvbuf(stdout, NULL, _IONBF, BUFSIZ); wrapper_status_ = DeclareAndGetSensorConfigParams(); - if (wrapper_status_ != Status::OK) - { - throw std::runtime_error((std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str()); + if (wrapper_status_ != Status::OK) { + throw std::runtime_error( + (std::stringstream{} << "Sensor configuration invalid: " << wrapper_status_).str()); } RCLCPP_INFO_STREAM(get_logger(), "SensorConfig:" << *sensor_cfg_ptr_); launch_hw_ = declare_parameter("launch_hw", param_read_only()); - if (launch_hw_) - { + if (launch_hw_) { hw_interface_wrapper_.emplace(this, sensor_cfg_ptr_); hw_monitor_wrapper_.emplace(this, hw_interface_wrapper_->HwInterface(), sensor_cfg_ptr_); } - decoder_wrapper_.emplace(this, hw_interface_wrapper_ ? hw_interface_wrapper_->HwInterface() : nullptr, - sensor_cfg_ptr_); + decoder_wrapper_.emplace( + this, hw_interface_wrapper_ ? hw_interface_wrapper_->HwInterface() : nullptr, sensor_cfg_ptr_); RCLCPP_DEBUG(get_logger(), "Starting stream"); decoder_thread_ = std::thread([this]() { - while (true) - { + while (true) { decoder_wrapper_->ProcessCloudPacket(std::move(packet_queue_.pop())); } }); - if (launch_hw_) - { + if (launch_hw_) { hw_interface_wrapper_->HwInterface()->RegisterScanCallback( - std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); + std::bind(&HesaiRosWrapper::ReceiveCloudPacketCallback, this, std::placeholders::_1)); StreamStart(); - } - else - { + } else { packets_sub_ = create_subscription( - "pandar_packets", rclcpp::SensorDataQoS(), - std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); - RCLCPP_INFO_STREAM(get_logger(), - "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); + "pandar_packets", rclcpp::SensorDataQoS(), + std::bind(&HesaiRosWrapper::ReceiveScanMessageCallback, this, std::placeholders::_1)); + RCLCPP_INFO_STREAM( + get_logger(), + "Hardware connection disabled, listening for packets on " << packets_sub_->get_topic_name()); } - // Register parameter callback after all params have been declared. Otherwise it would be called once for each - // declaration - parameter_event_cb_ = - add_on_set_parameters_callback(std::bind(&HesaiRosWrapper::OnParameterChange, this, std::placeholders::_1)); + // Register parameter callback after all params have been declared. Otherwise it would be called + // once for each declaration + parameter_event_cb_ = add_on_set_parameters_callback( + std::bind(&HesaiRosWrapper::OnParameterChange, this, std::placeholders::_1)); } nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() @@ -76,7 +72,8 @@ nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() config.return_mode = drivers::ReturnModeFromStringHesai(_return_mode, config.sensor_model); config.host_ip = declare_parameter("host_ip", "255.255.255.255", param_read_only()); - config.sensor_ip = declare_parameter("sensor_ip", "192.168.1.201", param_read_only()); + config.sensor_ip = + declare_parameter("sensor_ip", "192.168.1.201", param_read_only()); config.data_port = declare_parameter("data_port", 2368, param_read_only()); config.gnss_port = declare_parameter("gnss_port", 2369, param_read_only()); config.frame_id = declare_parameter("frame_id", "pandar", param_read_write()); @@ -96,19 +93,17 @@ nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); uint16_t default_value; RCLCPP_DEBUG_STREAM(get_logger(), config.sensor_model); - if (config.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) - { + if (config.sensor_model == nebula::drivers::SensorModel::HESAI_PANDARAT128) { descriptor.additional_constraints = "200, 400"; descriptor.integer_range = int_range(200, 400, 200); default_value = 200; - } - else - { + } else { descriptor.additional_constraints = "300, 600, 1200"; descriptor.integer_range = int_range(300, 1200, 300); default_value = 600; } - config.rotation_speed = declare_parameter("rotation_speed", default_value, descriptor); + config.rotation_speed = + declare_parameter("rotation_speed", default_value, descriptor); } { rcl_interfaces::msg::ParameterDescriptor descriptor = param_read_write(); @@ -125,7 +120,7 @@ nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() descriptor.additional_constraints = "Dual return distance threshold [0.01, 0.5]"; descriptor.floating_point_range = float_range(0.01, 0.5, 0.01); config.dual_return_distance_threshold = - declare_parameter("dual_return_distance_threshold", 0.1, descriptor); + declare_parameter("dual_return_distance_threshold", 0.1, descriptor); } auto _ptp_profile = declare_parameter("ptp_profile", "", param_read_only()); @@ -134,13 +129,14 @@ nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() auto _ptp_transport = declare_parameter("ptp_transport_type", "", param_read_only()); config.ptp_transport_type = drivers::PtpTransportTypeFromString(_ptp_transport); - if (config.ptp_transport_type != drivers::PtpTransportType::L2 && - config.ptp_profile != drivers::PtpProfile::IEEE_1588v2 && - config.ptp_profile != drivers::PtpProfile::UNKNOWN_PROFILE) - { - RCLCPP_WARN_STREAM(get_logger(), "PTP transport was set to '" << _ptp_transport << "' but PTP profile '" - << _ptp_profile - << "' only supports 'L2'. Setting it to 'L2'."); + if ( + config.ptp_transport_type != drivers::PtpTransportType::L2 && + config.ptp_profile != drivers::PtpProfile::IEEE_1588v2 && + config.ptp_profile != drivers::PtpProfile::UNKNOWN_PROFILE) { + RCLCPP_WARN_STREAM( + get_logger(), "PTP transport was set to '" << _ptp_transport << "' but PTP profile '" + << _ptp_profile + << "' only supports 'L2'. Setting it to 'L2'."); config.ptp_transport_type = drivers::PtpTransportType::L2; set_parameter(rclcpp::Parameter("ptp_transport_type", "L2")); } @@ -158,48 +154,43 @@ nebula::Status HesaiRosWrapper::DeclareAndGetSensorConfigParams() return ValidateAndSetConfig(new_cfg_ptr); } -Status HesaiRosWrapper::ValidateAndSetConfig(std::shared_ptr& new_config) +Status HesaiRosWrapper::ValidateAndSetConfig( + std::shared_ptr & new_config) { - if (new_config->sensor_model == nebula::drivers::SensorModel::UNKNOWN) - { + if (new_config->sensor_model == nebula::drivers::SensorModel::UNKNOWN) { return Status::INVALID_SENSOR_MODEL; } - if (new_config->return_mode == nebula::drivers::ReturnMode::UNKNOWN) - { + if (new_config->return_mode == nebula::drivers::ReturnMode::UNKNOWN) { return Status::INVALID_ECHO_MODE; } - if (new_config->frame_id.empty()) - { + if (new_config->frame_id.empty()) { return Status::SENSOR_CONFIG_ERROR; } - if (new_config->ptp_profile == nebula::drivers::PtpProfile::UNKNOWN_PROFILE) - { - RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); + if (new_config->ptp_profile == nebula::drivers::PtpProfile::UNKNOWN_PROFILE) { + RCLCPP_ERROR_STREAM( + get_logger(), "Invalid PTP Profile Provided. Please use '1588v2', '802.1as' or 'automotive'"); return Status::SENSOR_CONFIG_ERROR; } - if (new_config->ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) - { - RCLCPP_ERROR_STREAM(get_logger(), - "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " - "using the '1588v2' PTP Profile"); + if (new_config->ptp_transport_type == nebula::drivers::PtpTransportType::UNKNOWN_TRANSPORT) { + RCLCPP_ERROR_STREAM( + get_logger(), + "Invalid PTP Transport Provided. Please use 'udp' or 'l2', 'udp' is only available when " + "using the '1588v2' PTP Profile"); return Status::SENSOR_CONFIG_ERROR; } - if (new_config->ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) - { - RCLCPP_ERROR_STREAM(get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); + if (new_config->ptp_switch_type == nebula::drivers::PtpSwitchType::UNKNOWN_SWITCH) { + RCLCPP_ERROR_STREAM( + get_logger(), "Invalid PTP Switch Type Provided. Please use 'tsn' or 'non_tsn'"); return Status::SENSOR_CONFIG_ERROR; } - if (hw_interface_wrapper_) - { + if (hw_interface_wrapper_) { hw_interface_wrapper_->OnConfigChange(new_config); } - if (hw_monitor_wrapper_) - { + if (hw_monitor_wrapper_) { hw_monitor_wrapper_->OnConfigChange(new_config); } - if (decoder_wrapper_) - { + if (decoder_wrapper_) { decoder_wrapper_->OnConfigChange(new_config); } @@ -207,17 +198,17 @@ Status HesaiRosWrapper::ValidateAndSetConfig(std::shared_ptr scan_msg) +void HesaiRosWrapper::ReceiveScanMessageCallback( + std::unique_ptr scan_msg) { - if (hw_interface_wrapper_) - { - RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 1000, - "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); + if (hw_interface_wrapper_) { + RCLCPP_ERROR_THROTTLE( + get_logger(), *get_clock(), 1000, + "Ignoring received PandarScan. Launch with launch_hw:=false to enable PandarScan replay."); return; } - for (auto& pkt : scan_msg->packets) - { + for (auto & pkt : scan_msg->packets) { auto nebula_pkt_ptr = std::make_unique(); nebula_pkt_ptr->stamp = pkt.stamp; std::copy(pkt.data.begin(), pkt.data.end(), std::back_inserter(nebula_pkt_ptr->data)); @@ -233,25 +224,23 @@ Status HesaiRosWrapper::GetStatus() Status HesaiRosWrapper::StreamStart() { - if (!hw_interface_wrapper_) - { + if (!hw_interface_wrapper_) { return Status::UDP_CONNECTION_ERROR; } - if (hw_interface_wrapper_->Status() != Status::OK) - { + if (hw_interface_wrapper_->Status() != Status::OK) { return hw_interface_wrapper_->Status(); } return hw_interface_wrapper_->HwInterface()->SensorInterfaceStart(); } -rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::OnParameterChange(const std::vector& p) +rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::OnParameterChange( + const std::vector & p) { - using namespace rcl_interfaces::msg; + using rcl_interfaces::msg::SetParametersResult; - if (p.empty()) - { + if (p.empty()) { return rcl_interfaces::build().successful(true).reason(""); } @@ -262,25 +251,25 @@ rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::OnParameterChange(cons drivers::HesaiSensorConfiguration new_cfg(*sensor_cfg_ptr_); std::string _return_mode = ""; - bool got_any = get_param(p, "return_mode", _return_mode) | get_param(p, "frame_id", new_cfg.frame_id) | - get_param(p, "scan_phase", new_cfg.scan_phase) | get_param(p, "min_range", new_cfg.min_range) | - get_param(p, "max_range", new_cfg.max_range) | get_param(p, "rotation_speed", new_cfg.rotation_speed) | - get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | - get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle) | - get_param(p, "dual_return_distance_threshold", new_cfg.dual_return_distance_threshold); - - // Currently, HW interface and monitor wrappers have only read-only parameters, so their update logic is not - // implemented - if (decoder_wrapper_) - { + bool got_any = + get_param(p, "return_mode", _return_mode) | get_param(p, "frame_id", new_cfg.frame_id) | + get_param(p, "scan_phase", new_cfg.scan_phase) | get_param(p, "min_range", new_cfg.min_range) | + get_param(p, "max_range", new_cfg.max_range) | + get_param(p, "rotation_speed", new_cfg.rotation_speed) | + get_param(p, "cloud_min_angle", new_cfg.cloud_min_angle) | + get_param(p, "cloud_max_angle", new_cfg.cloud_max_angle) | + get_param(p, "dual_return_distance_threshold", new_cfg.dual_return_distance_threshold); + + // Currently, HW interface and monitor wrappers have only read-only parameters, so their update + // logic is not implemented + if (decoder_wrapper_) { auto result = decoder_wrapper_->OnParameterChange(p); if (!result.successful) { return result; } } - if (!got_any) - { + if (!got_any) { return rcl_interfaces::build().successful(true).reason(""); } @@ -290,8 +279,7 @@ rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::OnParameterChange(cons auto new_cfg_ptr = std::make_shared(new_cfg); auto status = ValidateAndSetConfig(new_cfg_ptr); - if (status != Status::OK) - { + if (status != Status::OK) { RCLCPP_WARN_STREAM(get_logger(), "OnParameterChange aborted: " << status); auto result = SetParametersResult(); result.successful = false; @@ -302,23 +290,22 @@ rcl_interfaces::msg::SetParametersResult HesaiRosWrapper::OnParameterChange(cons return rcl_interfaces::build().successful(true).reason(""); } -void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector& packet) +void HesaiRosWrapper::ReceiveCloudPacketCallback(std::vector & packet) { - if (!decoder_wrapper_ || decoder_wrapper_->Status() != Status::OK) - { + if (!decoder_wrapper_ || decoder_wrapper_->Status() != Status::OK) { return; } const auto now = std::chrono::high_resolution_clock::now(); - const auto timestamp_ns = std::chrono::duration_cast(now.time_since_epoch()).count(); + const auto timestamp_ns = + std::chrono::duration_cast(now.time_since_epoch()).count(); auto msg_ptr = std::make_unique(); msg_ptr->stamp.sec = static_cast(timestamp_ns / 1'000'000'000); msg_ptr->stamp.nanosec = static_cast(timestamp_ns % 1'000'000'000); msg_ptr->data.swap(packet); - if (!packet_queue_.try_push(std::move(msg_ptr))) - { + if (!packet_queue_.try_push(std::move(msg_ptr))) { RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 500, "Packet(s) dropped"); } } diff --git a/nebula_ros/src/hesai/hw_interface_wrapper.cpp b/nebula_ros/src/hesai/hw_interface_wrapper.cpp index c10319c1e..18da9da83 100644 --- a/nebula_ros/src/hesai/hw_interface_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_interface_wrapper.cpp @@ -6,18 +6,21 @@ namespace ros { HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper( - rclcpp::Node* const parent_node, std::shared_ptr& config) - : hw_interface_(new nebula::drivers::HesaiHwInterface()) - , logger_(parent_node->get_logger().get_child("HwInterface")) - , status_(Status::NOT_INITIALIZED) + rclcpp::Node * const parent_node, + std::shared_ptr & config) +: hw_interface_(new nebula::drivers::HesaiHwInterface()), + logger_(parent_node->get_logger().get_child("HwInterface")), + status_(Status::NOT_INITIALIZED) { setup_sensor_ = parent_node->declare_parameter("setup_sensor", true, param_read_only()); bool retry_connect = parent_node->declare_parameter("retry_hw", true, param_read_only()); - status_ = hw_interface_->SetSensorConfiguration(std::static_pointer_cast(config)); + status_ = hw_interface_->SetSensorConfiguration( + std::static_pointer_cast(config)); if (status_ != Status::OK) { - throw std::runtime_error((std::stringstream{} << "Could not initialize HW interface: " << status_).str()); + throw std::runtime_error( + (std::stringstream{} << "Could not initialize HW interface: " << status_).str()); } hw_interface_->SetLogger(std::make_shared(parent_node->get_logger())); @@ -25,11 +28,9 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper( int retry_count = 0; - while (true) - { + while (true) { status_ = hw_interface_->InitializeTcpDriver(); - if (status_ == Status::OK || !retry_connect) - { + if (status_ == Status::OK || !retry_connect) { break; } @@ -38,35 +39,30 @@ HesaiHwInterfaceWrapper::HesaiHwInterfaceWrapper( RCLCPP_WARN_STREAM(logger_, status_ << ". Retry #" << retry_count); } - if (status_ == Status::OK) - { - try - { + if (status_ == Status::OK) { + try { auto inventory = hw_interface_->GetInventory(); RCLCPP_INFO_STREAM(logger_, inventory); hw_interface_->SetTargetModel(inventory.model); - } - catch (...) - { + } catch (...) { RCLCPP_ERROR_STREAM(logger_, "Failed to get model from sensor..."); } - if (setup_sensor_) - { + if (setup_sensor_) { hw_interface_->CheckAndSetConfig(); } - } - else - { - RCLCPP_ERROR_STREAM(logger_, "Failed to get model from sensor... Set from config: " << config->sensor_model); + } else { + RCLCPP_ERROR_STREAM( + logger_, "Failed to get model from sensor... Set from config: " << config->sensor_model); } status_ = Status::OK; } void HesaiHwInterfaceWrapper::OnConfigChange( - const std::shared_ptr& new_config) + const std::shared_ptr & new_config) { - hw_interface_->SetSensorConfiguration(std::static_pointer_cast(new_config)); + hw_interface_->SetSensorConfiguration( + std::static_pointer_cast(new_config)); if (setup_sensor_) { hw_interface_->CheckAndSetConfig(); } @@ -83,4 +79,4 @@ std::shared_ptr HesaiHwInterfaceWrapper::HwInterface( } } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp index b34e181fb..da1f78794 100644 --- a/nebula_ros/src/hesai/hw_monitor_wrapper.cpp +++ b/nebula_ros/src/hesai/hw_monitor_wrapper.cpp @@ -4,19 +4,19 @@ namespace nebula { namespace ros { -HesaiHwMonitorWrapper::HesaiHwMonitorWrapper(rclcpp::Node* const parent_node, - const std::shared_ptr& hw_interface, - std::shared_ptr& config) - : logger_(parent_node->get_logger().get_child("HwMonitor")) - , diagnostics_updater_(parent_node) - , status_(Status::OK) - , hw_interface_(hw_interface) - , parent_node_(parent_node) +HesaiHwMonitorWrapper::HesaiHwMonitorWrapper( + rclcpp::Node * const parent_node, + const std::shared_ptr & hw_interface, + std::shared_ptr & config) +: logger_(parent_node->get_logger().get_child("HwMonitor")), + diagnostics_updater_(parent_node), + status_(Status::OK), + hw_interface_(hw_interface), + parent_node_(parent_node) { diag_span_ = parent_node->declare_parameter("diag_span", 1000, param_read_only()); - switch (config->sensor_model) - { + switch (config->sensor_model) { case nebula::drivers::SensorModel::HESAI_PANDARXT32: case nebula::drivers::SensorModel::HESAI_PANDARXT32M: case nebula::drivers::SensorModel::HESAI_PANDARAT128: @@ -71,7 +71,8 @@ void HesaiHwMonitorWrapper::InitializeHesaiDiagnostics() diagnostics_updater_.add("hesai_status", this, &HesaiHwMonitorWrapper::HesaiCheckStatus); diagnostics_updater_.add("hesai_ptp", this, &HesaiHwMonitorWrapper::HesaiCheckPtp); - diagnostics_updater_.add("hesai_temperature", this, &HesaiHwMonitorWrapper::HesaiCheckTemperature); + diagnostics_updater_.add( + "hesai_temperature", this, &HesaiHwMonitorWrapper::HesaiCheckTemperature); diagnostics_updater_.add("hesai_rpm", this, &HesaiHwMonitorWrapper::HesaiCheckRpm); current_status_.reset(); @@ -83,25 +84,19 @@ void HesaiHwMonitorWrapper::InitializeHesaiDiagnostics() auto fetch_diag_from_sensor = [this]() { OnHesaiStatusTimer(); - if (hw_interface_->UseHttpGetLidarMonitor()) - { + if (hw_interface_->UseHttpGetLidarMonitor()) { OnHesaiLidarMonitorTimerHttp(); - } - else - { + } else { OnHesaiLidarMonitorTimer(); } }; - fetch_diagnostics_timer_ = - parent_node_->create_wall_timer(std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor)); + fetch_diagnostics_timer_ = parent_node_->create_wall_timer( + std::chrono::milliseconds(diag_span_), std::move(fetch_diag_from_sensor)); - if (hw_interface_->UseHttpGetLidarMonitor()) - { + if (hw_interface_->UseHttpGetLidarMonitor()) { diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorWrapper::HesaiCheckVoltageHttp); - } - else - { + } else { diagnostics_updater_.add("hesai_voltage", this, &HesaiHwMonitorWrapper::HesaiCheckVoltage); } @@ -112,45 +107,37 @@ void HesaiHwMonitorWrapper::InitializeHesaiDiagnostics() RCLCPP_DEBUG_STREAM(logger_, "dif(status): " << dif); - if (diag_span_ * 2.0 < dif * 1000) - { + if (diag_span_ * 2.0 < dif * 1000) { current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; RCLCPP_DEBUG_STREAM(logger_, "STALE"); - } - else - { + } else { current_diag_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; RCLCPP_DEBUG_STREAM(logger_, "OK"); } dif = (now - *current_lidar_monitor_time_).seconds(); RCLCPP_DEBUG_STREAM(logger_, "dif(monitor): " << dif); - if (diag_span_ * 2.0 < dif * 1000) - { + if (diag_span_ * 2.0 < dif * 1000) { current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::STALE; RCLCPP_DEBUG_STREAM(logger_, "STALE"); - } - else - { + } else { current_monitor_status_ = diagnostic_msgs::msg::DiagnosticStatus::OK; RCLCPP_DEBUG_STREAM(logger_, "OK"); } diagnostics_updater_.force_update(); }; diagnostics_update_timer_ = - parent_node_->create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); + parent_node_->create_wall_timer(std::chrono::milliseconds(1000), std::move(on_timer_update)); RCLCPP_DEBUG_STREAM(logger_, "add_timer"); } -std::string HesaiHwMonitorWrapper::GetPtreeValue(boost::property_tree::ptree* pt, const std::string& key) +std::string HesaiHwMonitorWrapper::GetPtreeValue( + boost::property_tree::ptree * pt, const std::string & key) { boost::optional value = pt->get_optional(key); - if (value) - { + if (value) { return value.get(); - } - else - { + } else { return MSG_NOT_SUPPORTED; } } @@ -164,22 +151,19 @@ std::string HesaiHwMonitorWrapper::GetFixedPrecisionString(double val, int pre) void HesaiHwMonitorWrapper::OnHesaiStatusTimer() { RCLCPP_DEBUG_STREAM(logger_, "OnHesaiStatusTimer" << std::endl); - try - { + try { auto result = hw_interface_->GetLidarStatus(); std::scoped_lock lock(mtx_lidar_status_); current_status_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); current_status_.reset(new HesaiLidarStatus(result)); - } - catch (const std::system_error& error) - { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiStatusTimer(std::system_error)"), - error.what()); - } - catch (const boost::system::system_error& error) - { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiStatusTimer(boost::system::system_error)"), - error.what()); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiStatusTimer(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiStatusTimer(boost::system::system_error)"), + error.what()); } RCLCPP_DEBUG_STREAM(logger_, "OnHesaiStatusTimer END" << std::endl); } @@ -187,24 +171,23 @@ void HesaiHwMonitorWrapper::OnHesaiStatusTimer() void HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp() { RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimerHttp"); - try - { - hw_interface_->GetLidarMonitorAsyncHttp([this](const std::string& str) { + try { + hw_interface_->GetLidarMonitorAsyncHttp([this](const std::string & str) { std::scoped_lock lock(mtx_lidar_monitor_); current_lidar_monitor_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); - current_lidar_monitor_tree_ = std::make_unique(hw_interface_->ParseJson(str)); + current_lidar_monitor_tree_ = + std::make_unique(hw_interface_->ParseJson(str)); }); - } - catch (const std::system_error& error) - { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), - error.what()); - } - catch (const boost::system::system_error& error) - { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_" - "error)"), - error.what()); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger( + "HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp(boost::system::system_" + "error)"), + error.what()); } RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimerHttp END"); } @@ -212,52 +195,47 @@ void HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimerHttp() void HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer() { RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimer"); - try - { + try { auto result = hw_interface_->GetLidarMonitor(); std::scoped_lock lock(mtx_lidar_monitor_); current_lidar_monitor_time_.reset(new rclcpp::Time(parent_node_->get_clock()->now())); current_monitor_.reset(new HesaiLidarMonitor(result)); - } - catch (const std::system_error& error) - { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), - error.what()); - } - catch (const boost::system::system_error& error) - { - RCLCPP_ERROR_STREAM(rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer(boost::system::system_" - "error)"), - error.what()); + } catch (const std::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer(std::system_error)"), + error.what()); + } catch (const boost::system::system_error & error) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("HesaiHwMonitorWrapper::OnHesaiLidarMonitorTimer(boost::system::system_" + "error)"), + error.what()); } RCLCPP_DEBUG_STREAM(logger_, "OnHesaiLidarMonitorTimer END"); } -void HesaiHwMonitorWrapper::HesaiCheckStatus(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +void HesaiHwMonitorWrapper::HesaiCheckStatus( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) - { + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; diagnostics.add("system_uptime", std::to_string(current_status_->system_uptime.value())); diagnostics.add("startup_times", std::to_string(current_status_->startup_times.value())); - diagnostics.add("total_operation_time", std::to_string(current_status_->total_operation_time.value())); + diagnostics.add( + "total_operation_time", std::to_string(current_status_->total_operation_time.value())); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } - else - { + } else { diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); } } -void HesaiHwMonitorWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +void HesaiHwMonitorWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) - { + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; auto gps_status = current_status_->get_str_gps_pps_lock(); @@ -269,131 +247,116 @@ void HesaiHwMonitorWrapper::HesaiCheckPtp(diagnostic_updater::DiagnosticStatusWr diagnostics.add("gps_pps_lock", gps_status); diagnostics.add("gps_gprmc_status", gprmc_status); diagnostics.add("ptp_clock_status", ptp_status); - if (gps_status != "UNKNOWN") - { + if (gps_status != "UNKNOWN") { msg.emplace_back("gps_pps_lock: " + gps_status); } - if (gprmc_status != "UNKNOWN") - { + if (gprmc_status != "UNKNOWN") { msg.emplace_back("gprmc_status: " + gprmc_status); } - if (ptp_status != "UNKNOWN") - { + if (ptp_status != "UNKNOWN") { msg.emplace_back("ptp_status: " + ptp_status); } - if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") - { + if (ptp_status == "FREE RUN" && gps_status == "UNKNOWN") { level = diagnostic_msgs::msg::DiagnosticStatus::WARN; } diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } - else - { + } else { diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); } } -void HesaiHwMonitorWrapper::HesaiCheckTemperature(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +void HesaiHwMonitorWrapper::HesaiCheckTemperature( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) - { + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - for (size_t i = 0; i < std::size(current_status_->temperature); i++) - { - diagnostics.add(temperature_names_[i], - GetFixedPrecisionString(current_status_->temperature[i].value() * 0.01, 3)); + for (size_t i = 0; i < std::size(current_status_->temperature); i++) { + diagnostics.add( + temperature_names_[i], + GetFixedPrecisionString(current_status_->temperature[i].value() * 0.01, 3)); } diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } - else - { + } else { diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); } } -void HesaiHwMonitorWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +void HesaiHwMonitorWrapper::HesaiCheckRpm(diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_lidar_status_); - if (current_status_) - { + if (current_status_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; diagnostics.add("motor_speed", std::to_string(current_status_->motor_speed.value())); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } - else - { + } else { diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); } } -void HesaiHwMonitorWrapper::HesaiCheckVoltageHttp(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +void HesaiHwMonitorWrapper::HesaiCheckVoltageHttp( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_lidar_monitor_); - if (current_lidar_monitor_tree_) - { + if (current_lidar_monitor_tree_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; std::string key = ""; std::string mes; key = "lidarInCur"; - try - { + try { mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); - } - catch (boost::bad_lexical_cast& ex) - { + } catch (boost::bad_lexical_cast & ex) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; mes = MSG_ERROR + std::string(ex.what()); } diagnostics.add(key, mes); key = "lidarInVol"; - try - { + try { mes = GetPtreeValue(current_lidar_monitor_tree_.get(), "Body." + key); - } - catch (boost::bad_lexical_cast& ex) - { + } catch (boost::bad_lexical_cast & ex) { level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; mes = MSG_ERROR + std::string(ex.what()); } diagnostics.add(key, mes); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } - else - { + } else { diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); } } -void HesaiHwMonitorWrapper::HesaiCheckVoltage(diagnostic_updater::DiagnosticStatusWrapper& diagnostics) +void HesaiHwMonitorWrapper::HesaiCheckVoltage( + diagnostic_updater::DiagnosticStatusWrapper & diagnostics) { std::scoped_lock lock(mtx_lidar_monitor_); - if (current_monitor_) - { + if (current_monitor_) { uint8_t level = diagnostic_msgs::msg::DiagnosticStatus::OK; std::vector msg; - diagnostics.add("input_voltage", GetFixedPrecisionString(current_monitor_->input_voltage.value() * 0.01, 3) + " V"); - diagnostics.add("input_current", GetFixedPrecisionString(current_monitor_->input_current.value() * 0.01, 3) + " m" - "A"); - diagnostics.add("input_power", GetFixedPrecisionString(current_monitor_->input_power.value() * 0.01, 3) + " W"); + diagnostics.add( + "input_voltage", + GetFixedPrecisionString(current_monitor_->input_voltage.value() * 0.01, 3) + " V"); + diagnostics.add( + "input_current", GetFixedPrecisionString(current_monitor_->input_current.value() * 0.01, 3) + + " m" + "A"); + diagnostics.add( + "input_power", + GetFixedPrecisionString(current_monitor_->input_power.value() * 0.01, 3) + " W"); diagnostics.summary(level, boost::algorithm::join(msg, ", ")); - } - else - { + } else { diagnostics.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "No data available"); } } Status HesaiHwMonitorWrapper::Status() { - return Status::NOT_IMPLEMENTED; // TODO + return Status::OK; } } // namespace ros -} // namespace nebula \ No newline at end of file +} // namespace nebula diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.cpp b/nebula_tests/hesai/hesai_ros_decoder_test.cpp index f65a974cc..97046e8f8 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.cpp @@ -220,8 +220,7 @@ Status HesaiRosDecoderTest::GetParameters( if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { return Status::INVALID_ECHO_MODE; } - if ( - sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { + if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { return Status::SENSOR_CONFIG_ERROR; } if (calibration_configuration.calibration_file.empty()) { @@ -274,7 +273,7 @@ void HesaiRosDecoderTest::ReadBag( storage_options.uri = params_.bag_path; storage_options.storage_id = params_.storage_id; - converter_options.output_serialization_format = params_.format; //"cdr"; + converter_options.output_serialization_format = params_.format; rclcpp::Serialization serialization; rosbag2_cpp::Reader bag_reader(std::make_unique()); @@ -296,7 +295,8 @@ void HesaiRosDecoderTest::ReadBag( auto extracted_msg_ptr = std::make_shared(extracted_msg); for (auto & pkt : extracted_msg_ptr->packets) { - auto pointcloud_ts = driver_ptr_->ParseCloudPacket(std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); + auto pointcloud_ts = driver_ptr_->ParseCloudPacket( + std::vector(pkt.data.begin(), std::next(pkt.data.begin(), pkt.size))); auto pointcloud = std::get<0>(pointcloud_ts); auto scan_timestamp = std::get<1>(pointcloud_ts); diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.hpp b/nebula_tests/hesai/hesai_ros_decoder_test.hpp index 43996b9ac..f12e56020 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.hpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.hpp @@ -17,6 +17,8 @@ #include #include +#include +#include #ifndef _SRC_CALIBRATION_DIR_PATH #define _SRC_CALIBRATION_DIR_PATH "" @@ -48,20 +50,22 @@ struct HesaiRosDecoderTestParams double dual_return_distance_threshold = 0.1; }; -inline std::ostream & operator<<(std::ostream & os, nebula::ros::HesaiRosDecoderTestParams const & arg) { +inline std::ostream & operator<<( + std::ostream & os, nebula::ros::HesaiRosDecoderTestParams const & arg) +{ return os << "sensor_model=" << arg.sensor_model << ", " - << "return_mode=" << arg.return_mode << ", " - << "calibration_file=" << arg.calibration_file << ", " - << "bag_path=" << arg.bag_path << ", " - << "correction_file=" << arg.correction_file << ", " - << "frame_id=" << arg.frame_id << ", " - << "scan_phase=" << arg.scan_phase << ", " - << "min_range=" << arg.min_range << ", " - << "max_range=" << arg.max_range << ", " - << "storage_id=" << arg.storage_id << ", " - << "format=" << arg.format << ", " - << "target_topic=" << arg.target_topic << ", " - << "dual_return_distance_threshold=" << arg.dual_return_distance_threshold << ", "; + << "return_mode=" << arg.return_mode << ", " + << "calibration_file=" << arg.calibration_file << ", " + << "bag_path=" << arg.bag_path << ", " + << "correction_file=" << arg.correction_file << ", " + << "frame_id=" << arg.frame_id << ", " + << "scan_phase=" << arg.scan_phase << ", " + << "min_range=" << arg.min_range << ", " + << "max_range=" << arg.max_range << ", " + << "storage_id=" << arg.storage_id << ", " + << "format=" << arg.format << ", " + << "target_topic=" << arg.target_topic << ", " + << "dual_return_distance_threshold=" << arg.dual_return_distance_threshold << ", "; } /// @brief Testing decoder of pandar 40p (Keeps HesaiDriverRosWrapper structure as much as diff --git a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp index d6574ccd4..7f80f6f48 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp @@ -12,6 +12,8 @@ #include #include #include +#include +#include namespace nebula { @@ -19,72 +21,15 @@ namespace test { const nebula::ros::HesaiRosDecoderTestParams TEST_CONFIGS[6] = { - { - "Pandar40P", - "Dual", - "Pandar40P.csv", - "40p/1673400149412331409", - "", - "hesai", - 0, - 0.3f, - 200.f - }, - { - "Pandar64", - "Dual", - "Pandar64.csv", - "64/1673403880599376836", - "", - "hesai", - 0, - 0.3f, - 200.f - }, - { - "PandarAT128", - "LastStrongest", - "PandarAT128.csv", - "at128/1679653308406038376", - "PandarAT128.dat", - "hesai", - 0, - 1.f, - 180.f - }, - { - "PandarQT64", - "Dual", - "PandarQT64.csv", - "qt64/1673401195788312575", - "", - "hesai", - 0, - 0.1f, - 60.f - }, - { - "PandarXT32", - "Dual", - "PandarXT32.csv", - "xt32/1673400677802009732", - "", - "hesai", - 0, - 0.05f, - 120.f - }, - { - "PandarXT32M", - "LastStrongest", - "PandarXT32M.csv", - "xt32m/1660893203042895158", - "", - "hesai", - 0, - 0.5f, - 300.f - }}; + {"Pandar40P", "Dual", "Pandar40P.csv", "40p/1673400149412331409", "", "hesai", 0, 0.3f, 200.f}, + {"Pandar64", "Dual", "Pandar64.csv", "64/1673403880599376836", "", "hesai", 0, 0.3f, 200.f}, + {"PandarAT128", "LastStrongest", "PandarAT128.csv", "at128/1679653308406038376", + "PandarAT128.dat", "hesai", 0, 1.f, 180.f}, + {"PandarQT64", "Dual", "PandarQT64.csv", "qt64/1673401195788312575", "", "hesai", 0, 0.1f, 60.f}, + {"PandarXT32", "Dual", "PandarXT32.csv", "xt32/1673400677802009732", "", "hesai", 0, 0.05f, + 120.f}, + {"PandarXT32M", "LastStrongest", "PandarXT32M.csv", "xt32m/1660893203042895158", "", "hesai", 0, + 0.5f, 300.f}}; // Compares geometrical output of decoder against pre-recorded reference pointcloud. TEST_P(DecoderTest, TestPcd) diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp index b00a9433d..047b2c661 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.cpp @@ -13,7 +13,9 @@ #include #include +#include #include +#include namespace nebula { @@ -57,7 +59,10 @@ Status VelodyneRosDecoderTest::InitializeDriver( return driver_ptr_->GetStatus(); } -Status VelodyneRosDecoderTest::GetStatus() { return wrapper_status_; } +Status VelodyneRosDecoderTest::GetStatus() +{ + return wrapper_status_; +} Status VelodyneRosDecoderTest::GetParameters( drivers::VelodyneSensorConfiguration & sensor_configuration, @@ -315,10 +320,9 @@ void VelodyneRosDecoderTest::ReadBag() storage_options.uri = bag_path; storage_options.storage_id = storage_id; - converter_options.output_serialization_format = format; //"cdr"; + converter_options.output_serialization_format = format; rclcpp::Serialization serialization; nebula::drivers::NebulaPointCloudPtr pointcloud(new nebula::drivers::NebulaPointCloud); - // nebula::drivers::NebulaPointCloudPtr ref_pointcloud(new nebula::drivers::NebulaPointCloud); pcl::PointCloud::Ptr ref_pointcloud(new pcl::PointCloud); { rosbag2_cpp::Reader bag_reader(std::make_unique()); diff --git a/node_modules/.cache/prettier/.prettier-caches/71fcc0c413aef9f44cc34d45933658dcd90140bf.json b/node_modules/.cache/prettier/.prettier-caches/71fcc0c413aef9f44cc34d45933658dcd90140bf.json new file mode 100644 index 000000000..f1d45e79f --- /dev/null +++ b/node_modules/.cache/prettier/.prettier-caches/71fcc0c413aef9f44cc34d45933658dcd90140bf.json @@ -0,0 +1 @@ +{"89c3ab2f8d568f1de2f4909e98f02c8eb4aa47d7":{"files":{".pre-commit-config.yaml":["IIgVK1mNeWSqgUB4F48/2oXJV2M=",true],"nebula_tests/data/velodyne/vls128/1614315746471294674/metadata.yaml":["rkwp2ScCJvYSp/u0PQ8O9vqff7E=",true],".cspell.json":["qdqZpfVDIuFwYUzZ4njcRyqVt6U=",true]},"modified":1716356405626}} \ No newline at end of file diff --git a/scripts/plot_instrumentation.py b/scripts/plot_instrumentation.py index fe9c12fda..7540aa35f 100755 --- a/scripts/plot_instrumentation.py +++ b/scripts/plot_instrumentation.py @@ -1,77 +1,79 @@ #!/usr/bin/python3 import argparse -from matplotlib import pyplot as plt -import numpy as np -import pandas as pd -import re +from collections import defaultdict import json import os -from collections import defaultdict +import re + +from matplotlib import pyplot as plt +import pandas as pd + def condition_data(log_file: str): - with open(log_file, 'r') as f: - lines = f.readlines() - lines = [re.search(r'(\{"type":.*?"tag":.*?\})', l) for l in lines] - lines = [re.sub(r'([0-9])"', r'\1', l[1]) for l in lines if l] - lines = [json.loads(l) for l in lines if l] + with open(log_file, "r") as f: + lines = f.readlines() + lines = [re.search(r'(\{"type":.*?"tag":.*?\})', line) for line in lines] + lines = [re.sub(r'([0-9])"', r"\1", line[1]) for line in lines if line] + lines = [json.loads(line) for line in lines if line] - cols = defaultdict(list) + cols = defaultdict(list) - for record in lines: - for key in record.keys(): - if key in ["tag", "type"]: - continue + for record in lines: + for key in record.keys(): + if key in ["tag", "type"]: + continue - colname = f"{record['type']}.{key}.{record['tag']}" - cols[colname] += [num for num in record[key] if num is not None] + colname = f"{record['type']}.{key}.{record['tag']}" + cols[colname] += [num for num in record[key] if num is not None] - def quantile_filter(series, quantile): - q = series.quantile(quantile) - return series[series <= q] + def quantile_filter(series, quantile): + q = series.quantile(quantile) + return series[series <= q] - cols = {k: pd.Series(v, name=k) / 1e3 for k, v in cols.items()} - cols = {k: quantile_filter(v, .999) for k, v in cols.items()} + cols = {k: pd.Series(v, name=k) / 1e3 for k, v in cols.items()} + cols = {k: quantile_filter(v, 0.999) for k, v in cols.items()} - for v in cols.values(): - v: pd.Series - v.attrs['file'] = os.path.basename(os.path.splitext(log_file)[0]) + for v in cols.values(): + v: pd.Series + v.attrs["file"] = os.path.basename(os.path.splitext(log_file)[0]) - return cols + return cols -def plot(conditioned_logs): - conditioned_logs = {k: [dic[k] for dic in conditioned_logs] for k in conditioned_logs[0]} +def plot(conditioned_logs): - fig, axs = plt.subplots(1, len(conditioned_logs), figsize=(15, 8), dpi=120) + conditioned_logs = {k: [dic[k] for dic in conditioned_logs] for k in conditioned_logs[0]} - handles, labels = [], [] + fig, axs = plt.subplots(1, len(conditioned_logs), figsize=(15, 8), dpi=120) - for i, k in enumerate(sorted(conditioned_logs.keys())): - k: str - v = conditioned_logs[k] - ax: plt.Axes = axs[i] - art = ax.boxplot(v) - handles.append(art) - labels.append(k) - ax.set_ylabel("dt [µs]") - ax.set_title(k.replace(".", "\n")) - ax.set_xticks([1 + i for i in range(len(v))], [ser.attrs['file'] for ser in v]) - ax.tick_params(axis='x', labelrotation=90) + handles, labels = [], [] + for i, k in enumerate(sorted(conditioned_logs.keys())): + k: str + v = conditioned_logs[k] + ax: plt.Axes = axs[i] + art = ax.boxplot(v) + handles.append(art) + labels.append(k) + ax.set_ylabel("dt [µs]") + ax.set_title(k.replace(".", "\n")) + ax.set_xticks([1 + i for i in range(len(v))], [ser.attrs["file"] for ser in v]) + ax.tick_params(axis="x", labelrotation=90) + fig.tight_layout() + plt.savefig("instrumentation.png") + plt.show() - fig.tight_layout() - plt.savefig("instrumentation.png") - plt.show() def main(args): - conditioned_logs = [condition_data(f) for f in args.log_files] - plot(conditioned_logs) - + conditioned_logs = [condition_data(f) for f in args.log_files] + plot(conditioned_logs) + + if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("log_files", nargs="+") - args = parser.parse_args() + parser = argparse.ArgumentParser() + parser.add_argument("log_files", nargs="+") + args = parser.parse_args() - main(args) \ No newline at end of file + main(args) diff --git a/scripts/plot_times.py b/scripts/plot_times.py index 3cbf93f61..07dbee302 100644 --- a/scripts/plot_times.py +++ b/scripts/plot_times.py @@ -1,11 +1,13 @@ -#%% +# %% +import argparse +import glob import os -import pandas as pd import re -import glob -import argparse + from matplotlib import pyplot as plt +import pandas as pd + def parse_logs(run_name): dfs = [] @@ -15,21 +17,20 @@ def parse_logs(run_name): with open(path) as f: lines = f.readlines() lines = filter(lambda line: "PROFILING" in line, lines) - lines = [re.sub(r'.*PROFILING (\{.*?\}).*', r'\1', line) for line in lines] + lines = [re.sub(r".*PROFILING (\{.*?\}).*", r"\1", line) for line in lines] records = [eval(line) for line in lines] dfs.append(pd.DataFrame(records)) df = pd.concat(dfs) - + for col in [c for c in df.columns if c.startswith("d_")]: df[col] /= 1e6 # ns to ms return df + def plot_timing_comparison(run_names): - scenario_dfs = { - run_name: parse_logs(run_name) for run_name in run_names - } + scenario_dfs = {run_name: parse_logs(run_name) for run_name in run_names} n_cols = sum(1 for c in next(iter(scenario_dfs.values())).columns if c.startswith("d_")) @@ -44,14 +45,16 @@ def plot_timing_comparison(run_names): # ax_d.plot(durations.index, durations, label=label, linestyle='', marker='.') for col in filter(lambda col: col.startswith("n_"), df.columns): - ax_n.plot(df.index, df[col], label=f"{label}::{col}", linestyle='', marker='.', color='black') + ax_n.plot( + df.index, df[col], label=f"{label}::{col}", linestyle="", marker=".", color="black" + ) for col in filter(lambda col: col.startswith("d_"), df.columns): - ax_d.plot(df.index, df[col], label=f"{label}::{col}", linestyle='', marker='.') - + ax_d.plot(df.index, df[col], label=f"{label}::{col}", linestyle="", marker=".") + d_columns = [col for col in df.columns if col.startswith("d_")] n_cols = len(d_columns) for j, col in enumerate(d_columns): - if (i == 0): + if i == 0: boxes[j].set_ylabel(f"{col} (ms)") boxes[j].boxplot(df[col], positions=[i], labels=[label]) @@ -59,13 +62,11 @@ def plot_timing_comparison(run_names): ax_d.set_ylabel("time (ms)") ax_d.set_xlabel("iteration") - df_means = pd.DataFrame({ - label: df.describe().loc["mean"] for label, df in scenario_dfs.items() - }) + df_means = pd.DataFrame( + {label: df.describe().loc["mean"] for label, df in scenario_dfs.items()} + ) - df_stds = pd.DataFrame({ - label: df.describe().loc["std"] for label, df in scenario_dfs.items() - }) + df_stds = pd.DataFrame({label: df.describe().loc["std"] for label, df in scenario_dfs.items()}) df_means = df_means.rename(index=lambda label: f"{label} AVG") df_stds = df_stds.rename(index=lambda label: f"{label} STD") @@ -75,15 +76,23 @@ def plot_timing_comparison(run_names): baseline_name = run_names[0] df_base = df_stat[baseline_name] for label in df_base.index: - df_stat.loc[f"{label} % rel to {baseline_name}", :] = df_stat.loc[label, :] / df_base.loc[label] * 100 + df_stat.loc[f"{label} % rel to {baseline_name}", :] = ( + df_stat.loc[label, :] / df_base.loc[label] * 100 + ) print(df_stat.to_markdown()) plt.show() + + # %% if __name__ == "__main__": parser = argparse.ArgumentParser() - parser.add_argument("run_names", nargs='+', help="The names of the runs to plot, as entered in test_runner.bash (e.g. 'baseline', 'optimized')\nAll files of the form -[0-9].log will be plotted.") + parser.add_argument( + "run_names", + nargs="+", + help="The names of the runs to plot, as entered in test_runner.bash (e.g. 'baseline', 'optimized')\nAll files of the form -[0-9].log will be plotted.", + ) args = parser.parse_args() - plot_timing_comparison(args.run_names) \ No newline at end of file + plot_timing_comparison(args.run_names) From 13a538e7e251f6df5a0b25bef3c463fb95db4d18 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 15:07:30 +0900 Subject: [PATCH 119/122] fix(expected.hpp): revert explicit constructors --- nebula_common/include/nebula_common/util/expected.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nebula_common/include/nebula_common/util/expected.hpp b/nebula_common/include/nebula_common/util/expected.hpp index 2a59122f5..25cb5f83d 100644 --- a/nebula_common/include/nebula_common/util/expected.hpp +++ b/nebula_common/include/nebula_common/util/expected.hpp @@ -83,9 +83,9 @@ struct expected return default_; } - explicit expected(const T & value) { value_ = value; } + expected(const T & value) { value_ = value; } // NOLINT(runtime/explicit) - explicit expected(const E & error) { value_ = error; } + expected(const E & error) { value_ = error; } // NOLINT(runtime/explicit) private: std::variant value_; From 8f01847055c1f58cec5230d082e3a913eb6dffc1 Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 15:07:48 +0900 Subject: [PATCH 120/122] chore: remove erroneously added node_modules folder --- .../71fcc0c413aef9f44cc34d45933658dcd90140bf.json | 1 - 1 file changed, 1 deletion(-) delete mode 100644 node_modules/.cache/prettier/.prettier-caches/71fcc0c413aef9f44cc34d45933658dcd90140bf.json diff --git a/node_modules/.cache/prettier/.prettier-caches/71fcc0c413aef9f44cc34d45933658dcd90140bf.json b/node_modules/.cache/prettier/.prettier-caches/71fcc0c413aef9f44cc34d45933658dcd90140bf.json deleted file mode 100644 index f1d45e79f..000000000 --- a/node_modules/.cache/prettier/.prettier-caches/71fcc0c413aef9f44cc34d45933658dcd90140bf.json +++ /dev/null @@ -1 +0,0 @@ -{"89c3ab2f8d568f1de2f4909e98f02c8eb4aa47d7":{"files":{".pre-commit-config.yaml":["IIgVK1mNeWSqgUB4F48/2oXJV2M=",true],"nebula_tests/data/velodyne/vls128/1614315746471294674/metadata.yaml":["rkwp2ScCJvYSp/u0PQ8O9vqff7E=",true],".cspell.json":["qdqZpfVDIuFwYUzZ4njcRyqVt6U=",true]},"modified":1716356405626}} \ No newline at end of file From 1f00fa6f4e8e2389510d9fee3d9a762de4f47e8b Mon Sep 17 00:00:00 2001 From: Max SCHMELLER Date: Wed, 22 May 2024 15:08:07 +0900 Subject: [PATCH 121/122] chore(gitconfig): exclude node_modules from git --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index e966ffdfb..f068ec8be 100644 --- a/.gitignore +++ b/.gitignore @@ -29,3 +29,6 @@ site/ # qcreator stuff CMakeLists.txt.user + +# pre-commit +node_modules/ From 0dc2cb591c603b4050ed2a6fee41314190369c9d Mon Sep 17 00:00:00 2001 From: amadeuszsz Date: Wed, 22 May 2024 16:10:46 +0900 Subject: [PATCH 122/122] fix(nebula_tests): missing serialization format Signed-off-by: amadeuszsz --- .../vls128/1614315746471294674/metadata.yaml | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/nebula_tests/data/velodyne/vls128/1614315746471294674/metadata.yaml b/nebula_tests/data/velodyne/vls128/1614315746471294674/metadata.yaml index 81489216f..87ad88ce1 100644 --- a/nebula_tests/data/velodyne/vls128/1614315746471294674/metadata.yaml +++ b/nebula_tests/data/velodyne/vls128/1614315746471294674/metadata.yaml @@ -2,15 +2,15 @@ rosbag2_bagfile_information: version: 5 storage_identifier: sqlite3 duration: - nanoseconds: 263164997 + nanoseconds: 277624032 starting_time: - nanoseconds_since_epoch: 1585897255313147068 + nanoseconds_since_epoch: 1614315746471294674 message_count: 4 topics_with_message_count: - topic_metadata: - name: /velodyne_packets + name: /sensing/lidar/top/velodyne_packets type: velodyne_msgs/msg/VelodyneScan - serialization_format: "" + serialization_format: cdr offered_qos_profiles: "" message_count: 4 compression_format: "" @@ -20,7 +20,7 @@ rosbag2_bagfile_information: files: - path: 1614315746471294674_0.db3 starting_time: - nanoseconds_since_epoch: 1585897255313147068 + nanoseconds_since_epoch: 1614315746471294674 duration: - nanoseconds: 263164997 - message_count: 4 \ No newline at end of file + nanoseconds: 277624032 + message_count: 4

    `?|8XipWUWJ3_WT&-Xds?>}(=Q1^M<*L6J> zKe6>ZCfDw!aWZA(eH6g5#p~$5Giso&wgxonX8@G?xj5h2( z`M9r=9N@a)`Mjr`(?}(7yKRdZ!Tsr^$3B9H!S-<2qM!JVN_Gy!ZAa2+@RlMnzc&pG zul~Pz)x;Go+E&o!(q)3K@mrA0NuftvK9OGw2H_TG4Z2oS2_lv{QPfI3N zP21r}ODst&*Ua^i`+hh+J zMT^89C{dCz&akzkYaILd9@DcBxh|huN1C3hj`!$2zlm?2XC%%tojy(mr$k8RSb8!QZfR6;2L>wucv|5w97F#cvEaQg zXW%FGWLmzghV*Y&Kz{2>vChh-)efh}$KO8;^)JCuOzT!9CDI_bR$9GTQC1H-0zbEfRBZlF2>)zkdwUE{|r|LQR0 zTIF&71+ni)7VB_7qC)2y*NRT$k8e_*sVnSjox=qVkAre^bE?>>0&0aT@W=d4+A=+d zZ1fbuLy_dBI`p0sqFn%eVI0H^D1mu zkWI%XeJ9TfE`wmmV=>nskYtbDD=ewZh?#=Z7iB@_z!P!K$;EF&v1tBB&g4rj|2H*- z`F0&?jgdDo519?uvYI*7SBj8aXoY3|iFEnm<$?eyHz*4Z5pzurIWeZW?}@OkUxH2Kg)L_hS}~W6U<8nSC<#X|H6yn|I(D zE}1{&^zBi5wKnVW_7(K?vxTL@`iVLHEq|Fm`i%q|UF!eC;HY34qP<$6OCm6dVWYa- zCz4vPjl;_|XvI<`c&1kap<5+*81qJmZcn6zzrIW+5j*O5_q&q2=-Ml+8(Jrkwx_7U zf=XZPSjf0+noNHCq(Ok$er_?#NY^@NfCiTb)21^YL|tzOqT91)+-yBLIGiNJkVn$O z2}h2ROVNX%ecWELzy31omk}9f(1`~N_={P-XtOq%j?FJ6rne76!@gQEuVl!wUf<>p zr|XgpJZ6-|;UwjS^z`X&E{zPzidU zAI1@E&YUoD9ocVh1tTo|C0Qj#MreQ7k;ZpR!|p@%&~BYC&U20`HbE_~Kiu$TiK0I{ z5xSJ)=$6vKtb?H(2838sf96T~a`rIZOP3a2tgR>gj|ajwmM!o<9^dzZA+|4Zr20uE z{IeYo;J|`2TpPP{E^W8ObM`WHNJfIkj=o@iPO?OI`s3(dsA}3md#u!<>)UP&ad=0E zPkl<19FifyR)UQkW|kDrjNi;*Vz7b zqQd>l+c?zkjiL&^AINw`W3&uVrZS(U;HRNG{MG!&8J%JL>?nV%Wpm@~|2T58vyazY z=q>JJ+WW{1Ba{8;oS%>Q7aIdSOBx$KUuu1TMrJR=G(9oLi=FjzQ!=seER zJOZNUnbT8jXR!_Q$GY@R`g=(Zd1)_z17EYb1x$zVww#0u?0%Rl7f=2!I0oKw za^f9dcut6uFU7Ka9x1Y@CR+5Qc)Q@yR7L(I^KsAV97^MR9`Ym2ZiD%U0`9LA%R|V` z1OMatv~qkqnd;RA!75Hv?uH7~dQQPzY|pwQ?L!=I%mtlal3m`^!VpLG455~Zsr&@f zAD~k#65mKK-?fDouO&E{<7t75&L&a=8!b_#^9nq^Hk;Z-ekaEC0{rb|`3bB~S&DhA zPBLAb`p#K`iXa&fICP5hpNoR^anQTZTtDqR{zv>)SSHKfVI^;35IhxR6D2ceU)e~= zKNiB>X-*)IC;WzZkt!YaObK>IAAsX=+ql1MziwqcH5n5n*!XLu6l{$t}y}v0BJIEN+c_uBCFE~cFKOF!Ad-if3 z0!5fP#U7QGZ>K@u5AyGh`Jm(aWNMdKN<8Kqg3otr#r;ZkKP<4o&WyG`GxGS&w06rr zFQx&LUy|@JLlh18&RKhO@+wua(98Ce9l8<3cWE@7l9i#6^OYdj?I2q1kQN4vT1Un| zF^8EN{^GfDTA2|xk8-7pLi&Ny$W}H>+@ePJONq|KTCh5j&nf6AfX^p}nWy`>#hOVX z--2RDJz!0>qEsM8^B`Vhd8(U>>PcI{atKAE$25SO7u>*R`){x(_84KLF$mYHxtj>yrUMjPswZJZ6NnT z!oQ!Y9*#llMpK2UW^C6>K^vB}5~El{uGjX%pTl2?xum*KGn~3wntFcs5@eD)ywF;* zn|}-R!L;xe`d^qV4DT_=_Y5arh8GcitwNBS-_Gf-QUrCTY5&paL4U?pxE~%8i+Z|S z=)F-N$jz|9s9q>XPc;7Em7PrS_j)NBHMB^;DY!ztsRT3SUv9>g71Bb3DT~M-&tLr1 zRLMMfOxBd$!xzw{`5pXO?*bSyKTpgh)sGy3<)a7EwVy!L@o6pO#F|r+0jlgq5{1Di zEeumSL7aO=!x^Oy7rbo-B>)@+05RgPp&*Pm;Q zx=Rh|#j#I#y`eY3g&yRpjTPY4qhtc8N>9d_f zM8&;}(KIQWzTWtqyjE<2=3kGvr#gyoDT!syFSnr&ug?|8)Js93Z72C(@8{brJ*?~b z%w@elz*~NfhM1o$%jLsFvf;Qltf+40Ha%iD!@$W{+Hs8jvd{;9U|tB#&7x# zGvBJxM?Fe#dO{1XJ#&i&KMW!}<8$Fh`Zg|wb#q8L8{t=@pWM|T%C9v3&PODcaTD0x zb>%Q0?67U2Z}zl{l9ep*OEJ6iOlToaJFkPXtrGowS_xK-u*F|N3>l?PAE*cO>zm7JYj&)2=Z>xE2q2usOe|lJqpa0L>qgy}P2+2KTrPqF+8v6HJ;u0;aB&%#)(y zWsrKsfi8aMOEwQo0Bx7MTx}4;C9P3t>=I5Z7H<&94-diWDJk?{RyWywTMM5lYf`Id zCD^>-BnW<|aC7Zgu9xa)T){ANOXp-FSABwC`AITcMtYm$Vz&4B?A3%~e{XDIp26#8 z$)wjM8O9i~&P1kJvQM|b^D$=hRH_tju|x+O9=_rDC5rG%i*Xq*q=mJ4$H?aK{XsvU z`S`jOVD@rv>|MrsxK@`E>x_ed_a%JL;k{Pa6l+O&brTPph6E(5meZ9N-w>^GW1JTB zo13BcoWIZ#4db6X&>PYbQwBu&bWTeZ34a zWA|}~l@)+w8lYvCGp!Fh&X=(qww@hlIBVu7YVtKjom46MsXESMC+p2sE|koW^2fW` z`yWk{C#XYdUa=elPq zLghshb~pB*|29;(Z<33{?Q`Skrm;O_l@9am>L}264!`-h|_G~T*GQqVS{`9r#Q=aq9gUhvf+;a9USbfm~XMG$-`RY}ekxWZWV9Ptg)_>UddRj#A^XefU~ zssTnuG;pqE?3T#7iiX|Mra8wJdPEpT;o|@=I_KbHlCteEMju@x9AsO=m)9K==YD9s zh$C7z3LsNWj%xL=?r-feSenQBI*a=R!6ZbaRV~5Bey>=6-&7O&>*ou8j^=f^zxN=w znkqnG%N{7Wt4~i)Zzs3p?t!YJ6aB|Dz%zD@!%s|;cImx0`SoEM$W9F7;#jXo%_3ub zdfAvh_Rr)UWWGT87@m9TtO)z1Ori9j+rY zUT<6)UqTxbcM6o*9sX3;dQNrfRV1 z_=@#JyfpsFDY{U8%<&I=OjQ~8Eld%bMr>dj1{vYcZSwpHTN4baN~S-?v=Eb~%W!JE zl33@Nxz-A^)4gcPqJ@Iv9(DYX+B#BJEe|5LLlyo}rMW-P@|W}Pp>$;l{cDRNs6GNlTt_^^B*utYeSq zOZ4c>_&I{@RTgYtliVRU96AO<=Euos^(8Y$#zJ)bU2*sEHTF!?72)(q;0D28kDk*hd=si4>hOCGcS z0;&nKzmCN{!O8TrdNQ$W*$Npc`#GNh3XqdzfnNJZur32x{@^k%-Q)%#BqYtcX) z-}{c6#OAt96)dCmy|geh^B4)RSAiv0_Hz6FD!}m1F4&`*OC!FO^J^ZB#ka96FKAII z%TzxAPlwit=gG}l7Pxfm2)Zl7#N)hb0^SS@qz2I+$ZthMTpjX)u##u8hX_84^|A7_KM#bJKsxLHrkE-1yU-9(~Mq$q`jx zcCvuetYsde#Y_hX()27Oi#iPp;QSkF+I2t$R@CNTDAOXoimxZb#w~!hv-`LPrZFfg zHo)DUqp3#z34Yh>7RVdg$h8$JfKe8^bF%)s!;|AY7V6C4O)4Zf*?0Ig_$`R0Z)T{2 zS#Js+n(>ad={zOh@5VwTUnTB7zT~5ity4zPhZ?4Q%I-uw(49m{b~X8xERBsPBsf{F z$oO;*MLOk=ufXQiIbKyLnIT_~Ho^e*-G9EMh}87#hrV6yTtDV*nZ`X4`2b2wgoE=^7M9Tk|d*;{wPKkf_j^i7z%2KTXf z&wyJ*E~|9&-#WcHCsWoH`_=*#j|b5Pe9s&H%>~8Nk~^g8APby6U59=jcTTixrm!iE z`6*6D&F7Y^T>ysXB$(MfYYqAW>o|B?NrrE8gc6#=RYfX5L9GK`__T@k1xNCKtybbf zt7Q7@RXX`KwHCIdHgIjZEDMokOieqeOP}st;xTCU77VyKfvQ_~5tD}p(6nrgu*sx` z@#BRMa?*h|)Wng9$p_%<6ghDwo}AQ3{O21(<8%HB4CPI6)hBa$tL-gcUVQ}~mL24- zGQN69QYH+NH=xgB+Q|lw7MSnrL?2&Kf%Qc~?22Sr);GP$yn-pPEhkLO@8D8Bj2vb_ zuk@w!>kf27RfmY%e@y}IXd6L;VkM{djrE1edZMoa>!Z@}Eq@xF3}3i-URdJuFBbQI5%5iA!d z^1g&O-}cuFxw;a1yI`k4afU6N9vRAQS+$j1$m<4?i5k7os{{(6+D*@NbcKP7%Sd1Q zUO4_*vV(7AI-k}4Ke--T%J+3Y1)7}mcO84pV&Et$Ph~cM}aSO?O zc^;n5lgyJhKDeS=+-%xs8zL~iR?Rp5sUwH4GM#*@3334g=!)QrylX-mMs}9c+{%4K zwMzlUJiEc2RZ@a6%(r`*X~{$j?hE41ABW8`{pn8sUefkT4&7Qt)6*HMFm!4xtjLPz zCViHNCsPdZNQ64AkPhYz!U~{qe+cz-Q-_T#hy1m3IMo{K+~~J@C61rU`uid)N#pt_ z;J*BsxbIju)B#OT8PE%_<_l`?n}OYH34Wd~EQFjE2P${fm+=&la3f!WpTqV$VwPP5 zeW18e5PB&Pld4nb#5diHk5j|h3_t&Ot90_bhf;|^Ri_7#hNyB_;wZsVt8->J@sqUh z(9Ow2)8;ULlJPkI^T-EG9*QlYNz{kefD@V=j^CI}E2WajjV7mvoF+F#X)A`w}dzGy1IQ|qU};vZ z5k9{mpi>8_z_6SXj6W*imV_$6L>FTmo-0k`)+dV;rsTq$K5J@uPzAOrW#NcI_N@u2 zC({kP|LbRWv58dAN$4%s-n;EKNm>umZr;xqDpNt?ORYp9^T6Vzr1$t zg)f`)Ia9o&!|qNk)$adNBk@{r9DOO>L)upkMkh@bnx`xc36tG$wdx>hoQQ$}KaAi5 z>$%YSqy#3vm*d>C(!zzq7ZI)DZ+PEplDlQmRa5LzT}{LOz2~pr&VlLACA@iemKok* znqlAH=R^UMXMly21=U@s3da3c;MA+q!m}NfWXNJ$NDa>6Trw44bE_@he-lp6(9Qhl zg-h|*SP6bcrdPr2ga+~5^5Y&0RBO?tVZ}>4X77l`$nlft;v3J&k;Xib|KULG9>o#m zlQ}RpLXLhLqXdT&T=2@sIJ$ML6uBZ7BKjSgDflm6i7&ipjPuRR>7tZ3{L++5Fy_rc zu8aAkqO8(E+020c&T1zI``-Y4p%dL$t^%sm2ZGwdxbj8vV6=WH<4=vLiF79KJpTh! z2C~X?MMY>0(t{CxmE3x!+o=~4e6CqcC#buM4qTprYa_F%+uL3;v92D@2R`Q1)fB-) z$^k>VT&cOiazVV}55C`h$qxQ%pe{C#|Hci@%;%43Erwl#9qH2NYzL>KVTD->=kiAp z&eo5^Bdkl}WkZ%=c0ViFxFwVe-Mp2gzJ3Q&ma5TjgOwp_SSx-teL(LiZz3axWI=*u z632<;Vdf(?bLvS^WAAaiXyOCDu2F)S7t9jS>8AuUKU^My)svFwl+Ig3hIwPp$4c&& z!*@8NbMPE`LV3MFq4*?!eS4kQBd@h}IId;)mWQ)1@waW8@$iXa+LDn?E{&Ff%R_E* z%`6|@%{>9r`VSOdoqb>69(Vu>8Wbtl`hsXokj3VAquEZX3b(cyG)x*z74siL1d`#!)a&E@>ve#^@h-x73xsiV2kD#!l_fHb7On> zQv5iB%@PYL$)aVCAhY(F_?{{6XOB7^hE$K;5HjAHfa1S?;*61Pr}7||&0znVMIY@7 zgFNP$Rm@TZz;$-48`w%auXZ()DiY3y&?w?hMjr2?!ENv1_# zlSmK7fj65=|Hp}IueQQ_`VKUHi6VczI}0`5CD9Oin*2Vih29$PI8Wv;GiT2?W6uvv zI7Z658@=uY}}f5-g1zy$9p}*YR|3 zEm_>E4?#5&ENz%&h^hZPXjG&!Y*#t~WA;d})c6C-Bf2O}GqaOLpW^qyE+-qBdPxOt zdhEf8d!>ca^XrM3(i|9iO@gIO7uij(#*04oXynb0-GX86Y%XPc^vt8I2V|){ZL&=A zSiPU)AI>o1;@REc+nNW^xI;3R9-5Va+all54bo4E?T~Po>su|(s~^^CiMMU0&}E+g z@ojZ+m@$Oie&egj=rw=f!0%UFti2L^e5jAFo=MU3<2(hUR#fpt}DRZ1YI;~ zV0Rv$A`;w@1-|zrb1D3?#gm(6(!}~EciUSVQ4|?Rr#}Bo)?OQo7iXzaLj_qFVK@pG znGK?YLQuf{7z_cjeO!vNGE~+s#Lvt(VQ8?3V8SzA{hQ>TS?*?!Edyg|cY+kmIKCJ9 z>*RB}F$$1wYl_!zutb@b^P=_o-jM2SK}W=@LLDr`E7zrk-)>hDD~l0uKP89rXZiuB z&n!#)ZWMi~5ySttei53moGanobkeGF5`Hu_i2a*WM_b^k+#z(7_Hqxoh8Wy@&6m#I z^qMpu&4vq&_B8uVEUE6>1FpN|=s4C@G4;Yqk*0r!*cU&JY0Um@F{k;>Z}Vr~+vT9DYBXPUoJRN`kY-gHd&uIB%qF*ATp9 zJB&_SkjWn!{|+YV0q4Rvl=AaBFsi1K(`NI(%OQ8H|5rl)s{JP#9O;X15?BUZYcH8p zRRbqWAB+2uXMA?X-RojyL5{vg`9;+ z6-v~b@kes=T=1g%0y^1alOTOfCGVqIFV$2|ZDhnp7#loi78Le10ehmz_UMIxm!fd44MQ z$yEVfJL}@7pVGp^IGNm*+Q-YfO6Jd7CkJ3^;Wp}XRvq3)M?ui-{oF=5mI145gTGgd zq)!yoc)8kL*k3i7UN$*RRxi=Osp{{!$RCOj`e+c^{F4?oY&}MP&;QFWH^}Dt4`ZH* zJ#OeY@;H5?hWuWOQFx4LYZnYJB`TZufMQUcm^U9Ru*Se@S9;3G-s9HzcvQF^Ld`tC zk!=QM*w?B^^<}^F8BtTfNr~+>3@7)mng_e0Wtaz$@#c#*;5yn#H5X4IeKT}Htw(~B z+Xm~Q_j#84_gER^hm=9^?E2KR{ao&WjRHIk*24kw2+jCY!zVUh1*LF?lZ-1rdXr@z4N{Oh8^dt3ioi+?y&#ezJXZ9_N?CyMPx?D zF341TAm)8!?z1`e_$=B~e$IW`&-J)GJdU=PeI}2sm=CT*gXXHsf%GX?e8FbUFM24L zhy7vwyMJ8dS0ykHoQ;at7*1*~BBPrh^JeNkVja<$eKz?0VJy}CPa0C!`(ZNEF0Obs zgG@=^1LLRUbH8^pPAz5_eh(T%rDv8lYQ#f%X zhfB{_V7@~O{8t`H1J6eB8kv6hm~{%YUrr|-DHYIPhWQKF{?5{!vCqbUPP1I)ks2I} z_KRlF{f_U+>)PFLOWKjHy&6YOPu&UEE9B_8sY)>JkUlE@HD`TcZ+Xq2RUlO%OcYNzD7CmwE!kY~Xy-E<7M`H-^LV7~}BZ`P7B@F z2s)&Cc(3>_F%SM}7t6WomZh$)rTi(gNwCevk@8O_lJ*>1=)Y2ejg`kjvB#v7-cbgD zZLA68xP)=dwOh$Sx98w|Mva=dD}w>u30ZzgTtNl%`Mx&5nM-78^%rmc%iv3V;Cl%+ zTJ1=|kLOK=+s0b)f~bKQn8PxNiknGWUIUE3q(o=DQi84OPS~|%Aw54QTrlZj8SgSu zf{l6IhWJxan^M+6xuxzpzT!%#^Vw`dgFo=ut`cl~zA+Ii?ivZ*Z@(4HR!f6(cl)@a zTWusy;}19wcB8p*s-W!Who4wpI$f?wyb3lzQCB=?%Jx=)ksc;zupWmi>v;LaX)u>z zR!vo(?QG`KYW|M%hCuu5{J>n_~yekRsf@+_O>(M=2bYw{|=B}Zd;?j^y- zuG70=pS+_O8!w&Voo1?5=2=uNFsGUnY*c$X%@!l~W+spK-;t#0J3(iPy?F*7W&SE2oO zr+Mu9ZpX)z7>WCi2O3<5;KFG7d#pM<*|!E8Lpo_c*Lx(?FBp_Av0f5(Q#EuqWxTL2 zO)nV5&#Byu7X=bL?0WqTRF}RM`-5hi*kQ?0#u5KrB*^M0csg83gNEwWV`eN-(X`zwKB4THEpFiU2!<7wTotvq%@zUgEI{WGjve#i3B#qA(>($Md znq#A_0gbG=E-F6$A6(yWK_{PAg%dWuSlTWvyor@$&Us^Sx|PGJu}tzJ7YocZi=pZ1 zv3%l@*=W2dnYz`cljW_);k)8#u|HjEzd0r>HK0INd3<^si;>S~(>;&6$(PgH;kz2^ zNV*h9CS_zmU9B7qnV2Z}yz*)8t!xTIi$({miC=hpAMMLCnL z&OF2kEEGWVdL;~<>_-Dn>2MjJ&%&S8PGaw*@%2(X!#F8kpvZ-Z5FR=`$ zgpdc1ITNtlkvWlQ zUAKS(yIQy}dP-oe^dI`&FQ=K-&$4BueBS1IF~4)-f(dHZ>d_-C3nH)S8k*&m(v8=0Nb>J4zGeDN?x>v-WIT_> zhgXe+n#bP?%9kfW#q~aJTtyq1VDugKu5qLCWvY-gaU!}rjG=xB3Zz?ZJzVdXAih;b zKh?)}CvDo~6V6Y+wH5rguBT_1C+Q~Z@X`#5p+D3|HKwum#FV`!1uB(fZdMDd>3b&b z;25sqgezSw>FuMd1X~OZ;msI1aTmO2{dOo&cBBnwd@~Z`?$qFiecOTQO#64?WdnIXNewR*zUM9t zRf6PeJ-lOx1OvYgABB<6Dya8>3%s4IGrrlDOkI0RNWEYuoT#Z2cW8QyvBSOwcdA(J z>JiuxgNxZrxaH?pa{PrcX6{g+FPDDh=c@~W43f-*by-tcmyZlByrcwyYZ%Uq>!dfm zrVu}ifzZFvpJPZ1=Q9W4yHf&s{G>9Bk0^mH<_9_T?FwK!P!HuENYkHVl0`zhG$=e| zLz{l6KnDE+R^ri3oiuCMJu*cz5HwF#i#?KK92hqm z>`xaujpKWcZo*c#WLo21O|F#mz@dE-47}W9jV2ZS>8Bfu1o=t1{4<7u|CKJ8OyWZ z&eiewp5b2S$A!deLJL37z(>q?Hx*3BUF^1FS}}u6`?>@A{PV>ca>bcO_^x6wb*a86 z`aa$cWGgJF;Wbr=e={CcnI24quOut1^}#DsqWMwxGRLsWIC^_uJnz#u9ltWYO?go| z>2xfCq2{N#t}Uz&*Tot=v`neN>rjvDbK>yF3O_nJ{tE$2fkL)R{tx%uWK-d1uN+;p zneh|~$1pouTA1J-OB(8@i5mGN!RB5mzMW}1Ewe^auDFlSiWWijjziom7X=vlvL0?m zIMM(1s6c|=F$~`>EmV8~4g^ecmDS{>XEEw=9*azN!^A(c@M z6S!5q2opdOA8I$ zRV~p1t=>?yF4U$Uu7vZ;Q=-5{E|mW4RA*feR%mm7EA3uN8a*1O<6owAiTYYWdgE`w z-$~EKGhS_pJ&u}XN$>7oCHNPv58B%$GoE)@3Or{s|F8mIa{Kyx=$R&&@%D7h!5wvJ zbino=;`mq=&kWEK<5+#2VUw}$VBy=&Ix^Hg)uOOh?YDRjPbw}W+zadO3^_9e2 zHNxusN;I$NJFlPR05#L#7d>TvbFKYobsq`wB`@_ZC0&@^ z;;wOdCC}vX2Y0R0iuL4qx1p z7W%(iNXGVF=dWk^aCEdhgb#H<+2C~gevc|ltC@nYnHKuX&KYFG12#t;%ol5Tyjk}C zjwBPRnsP^E_Q4c7E?H3izAEdQFVR%(?7Hbq?k87J^PtDFv}s$7HE2 z#7{cGO)63Zed%fFmETN9r7RIOdI<1kVK&_m)=O;MN+6VZZ~w=k>~wR$`}SV++QdzQ zxoNL?ALFOu-S)Z@XK#-$V(9j+u@p?zhmM z71e^9{zG8eEeWO_@wpEreH5sLWHPI@9CTWh=<8Y~=!!YQpZroM&RXBK)(B6@45dAHZ}XaMSNWN2PFu;k zK@G>p0u;j@ zw4PwNryfdob*KZD|A!xMeW%CXJSQ1<9P!K54C*yzQsZ3q4lH2rz{Lj@q|WF%SdV=! z?m&M<>~ML|2dbVL8lt?}s)i=jaN{ht`oV+Jzub)5P3|+vBag_C;6jc0YOe$;o4F zVltf@sR=7AgTQan0kQTbWSueUN4V1D4i!GLIu*MtlIi!n2Ga0V5glfK;2xMVzozmd ze$tU_PKN0urA#Jc*1Kl9aO``21>>3*=OxqZ+a*NLI~D9@>&1E-w=tF&6(XRIdPjQH zFW!iAl-AQ%d0)xVv8?Ciq$;)S`NQYrn#1uSjx^b4xVsWI6$U-XbV)uHiawD!^@)eWX>sg8GE}@L|ns zam6&&IXj@5Y~$X;f}wB3I>+)_8~L&`npD2?P&Q_#bQ@`yZxVFe``mj~(cvj9FxI z-8P8Z`#|jPn{vet2h$+B{qbG*hObM}WltQkYyRU2QsXuM*5!(}C9cNJl1Y zB#O1~`MlYE+!u9a==B(l0gt7H2cIq^7N0NjL+AU5{Ve<5*kbvs4C?w@4fHQ~2_dh}}(eJdLZozj-HP+ASfOd5^zUr7rKj#ZM@RoW0A zwU5g(RD^j8>~OE=b~?vk2Vefc8=YC#hGlp<(HeLJ!ctC)JI)HVtg!H^1zpe^?(xMg z4zIuVr(XI$NkT*nydTDP5T>i?+8z(u`ttN-f)d<5Re(>JZa-#3ELk$n7|Z63q>n%S z<447{U~APa8aVbO2|UvP-^&hhDQr)dX?DZq`z8v{w0;%zwN${ZEGG)7Dp1)}fcybz zVGoPg`&%`V?U)hu$w4EufU{O66L z^kzC~!4lD?kE8L;v1~eSUN0$8JPKExJGd1;72vqTfB0_YR9cf7FGxK2g8#Dfsn|pP zsKyZ8ZqOF{TjgA;G%sL4)A7rDT3<5^ljdrhj&i?GR}9>428>22ON;D=~1m z15pg?I`oyHBEhU_^<;P9&N+99TV)DJKakw?ECYt)4|jDM_R^2Xodf1BN?%^6kL8A&kpdMq7hsYuS;UI9~_ z6T}|CMArQ@wA+yC)Nkdj?ktAQxuLY5r3SdPIk1|eAN05E3v%t5H%?}rIOmHMB<$a1 zSRD79qYQfwEwjfc6iHRJC#Cmsvm8BVW`z zC&9oyr~9B`fflW0x^&a0gPUsa4ife#)sl}|2VwE7G%=SkS}}pQKO^z89J$;N=d=Cd z=yXjOUKj{lXGt)y|^24di;h#~GDxPz>#r7g6be^ijo z)h$&7K~WS=VtHt-3jIN_&H}ZMCDZ+POGt5E3M5$9i#sMpwcB9t5l=d(%iUwB?FLMF z8$u0&zmg;04KYTbLR-iF;(zO#!oQ&s47~Wl4Mz8qr7=vmek-T%lu{>eJ@O4weH zcX_J(+V_$fkFsn`y_6XGdapYCST+xCSk;K{a@8zPKu2dCb*-4ehsv+U`l&1v{&N*+ z9{dKTdb|&2MJG+ zXJCbaqpYakjYp#7PGM7iiM4P_(Rxnm*Z|1;X+fpGs>1SRPAJ8={;0!DTRTh(Qm60Z zR(w!^F6MJ@`fmrFA(hFGwjYnV|9k%0bP}3-2xQA7c-WI_iP1%tv`IG7OB()JNtR3n3Q*q>*O*9M<%F|;9l%RghRMgvDP7U*|$kDwsMN0c5^WK+SW87Od znvScKh5-e2Aob{w*az*W?tn4}Cko|ne--rDl*0bY5}me|*8yC4SX%hD8i@8DXXvxv z$hAkvgU7icXm-JodM(c99lRbw-~<$Nz6l4u@Gc>eeYWAmI6V8Ug{og)D%#uOiV;=W z)NxWTY1KOnu&9HZ`cDD&%yhw18>do!bG+d5!>9bFzNh4Wd6LKG8KC`M75d(~iqC4$ zgF;tFI``y6LTa?&m1e7W_DlENh!?bFgiC@t1jU5|p!stc=fiI$=lyTPITdxPs-q12 zli^KK-tNLCo4W+Nl0fmh1P>jD8sasgN-yWn;fDoe^J$*t+@}4CAgg)=lMbyBjv2av zzZX&r>)6eZj7=twX0ptUKN8Jhh@~qYnHx^OxTLavp922tsd{p0y*v~@G{h5M4e2`m zE`K(pnm-yV!NX^#*TW-MDLSpKjl2(d3UV!y`S5(w7_{CROM@>dkdo-7uzp#Bn9DF) zqmP#o_388d@%**>!lvtm*1|!=i~BrtCfqRzqnkn*HtJiUN5^-n)B2pev7dncFOSl) zX(5fPY{p|{STa3)vV!RKy9kwMo{RZk-Evo~y5dTg?}-xR_YMNpuM(UrlHUlg?O86( zVPC=%Z*Xg9ZLTgz`lprH~)rX>$JrD@A|ugn*RGR zNGRy5A%FOnk=_|37pD4z^Suaal4N-jvX_B zUXvTbPdk~2}le;5YT zvChr&CFJC|M40U%nH#&7Sfaa>7yb9!-Gke-7UvtSr{gDnC4-!dv1N@0^{tSC0^tBi zRd%2UEH@Ey&<-?QW$D#{%8+Taj-{_i3pdPSdYGefU<`}J{^+BMDtKTip}OakLHct( zylIu}#XW}R_~-gSs$sOLujyb7|VD$7+Npk*ztVp+uV{?(E7FI_>oSb~|hK`giD z#Y#FR`2nB1F917OmS&=0Ct2Ek8jgFP73c5_skB6)?I3D?Z?A`5g)Fbx&sf~cV;och z$#-Mu`C4_@c4#IMvvJ3yPR{H6rg9PVMd2hh_K!^jGSX8u%8A17<73^q#ESpJ;N zkT({Rxyp@v^hF=;jGa7mytc$?3p1&&k0$icu}GQkW5?VX#E&MykoWoA&2R+>Wg7lc zD=R8WeI(NM%)wjCn-lm;M2?SR{JM@MRhCnOfrG8Fg6UfC?W-hv*iCR2!%xj83Q(@) ziY`^TRA=LU-gClOERIU1vlgY3zyI=~<(33LBje3+->?xhduyb}`BR(m#RGr(ZPyR- zxHkyqTRPJ2qfB#Hu@Q8pO7QdgB5w@4QAU5B8$rH#PZaGgO&4eN)O!p=jYA%E?96^} zXJ69s}3Pxvbi&&2q-!POWQ(q zZycZSMsJGwfK&;7w!{a4V2l*~dAW`B?|TGU7v03#>=(mFGe1Zi^F}F>y`767H&JpY zToY@A!Tp9)FV!S|ci=c!(-uk(d1yd?2NV49NrIXCFMHv;m&J7Aps>bNud&#~boKr7 zDu`NL6YRSr*{?r7a>9ZNSE@BKO7MA<4s39i7yG7X_XI(YDf18|`H~pU6LN1!Fw;H9 z8w3BAQQhtmL9*fmth|y&i`9DA4E7zimub;e%}Ox9{Q#`rohJ4G9^V(lFX@)-*Adft zq5ToNsg`Jha==2kazcWWRm?Bx`FS$!W7&rKd0R0-j`{e$)|1KKWYN7{GFz5UILF(4 z&*m=dRfLS@NJ4L{m6df8y^OsG<*JC-?e00 zxePqAS;B=l$;0MsMU;I==wBHXSbYBgpur(-c_quhdC2(dJvuZ|J5RJMdJz2&5x0;4iW6Li0)5quFXT}A`um41h0<|#Wvo=-grwm(b z@8Iz~pm(-~k(7T;{DE(MoY7Qe@VjM#&R->SrsA|(-u9scC*O`R!*?fHFI9#noLffl z1kg>#ZNu$xnzBkm87&P(Q=Rj? z&k;g|C=?}0LK&s3ifC&nS|}-_Aw?0+b3fTcLN;$7ea^+OVf4u9slxCF-vt|Ei@?cyJXZOk0$Or8G^&yL?yCXy)>wjZtb}LY zeW*|SPPpJ}AIr#1>HBc_8s!#mU_8ySo%l3Wb6=h*f$90}v{8PL(C^d%(fmnP)RgYU zM@RfXqDO^bviCW+<+~!xGPk1!Sw6V!)J{Qp%M)_7{H53{ed_uMIxS=%-uvhrS$30o zX0ReP>N~vE1NpNEQTr&L`D&5^U@cG2VX77{_mYPNY`uBlk*fahsf# zp>*m}aONbtM;V2O(4gxgp0(3w_`)A;5TeWD85X5gp{MM{MIU!?o{GvK!)Ao%S@!t+ zqfG*J$3dXypdi)|#{CL_%T{a--R6ldtQ3IMkO$m6_PKCXlWAdlB_4MAm>_x3TPk!_4=0%@=}? z7IF^5SibanORBzbCXP)tAXk2Dr+1m3V)L)l=*d!9daCCWXRg8gVn>14z2D1Ov%CDz zUwTwnorqWNKZ>rIY=ieFPjftZB`9qhOV5VS!3&R1l!lgzk{gQ0TSc1p9N{5S zD&Qtt2u|%qVjs$$d}I3S=@1<3y-%cn+z*a7S>cK@RXF^28Et32-QO?k(S&*%umcHK zEL&wv>#SB{m*D55q&<+H8!y4Y@k*ybbn(1cN8KR9dVas^V5^mR{0{-IL>C80xZ;Ts ztfTE;3|2YA@<)rOLBL%J2G+E)JYmM`ChPfhHNxOy_p> zo&`O6!~p*|5-wQmF`KOTDdCE)bMjyW>jnyRpNGarM?l=zC*od)DGC;Jnte20`R|46 z4d#y+9L_X>qrM>1of>q7`w)yBc%b{@E_I7*#M7!Hk!Iyd@};+*tDnw;>#_P&>YKE% z`0^rjHLRNSi6ol9x>-i_vPuSic~1jo_iuyH#RoXQBg_vjXHEyP?~D1r4w0F0Hnosq zonM(E)UMD){AQWqcyl!{*riYV|1lkP)^W6OsT_nH%;N^}*etWog$Bkk%y&#h*V^-- z!tN{=TBZndSXbco5B9il%}zdN8$soV2H=Yeexe_uv!L83CtNXMDjD1D4dWQ@S>?o` z%3Hx;6sv$EPOy9}^Gv$wfVA+_=NMGKek84bItkxly9MFI6QFqZAU85l5gx1nF!4|l zPRl(c&`T|V$#LWHZ`Qr?&L@*zVKc&_VnFF*%pqfEr1(ahR4|fut4zj0-;a~Z33p-n zJ1W)+_IckYdml=$Zm(esRZtov9DC$|=+R3vI;dtZ^PKjen>BeLI{KVD%DBDBJ$t%h z^&%X}C9{66M{GWQh5j92euQ^J>4^0zSax#_;h*?JMopDq-F81InA0NRgk4FjgW*5~ zck*34I=by59QIZh?-h4d={9Z%b`@T_cMr`s-Ud^qB#L_(w#ezxIZhh*PKGZrEnQD+ zrdM*syO>`)D;M^v*q%TVX$xLlohq>K$tAKr5`0?`WJqnk zo8a1~Z6xwVCh@3{;M+@gKR6jAg^#_ukNoTJz;Y88JfubyT6X)u1<`gc;+Fz=kGFtz zz3cFOHw_rERX}zB9m8**M4lTI<3jf&vD}{MDl~icIk41!Exwy9kFcXihL5**Zxbw< ztObXrD2V$Mig`XTRv_VZAG4j{;=%{q9Ol!>$raK;hpVt4s9aF>2hrV(*Ll!x)Zf_! znq33%#iz=Uo0JQi6;rvFzDzSV#G7pTDcKpm)O`bIWRq}e9lHe^ZJ?+9+p*u2=g9EN zT*&!V$lZ2Pgil*c=>1VM@X9cK;yELhKC4T>s?Ln#9b~Y6Qho-Jn$NTQ|5%muriAtD+@1egspnX6VJ1^rw4_ZLG?n(=5 z$A=-iYd^{B$R*-F1-e3(CI)kOpsNa;AK*uQ+!Jwef*&&Aa)CF!m|I%Fv~Ww!=+)u+ z*e0(;BwRTi)|*)4i07(s@zs1fi)nW|9@e81QsyxIo8-2#VTd&y^D7olI>@%DKYZyU zZ`K>Gn~9p7YvG~1NPK76Jj{ev>+0el&wPG+af|5NWFv9MqT-v~p!PlnXB<)ogX&3O z!K>qz3}xJ4qZ$2jek1;!F0#RbI-PXDZrUG3h9k0Q6yy9~R*2B&Nl(efC^LN7O${!Lmjd6G zJdPSO577`8x^GSe{`kIvL}fVA;faYj#Vi%YnC*oN4rj&plxcmIv{=;%Z+V@-fBSq5 zojoD|JC6B@=Ji)Vnzp=fuSu`(Bshe>mYYAlKB)YS$DRllJIWMA%RKa9@w5g z9#7R!1>v*xw8f_#&j~3*yar>it&rfJ+)7; zn%nVS398-MZSmb`;eqxV7Qw>2ir4qzr{8-}Z1Em=_(a0-CVGvdQNtEt^Y2N5Tc-EP zj*F66c=z!Uw06}{+*m|OW%(Pj$%SQwPG z-~V`>l$J03H93)GG3lUjOJm_2>-hUm2l$!kjXy5c#G6eQk(tT<%-LVT>FO%M5btd8 z`(=Ymv=Y(8L3<%BlqdF#3=bSb{W7<(Jh4>4w<9@Z>%ueQ+?(Ue4Cs;#rdY+do%9Cn zB)LtuxQ3}L7kbn@cpM>xz2DzQvlre3FJl+{_JAs^{ptmE&n3KW8rxweI-21YK@%WRQ&&d}%Qorm(?6|TD4bnOT&+T7}dk}O39Vo{W;_B%; z1*ID_Atp+~<-F%@gq~c$3cj+iPH_fMc88LV_C(9Kv#x~257_rY2~x;95hk2aB9xbi5Wlbe7FH>yDzP z1CdZ*bB0SXRRZmPbNXb{JS=bL!Ef~ppugSMV&#%=sAK3bTJk^>k6tegrM(Y{#~NE4 z`XdUt9Mpo%hb4HJ+dZ2$-e3jhaSE^sYFzniDBXhYwXpc%DQ7_(+TYMy8B)|QWA}Zu|ondnDKH5?o*5@&_IiD6y9$MmsXT_OJzpNNA0 zNit?9E2qIKek>0BqzA>$6>~MCrO#o8Q-?xsgwQ5uz5aIoAof3uBt_`&mTh6 ztoPg&z9j!s?W-w{xf&zrF}ER?M&@uxiOswd)1ijp;bQ%HsA*{kMC^LPWt1tw4?`0w zD&CBZ?{v7{Lmu=E+sSA*b)f-HDztv31P=u|xx`0Vf`PNX9wN%ElH1A{q|GvE)A6@9 zb&v}#r;RDn!dXMFp?`ljLvP{%?lSXhc-|R9SCl&8T|u8kp9f^nHO!OVI8KBHthq*R zW|`sUd1|2jv6qx|<#9vp*lZP@&1RyrV(niW>z9A7>WW3DlleUftLYol06f397x`%J zhbQXt!WomMlH+AUsC;9?v_Ns_*LNQ%JEeegZYhIi=xQ3tJUjQs`=NCUoJ49vQw3L6 z%8{pon6KP)8a63Xh3!`>;Fop@=M>Je*?$&;&U_`|#r#8pg6K^6RW=@vR8?hpVyo%? zpmuz7Q5iCrG7{8VB)IqM$p~t+%mZ)mJVh$1Zi1{yqgWHzy}Xe$Uasb%*&bfDY6o>- zy5i;UYDC71SpI6$UR?dS2L;CLh9N!Ax!qliZ`6*Zt&bPs_p_4)d+8lgR`*JLQ{Ft< zf)0rpf%$uy$%mr5WT>$%R*0C2R%pH>RUajMFS<|$CY+PtUSY{OXv$K@aqJf6t>#1R zSuU313vJ{ucnheVNfc`WE7lp%rp&=u{cRArxY~m}|6IY1o4~Tfm#4$s!M6B|ZX!yy z-wpPgCAepCJ&Rm5I)fffQh=8;Mp5Sk8$841BWbu4L3BE9al7U!gW7V(Kl}9PTL&}TU7tdPYX-pcXX|lY zqXw8=aAaE3O8mHbg0|q-+-pr`kS$}`Usgig?Y>iRgWV(3 zb0xS}eP}6Mjsm=$lZ7RJg^+J&i!B2@(ScM;c(Gl=1Gl_!q90yVVe^P`f&M*5y5j_! zXJ>Syy?t-s$uuooAj5-+)!7icAXPli>P~ehR!R=yEW`l;PgxEU%hOw@3AM3ougfx! zT@9b3>76qn#AqLPR;UPfey}dfb^iD<8bfxPY^H}C8Fyvbs>^Quh0O;)i)Y&w!^1@X z=Uy%^S_x{7?x0Wpj27JKRn68i!bBg zPp5Ee@u-w<=)o6VDm88(R^2HJg*WaJMK%lkr=>Y|Llbr$m0;a@tywhwwzRNID-0>T z_(BHeNw}ZVU@6*Jz~K{9RN%Xo4+WMNRPXMG>SpJ_vU$Z~T}`!u3B7n!A9wbai2REY zY&W&Wh4)m!MQ;{e!SJ)-N+p&cXK2|8u5*vCf$^y6J%rJaQDt@a*8e}CA5l@0xgO{^DH zWxnYp%WKiybFC0`^gVZrJ#PnAj-}4;O>s_ajKCn=kT_`Pa4UW(!cO;O@MZdkjoS0j zc^n8fMBbL7JMH_2TP~pL3`D~t?n?*%8(WYN?$`qmqfw8)B|FDV2GbN?dMIvTl>32 z19W%MB9{MlTwjFFd)E=ab&{RlD&}j5znI6plTm^XZ!%%{+Oy()9erRy!!NjE(-A5B z%dVkxvvUAmce@wuVpzR;q`c5(@l>+yw-ZE;v&E~o$DyWxS+I)nI^ktysMT9ea~U6N zG515V+<1{Rmm(OSE=x}T)u-!wr{bIJp7k;B82p)6!ad&3?ktc68~v4p(fbbxuI)~R zTW`i=DO*)=w_-mhq#ffKWoYb;;jAw}a^u+7Y(#l4X5t3_dNT9pbvWiF!MFE$r^&t- z)tvebCCIzJi#kyUq1~@bBL3zKkmI+BJstnz?dW6M5UgLCAuy1=O~(0mAe|Zoz(FJE z*-g4wW$k4mw0TCHy6)|`ej$JNE&jpaICRDt1G-z9DIa(pyc z-b@txf2FqR(V~Zgaf`t+^6;56*>kv(Tgvny{!5af|~dT@)hu*fqJp#%@uEFUkPVSm0hpw{cHu+pb=Qh!<&Oj;yd zuKAh|?MZCGyLo%hy}dq`u47#8mSYu~eyj$J5+z*jQi2_|@|cXxWs?M6?C-d7L^98| z8_k5~&43M%Ecmm%-*87;T;}bGXsrpfHb3At8Y;tspTYEtT{|9e`iWpr`*_-MHU+P6 z?MBnyzJk;s38pSb!5FTb99cO+e#~8yn_VO3R#wy=D;O*x|9#!YyJXS5V01!hkio` z4i2LOQU_y&74mTPyDZodS=_Xm2k+)jq=Gh<{iPg+vOm2hf;USzDNhBs9`*y`b2KGraa^jNm0`kU4`SbE~Y|4iK`;hxc;xP)D>M1Ppu1^|O6! zcexpzr?L}&Px=sA%=OM|J%`dezT;Wx)|?#_EXe5AeCnP z=i~l-9z_EjW{_9=+kF!}{ z44}{am^WvL9~u;FChEGkL$LGgUy;dn=E2!Ljd{mZL3ha!C`v8ix>;V$r=8nj`7$M8 zchMoi-mC=Jp~zBQ**tsYLjbkk(T*?7EJHy#dT?y{22LTHU%*K-Fb$=TwD9|=f?={a{)^KewJGE91vM#i3(%%>r?#&pGcCv3I!2iZ|F znaC`e(4SaQtFL;(_YD}nz`>h90-?S-KFjls?Yw%lSF~~As(0>RS{!rpw#5cBJW*kh z5&UR*z!?u=KJGW$XgteHta;KWaBm$;PuHg4yQf!>;S%0fO%NSz!+5fbEPm_-`pOFpjM!u+xeR{8pStch^f(@T+sn_CFcy#F! zzD?6Sx;Szzj-Bug8K~>hj8WS74BMxz<9?BZTe5iZ1|B@pW*Ob@C79;Cw~b^;1&T54 zA-@~!+d0-ppaPpVd9Xb&^Jts-Ay1qRau16+4VDd9nqfkZC5^&5Cyt3m#*c;}S=P8m zOAWLxxX{op)~h9|M_KmTVAPn;&3VK;kLI@Yvrjs9NMs$vLJ#_AMIxSjJp;w090AWv zkvOlwVvGgdX2tgKwTJn-Ym-E76O6)X$vfDccUK)(!sdk}rd=;N zoQCgTizb@;rqcv=i(F$>i#}U6!)nD3VxBgWbzy%3comfWo#F^q$y7yej9>cx$$7Y zo(1IBcnMEalFlZ*^F72q4*P0#8vZ^L@9`S|(esPw_X265)8nh?6A6Q)ZwEM2cFR5% zZcbm$=kV;4y&`wzWGc&ii0$M&n$?g&bS|6W=m<4X)Ot?dspoSaEmsMuZt^R7}gKm)Q<-V7h)9Aetted@mDNUIffGZ<<(V@Q4&}eImOV-Ds zS0^y&4PgB&O6+!gatl4lG?|Z*W6`^jAQejR)XdY8=QGH9jy=~gVh!ZPg7<+p+!y67@f-(*cM+Sr&+J; ze>`oM)o|L&dIWl&T_I1ZFOhgB33eSz|3dajMT&iAws)#w+DCQVHiZX`#Yu>_2pIkiY-NDj87`XJ>HzfsU~3vf@kEPNkq4A-VfI9pwtE=+NI$PM>m8C*-Y(!v2U z!j9TLf%k0-s(U;ITfO>%Zr*qTc_k7YGw9g``(LGUGFdDKPc;bcdMgO0+s#FD%gxDZ z2M4jIBf{}A8+enjj=}&~aRx*CQpp@TWwIp=vkS%p)W?!2_H1lm&&Db5)2Q?ASJ>*= z#nldEcV|%=@iWimHl{1ViS-pQW#L#Xa9Mzgvx6Wk^9&bZr34Lr4wPTMo_VfA`0D%T zQk}VLalOhnl*H+=TtOYI>ZA;@%{`>^i!45x#{&)4UmVIf)u->P(M7}OUw0+KNO~i6>x%8ics;^o=QF3jmysQz%O(Pqy8R- zwhRepa}u$x5Nw9$ki-1wif~aiUxI0dY&MkjkHb}(n(+IiC0sgM$FZjp7XKJS1^T;i zP1Hs*`SBF`H6{_?SFc4czuf?Xfgi*=lOe0D=<+#M*g9sr;BClr(G!^*an8Wz&ykSK zc2Lsy=Au(`XF;RkQ|>0yfJK$^>Ew(!ELh%!9RA4ASG_~<7i;!AdkM%6Ybl%;$^-XZ zyGTHY1jimP<l$_N3r7}g_d8k0af zhbAy=JcoF7Tgau~W_aO#HSpHDPd+;5bGcKM;I?G~ow>RVYn|^v-K@JX|L|EZmfh<= z&14y{>)r6(@C^Q{xBxoAKLG2@=|#V{>A@KG-8{284p~J`03{7Yyx^}g^qr2R7a4Z7 zhR2}mM=V4&)w{$wRN)^6(}+vcuu7FG^!_b@I~^rrt%%Iw$j^C&n|mbsx}TkgXc+T82xz}ZM*k>`X|=%$jp^vl_yp*PZWHT9in^F?wloTR ze999%TymKd9g%Re!oS0*`s?9%aPke}UerJ?Z@$MJXSb4cyZ5APN~HLHI-$J+;-5?I z2#$qQ=p{B^tj^X(e{QdWB()^5K4g#0F#2-XFx;-Zk~DZolO4E{OJ1!6##1)HC{tVf z`ELSRsuB-wk9l~vEDsjXokh$0D{w(75p0x7B1QHM;yeMv)y8!9T>*}c?jwaTjOhC| zb1BU4b9%!_T4CTUyy&fnw(hru5!F(x%jQ06w66u1^%8swJv)m^c~xTDG4|+IDuz`K z@nRivb`R?~&bP(8WOoz%rj8sO6oGf%)d26OQ)sfoU2LV1d+x#f(JV8Zbz&-3p+4QC zu>Y|H-#R_)X~gi^c;N61LD5eIpdAu?JCLjgZ4;P|Xo4s5nmPocc0J@KMX{aCnho@U zj*Rf@(LTY%K2tjAXbMg^^960KcmT0klAA);k5sUJnaUkz*`6_DhY>p3ft&P69=_@| zfOdTnE;AnhPs%31->njE)~&IEzGC0&)`_Q)!?sVrN*~1Yrp%fca>ZVPT~8toLF@jp zI4EQRn&;;Sdt@89I>yu19Uo5%q@%HL{VM+A-!o}v)>?e+&sS8rMxu-BrJc|;664qzDln+ojcSJ{;@S>hwCheX z#Hbw<-${oJWOG@&IhO9N79|C1f!See>^ejZ`nI#(HPdlzD62=?S82lh>;i7;dZuM+ z8Bc3xR?skM$?(zTe&O)om^c4ySf=4%Vh7Sx281ozB#_Ec9d_ob-L)Zkr9{B zCl4R$yx@^{90n;(P}yP%(S>!~HkLQ|p5=AFIg^K<1|<;1ZxiV-mYHzrR}D%&bQNYh zeh}XU{_xL>MjJ?G%niz`z~-L~zV>V`5>A>1BRrpSAMPrF@`Xus)Py6rMlG-&X^VgQ#-Rk2@o>&Y5ql2ifomkoy~uL_a4YBn8LRbL%+02$ z7*I7YL#+S)1`!^vB52t?Zs&DnIJWB*$t#ZJidA-?;c`dey_yE@oydbzl;xtcoknPi zHe%T^aAal@XYxq_Om*~V{Q?8*K5s2KeCny_#oJ1*^E11zEm#HTooulZ%NBlQ7Ylvg zdALf02V)j^P=n@5T<8OWomo4{$xI11vxyi*^O_K@%IYUlS+eA-cQa>{sSJw;>d+)p zXW@1qMKpiw80fqtxe@GEtAdb2l6&Z!L3y<4zn$u^M6^>`0N+=}i*E!6Hx!U&sR*op zNdp{yhEc+k5mK|W=WcH{qKB&z@vuLYDCco0^mM)E{JU7+$_7Vzjq|~W9kK;76Xjuu zjiOlF#sXwvw$j#FksGjWYbc+$b~>Gqvljnt{)+5Phtiav!|(#O`<>r&lU)2I%lyAQ z__oJ{D)mSUo8GKO?}ptZ1qp%Nz(@rsHGTnC2Vop(!*~~)r`jUe?(VuTQcF(+p@jsy zPDLBjk+;mT@A+zx+esy8y=#pxk5hvtCll(ye&)S>_2`tEDi{|^c$X!$r7tGsR7KpAVu^jd3{{cH?He%h%Ek&PPgiWhbPB^qJ97JhE1sZ>B1whCh;6UREE{ z?f(by(L?d|H7uJ~%CYf4oU72TOp7bOFY~|TemaY4ZrKnGHFLcCh#Fk!xk#K> zh zTP+}af&{y24VF_O!>-%2V^F`zDA7&-U1I&lEUZa|1E=F9b*iv1<^Z%#Jj5M7p$PBC z)smVe<+$bA48i?N!7%QW9Uhg>G*=GGsmC4GStARmu}2*`{%+t%p#lWGF{YY&E3wVK zW|C37l=iVZbx2_jQgJ;G?wySs9>wyJNCKI~u2Kz!Jc=a-2INk3t3V(3gMEJC`4_X!HMUQ9G2U6Yd7&a2=sODBo=9Oeod>Az;}NC{ zb-{Kbrh#9PL(}(43kjQHbyiIP?X3ULm9O>az>yR1satuZFFTfu{u+Uod1``}e>_c= z86*t;a_^jafj*sElZbWSRieJ!gRo1klWTgd1Ocr7cd%eS9&s&O5IRa0M4F1+fsqPu zD^v;E6>PD}`%+p=E0DGEZ4%Dz1M=Q>G0uEcyQ=S ze(JnwR3%|8);swX4N)FS8`E@gKgWZwi>{NMDstH6AP*i~7)@t0oKfpojn)U>AVXJ4 zX2wlQ?NB?DNl?96FScZUcew^V~aFq#fxdQ{Ea zdUSMw3fyll;I^?{O5u1ry4ZXl`+En1!ebWm%Vy7{Eg48>U=hfE5^)d0SmvbAg4%|% zY_TQB`5quADvC7X>^Y_h`Qre4nJ?hg2u(<7H2{midT!xCB@otH(R029IH5L?KHyHKa3x)E1*aIBw^l`KGb>e7Zk+}#W9O{FvQxfv23%eups0! za&)*WQd%d4FIVya=tdG$CefsQi~0*gArt%m)MS~Eiy$Goi1WJ6bn!3DX!-aV_(_c{ zS)~z2V}9+#-bH88nK~7c{@D!APE!LXt8-+VS3b8&s08wRwt-XDIS%eA!u2wivD`NY zk2#mm-+$PfW+w&Uz~?{Eu;2>PS>1xQrw%7D?jPC1zIU&d#Gxm1M#GLhia2pO``zyN z)6Q$m&oVIvElW_NI~PyKU)de`_qcsvw_Ji(_tMfx`j`qFd1j_yTDu>-W*rvh7gSk? zoj;XlU8{fk2#OS`fK*x(*TVLhEkz@#s{2YjQ$de57d?>h0MCL$un({Awb*>AbtY2_Gpe5H!}DBS|W+ z(WOlaK(Y;K0qga+HKCR0u-s2byvOObvJAA0R`O%FWHzjqFNUkO5`N`TwFCz2P7?d7 z_-jVcFE5$T_fi~rppY)o`%%fw>S39ag7YxmUS8O$s7&y(`5?>oLao0NP>=Z<2ys%u zijF)OA>wHNv6rDaS-!tDCu=0%h1dO^z1uorS-A6;ZYsBcUA< zTyiEQFiFD|uehrU$IfNa_I$R7kxoP-&p5!{G6^mj|1_XSdJqoSxS#McrjkpGBk_Y> zno#K!OQlr@2?xEqcTW3~4y`1K_{XbCG;{g^n4{FmmEK{xqfiGrxMUIj?w2c=#Ij~) zxhjhH_CwG=;wH4keI}mhx{Dla>wL)RWGRDV^$i$4U?A4k=Yg9#%f91FaOu&zDWrQ@ zHs-JUAUL4aD;n-0(O0awR{~Gsl5xh62{;Eem$ScUt`@-#WQ-+HXOUdr+a_pMqi<0L~CzqWh7&YW~4s?yT!Pj3bKuX6v z;H_-~_hS~*1OGLnGloQCMeSAmuhDLFdhJ?_vcIB#Ap_~`$GZ6F93IqdsV0d^a@aqI z2Pfrq=()erLeKIQP&*F0F#xgF-BgPht%MbJKBN}q1F z#S;Tgi`MnMBb%;S7wwNa80PCQVLhHsUH-j^&NkKM3RWm&h8%04__b|A#| zIMFnw{~Wa;1NjLGVC5*nS*}ooZEBYEINt%Mx1HoCsnPSAjuOAX=uT5;Q)4+Hg&J@( zMhDJ}tLNm{9o9x?0^N7&7=B^2hlu!2^hFNyY&O)O_q8I3D)}Jx<_m)aG~8nve%YEU zIB>;QR6ae28_G1d8;mwXei>jH?JnY@H4|RT+v3!-b5Vt*6TFgn#%&m;3|3k$^hRzu zZo4#$pKCdRie!?pNnjsxkL!V%m8`dd-ED`z&J&fzvt2!5vthw%@`34Ql{@9(t@n56 zYtF>Werv-0uMsqxX$bSeE0OT&e6ToJ#C>?62m>dMp=Jl>;06svGG^sgs&1HoM^&9g zi?-hod3`s-4Xj6N@WEOl7naXmV4tb_uLz1*mh!!6uhHOw7`PsJPTZAdlx;zS`E&88 zqym1!3NL!1H~>dnWFE|!8;P`X3;uJ}fDCtgM`pOPUCm;aNm8i~E-XLrr8f^scFw0p z&C3JkJ5ezVrjj{}kyhL;G9u!EN0k@$Rej z^E5JW#xd-@!9$Qq=7711J>Gat74DbMr(Ue%Z^LhbM&4C~Pn` zq7%N#`cSStt0KG@(3`ROS0cLWr#Zs+tE zZjVT|pfkg^V#DG41T`^d$UHj0VobABPa%o1l9{pi$}RH#y5tu5;aefo z;%kU?7g5(1!T3W-+|Ta{AoJINO1GQh;*MA%HN{hOyh}1C&R;SUDwysl;Y$L#!iB&* zTNV6dBoAzgT&Ul$3S4F(5(HXqA;A?A95eD9O@~jMj*kvi1pU2HqVajnoN~P~48HOW zswO%Mof)PLTD2cE2D{=p*HvNNl?eJz(2lR!hoZ-?#=+2%c(ET!?ynx*|BJ(|wg3Gi97y_~M&g(EH9`0>nd;pdEu7^0`J7AJU>Yt;#CMx2(Q(5B^#^gS-QB{!}!Jf}C3*Qlw8Me65!V_6U{UrfvkGNdM372dR zqaWU>3j+_UAd3eYwAgh!?w~J_r_UAe_@jlRzA3}4R9_m56Y;}LBUGrj1JahJaju(~ zhjF|D+0e5a&p-cOu+HwK$WGQltf#%cq7bItOU5^>v_Q|^947Ye!Inq~) z$;!cU`0G9%tUhyw1S}5}`vrcyyA20|FrMh30)_1r^c}kkZyei#*1e5`h*J`7_HOqW z)(hr{zxaqmx$Ex}s}5_tWvm(;d;gD|I97|B>J;bRj@!>H}X zc0AwpHL7{A5lX+E39bIWmd?F_-1_wK+gwZ~!dYT)KGn-1+{I)Qft-Hw!l&!$n_ z?rjRtb;*aOE@u6wvvSZpyHhYS`GWW^8CBgbI(Re(|K#mJJl{E_aBsD^V`AE%40y-# zIvlgp(PmK?JkD(A6xgkB;+8sMTliY+fr>C4Mb$^y;J%c0LhlEQ8dna(_x-Jr+Lo~r5CaHcg8RhU-|f|I2i z$i@`OEO}FdbuF=*pfAfU3BIl?nwH$m*;OdRonOzvX}W~7om`a%^0BV?pQ;)tuV8yE z+>V9%q3GJEvCvy3(N`R77(xBWbUfhWVPdpwGaY5c{tv_Q(bnZVsfvuT@K46)b9R3R z(8~8zUYC-`BopgH6#(wI$MuQm$boRwQladKidx^Jr_N5 z&c-J3e6%jWp3Du%f|lBcJvy4726@W z99oNaPydQKH)zsF9lAK!f!*K7?k7LY<#0eP57eWb=<6gCVbQZZWaxUD+)R^bFh)FV zhJb2}4=q=LQ*X*?A$w+~>$aeX@Hi-cdXO9VToFcujG>vmj`&WyNK{gPhamN_c*ZO> zs6YRglnpB64pk_EQ@=5tyQ&Z`S)c{?<#Hk4jc{>nmw1oO$p0p~Vy%(}e$b-}=jzNP zyZuP!C5XHlhYOZy!fkiv@Aa+c)T5YAc%uzQkw{5NAdnfMS?DcS8G<6eVQbr#b> z4FFl&5W0lnTifJH6h34YsQoVDUNSAN-F8cQa`7Up-JnKvvZ847q(toW>m2&`>DKv= zlg)A4JvF#K^B{S?MuKlfGec-_Jj*q;c#VenMu5&6$?RGB&5FKu@W)dIR+qAyeFVwSIdSuX~4e%25LY)ckA#4;qs zTAl_B^1y?bPG;T-FKW*G9dMBur9=0CYL^7x{0mG)_eIHg#u5{OexU%$XWL_+E>*D7 zoJKP~u?(eG1pPLYhP0hgTy&`d+>~;nhGDz#tk=It_+u{`8^kmi{2Zjcw}$lxTo8K! z{;ou%!si5c`->7-*rkBgC|mKK|88ao$~|ru+xZOOQ8HU`17|F|19fTU!0WXd zxZ0Ctz>YgY%VVU4alsjAeE&Q!xs=4sd#wP@ks zH=l2-ZRXssFbuK14)Yf{3qLMVL~>@?Ad}~cRR^-{!4V;J@cecxqZ5k8q+3AT<9P1# z0G93FH-fr$c;fzXh&IV5Ckj zT~5TmDl5^@gE??LxRZNwQwg?DwWp5`gy2DG2Lvnk^^yvZ?Eil*G7&{JB;mjHXNkOf z2if8Hi2KO$%#(r_)9`L}VRViP+TEf=tB-ESSKMBre{%^;o;eWDWZi8alD%k(E$gdw zGeS$f;y`pOjl05hlFuK0I=iSm8T0y|2+9M_h?)%?#Qlt4jnY8JAO-iW(1N~MMlf1+ zzgR;%G;%h5_@6%N2;*-@9>G(qZt>jOx+-|W!--Sz`9IQVVVn-x9i7V^u3)=jcIT>O z**@-33sKihK72pbz)g=+0^j;k^!m+MOs}lxKk9d;;kVb~T9)ZlE2qXdfFAxA$%EbV zSh>dNbQA2+u!|3pP{$m*z`gJrCoPDk|`EM=9N!EiIH%X+d*0 zZG@=H2f6<=X8z->=oW7dEAp?1j(Hs?JiW1akCz&Z81;#4b}i%@8d#@xo&g=KREP&Z z8vy6I-O!Xt#QU@erWy8k=3`sWv-~xwjxL|(OSH26E`Ny(%OeUmVOcc{i+eWLbEDYK zyC93rwxuk`KDGwUEj|es+CFf$Doh_+bj;(gqH)zJu}m z=b{fkjA7T|XWZ|F$`H88iv~N~!Bc!(`Jh%LUm5y`^T0OxYVhK%Cv8}kh!(T<||7m~Ooj9NCTazx{v1)Iga1T!LdsyBug+ z9LtFsQzN)uR887TJJDfPMVS3$H1%k8#1C0E(u4Qbt^;oA;P!GWblZF;@pyiZ8~Ixq z8eTe5rw2~LS%VBv+~fvwVcG_6uig%H>30V3!ZgJC*b&Kxs2S^_Smc+1)`ZQ07plpe z%OFMQaMz*at~qWQu#N1}xZJB%tLxW`pB-6?`s{?V~D|&@_&5 z>BwHeySuAM{)Dq)U%;$yBWd%{dHCXVHP}+|$z@YhGne>48J-86f|H9Sn3nfy7lfQ} z#kx9bu;$7V8qRz`h0>u&w%HU?UQ2G5icN-WKAnY&f0dI3Ti4U(2`oz-<)iMQTU|3v z7GaxtGN4zSOdFIPg*~I?&UfFe1=CkHtXd}kdGF4G71ugB^Y2PvRVJYGgd1^c(=ow- zMc>ICGbQdvCDWXr+~>OXMG}_&be8-vcu20fNch`0UvC=wO|VA5ep{zt5}^gpuINEF<8S|YJU14OrJA~FSn=9iav*sI)n+>@%Zz%YU~(Vq9lFK$ zg6@ZQ{OtJ2*v~-!piox=E!Kn0++m=@m+&DnxaGS#j-?Q*zQ_Fdk6e>5D52mJo_XA*11I<+-y@yhJE z=;;kZ=%dd#xd3*ndgwt55?b)5LoR%y$T4)kb~1j~`wyM`(E;g;weg?hJeU?Sl&=~j zg$)aNu*QNT`WGc!uKVgeSlN(;v#SR{xl#<>$9fF^OuCAae@%u$jbibw6DBb(SF{Z8 zyskwC?Fy%-gshL_=s6V1cjqt7GiUE~b@($llZ;7`;NH;Hizp6xiBsQnqRRtA!D{Y# zZW`-qS52^`-TPMIbq^}|{oa!)??C`=v14}xIL>eXn~g)~y%bH_)=zW>E8(|nXQ;N& zh5luF!V5AnD6&*Zlr=O(P<%p$c>U{xYl|cp=pg4oFSA_P*4iL+t0NQi-AlQMHl~?W z-pLO{fjE1RvLM=X4ES!c$A`o_p}#I$1cb z=0OLtJ+qO14$>c82{on{#eViT!sBr%gU=liU{+bmJhHy^o%4Pe(h= z{ou{;7u;OdwJ|E*n@VL@Vwu;i0x6YBVmYf5*)xyHtBa%QmYb|AFy<2}inHU(Ki9$G zA}b`f#(@m_evhk{pDapXx-gEQreq#ChFKS7-Ao?yjyfd_qOgr{pYb76?ev z5)*jDZV)?K643p)si1#I1&1zW_nNpE>dLeh7GWA_hRJfW@OOha+f7N|h%O6fq#;ZV zwh!-d{eDA&jfWbN;8(XR-r&l(!LzM2qK+QHq8%5VDEtp3lkN6(Or+MP_7=-}&C>_aAuaKJWAS zyg%$%pj3QvZ5n3GJUOj)oizEi z@OmuQWx1a>b^56($=s-hJ~masPsS$0jhndtsb$2)Y z$lgtt<_4sDeKn}R7G}K9Op8@^4rAY>%hJJbc94s+>~Tt>24tUVCj+My@E52u^Ew+* z`CUbL_%Iy^Kb}VKEp5dScRSI3wJmVJTA24ry=-aS3^yEPLB)UO?RBk+7Vf9Lp`JW? zo`CgPK7r;yIXL$4G{1&vOnMF-PscSh;#vKw$_Qvp!VPIJr^A6nT3-|gx;R82|;IYkks(q^wKWK0f z7j3ejF~(_F`N3NG`BweuS3*Ifv?j% z6Gc;*Mq>5o%SijO1O_Z9;UBPE2zh5ay5Uk7t`zH&wER#SIzAOYPOC-!qmPJn<*o4N zofwP}(#m$Jx$Z|Y=a(`rDpG|Q&Ea(5bEYxqibJ7O6r`0$gnibe=m#`i z^2EOx=kQ0{gU(>O#DdKs$RaiiwlfU$xWIaI96QDTo(JL4PgJ=4+2){kbp*cXqyes$ z!|9A~@{+stY!38%M`oRgmU*KtpBhO+$L8U<*^1yYfaM>u-*b>C2laEWgrOGaW!zoF z%Leh)WDlG%$PxYQp-5JoVmfD@SiZ(%lmQTMHPduWUqn+q>`Z-+n#O>csg(e{&7m z`c(-|`8v-0 z)c(ml*PmsyUhGdpUe3l_51$~l+e7JI_f%Y?xfAW%Q%+y(4U+_=S=A+S`(TcrJ$_OW zh@u8%Kzg57GJipW_DHIFGX_s$<^-IUcwratq5FPlHSHvGIR0fY5j&x~CE-r1H zPu89tOA)&*s)U?I=Ha&>sPGdX=_mqY1zoQ2@oYT!lLjhnxh`Fvk;iu(SAjy?6;Q$6 z%1P_|(U|I?;M22)@1Mzbmj80IukXc0cE#f1h4yq-k5yRd^(VA{tr8u0sUOyeQw8mc zMzQFw0iI+q4W(gw^4nhlA82OzvVZbP@IB!syKdJ>=wF4|+pPw#<9E{feFE-v-w6d% zmh;HS->FR_qKokAFWTTE zN~Z3cTk#;;iS{|B!-dzvP1YpQl0Nz9j+-Ou#Xpljut!k9J=c_SvO=1Gw|VpiSMRT6 zcmHbs;uF?2|JZ28hcfIsAcM3@68E z!xA0V2bw$$JuT9K&f!n^#oI)XRK~hx*>Aw*)*p0unL2d{yZFfk&Tm$Mh1&OR^eeMr{s%UwI` zjmd$L$Sb2=nvi{zAIEe!wbPfuFk1&aASDY8shtcl(NFnT>|LI#<3%t2I)raq-Q_xu zRuI+NmuSje<`=$eMRRS&;|uk_iMfB9_>!wWj=5ls>b@zHTZ5W;D^pc?Qf)}rycck6 z*XeR{{X!JKL7a^KXeNW`Y%iSXrwXeg^63lKI~F=*3krKR4zA5i<2Cvz!+`rnG;P-i zoL`+rA{-LL5ACXWaeomMOw@*T%wI5Ke+s(iF$RY9RLAO!r?uo})B0EMaH2s^RCOYN zsN2@a=C|I7M)U_a14mrZfEKl#;?+k4zV2^n94G~dv1*hCT$mV6KV4$q%lQ;!ddV09 zoCF+makHe7iA(U`4TQ|DT14Ae&j0(r`N;885zQ+Llk`|)RcGo_%Cs8xSRpA8z59|1 z<>(ck!fq%okDTb*8L@b1awXSsuY-(SqQdVeQi9v}CUNuh(y;%?T5@jRaZ=(b;8-fh zQTZR5lFH?3jG-uFdI;vV+?&UAl~wS0yKsZ($+9S$LQ=7Xo;kA4SqUFZHp_B~7GF{3 zjP(t1`-_#_co%P}owsm<*nM|4G@VGt|2nn6aD^eA{kRj`iaXG#@x8&nM=^itwKAv$ zj-ZE^6yU;Lq2#0#Q$waf-QjW?nRH)+IR`$;w7aWTI&jv9$KuGKe_Ts(r8It79)E#l z_J&(8gc3~$wio!Lu^TO+!lZ^*-=+cqygRL*zaO71*ewn>x220jtFZNzPbk=1fqw4j zhjSB{rn*YRIWE@6-;I5d%^fZBK28C5e^UjY%55a%yRgs74LkzB&S31LuLeIK<ZwG|LU$X)GC^zRvEmnfH zyHd&92Ij}~?+piEc9IkN)qKTumR+W4LMPU+9zd64C^ca(gl&7v+Z&4DmdOYjWi%7( zP2I!2GT9;?I3mZx2YrnH7If(C>Tj zGT8uYW-;BS+Yj+6b9uaGsT!O}Ga=?jg&S+Zj~cK#nvJzK_JN(-M?=OU0mlMr?CADk z(K!8pF_ByerqOelpL$*`nlOo}Di8O?au4NTU(_;^eRL=P!A}LAADBpUKeXe+7O#+W ztUs(eDqz|pKRX&x5rr>YJ1%~d>PiQ7&BMztbfdUzKdw7yE|x@8N~haCCTm!R)wfj! z{EW^kL&7RnCga+7o@YIoE(LMhV^aRpCx~N>{ zH3+^roy*wF@J*t`x&BcHAC_qu!fU{e+`%+ku7~9Mae{gzw-N)57}?!{YC6-v*+m#J z--;p6)3wp5xa0126x&b+%CYBVeBJK>?%Y>23Af}9M+W!KN?kIAU3H9KF!W{m$sO@o z=)v*{urf=)x2qdj*6Xf=I5Xf5cXM+o`S9;0TGpWihn^3ix2JnxFSWm9)w(|1v^qUp zGTa(1SlK51;L*(cI;p~b-(K|O=TVXX4HLAcw1_n233J+X#{`($-3xC>Qia9Wb7*z0 zyu`y~3-bOfffs>k{8GjZ#%c7Yqgd|Njq+?VO>v)inyxUXtqo?JAacNkCsR<_R!3+s zSI48MD#SVZk;N)Cvc3kTDg*j>&kX$PGrQ@;UKS5Jb&EfKT?Cy|P7*iogP66KbM3=d zL)|tpo{^&gh2Iv@UrdXbR-J-U8_p2_?|D`glLWkEk}2*sD3DG56gOe z)=_K29o+4JHxxG#H^s+fkxCQxa-zuHy9g441+2T)kqmJ76~EYl?Ve@BsL%6QeB(+b zx48ccvTK_#v(bT%$<)D3c<0b=BPKW2Rgr56N2v*@ou0D_>vRNpI?B7Yz!sk0X!{dIZHQ( zF@NQqtKfF+lg#t(ovX!7ZPUkRN1o$mC+?OOqzJc(t!}|k-`@fIB>JQBLJR15?kul1 ziRHE#NT~J2eOOz5x7e$v4ek245>GAvgtk8GNn1u4V_WvOOB&sW`xT{!eQx@olPPNC z%MJy6sE-;T<7~1|Jy^E4R*4RSj*0~5PgH~0dwH~Kq=MvX(;XDPav^*RFXihRSl`VF z8!Bq|#5>pAmd0Mu<0g#mhkdy-DD3Je@;1{RPcPMgP`FIWS>~|HTejD$Ytl1gi*Uzr zZ8+k<^g^kvI5D>qbq`2|*JDA(lrq5dWC|2 zPJ^;50tSZuv!;37QCRc!aj_5U0&`ag!tn>X(QNNz&e3}=Zd_C;HO#9guZ&eND^CJT zXHy!`B`-O9Hx9kH`K|6w`etsx8AbBmpaZTx^u*pnG{8PN6_yp3^HQlYq&4;c)YBO& zcxgbCrzy===ph+@kf1q5_sOl{F}wrovQMZPNr$wQ;vVCA!J|d4v@wNo*A3f|!d)Z(~JdS-_(%Z*+<3(By-%Vkb=gUlyS`AL;3tnbK;eov~x z%De7z7j74mkBeW*biWl(2h)qIC*Uf#e5g*xs|Z4C{=BWYeL0n-o{FNe{U3bziu&HyCB8|?A`xWK93eKF89@;6m(>c9^9ED zVBOPc!)W^6_4rA31F3|$^cS1+>o4b{Uo0c~P>4NVwJZ>ccP7HegRf-$Tz1YZYfCi_ z``tdsJ$=(ga+j&_vEfSKwP*?#t}qPu^d?}^;^ z3Vl5DOFg%ie4BsiJQrK5bpf)L1q&VO9Rssa0<%_pZ9ztxvm^6(*u8x zDTh(!5`5KN4aV9<(?pgPY#Vw4mCOl*fXq^v&;1-{LlZ9e;zxXo^qkccZue0`oFqAg z!@aW=_WwO`F7x-{*^eE*JLD8^g@VtVtVKbc{BnZ@5Rc&#dMju`Jf}K6*6a zQYyAFJ%(Ig?1rn4gqbbQ$(6?LUyKu0S8;pxHi`Gx2%KBs;Wq^Lb-;Ejry*ml9_$-_ z!f)Nnx;6D;Xrckj)$fxm{u8N0%TKJvsw>)1__SNlqtE~w#i+9G#1Y)&D0!TIT@51C zCzC^s2k_TNS}19!GC9>K?59nA4#Fb4ZFt&;KA=!L406s0oLg1CB@H&`q zre_wV;z?GuDChc2?%J5Xtm{Dz5*~RIt;z$q-Dx3e{xp&Fx+q|ptqw=^Mm)ng_!U~$ zJ{h2ol;3U5`j<~x(&l?Hc(C$zTd3er zrV*<9+F2)^kRi)eOTq16{?rpM>8k>o*&Teaczb0VaAv4G6G zCU9$V%+vkOVG=eelY{AGD))D<9@ZLQjlL))NS_)v^Eo=K57(?4DwIY`?)Nr9^1Zea zN6Tpb%Zy|+ZN^GipxYaVrl`W6)sb`)yOVCRh(W~01+F9t+*)qbVA`_X6UR00B5u#R z#Vw}7eZlqC8?u7UmL0_@Xyxw#;OVZ80~#5(*3*kruNL;u_9QJj?&u8GrJ?~hFVCh2 z82&6ivkV!#Yjc;kHSp8e4Z;QuCu&D>@RxZrxg^^_`0`SW>xl*&WLaVDjjZFTA_b)- zXu$~YWSLj=Y?K}K8IpkW&Nq=SH-y~j_lNV*?AhDFZ;3rt3=BlIHE~dXMZh$zKQ`32 zG7cXbbci!GdQ8@*2$=RdK8Bld*d9l>hLh`4vWU+n0n=ul$^ptW@F!FAkXyhW;On$; z(_ayko>~CIBLxm^jVP2`vsoXzCWUhWCHv~snf~o7>vo@-I23kUXW;cSwBbTi5BRKH z%-daJT1sPQ>Rib*NSde7n=T5qeqFpA(`AkP5X!Ar*T>bv>bY@pBI&zyVeWEp_khyD zO!E-vkMchmf=5IRf115zy-tp%W=e-J-&iWnsqRl32Cc&B5uZ@uqhFA_-Wc~g%ew4? z!nk^g9Q5Y92%jjqwxEoacBuoRZ1_9Ss(D=YM95C$! zYU|+-+|5#+Ff4M6A3)^}PQq($H%bprSpjMZ0gLVtK7&=wNywa3A0Dk6C9# zOrKGdJG%&zJ%>1lpP$8%mI8Kp-?~c*8Q=TgzIprEH`1^634e~w-gjePlC1f) zT|9C~Pg}hWDoL%RN`;nLQwbK(PYCl0n_F^8A&fkJj2S% zULo^>iO^;*<(Cd)-l8iObpDLBcxCG;@tG@*biQ5?p1zHiTsh+gQj&2*JOM}bE z!>KA*`7zT#_WxK{dUhLkZH+3ac>D;kw--Lov^^c-gY*m2brMxx! zS=dQeO=$ytcI#ZPZh{)k(pV0jfN!1amjIUZ#>XpIhlOc4jh)nn6Ln*dkJm`pu|vSO z99`xw)Ahvle!EDShbEWt>yS(jEKNy1p|xQSMY&)sw?d zuW5jfp)Y;PbUy##+vs*pNR1Nsw__KrX_j>Y7FRZrm=}K3eJ;y6EX+q=3!=EhAbs3+ zsk_8dV>~X$#AUYow4Kp-5ct>ZZ>&s~&EjI&pnA;J=4O!W*Gvz7LTUgaTby?+X3j@(=Bk3&Cl&sdFY)-5!3N#V_Q{K2(~#$ zRifo3dl(+h{uKoKPjBYGoM!X9Ybcr>;0tzv!I<>G`~bGlVw6_$E@Li$I4g4S+h z>~)KM%L^j8hB7@o)?f-+v~_~?K$Ze-R8WKNN9%}IUtxapx?cn>;Sx3jtAV$9IDO&S zh8y@3=w`=E2zpe?FJazo)m8mz`S?lLGq_P&zi%x!KDsYH;dmNxLsFz_FYNKR=Nh0C zQANIhFuzr@+>AQ~MYyd+8_vyKP7}7Z;&UFI$ai2o>^v>ZZ{2E+6fEXp-IPaSUrCPm zS*oBR397M`THaZYcaGA8nVZg$d8yU>@82vZ?V={NYGhryJ&vIX<90%K+grZ!*XB9mj_3bi(TE7V^LQKjEn?o58wU8?T2)YZKb4MT`b?uXOSEUeO76E} zPwbtb0jD;*NY^qC%eX1;xczh5rIJmHsT5$yhH|CHeB=B;^ zNyF%^WDCiyfn{ir?>(@Y?u9EnG$5^ZAAQU2<8LinP;qnu3^`mb%gbF~vyHpgX3FwH zK^#(eg*5vMb6xV-^JLZ87+$}T^{DQ(r^(~?;}?zEAX0Up!&o-Of4Dc|V?G@CE8I*s z@wwdJUHx&Ng5K!$))jRHkB;(1SOnYNxxg)^!Eg!BLMML@gMx^5epVafB(;~&jb3dy z`-}*^Ez2b_lU~VmBY9PW=m*8A_~d*==zThkD>Bi;d7G_}>fbGOCW*~_pQ)-aA@@4m z?loHCqG^J5tw`q8pm!@GMyu-;q1y{`sKXpnCkc9D-kP6wRe*D-;M`=T{~ZazF2 z_x({wxLao29c6)w8$8HGdTwJH-tE6x+Wb}r0@Bs-ZACS(>_3Apd88t#&D2A$GbDtY zFYKzL?yJ*cf@)Vjgr3TKGcFAt3e@EwW>h1c> zD{+n+BbQWDTbIW#z0bO_wz$F9NWeFY?~$yA;cVx0z!sDJQTBsg;3KW!CtYTJ%3q9V zFUM8*I?Dv!U-=m>bQ|M6U8>-)dB@q4WeOPeRf9K@MZ}j6mgP^@oXmk9M1sAxs==M* zAxu}$h7XK7f!_K~0c=~wQ*{-vQnsO4Tp-@H<+*fOL;+_#uP=@>JB^yJTpjaCG7N{? zYl3|LVuBk53@qr`#pd85yrfbariBF4K{c&7P|}H_>sY5lgTTL;SKCk<|G9YMnup>5 z*S+FptA#nx@Z?O_;LGc<7t2$Mv^qo1CJJ-l(zmMg#(l<%emjb;S?>Vi`;Jdycd-SL ztV^^b3?GslkA^V!NoST z;B`G@{}cE(J!KzylHKdIu3I9tH!Hb+iEsFWlm3tsZ^B$FnD%?T`a5p-@@vx2ZcpBE zkP-xnw}Wo=He5QJbxlMK1d|?n_;8lXR5;y-X2zuA8?7}+aq?!aalQ!e{PUb#SGRRN zdd34!y{C-EeJ~*B?)-nobLK&As<5lZ)>~4{C$sD_5D!nZrEz0|u*sNi^kh>bH)p~G zJh3)kn!0M4>w;ft*muVjw3Tioeqk#3;5${gBWkJh7@j4|3E7d-2$w^=u)Z7Pg|y4* zTBi4&*RKU_ONfJeo#isWs?CgYPP5n)dmR9AIpfc{Y-gOhUjs5j>d54eF??FP5)5Zv zv;MpH;afws!KTxWcCh=MrgbjL9<9z1y$JUE`Be&>0mjSg$`Bj#z z)9tqd3}#x~|7N^*C#_*Yemif=xQH32=hKhgOha2KLK#E1k;vY!WZAj3F6@Q^EYF8& zkJHEQMH+h#{jRSQgWwWVH43ELaxZ z8~3SayXV>Y^zxK8-1RIPgSNTdrwd4KpF(XZwz_O#g z0$3OPq-AK*Wj}83_(tCQr7E26BXK<(JRfg18pI7TL@;nEhu5fRf={~}ecmB2so$A` z8VVTKlOxP~UmFp1_uql%Z~IErynSfVYL+h%pO5O^Wpn%QYv6t<6~tOG%=Pi0Gn7|4@pe>+GvNKPi`Wo`-%8zbu8Z?v#0BfS%!G$ za|a|pa0cnVDd3*h`q4Dt?kLHiZ%!`9dK%49$Gv(7o7U&$h`b-<;v+swj+!W z%R{4w_=BWvGaqn->46{b=MK0S;%2mplRweNRds~0|6XyEgC@5B=1tIsq*I+FdtNbr z>?6z9GD387E#TCEt>jy&HJyEy@zr-vq0olYpjY0-Ut+w6*28^VOO`&q{konDm=f<= z`Tsd^X^;H~!1*|6Plpuc9N|GzvsS?4P679nZrRbf(nZ*N(=%~Z$rE_YYbY5#@*cpI$`f*cZVJBE;Pt77WeQx z%RMl+=H?p&N-C2gMzeGTzb<`<19d zsF^2)Ni2`9+7cCgOXi{?U-Lc=zsX6p7_rLvx%f#x;7&qZT#^J6? zCDc-?%(~JA3`~DA2JGhvGv2)KcJ#JqCT@(nF81}bq91*N@NLU(6ksw$9CcP7Khl|v zQg1CIPLow|&~;TX*x*R_N4iS3W}QKr<=5&iZx%GeZMUz1ai$j@?yUiN3rpCoQ(kgG z)PhESiveYW3fUcYioqG~$2fC5;8?x5^x|&9LK1Nw#>ZZrbBetF5+lnV@iHAux6Igw zRa>>-4(qbi@JPo8gLa_LjB6TfbwQRr(%gB3J3gc@wl))?k46_<>YQv0DvPiz>NI zl{&cO(-71i{MPlGUo&4giut@WN@422(USLiCMe%;DY2X{?74nwzVLB(Z@irC`_q)- zse3KkE1zbef&XkE3rr%5jibG z$@7a(V`}8hHp0Qt0H)4Zlf5iXwhwmJ)C;Eyb^<8REOG z4(NytM?n05ch+Y2*8cW1k7*7~emkK`);Ic|{k>w!@=)EVZ1`xagI5kwg$l0{x;;f+ z!q3V>#droJsbul#gn8M#4s#>H0C%lh$=PX5bnS9?=4+c3!Squ%K|zcIOw@+LBOPQ; zWHF!mR~gKjfw1%4E7)w)kE-WdWH*zDJr_ebv;hj>!EmfyoPnXkrr(~oLR*me6w z@!iS#baKyCczF9qWclSC)b}&NR$tlolChh^&(*Mtr3CHM))sfxD&TL9YVdHkA9-F9 z%;&9Ff(-jCh~(XHb*mcKE639Tb@GxKTmzaIJ_!`8%6Q!_WsuZ3&?CuVSnFq(bnvU) zT)v|^)|ysnUK0;Y6SOD;GRp|g73RR=kNY49+v8-V5T+5`0`U>= zWPD&;>PQ-=5{q>-&vF)b#&C&dg7^RRN?q=PPY&x$IYWNlyGZ0TTlvmABG~G-AHL<= zW5c2nls)e(I1V+Gae((-Jm?&j`Ar3wFp zIdI7Q4RAVPJ8scobN(cjJ60Urp9BwUXCLyJl#AZ?B@VO~UXk^V>Y3%czy!%2Ga6UMK?RZjN&Q%4rvW}jU z-a$D3?-vwUahMwzp@t(Br%I)nJH!J*^>KKaKUz>cnT(59!4^N6#_ZD&8kOWK$<985 zQd)1;9g5h-$!n+*w|^JFdz&yH#-A>v9>ww!-LCscacKn9NGf>8YGqJ-c9@%3u7-E! z?-RfB${=HQ3G-pYvcsg0VXSOE9E%20I`1<^83umtPv2gdjgxOw z5U*H&ZVX?=Gf^lsuhHcW&&t8$*X2uf>V6WxJ;MHb#St-mj!5z|OAiewcOqw^Yf&oG zw4A%yllI%^hnHz;Lc6aA{Ta-1(M8Kp|5u4z)T3K`_#ZZ#9eFISTOWXJn$5UpZ>``+ zEr;I^*MxUtM$nxv>tUmyy!3531(I{5wJA_%!NmA-jXh35==$6e}sjSR^b@%F09 z@V($LcPLB^A08?uxfOZhx(x>S`rBcs*Ym+-aqt7a%|aEb$RKLQw2P*{oY1i`vG6j$ z0h?}Pyx*|R5IIW+zsIVurKFIuQa{PBiFv4(jW0~=oh6$ImsOwPHZD}dxw8V8cjK+= z=wLxtyfV3-oG#12|LV2jj`jl*xT}~CWP9brmH{-AWl#OCJcVZI9EFRDpJjYtUFum* zZkZZ>=6{?!kT_n9O7r+lj355-R3Gk*aKL?>{n0RgIq-6?<>#}!uLY*=G*!L{n=H5} zz83NlhVmx3?+2EXIje?iV&91TE{s;z92JX1ig;nN8tneUla{H%>}N198NR8y;XUPQ z@O0uTI{zBWrn7567OUKVpDE0Na>};!`1>$yZu(i8dZL#5#JGr^f6I}@kydf_iG}3mEN3d29A|*s?5|$7`c8 zD(n)Q?0765v)!D}Vi}%EVLOT4{c7HkeG6j!GT;~68VSqMx_qL<-AN$>2yM)fQ>p}MjVgFSaJetN-7T}2%V@YMEJKe;vPMOUO|C$eQ zw)sE#OPviQ*3*>ZbY|n4;W|ib`c)q@s_P>G`9bMh@gzoC^NitqM0iOlbco zS4q~oGidt&fRkHTSFfW6lxyvzr3d6CMX&E8ql@A2bdG>^O|PZgh2d)0+;E@R==^e$ zOPulLdZzzhxsSNp2w1m4(Uj_ct;D7(y3qU52Kqg&6$kI_LQ`F{p#Jj(K89nR^S{5H8Q8z*#@lZ+ za959clcZh3F1*K50^8p9#<;f{6wO~jk5PHaA=Uvg*pi7u$TVq!x zd8V|SGnrV$=S~xWy))B!UQow=4PVIRwO zh-DopZ`PzB=b=AH+oxpS-d7o3J{?5|tth~wR{bSa>)dG^^Wv$F$VY3`rQF=@s`wP$ zLk2w6;a(i_#1(d~D7rojyfzECH=^DTHmkhmmDY>kRf89u+p7xyeAUV6lwBm9yhx@! z-uP0=1vsi<)0eKK#r~0al%WBB5k3s9-JnUHg+Jg`ZJGCfju9R3gUx||oX~{P;jo6y zfkQL$&@cTom=vjlJ-pcc=u19L%$Ap&bj?Ez-rjJU%i;&H+wS_=SGZt?S31iAxF1tY z#Wqs}9dc+wDdFWaah|yjOtNewUV8=H>(^yUqZsa0XP-j)Cl7)A@Xs<0UcT*B?jGy= zKCtvSCm+30JhWc8gREgZsXEK{`49KJExwYG6KnbCo-AkPWhhNI?jb2>-^f|Tp7aOP zXnj_Gg4XnFhvt7 z&o}7!@_CTGlJfCP=d)JJk?xIMgV)dN7WY{FK}^Dgn~2GmEK+*7n(z9m0+IT~ptMk! z{p5S5L73uuS^251-zgkDmd4G%Aq`xH?DLL)lBl z`%N%j1S?-`$B!3lgCEz^8 z?8x*Gj#G|v_b+|oU*%sR8Op9)dHOg!X}%KbwQsNVi0UrBD~ag@KU%}~a)A#tjdi0A zVf*pEi(kau>1Oov+#sx5{{`KHo7~tS=41NdD;@08i_>({$H_DNQ9zA0xmc)zO|;eE z^A&CCvCCDmJ?{)sMyQ`zIZ^{8A-Qz@5qZhv=KILQEEJMs1U&rl z;U=e^sD?kU*(a`R7)$IQI^$E#8nAhK2^pvv%g?#Y{D$WZ>4f!_c-B@O$S6vnMj5U6 zZVvNt2W5a4!^6NRrh$yV#a(}D*oOa9oTAXcye#w7;t1Iuldm z?|W6;u)Uf8IA0a~N^X10j#l*ID4m$CisW*90k z%Ho{90Dse54i2FoauI5==+Mp{l;rTKh|3(&$N_RVp5Po*(Z|pEtyxD z$YxYyp2Efo?CY-#Z*qCctxd&02jrukd#-VH<3u=?FChWT4Y{=M=Gfzp4!YGm9}KgY zu1P%*-R7piA~OLS=REbG|8%RcLQ^LfZgGz6&K2?6kCb4q!Y%G^mKxR$6_Yncy*Onp zef*NMN4@8~l@7~!z#r#TLH|c@y87=ZiTO__^ucujWQ7Xam_rI1p&?%fJIzyt>yvWn zLdLN;IOU;JvnE32oGkv#O~#2OJ>+ix*2WqtOS!+zw&Ifsf^PY6NIv=gAQP`w)P;KS zP4eY-G5>X_3bd|Cre-WNdF$sV#AS;K-NC#DF3G2mU&%qZwB$3d&5PjT%12yNp$?XF zCfv%}E#lfM!j7E(Mis;?$6jRXj|Mt@CO@KTc@1+B{9KnzBNTKbtInx$4=j4n*U@wF zO^YXJUPT*>3KC|;w+U~!;RYsnTg7a2Ozw~P(Vm!48NuP_MprDM`XWq}pUc>10p0QZY?Vt4I z+9%xMKf3sV;xQ!Oq0cS!H^V)dUaRC^I~m#8i2vT*hBCISCUWh9cO!J+4bZg}FcaVM zpm4qwuYC3f%^yD(mM>&8WR)@m53#4l!O=KudY5?8Jvr|FMq!3r;yH<1oG=te^r|Pi zLr;)f3QbsV-z9YBdNK+7Sk1e#|C6-_J7F}_v=4n7jHHDdA*JVg{;stMZk!%UY2+IG zuGhQL{hL`AHoHNd zTXvS)arQNz-C0kp7A@lLB#y=JjwzxQ?Hi;zY>)m=^W3=y;Jmq_WZrrO=o4l}hy9Y5 z6nyQ;&p0+1?lcJdb?r@#YH!_-hdlfuj+$XiBUcCE>qowze}ivvqaVoQGl}lfRj2H^ z%^&sf{qM8T?Nx82r%P4vIOfwSQ`}!?(Ur<|7|4-tc_+Z{tT1!#KbK9l+3xwi@jjBj zybxNhRq%2zSzf`N25#!B9(aREk+}T0Fx9j+dD#yj}4{3yHmw1;vJiPczBG}R@Egorw1x90eDCUmb+Fy8h>6B>81Th}KY zJZrWk+KhjS%j%o?D(30vUB8{_e-7cmk=r=XbRs!z(fsVhWF#H$2*+_B+`u|hrrr#q zWh_H=NKF=M+iDD(CZ+T7jx6^y)|Sqwiox&4))E_|bS^lgia!(~f;V2?T$R=^+)r+V zboGO4WMaEI9`2w9Ar_W2K|>^YyH*eV>Nk*FdMI#@$}hX&bdZ3tX}dW3sC^UuW*?5a z405?YHnsfK?jPjw8gEW})G!=*T#mc-n`K<~LwLnv)*ZdvjE-O$t^ejvL-jYL^h+{d zJz5$5ofOk&dHe8*?`+4ccBMO*=KQEZKGIis$SF(^Vcm%(Byxxg=W^N%zrCl8Bt2)r zky3js(ho$O;Uq9FdCj}mi9oVbLO*vN#NK9aIA%>C8wy1HiR()6??w|hb)W)n_jMvx z@%Eg3y&m>|VTTe{*GTuRf51CAsKSM8C2HMcv}EvCCv+}Ge0;+vtu4LS`xh)PB#jytRa z=`n;@Jt^kZhNwWP{yG}_OJR$EL45;o^rpH)$3XQ&80T(BKmi1PD%K6SM-Kc{{ zS`aSl##J$4JmjSJD)3bQ3sGTrz5lZKhAn+cN-Apko6HOI{VmHaG!`(nF#QMEY@LhW z^kUtzx-DR|!32vsn4i~D2@Sq%iVtZ8qL2L?xt80CSbnZL6g*!_20yICh8g`(O|%iQ zG!N$6^^{;~{t|e3%?%s$QHME=fsA_>FgEo52pC8OjD5JwnvUNci+2?LleQ)N<`N(4 z;^ucpQDC_r_aKEee_dmm*xW@Vear#eVYLEH88nT&Q7n}CM0CUIKyzF%9%Z5f=QoR~ z!&?Dk-Of*kUgs%q)xdfm?po4inbEj?beFi-EfE*QwATOm77C zilZXAhZmT}iT5X-ra7cBq?I4?Sp)-pb0DV79`9aIf^IwShl~hASw>&>KQYyu#dx-n zL(vuGb6j%NbNnMMfVP>Agd$MV%1D-ZB3;F6Q!I3?}yt=p1pN?c6 zmMBM4^te|%+3emS(<^GuGooFyg0Y)YFF5b}m;3is2fHt^M1%M0av2Bi^7_oHzWe5E zqSvDeC)94^?pO>a{2KvFUB+9(=iolrZ2{{zj`OEoESo~{Xcn?hGlZkA!v3DYyoy^| z;<3u`dNM>mhbykA;=>P%z``w(`^0#j$j!s0JsfL^(RXz`ll6)wS(}o#9>R?JwCw}* zOq+>M`)NXt#T?zVHv>04UX9djc5|&IHT=5qKgh9|NY0Px?yTp_as9^00kuXrez_+2 zo@pni2Hl2GL&3D_nH`@817p2)~d2Pe#4%6aHz zirtW`qCEcCG5K_B$+{zPtCQV&cz zSZ;u$8QGq3057mLMqkcql695>es)cr3*Bqnv0Jh_h~1~tHSFyRwQWFsmN>xSKV|$f z*6XUH~)_^kFH;?-b8oIX|Ji4czVpOX+9 zn?im#%K=D9I0^4;cVpbC11Cp~q;(yw`0uFEazxJvC&V2jrfNZC@(n@j_@h7T^JTsy_4;6>Ef)_#Uhif78eZq@=$Vg6 z*tz~3>$pkb*6=y}PUfo{bzw7C$~f@kkF$uw?o?9B@YCeIi20zmz?~y3=OL&Bt+-PL z&z2j?G>sjXYPgeOH~Grpt)yc>1h*xHVdmxp?q9J1+h4Q6*Md2gAHaf$j0>O8*7^6AcMVDq3`+B-Q1_ibOtrPvyf4Y#BD1uK%#0J8zme?cF-Y7WCp`>FKN zU3p2*eOYMC6LLZP(TQ4bBJq~0~8{&w2?}VL3A4#PH#9_Nt=-M^SWS7t%Wo(k8 zs+y2n_9zc8V;y04K26}-nBOO&D+VUY{RTfbE8yEF6Un4}Ur<&v9KU~}1#5pMQLQO5 zqFqVi;uf6iX;hnB++<2yWmh|<7A>M#Cf(jRs15W~hpEAru@F-dgJ zflid5s6Z|DXu>t)O|Yh3HMp$)Q@Eyp$Hu+eWQm4glIdz??$Ryx3WtvoXyE|=?FGWY$tg`3sNN(Ed!#J+2N4UM) z07xD+MsIv&Sx;IpaGaroA30|bzX!9(ps@vLC(BN#vk#^}_E}@Maxb{z#C~cN@dX`V zx3c($7F_frU+lKM4A@Q%2ctcrkn<{eI;uMfc>ZG^sEDP+v;1AjjCK0h^p!mfS+|dD z@M}d=7#FFqDVRpwX8w+)iEw;y0v&vU$Hwa|860AnB!?3dV5VI;*gW$wvNdQWgU<(o zFFUo^eeWn(b6LN{O@+UOzE?J*V|}8qEz`P_a}xB_-z2msOr9!f%;b9QI2=&1ldLzj z<%Y2Q!=rXZ(BV%$*l?f(bv!#5y57*j&*#WM%UTm~jm?usxWP^7S4GH(QqAZ<|%u8WK)JWpI) zHfIX;yk?E(^?SnTaC>_AM+a)W$1+{dcyp6ywqeV79VohUovi-A-#;Te|AIXd()hIF zc+#pL1U^Y<kkvLt8usupHDJ2a|911&CPI2^9m~^L8UtO2ZlYCE zTKLjwMQRo0&8=ft8oZNXsqN#U{mgNX#m0ti0JGAiUJ8497&$}tVmd(VcmO-c^nnWfqEkKu-D^O18 zPkZ)SV_}{bRP5M6>%?EsW5#c`>!xyj$0bEez5wWOHU_lK;W2ahw5I^&&cwC*4w9V@ zbEXvL>ER!W_R#j|3Nk0Q6}ihP(%^&sw3Y2d|6wLv7)upde%*h0HJe7Ka>ZeiqVXXK z@IhT2D8kj~*N)djzU(}B^GOpo-#h~JNE#}vXZ5Fd$s78;3#~eQ-hjK{Y5m# zCL>?w>wLd#DmUmK#j)#l5_trIQ#E=bhM+6w<*CHo1>6n&Y8<#x2OK#yn8Rc>?%vu3KkXOCUBIoZoEQtJmvcHw>}7W|cO7_0M-xAnxh}lEHx`r!vn;GdPv9oEXH#m#_So>43f=hV z5IO3}b4H^lNpi9+m+=^?L2Xjl9kQeq@3Z>>8Nq^U!SOJr^Gw=I9(2g!>{j#l_3t5(Be#bm9cNAHJQ&)vHU1PU#y$pSM2beBFB( z{9Bgh+p2TE%h%$X4XSj+H60kWo7YmlSmz03Hq@iVi2_<>{&&iP@t!y|bqe^D^h-Rq zjOUCBKdaMRUo~v$EuhAc)40vgB}LC!N6A{KLI+g^BZVET-$y?UybVi2Et8qvIll_n zn9anBjc(%LW!I;StQvx?k8XiKqT z9!~RDhVDCU>BS-*C$AgX(rM-&kOb>e@tx$w-C_FtU1!+Lsh&%23{^x=+2>iBEeFFN zNaKkf6Nt>-I3Rsc51$@B4!+)aU`p+mCbVR?B3&t6NG}a>7|@f8XN;#OLYbFvC)16? zHB@!E7CuqO@&T|Hr@(pv>^J$scdPAaeiJ`)hSPR1b94jR*R;cnqVLr0- z+yOw1+NR;+>q<0kHRLeMweZlWf{vF)P$5V~`b^()`JEwD_@ITehO>^gNiiVtsvKVO zsF7T|Fh=M)k!23&D#Q09R7u**OUOl=^~)&9@B=`g!LjRg_Q zc;06s$^t$C+PLpPI`NV>7A{{ZXirXfx+#J6LqfiFh`*qI07a={3LO z)bFu19zH)2a^qrX6Z2IiGmZV6-HF_NhKE;nC&0$5P2k?E3KZnmOb*Ij0RiWjr(@I+ z@O0+_$Fk3SuGi*|($u6l3M(0DQnBq<@&qTN+1J=jV~aC)Ch-B5vOGctIgRErk^=Db z?m}4dxEjogEJJbAl8OBLZ1AyH2j@I_2y~t&IG+FC4Eftbi2{a)TBli0M7|rhpJ~I^ zJL!OVNSXPqR^yGZ3!Xlu2#Fu-Qp^>JBMq*D(|$v+$JjOSZHBTi{eQc5wcA!YxKdU$ zqRto2D)KK8I){S({z1fD7(*{syJ5%cjGOX2#{Ij`w85(z;F<_`+Udz-BUmqh&I=^* z<5jW3?m$Q3)#izqFn>wl(=EiohsVQ=h+ZmOd<7e^`*UEi6xy$kNiBmwu01;L!H~HO$1j&$){?TpTVmZ5x9BMQ?%Q?i?T`LS_7TkAPm9W5dn* z%JeoLU7*E8MWU6-&y%;3>gix2N5De zyma$B;mSdoq&yYkNw-z#?L{`+jqXXJuje?JKJ+em9LUd;$jFW>HZ8!7YTC4H`DpI; z%>YcAW8lx@iZJY$1a32oCJxG(!0DhC{%}?S&W#*NUD-|kzZo(#)`DTy2UO9bK(l8b z<6wcLD0;FLlrqU8KE{dz_eu3_s_=-046b`Hfn=pz0q+d8@IrM<=-czkF{Gyn`5sWD zc7wLkkMXji{ja6qh54iD@{6|EV{Z)Xi1eT*thI0e^J2_$JI1|Y|Nia|(QpzRN1N*S z8S?9u_rURaJ?gt;0YZN~6?X2kLs5fesnhxxqWB~pUHU0U72f4g1D5~4p~wdw)Q_P< zhI9>RioSkp2P4MF z5NwmG6suk1bG_!?nnLft;xRB}k&v@zy05BdPvD1XCe%eEb$}nA$$HQCI)vg=*HlUI zqS?YaHD_#MsRWyH1f+23CA4}3n+Haor@PN5;C17)X!le|oxIo{-7iNoFWPdC=7!|ypQJZk77{gt&Ou+q?37_QNnmn1KfB`15UlJN{)^zKpQ40uspGSG$X(o zZ%gumYc8*)KLlS<#Tu4fxnwR!xh#Bw`~#a(E`#ysqtL57mLIi%X_zAg*wSt+aW6V6 ztdZBn(^V!yx16zLT|+AhF;%2en)~VDht_!Uv_#n16G5A#^zk(2N84L*i95zRqfIv^ zz$F=_;BZDJnp|E$POQ%Xdy@p%@#PjEr&R73;>hzg9+~gS)h|)_!fZ`?O#UsYbmr&7 z@y}*(r`4-*w#P}LvdN6)wp%4x$uLYk@79&6JOJx7X93anf-OgXZYf98-V@}_vX2s5W^g-(RpZK;I^eUn8r(KT0v~Y|i51!3%}EyEMb~G-YdcR0 z^&A!Oq-z5D^qV^srpSthWc$L5^=GMSy&HaaMVUTdx1Z}_TGs4wAcMs9W*B2^4%Rwta;QTyfS*SowCJzQDw@2ZR$Vlwm_Kd8J?JOtkjMcQ?o4avtSWxr6)BWjq>sOrctgkGOG)VjWqh5@li9D$xU^4` zL|0z8z^xag$wW{*kZsuW^eN+gJaAEz3biV)1I6n~ko5aMq%y@Hm9lK2X-so6Ec7;R_S2%{pP6%(wTvH^y8zp# zqs!Ti)cThvwAL}DFPDEnk*^i#^C|l|gM3MmXoM9UG(Lmmj8GiV z2r1vtfLovx*6y_-oMjG}!8FyjPlm(a8|Mi-l$()c5X%^;7Sb(Wx^b%3S71Ngh)xZ+ z#S-gcVE>M}bi^txe6CE9HaPF+s*5B=R?nlMg_{*E`5lJbSx)KCUA>^kuogW$F$%cq zbP6*+PehyZWN7E#PT{cy7<0xC$zd*#RCV$C$$dA{>Ajyk)@|5!mj1zA1N@6)Q!gm$ ztU>N}f#B{z7a%+sgB*+GY27IyP|=HGxz=f9s#Oxn|5}W0GvAEsk#t%t#kwFvbKsR| zG3^{-IKZQ?=p&X!(x7Lu3*IuZ5Y#BdiPIN*4fHDo zY#T*y$~$3Pszm=K+iyd8`w!v*6aw48yO})d*TV4vsX|#SYCkpv{5| zU~lysc{JZAOO&L+&>UxcGENB=N;HTs&*5jkt?L8ng<*;KM4}e`yk{b9I9`fs80HUc zoWZI7$iTI_Bfw}~2!?O?pOY&r@&94qztk|Qsj81Ji51!Z{Q_5U ziS_s_O@NBy%YpN%bac(;COI1=2JvnJ43}*Ik3-ainHD_%au}DB!BXdNrKct>?0Qa) zFXLyzEeCdRL5yG6axa;jJv*GcRS0 zVcNuts3KjS7F0{poj-XD{5xeTSGKzvr|#DQ+g5baui37+b>?$;d&)4luv;3Fpqb*} zCNWTC8puz9Ga-y10v*5J4#w&08 z@N)f5aMLjlozGUFMc)YV8r+VCuwKQiRZGat;T;2ev09!y*Z65IHb13GkKeS0IR`W` z)gA?9W(R@AHWjF9=pcG}>0mJZpey!@9ScgbQpN2%_9Jl94?fz}O?;lI;ST0c49mCT zmUc*r&K(PbdyYxb=1Q8Xq@8g)^+jcDypqWPEqup&{IvZ<9oW8(d)5*neV~D?CTjyrGh2n|WXv zPZe5K@dQ-FTt(ha@5z?SVqoGaz)oi?gsN)C$oFc9k33`DG(kf+TS*7e;V=$5YUPu@ zIDQUHI%mOY%HGDgOv9fu&y*`r3}*h>i_rD;V0i0bCrT8Ck?o(wpo!@rA0Ci^;g2+F z3)^x2<7Ltw4WnsKKOn`Sid4UEJNK|uQuJ!L6&#bCLZDlWI&KhGZJh6Ng~XCSC^mFY&vu-IHi?(xwEN zu)B2I`Xt)iWrMG6&VhMOg>>FRL)@(;pt8kw@Ql6|zI?ZCY-8IOm(iNolHHBRhjQKG5~Mss3@ho*O*zz6TN>6zG6w0(^{-KR2z z+pm&{Hz%5qOZ`)zP(}}@_uPb!({jPQH9ye#gi>O+)fybx~R9 zbAdciaR58egPXSyds?Zd&;-&r5qzE-5%j&t0VWJ%HaSqbo`-6OE>atb=(nn%9ud<@`GHWS|3 z0s=yT&{U7V8H$a3qc(A+N=$!Jl1wBLhH-0h0`Q`u zLfDvB2QE*|Liav~krgK%gF%4;Ji(|KjGn}_vSWCj#Zj`CeA1#w;y%k;n7fG^XCfu~ z0w)8>j?Yv@au!~5>N)&1-2i&n^rGA*M{&upC*aBt0rs8X0&{Qv6FP(|;PdiI)TKw3 zI=gq_FK@QMtJMojmJ|d4;rxGMTjf)9`!aXz`AwOE9&c{sH%U>8X9JvW(iaDHEwS^a|QlwZLX z%QR_6Y62~|YJm>6~JJPtQK-X-ZOZJq!AJCbn<;ZYmUh6O?R;516Cc`-kwDAX_1>BJt z4x)~gp`|hXjL%XcZs(iD28Izci^_=E{$34frUF&Xq!qC zDCoJ0?4G?R{dXUOynF#xH>eca8ZIDFZy}CtRiRA=>fE9~lSJp)DjVQ;mDDHj_rn9h zqqs`HB7E|(4(%!*&RIaCM$gp3HMC2Tr=*iMS*)vUcS+V7F;F zuFG_Ul@}|8rE1M+47;Tl%vPcwS%=GiJhi$KrscU>IQ$pWbYJ%7&fb+2{Vb1$W)9}G zOE-K#Tkg{<1JD1hLxWWI4 zxK#prHG$>Q(*%0H(gqi<@PX+qp)~#ozb~8abAaY?OrP+Qg4WDcAd1b9|9KA=UWz2I zEK1O%WeRlZ&_r6taxb^1=D=mYZ_{KiLoCZQT_y_3@Z`K#r~nLu6JxG{pMSri8f#>OIj=j=+s8%ZN3{~zc2WnA*jNi>-(-vJ z*Ydmbo}|OH*C!FHywalb*VMSidu_Ph;Uhe(ZB4yPOVKDzd3vQl#H~-yz-lOt1e!m43-{ffg>?SN(5iX6-YiM>@H6xE+l;$9UBTuB3l! z$AHe~PqY-*zm?y$t%P_cIUp*>N1+5{ISAK9dq$ z2@JeqQKaHea<%X=NSh;tS8B_OPncPQyczm9;F>qAa_JMVU7(CRP6+5$D9`Yo=S{f8LxniHL!0(5ILxJ;XvLe>^}?h$=G)Zn zLVDR@xOW`N`W-1P7 z$d~jDg;$1jqMP<+#9Qt&Sh-0H-#BRrv)B9=24__@3yhMr~}rVBiL;HotN6lZh|c()TLPlq@_ z3s*H$;4bW70bscbiS8$<88@mSgrbd5gR zZitr&1oSJrIjl2#j)qF=!!IpjkRQ~J;J>fLvepTtHtXQ&qk@5$nu@)Xc|DIuKkL$4 z?}U>&m8jA1A)F`M6Nlb@0)O_i+|uVfmhSVI%=z!jzzhG4CRNAO;ncT{=wZTfxa@T% z_+$78{VYu(Du;_^oFO8^AT?R@P@mN~wyiW`R z3Q)yXrvH3(o&M^Q7R`D0j^xJAp%0VzS@hc>7rHm=E7A>Apsitmo3T6_k5iL?ovDSu zC_NAv*8L%0#BIQSfiyOrKZ0yH>K`eY%juWbi% zcQR0>dMJrF)CVZbwDCNCA1qU-5yrS*M0@YZ)24}g$(-Wb_+<7i5;3)%L@%bOn`IwG z2Oi|$a7~d*|9tRL`ZXQ2YZl8De-8CKhr=sNzM;Q%cH$R>axkyX5U;n`04pXqfU9fy z%v-ak>&YXBZ1#R11<#i4r55+x@n};OntW>+N16AhWqJd&%bi5`DP^GEvGR1BnL4aL zQ;*`0o)FGxk$^)>b?~>UC-D2h)!^P6Q+)N$KXP{OC^Grvfq~Ac*SM0pJ7wa?d`-Ih z&pBFHV}s`@Lm2aP8TGB_Z z>d#ytK}XsVIHSO_Rh-CJcDMYGzaC8g(nldYmR3I2gtrbiqwrC`L4{Nbh#A45$hhC6 zXTf%G>z+0KH$)peR52GPWbs&fc-LL>>AMJWlf4FBEcZOvyJ(0J9-sa~?%LT=OOpLL_6t?W|LM`LW$%AM8pl+8Iz8h@` z?|#t&N@>k#)^|nvw{|+w)jWp-UYr5#JHC_Id)UrCAqEN2X<4l=W zKd&GfPS{~cQ(VIbw3KT;sKeD#&ye4sk)U$TaNxLt*Z+Ww-QZl(a9rMch0I$wi~QM^ zfV@`7)0}S+^tG-nZVB>%t9AUS;=itej)TAiclh_D7GCg{f^k<*f#XbDzMplb%dhqa zrbIG$N-)9k?{& z9(Y^bf)*)!AScQ?>pgBEI&bu&A$6T@mP9f z*Az~zBO4oTwI-@Z^kA@2Gvd~sfKG36L2K(>bnj;zDG%}n7vJgNKYwe1*9CpCQt~Bq zZ2`L_=DX4ha!DAk(x%*MW4hM43_Wv|r|WLoad+uu+@fu?R^*^|s)0)$UUmpsBSp6yZAc#aS zwWZ{ezvyrD4y;L{yP|78;xz<0w;(6vBYQcCh$oBGTG&iXaVTIIYP5Uzk!2CMNa>hdN$F#`z4p z<_sefE?&b2qH@X6l19=NMbQm81^UAxfKzy9Dq6L33wYu1g7zMpg(JvwxNg}PI9tC9 zWes-_cdE$4ZEn2IylCHYFp=fAtpBP^UqniiQN@wif0G)Fksn#2wU)ng22A&%$NJoH zC)2{bUbuie+s$spqZ=UlJf2n#&Ooo3ZuaJIJ*d*wfOO~k3eWp1La3mJtuH=>(NB(m zb!&`p@UfpnIm>`-ZQ-*u&gO8`!z~j(zM)C8B+gRslHcq5$1S4w-tj#6FDGqCp4Fh% zPbJ{(k4s?9k*mm|O_pV+hkz;1SdU3oNy+bqP+}U*@Abk|KspccSbD+j7k!(-V`*^Y zJXloC^0l6fhAov>fr$Z+r3W^K0QE8+OB=IVN+vztkJ4NHV4~Yi(ypV9KU4~6*Z8;O z?__=!&09H@<X^7NZ?gj(&B~chs3kIl(BRe(;9WW zrO|9|v}$yLi$t|z;{+Z*KQ6yc7o6hx?r`=j4P(#JM2AwSKBWU#jZ8&RJ9X65B6D*vCedHuSuuI{FTxF+m)h!MNbQN`4m2+^Wmf-73HhW3{Q?-ECZadMnnS z+Y6=tXhF*jHE90$10;U09K;!HCTUTC!R=N=JohdhuNGR|meWjL4YC>V=B(A1p$~U{ zM8}xF=BUvEZd(o8!Fw#>l7mrXXtN@kZO?KWPL73%CEaM|u#x2B2s!xLRSTzXw}fgZ zEkVPzW|a7c_1Y9m6Zk$7|Gpg#?wx%>`U03Y2gJZP7e`StNE>sbSSOUp0&XbN_FLvg z!vbdm`pYqVAY<*`7fm?hQ#Cr(V-8N_nu4dFyL)e z(>hCae)Dr_Te~k^tI$1wpV7j3@I{msPLkk&zhw~UOpigYnBL5ERtVS-&*SI3aBmVN zQ8K`TCoDTlomuvKz?mGlZeu3ZaWKR;@34;YMY=GF)T8x(wBen~LQu8rG5W+ckdDTk z!0WIc&d3Y_fuAc&Ebj3J?hGh@#j%PYO*{NKWc0Rs()1K6i z)Q2wfno!2)<8WS9A<%Gmj3(uzl3cy*z=+KuLn~`R$8IHY&)G}pf-}=hrp=%;4<_NW zmD<#Pt`XIrSB4HVfAso`Q@F9?a`1`jQQ-JSAMmZuXuzw;f}P=`*~-{u-6bNEcNP@9 zHpUj6dhncnYRTg31?V61UcG+mNT0GklslWf;Oh_}edzrS$-Ypamy9-X-3!`qVz?=E zQ@aQDw)vxu_dUc>{U1=gDvh6h0r{`2Uzu_qtZhmWMil%TpX;Avwf?;;RGcx-G=AKvwl1#=g(90f$=Hd zFZ*(In3?ED_7*VWMm@dxXcoTv^Euo*YyuQ#_8>#^DdK$7!EjU$(_p_}0-I*821AN^ z(fpZziCx+SvEKJ=+^9MlmYp3^5}mA!8bXJlMkK!LE3_7AB%HT^gT>HNI=oTHR0@$GS^i4ukM#)Ew&lvmDvHm8TzW4uM&lYf-qL z7|aMu0xyPMMoL7A9?HH2DzDGP{yQ5>63vd2<)j@IT~(kizs7M&tQR1EqbuB>8*_BgR%!Cu5eQ9?ZeF zb>U>}L!L9DLp8X{ORS7jpiLbPdvofAtyq0VFFeBnZF}0Ep~md}#5i*>>|tK5e_4uf zSIi!93(GnG?(9@Nqq>|d?B;p)UE2L*SI|c^W2qu7tC+>TVY8yq8%sEC{~0pqA%7!X z5H}P~xKf8A-l-EW&B1U)yB0oXVFk4=I)h^8=cshKfM)HRDz^Hw46nPh5SX|c)7e9{ zal1Y9JJiqOa+@SY&FRt5bdC;nSi#>&yBZAPC8qybIC&H>J3SHj|Cxx6zm%aF)8oO8 zBIaL~$|NtRXO@_~55iyP20+C*qsVT|YthHI2hw?L7X9x=`tI~0)@Rv`a%U^h>%}o( z?G=9h>mnpI(kXo{=zcYb3u=RH` zU3tI||7v6X^#@E~=cWdf7^nk3?W_fbTn!p=x|NhZItNC~*Tr)agF(-b>BWWqUTFI` zSvu>_6XM##W9dXU32Hnq4H*~8(}|y-flH~?D8ltJkzExH^pshqx3CVZN?Tg|HG;>? zwmT!~jyXx#AXb}B@YkmM50s&i%=_FawU|q~T#c>dT!G5O-5}(N(Lf)~w-1Bh-z-VI ze1ACEH!&7uGXHhk4>dUcT+O7!|6%6n)^YR>^KEUO=LHMp?3w@J8=5brNY@s4aSNFj zVB}s?_>4W(2V(t^((xWLm&n8AKC<|ZtU38M`#ca{)W#uO#zW235)R0PpE)NMpQ16| zGNP#PEyA*O<7tP94HnEugzgDGl$7gZZ*2j6UGK#?Zfe69eS+YI4Rt^-HUuRej3JVV zP2gci9ST>q2NUw23gxAF{^-)eSO@(x0k}&bN3T6)_uNOxNUe!w4IK*M&;vV>?4P$p zev^RvdpiJ2FD`_oD+{e ze@1e*t#>H2n2A3`X~O(b|HKa;@jUy)@j296Aq%gasznbC4xpTb?EtSNwsEDp;6B>M zX6apcG~DLiidJka2l@SJV2pVRTGZN41VFc)=uyTZmvwxnZZ#{l0{flO1$qa6*Xhdsw{{k9u zWuR{+MN=|+N$u%4u&c}fpO`HTbUvP*G&GmT(vL-vWS5OP4s8}t$?Kyzl}qNLVJ~jO zf@gJPqhAQ387wbI^bSnE5{;Bvzmj2XQt)P)1a8?cEv~(q0-lx|;~``Bz>!ys9md-$ zgO#~yta$y-_Ka4Q|o*WJY$mzee}$Wo3ftmJBFpOT&@OmD+Qx& zw*peoq62?1ovO>^MxpbLmE!w?M zo!FY_z{E3}_{in4a6#cpu<_1wu59*77eRMsc(aT z&)P&VjOD+jjZ~nH5~YrZe(T|?;f}DO!iFrH!}Czu^(U!5%c)D=p99bP$J6a0Jg!bP zG=;Z{s!`?z4cKw0gx&G-kn!IlGV4zYcvGx}S56BAa|HU19Sis!U+P~05jr~K$t+(> zY5Gs1vm_1exh_v<)LTIL4^0DmeQ?1G&`qk)*C**jSe*fW?a;*&YU+Ug%his{Zd^j; zjMIOqphGv_Nx}(II<(3`jkc7Pq3WaZ6!gvEUc^@8d#_!<^uLEecA^n#V|c#pr~(w~ zvHV+dnlwb^1BXk-tfx|s>73IX4WAdF30VrXTyiuGWOM0%7`t`04ehGoG4|AYPtJWY z^Tzs^!sNCZAd%>gZpZZy+ffRz^2|T9s%jWH@-vfZBy{nXRTJUIO%EL3G0gdIuV1re zG+nD_gF`1KLU~6odQ#E=rwawt*3Xl3+|z~|)&#+5>n5PyABaBYMvs>rsf< z9=xu2FC4`DkJv$$YDHcm%f!hj_b%JP_nqQ)NZO00S-vBIb8_jbW*ay$*@%88#sEU6-7i0hlhMZz_93FXdUC6 z7dTH8w)C?1@{W6Ko|-{x&>TE=kqW(a5OC83QX&KG2IwnmPR}3AKxWLhHN;dMermjp z;&oOEuY56ut>^Udo0ezrfn^LZxFL(LetAOf>Dvk2-?-qsCM{Ui`$}Aw%-=$7l2WPZ z&@7B+Y0+2TPSATzHu&We02}u^QL72}2lSkATSvpS5%oy@3@h7h%mUu>iRiR`FUk4z z8hjVez@zs!lsNuX5@t#a#o2=oLGR6OBv<(jQmj*;|GwIC`{ZnnC9o@tApNNWS>sl#+p*%opPl>5^^_ye~k7R@|!tyK7FN zX3d-A=f=+fS-n87yAy;7SK~m#E+u^WMF$K&lR7K(tta);5=sXK5{F`5yDoQX6db>~4%O7D6WtqDaP~D5ELsiVgVa61 ze-57s9QWQ%7*OGgUFDrY@VUV>U#N{`rwiyp1i1LulA^US(a?^42MRBFY#eMc8s<*n zv2pH_sX)l|od3<7jn+3n@)1M)GBKSTJ1-D!-f4id!gQg=@4+NcCjsq}VOnL=6Z8$c zX3e@38{evohJ*EZYN-7`gzZbER@&6loTYCE87+Gig}U!OM|$Rmo6vVharJ-I?w7asO41pZ~& z=u}cZ`KFrz+$%J(@`eCV9XHGI`A^>eDBf~|_z8KO41du@TwT+UQ5w756}xeLAy4sU z=lSH6lqHPQeU4m*_`-zel|cP-33`(gL-r5O0uyHG;>8Jd!2D{cW7wTb=*4!XO+BGO zzrIew`i44GQf4sS6UTOWhNV{S?%WaMYFxA41uQ%03#LTyn7MHAXE1X(TUsW0GtWde zuxk}yHB}ktv&KxAP*{KjkxUb4ZbWNY4`AM6FZe2cG|l|=4W$bd>HezyT)taemP)a1`uuHL6#h8Ka$R_A?CpTmbl!bb#d1x z4KQwV27tsB@1^23Ee~Vv7GTf=ukC*bSu6=Mo$%};n9)Y*$dhdee8Pi&z9mh17td#ZG7tPPazXh7ZZKSAKnW)MJ1QF?D5shpk-RKf*# zw%KQ4T}7+o`2XEJBd2a4GiIr?3~jcj+m(~zEPhXa@v4~E_b|IoAzgT&3#vO#XB0LyHc5C0V(5yp;D!6oyRXx85=V#h3=b1yc&NayM- z#hT1he?a;G7t6G=@oU>)>i8z$FZ4qz@~#oZqF%6H?*;nyH9`2UFdKA#6krd@4!A<) zlJKRQ6+TfTNnIaA&~alOM1lYg7G2y$%75@0csKt+9H0ewrKC3f$_kDW7*D;Za~gcG z)e8Eu9pv+^LnMAI^XE*^$8W7v;Hohvz_(dyqHo-j;_!$NBB9IQKd05#l1D#2qL|}~ z^v4(0-^ymo%14&)bA}&TQOV<{PlG+2lFnnMwEGD#?EO;|)+kLwzvK%QSSPRSZYQvI zl03aNTN_8a320`w9oNHfSS>sn_FfdwFTcXk8XLx4-=74xeSCqe{#k>QOBR5Wzb7Ka zUKwgR;TEv+5@6lHvt)VMZDBGo!0(!Mq2k1MVz1f!p59}*o6-UsyfR}GOmo>l13z{n z)k6w&!ng^rNV5UaxL^>Kp9}nKqEX#b#;^Uo1-7ge;O-^^a^gUN&|;4so_S&l9F;9c zmR>ADVZjR2Db9+E3Y;lAK1T@tUD{2TueZfyRSvw>c#dj(<2^yxjywqwlU$mnxI(f|1OpbTxg#>!@Z zKf=O!bo3$v9I#tJRa16wmaMlu>q9);=1<_Z) z_J@>?nKm2CX}^H6gA7;(G>@xSvZdjQC#|TXbU6H{k^x%h|3drw``BGU5kzpa@j>$n zaMG@%I4+;Rf8KVprGswH!8*|@^cQE%jb{A2O=CT5@Ec0cp2|Re6M;?erZpJbR{F*rP3 zfbSiSD%tNcgjkMzgIZcy7P|2;?%}UVqGR_~!{yS3q_u^|)p2?a%v-)5UoTLl*>~*W zpy5qu+mK#x?8{>?FW@S=fABT@}wE&m4eG+QDHy5rjIDk|X{o%GCXJR;A9ZzTZ z+qE7AXB={o$W@Y=Y&uD!R2q#-0J+%u5U9!jNBDWz1jq)leZN@*G? zMbc8%z2{s>R;a8ZA)2H~p}gnUegA-b!tuS&^L$sz!&Lr|3h!V3Fr1P^?+2{J4J9m3 z_->%Uf$=pB9_{cHzYP@b4@HMJ=Mvs{ak$#$6-v}e-dLwcJ+3;J4 zpSv#qp;L|(;vb2c)D2#xCT-RjH@m_)v6ErT&~s#H9L#d(?BMlNEJHg(0lKFLkUDm! z`mcw=pI=U1YWAR?OwYNN<%CE4Vt%4FOL#yvgiNyF{Ns!+m*_($l>%gW^$$Op<;M5_ ztVGX(MCi27HC!`8U7S#<0UWDF$Wi9w3uSkSnmbkk38o+JIC%!PM@ZADBJuxraK|lI z;1V-{7l$MRH@`JtVvTUlT;f><#;9=c#;FOU%<>P{OiB;0FxQ4xV;=Iq2c)9Q?lScE zWa)EZ~i`9X4aEqywrAI)NObmh-HFM7x%|t$dZEsbgur0SPT=_D0n%>A_uqENxE2(eLXGxM~w`TW1xa`7w!I%eKily1(vKhw4d z_A^h!X(IsJ?A`;5tH+Qr{!R`V8pEf2Q5>|!n5@mI1~;=gxO|H_JW^TCU9hnoP29uu zFg^;jjQOz4zq9tAkd^K8Cme&oMPwg@(|{`YI`De%IIZ{W+0XcXspn$%4Zhvti( zqjZZY;HxO}F=`31(SA}0DSj*D)4Tf42?Fl=JBLovpyIM=G(5{1ALj+Y*|KU-W0?K? zX$J93zGt*{0&r_8_-H3IOaHl^6hAO@t}79&f_#?ZEb zh4>Foks9x}5R{2BeOi4J)RoYo=bj30n5RA&K#wi=5dOJ>eP%ksNAI<8|B5;&IdTUO z_aCS}wU{itX#+0Za>KP{s_=B*NxnAQ!EJ6zQFJqkRxQoJQ`|JE=ZsCXYl01aGz8$R z$5W{NiSmD5p#zJ`fb+c+G|zE>{L!ffy3CI=J|v0vbVM3#_@jkK$?bwuio{5mV>i0< zfn|^us|n_eOmh}1T?dcHX_M~mpQ_k>?X9sryra=+YF{` zy@@W}>Lk0CRRa$5VMU7fa=#v3!ws(x^6Aa2Yo>LPaJH26dqBEx3vZRuYo`g!!>h4L zk2Y;E`~h5c9!Cyst>nGCCVZ*z4JjP{&5N2e!d;N8h;s$R;RNz~cfw;e`Iegjl1j-r`%Ib=$t7VMD!fyNZy=4Pbo0~5|9ES(`r z5BM%62L^<^`Kz#R)JwJyUog|85!z`qgZc5}FScUuUwS=OR&lOLZdcOKW`h{GAkE4vBS?Tg;6+m6o;NX;|TxkZbC1#w4mayO7K?tGHTzSP1adG z0qTD+{c!7uN^g&ef!=lD{HX=8-h%Sub#X z%)CEp0OrpB2|RU@Eprt?q8urrdE6cuY)yk*p$f-g%5Fud)rZS71N;w ziPJDu=2sm|gBITql?v9wM~*Nro`etc`HDKPZ%Bb}&-?M}D*0@?O5LUd=fW~jGplbQ! z#4}kQK1ypwyp;*y!3YvWPrMEENQ3*Ep6X>~TtP{<*)ie^eI8s$xD$elBWT zD#Z`ltO~iw9jMpL6fT`803Llm5a+^gGJnB1faYmq)6b`Xo1Pw>t+5DqRw>dGR;-hY zW$F%8G{LJo)ae(w>qs_~Ph zntT;P(?9&nQ4jfANxk)baq&qddN%|^E7vBJF5M4eUVH!w7WdFJyN~3C;5c{x&wWVy zcNpAbFGUoVt77r*9J(?&mq?e!p!i$T^m&twz&oo7U$)n#x^6>YF5_8b7PgYW6h(Mm zAe;&B7JUV3PzUeu+6=QN8UpQI3fTHGhssWhBI8amzw@KZpt0~c{~QwX<1%7V)I3Xw zlX)&ag1q0N&c>VD;RN%y;P8V(=(}tdDaaVb=JEmLx!@j`GtmWn-!=(9?h~b7*0>RG z$%ua*bLF)6G>2*3f9}0g$kp`%O$Dr`QqDz#+Vuw6uU0|&`3lcpja7VwZ*F*^7~ zglvMU@V93N`p_m0kHZU~#h?sL?;0eN?^}R?QY{=1rUq8cZ6j_mns^)Ar&3K!1P|Hw zHSyRP*lRUH4Ccink7Y8nV&YgB>vtb{UQ+>m&vyd#d%{_9t(h2nSZsiY-(Dex7IVP8 zBxAhgf*}lkwwHf5JQeL@9C5AVQmWTuh3kC$;GDOMnFqTcd8M)p#-rxwbL}WBv54iMM!3ObK@&Rcs|9ZkJq1ZOFCeWq8RRtR2UF}>j`UCjP?SvM z#%BvXMDdXtB>IRO*0`WRLnSN7=5pbzn87;#eM<3+}|mVE?9 zb*%UEK@3@Y@fR>R)xZ}PKLg>cZ&fQpxKq17|3ohRhlgxd9PfQluv$aid7?@zX!1+~ zCtQShsBEhSO*XthyH5p@s`JA@H-hCudMLs}Zoj#;6+%2*<{=^L${*UnS}) z_=+&ol38By5)`nT&v^v^#npR&`?7;*UNH0X9v%%(?EZ>QaWzS-UlcWRBJUTJVeWKmuF}o#kb%VPBKvk1nA=6VT^GCcGu zOM!LcM4)_h6dGijHLn3hXgiwCje1i+S?xqHk$Hvw>+-(izZr!8o{0CT-5}MX-bBYN z1IaRN*pAVs>4fVnM~?LiEZV0J13qS=h?*F3ws-|>J!Xsp=f4E}&mo{jRLF@h$@B-= zM%H-mXe;vaW++)dOp%6;EIpAl8kQZ;MT1UK{Ab=;Ff{fx`}v!|@T(6&SIRr&so6sY z(q@A=_MR2|PJ!#c9Ex=h3iX!q{z_EUW)UuX!SZQ8>HhP3x|TP=66R4{HTpVAijtv+ zc8-J2AMc~X7OT1E|15$@)q1$9wgK*m$pHs;KS8`Zmxy=JY!H7%3vd0=2Aaey`O{wt zJ(bVuw$j#!9PGJ4lU{ILLOmHaKJNxF?Enj6;II ze)!jQyD+DeW^WPBkhAe0ko+bBq1ER>quo0YU6h3sCEJMKu2ztBNDRw#zT%oTXL9#j z1tUqla47P;l3&ZX@BcKJjvHgC=GbRgBElCAW@eI&ycpD%Dovl8RdH@Rd?xlD^#2Y*e_gMVS(;mitJmYvWy62;0IqHoJ;fa`jPwt=FfE(fnK5!Xl1b_XfmLn-8dQr1^yzl7I%P(q7gJr zNr@EfS`GZqvTUWAsqovf1$>h}9;##B-gbp~G;@ay?wytkzxjsIhV4QujR_h7ckIKF z>CR%HI#3G)(~{6Fjf*eEEt#Y?7mc*&YJ%8m1o`L{OfUWoy;9R6Q5sV4<`SW%Jvez1*f!LGEcbHgo-JcYe!~rXY^N@_{%Skf z6=s7)m!-p(Zr0SVN)NAnz@ZKT4?z#pk~Q;F;0tFlxTY-v{Vqr(N5j;ipE$!$g(;w> z+#Wown)@%)vTs~C$jX|4BdfB=;0h&@-f;@2iu=IP+4G3DLk3D=y%_c}3G}Uk4SqNh z0L>nV!i%#bP|V+Tg!^Valw^8T()JRpo^u?`X1q^&l?)x;5(P@wJ6YH{iOeVsBpDxt zyie!F548T%2^`X?h5nR?z#ojm%H02i=jo#jEkc{o$}|I*mtFvl@N3YohtEjjcYhFV zpo3@flR)rF@#5kwksxc&U;f=S64Y(oA{_TqkzQb2=E3RL(Wp2XdiSXaoZ}UaI^bw- znB7u1ae_Af+f@g>HH$&izNg5&K8@(+Zw1E}X=B-e*TD1RSKbAu{pi846kYvr1&waX z!4_9E>C?yV)Rtul%D)0EYsieQkgh<}EM;jx(Fl0HDhy4kVVNh*?Lf9L1v%~?An*6F z8Elyd-qsYwJD#xzfILIIwfzvhGj$dJKEE6JPL`v`%sx^{mFdosWF55klO#z8KmN-H zuAIfEE$k+#6QV>fJBE7nc%qp2XOM)736lOiPXEl2RHuC%=H zCizI>1b_7|RlHYDp01m4jOHsp!}c3|;k((XWLuk%_o>J*7aY&6!gEGx)9S^d@b8;& zB=@#~bQ4WjJFyYfd~fBwNmqgMZA@^2>RuRFG7IE97sZ*Z&$jZNA`$aDh0PD7gQn@* z_;=}5PhN;9hHy2w3p zfcYNZ-N2J_Cqwfl3!=hy_WyD(^JD6%NM#`|OV^~+0u$&0#wY%_vmag~0xi44&}2tL zGVYEBJbkksJzHH0OjkvLOqS!irGB`mJU@$nXs$J0;JOBi6r3UotA%rEO~D58;3Nla z*(goz!bZSx6oyoL?(^5~zYU&Ue}rai8YH~)fgoF7AFGyX0g1glvM5#)zw+nMsa}0V zezOoK1M2^RmEFgXzh^ynM*0yTQX=GZ{#Jbi{zMF)i-{t^n*%^H;{s9+YeVlsT|T~@ zid6P9J;uUW^utFh>@?pG`Z>?0=lc6m4bws#kogP#1|LK4;CS#=wFH#Bib9Y643JCO zy}(vl0xu{~BO3affWt}+tQ9&Ht{SxCOUm$3>@&s-e{rXGmf2th!(4dR_865(8-?40 zI5cJ6FgSTC6qS_ZgKtUIV1q|IY92`@ALJ;Q($RoQon1gu&~5JA4Z`lTsWT}50?R3q zEmolShIvG~|0*(LJm&p_k%I09Gv}bQnPl7iA+S#=6tx}Jhw+S`9xcy9rPGqh^2aLh z(+U&ZCDsjUAO7HeID8SsLYC*bSb~i6kHX8}{w0r2ye4V8OVJqSD?Gux9uDH8&?}A< z-FQe3hHtG$H52^F9#170<-#&-wUwYc%Lo1>5YC*v4=aiB3*pSU`?DC;SN?_^16c;q zrg?&UO>Ey8;KCzieL(F)AUdu2nwZY9ffp0MBa=)m(%Pj6S5#@>YWBvyPM8JEJUh|V zyBzwU{}$gRFdM5+(cw-d)g&>|25(%Q4!w_$r61U=rOfnWTX)VAgtUn|*WXKlwwmH_ zu=*G(+!;p}-qwX)OP-_DwNt=}4K84J$J~FtJone01(OmcVD|@EWR~SwewHuG;&WRM zLuWaXJ@y%>UQCv{grA^1hMBiN1i*%BF?c297|VHEO>STEgQxH)tix*tJ_@Hm=H&Cp zv_poDn{g4$W#0K`e5S1Wa3;lok*`IlYr@%Rm(=936sbLKDkT#?M*A$1DR zQ%ncLUp@JgrwTcp_g>rR@KP^)#axNTCeIVRX7lH5({`vU=mM2|Ulh=FjtmqSLXDH_kkXDdblIZ4r+j6;IQ-&TEH13F$%|l&Q5)NSx+0l zcQ;7V6HVNd&Y@$Y-;vU*@#xht8T#az7);Y;Uq_~n>+&cPIL;Dg!DTNIgKf#;*!N&G zSvuo9XgXw!*TxybLnF#OyR1|+W|s^#Z?&fi%~trHp&w+=hu(4?K!8IUda9`|E z^tIj`@Re)9k-{jH+&)0I=8C~_N#eL~h8m&VIAAtb1HYd=6;^K1<=uVHLtTZkv_fY( zJsM(zzfH-7{JHyR^V3mS^(2Q{_ld%(El1E=)jSY8(g0djPom_jNyMe29;omdP>HPz zD0gh*e%&veEzh2h=fzH(g-2H^(vq|s#u;Bl!F@6`WA72cJl1XDoR>*@*NMX4#z&B) zkq$g0rv#TJ@{lAinVk651c*a3DvwPDUmSEn&Gn1unIG%RK68_2bT$fW*o_dsS5;)= z`BJpMLWVw{mJZGej8MxPNqRlh1SVB9pdDq~2u{}gm*ZqFp$PLUrhx}HgmY$RxDL-E zE*h`h8$f>kxlgvUxvP7o51hN~7x6L_;-|Noo1mQS)R}L%aQdl_KuXLP^?-Upb4=iO zkw%m|Qes`IpK$0X z8#h4{%MkkyGbge8j!WxNRKDN@Y29HA)xGP{xutd>DRDjs3KQNfmww3xhZ@FXebFo; zxZGL%FlG)um!=QP%PfdMJ>#Dbs3|;>j?u8enQZ~^@I!GpEI5jcyOxt1Cr87^u}x@B zbUa9)7r+dLnG4u#|L0F7nA7HtJ*s9AFz#k?f|UWbF))Ir(`J&4qXIO}PnNFheo044 zPU7o1+UUSlF}UFR5i~>U5l^3Gd)37?BJBnGaQmo2aBF5h^88jrG$qe~kX}vvAuSP1 z`16A3<}AWoBPAOATa-FPT}SI4u-kQ+80;%Qf^;tGb5~h40BQB-sM_Q*nKYOT=5}i1 z#D;cIEY2yO{#mF|x0r5A*IC}g0@ja__Q;O9vOWDj%*>jmOO?h8XG=Q~F_<8E1U=fe z0mwGK1A7i8qa#~-2rpd}PFNv=N8U&AOwJxEjx6s+3+?47FM-lNme>8?Jh|NDD?eT9 z6I{S@Hh7-5>Ep$|SpFd6cbY_@ThU?k#5)0e;n#z~&&QF`==&sl%pmvT$i9EPc8q6w z@#8R6tgp+sLG|TydG%AQ$MJ=0!sE!Ycfxxn|CGMqo>Mj6xLunjRK5kqZtGFaihIOq zuL*Q2Xh10`tvuP94p0#P8VxKT2j@OK0w(8*V4pF6$yv+a#iP5uaoLnT0M2vaZ^-At zNO@`M>#~k2ob|#c?n<KBK)u7^>^gleve;z`iFPk7JlS<8V+ zHj-GxHim3Gmjmt-V|<3`=*Msroyy`<|9Q->NKc}RK3m~VOFy`I{4_c?U;yb2$+FKz zaTqe`5c1741wT$Uf(0j|5clc;$uyIKrgukBgs~FYdLalW<_tr33u>)emm%szERlr0*5xg7lVq?2axfx+aTpi3)m4CgRuT7ayhdD7#(ax zi@vx3yXOPkQ(;1l(4rg9oIV@Pz?)L!X|HPr`6ZJ1ZwLRpMGT6e{iwoP69%fNLe)!! zsMhy1iE@1d!ge+x2Tn2&sT~gtE(*2id)F9of8%I;(O!hwf1{-IekrPBoY6S{tKj^0 zBNTE|k{*d13pYM)Kv$Z#5sQ2ynDbNvcNHqaExYD{&n)BUKVRg$c?-GdTr{2*6+qw= zroL(tayqkLd?cc_-_TpeU%Nj7f(SNSj&J0`gIYb{`Gj>y>s>8rO=TW|w+-k#`wJTe z6X5j(V|?c=f&q2Gz-4a-O0(in$?XfdpK_y_26(_Jc%2s27^RPsKXT}{E+DwbGQ{e# zQsDd{2}mmsA*(yle^BvSq6W%i~MTb(QQ8w7*MF6}MEdd+99YnedJc!5x3#jMTgjQ$AgNOrHK*aR( z=qj7%N4E4jCE6R{eP%{b&DVxB&J~~(BuiswKBw6VvH1EIZS){q9JYxZKy|VL-iPdQ z@X^6$)KY2yJI4@kY3^MV@%}yu4ZjMs@36d@fCO;Y*2Up)?@^HM`Hk;=poDOW7U61B zCHlyHko5`(=gCpe#NqPz1IRo>hdV8;4eY9~L-V(%5uKCQ!JIAHc*4YXV1B{L>4xEc zt>Y}huJI#iKDa@D1afb zV0j7}J$isVFqMV-GDL7QjONAf%W*QK!d?5@qip)aaJuu%qIK}n?N0vBN}*@x<6su8 zkMPCL@k&%LK@8eV2uArh7EGMi%x+0hs5<2iSrYOQDE@9iG2@E3pLIE)LrZwKv@Ce# zH2=9O_VJOYPcI_+w&E$)7W0LE4EW>VV47exn%#Vh zj2j*c4H%bK@A-s4U)U_SEh59gLVJ_UC2 zC9(XJGII2|CbxR68`iU_1z%!+^T*f9!ab^u$gFP=a8v7nec)pxS3gXab>9a3k4D%d zR1Y|=`RH_VvL23w$6yaUPU1Tm=W>&EQ>rzQg(>kUl=0nW5n|Aq{VtGlIae$r7HHcF zXUnpw9iR_AM@{QjlbPf5z(|V;-q~ve&xHp%)t(h{&(;-x>Gy4B1njt zGEYR|xjR89bAmA#zp5GBoEC*vs}B&pJTW*tlOz5@0YtK%azcJOpktkW|K zK63cTva^&XQna7-m7CT*je!V?<%^&b_GfXAZde=nWXy%`%#%CzI0U zZ^3@mX2f!iz@5K;xDJbj`*=W{9JefVDsF&cG@&AmB)+_gf*#Azcab76(RB}cJY5Z* zt=59RCn%Die4fOddjnn^YCyNLPXjKV1YRE(-Yxrb`Q*|y;SAX(mJQ+#7$Hk`*KN$R zgd3SBE68{|seWS)ubtPxrg4hUZ|!=J&NP$%`E=fW_{q&3lZ5sAj}qCVu_XVK(6f`b z@D(9Yh?9aydx3VhsPpxgTsV8`2k`vxa%3)9P9&FU!IMkb{x12Bzvn2+(Bv88nPV_q z@FtdY`Uo}W8J83(huvE)z2?x0)2!>{v#4`*Y6?WRB;l=<`;h392;$m2392n`LeUb_ zKyda(;Ce!cja>R1?EN_bUmcrG4h}Kjw?sB>`Vj)l3?zx2fpBj0ym^3*e`Sr!`~u)| zUrBh6^$!N?EhMIoCqZqOCba&3JlM;0$O*OQ{&{u|UOB=IRnW(q1`OcdetohhRDjm_ z$kGW7_JV>1?#^jUJ5cUfO_wyq;<_Ro^k=ICEE3s^5@+*xS8rIuoYOB*MT#MG_kIK> zb>^Zyd+w4(^K9_3nuEp4BiY^hjl=4?C~zl2gnS@bq&#F1HXKr{TmmPE!nWP>}c9Nby-1T4H;<787T^y$<-HK88%Hu!iR zfR7cF=v5!#uHE!q9F`dFL9IM5F!SPj5V-v$${uPZ2Tl6HM2{AZiAXk($>HF^ zP2O<8-HChPQa7STEUQ+dkuTx#@n2?<3onD}_xR$Phf1{fk~my@WH&l_H3qyecm)hL zM4&gzZ;{;D13-LrD|&yth`Vk?8)$tI&XD`f1GzujRI$MhdFtsfj(Wa+iVf9$VKY5K z4ty4BgdROr77VmkVNDfnief*3mANaC=)s$0j-v*wDY=g#DvNp6j+0^K10&oUvJ-Mo zr2wv{82-c;p|kE^-Gj14R7sAp9h8xOjY{llfEdXF z?t3}-SIpxgC5Z!EiH7deD>_IclysgE(v#>WI>rW{C9dM!R&b^Y0;R zcu(yGx_108ct7VgFdi;Lg1N&)`CS$eV|vkfrP5%q?=V-99VCjN)8ScFhPy{FS8Rvu)sqL(dU^&sLK5mc5fv!kgr57z6^V z3eZx%EM3TP0^$!&VL{SSGQ58;+1V$=#`kr#+_OTrxMK$Lx_fVbIYDh&M6jNGOe!WDW|z+&|c*r@g!oOk{u8 zyLG*x%uqbnB&QoCTCkkk@^XH@@yCB%;g;ppz`rQi3mq+^>piScdINWwomG$ET;**uWPq>J1>z z6i)n`Cp%|x1X7mOxPYroSLc5LC+@63b1QO)eY!3T;yggc<~-iDhhi}G+beX-(E`r5 zxB}Xz4j@*BLEzRB?&NRUEL+$dXib&i56ScXWe)crcB12dd*R*yCAx2pwcs<$>dbF= z4RcFAgNGkIQ9n1Htkl$n?>5{=8z+Qur8P3Zl5;goCF-#z5@yFT;Z1w zPlb1w*S>Gx2#B$-0r$jmk$nFvVn4NzadR9T7bgv#PkqSsOwhq6+Crd(++s4VLldW7 z<r1Unp(59DSrM1+^A$M{tfF5ZJr}+w;Ou z@X#0Hc1;V4==?@sqc~)f&m#~N!?K-EjfWdkPjmNJ@{!pWS^9H~DqVXM)eyZwLtWxz=v7`6aB+;^MUzfK{%yFz}a!TKKPJ|)D`0Z%;` z@#QvJDCtH_risJkGxcbHZY8*r7Y^bS3ekffvNY-!(`obz_2-Ybl@N{iZz%eV9Buk; zAxLAo-${?T&>;B>*r4ixBuAH$oW-MHO2z|pSgo7CvwJGM+^>#Z-r2yJ2NJ>EJ5{Ll z{18z&w}6-*vHq9SULQM1a%St}H^Z#!L3*4Zg=O$QKAi$JL!{ve@f~PWV+eUxbroJx z09ei?184*t1iu#w@pIpi3UG4_2ixSQ?I9z8yXEm__E^ya!rVCLl#eQ95yd1&|uedUN*4k)6!{_-3gdUWN={ z#)CKfQKbU(F^2gL)|m*bliZyjiN*tmKa%jtB7d|{;Xco0N(~5*%|vS9Sp>>fg3)1Y zt~eeET;A;^v%fCFr&%V$)~#*CN+t`req*_viXS}4L z$eb25v#5}JIK&p1&ll#gPih+GN{>^+8w%xVab`c+*zpvvRPcqCuItEo(-WwnR+_%Q zC@Bb;RgGV`Y14&+-$96qCwlcbo3vCLK^wUTXkaRjr_(71Lq$4J;DzzfcH&*|c<%t} zKJtUK-WCHdMr&i`#4#XzUmMS0o{+Dx$JSKObQK=M`ZYGQ_j885AG>F-q3Gf-z^Y*h zI)CaU*)YWb0@Zs+KRlEh_v|_djQNOWz0M)IPB!5Ef%$mG~ix3;5cb=w) z?i69eiCWZSa1+havBB@RxI*ayNhtbqE1IxWp3Hn%0q!!NAU^uIXy*?xusT2+JF&B( zp*@E@>FGgU9dgvl(~cDT2=9=t<&se3=Tj^DySBHBwqq$-v6}^j;p=&D? zsO=jo{PWjl_{!0Q-sk*65)lsqevB4kBT%ikU)4M?6*ATQ^s)uZ;*MwZwwb9rm zLw?!61X*`9@#)#DHEq{r?u;3H=67ISlVg?Wle0oR{5`yg&UP2>*Jnma!R_(>s1js? z5c6*!AU7HyiWJfi=& zn?V z&vJ4InO|cFC)wOWHm_Uw>&;Z4!UvYsrY#L^SvTm7_$rioaEOe56bQmyz43(|NNA z#rp$bp}8!)@_j2Z-{MBr^q3<4(0%-AWG@W6^8mCiI*AfD50R>Y7a%pCgLTw7WVn3- zxP8wE8|E6rdE4^&qK}0*DXXR>7*26_b`XyTHV0&3LYO~_o_(LkUsDC*;xD2vZ&QhC z&RZbUriOiaaX|c9qGO@2P$R_2pGg$E7U7^NN;Ivep7al0N0-}V=)^2pD9+yG*&oW> z+g(4wz@|tv|A7O%J#GlJC6}NXr%#iG*WQCkqgftKa0}R06~R^L7VEt9OCIg@lF4HI{G29 zurk&k{g@L8+#kLLlO&FyGrd=daWMx*hBu=LTl2YGZ46`@gOFE97_9a-1gqw&V(U*F z`h`9w{_Rh3i;OR<+O&x5)D_N_$2>-;){iPY|Bn`Zdh082FI#{Tl&_NDCkD_#BNtgJ z=kZ>&E5jFu+EJ?Ocxcd63?g*CAq%HIq7ZBb#oQAXSlDz z`Da<41bbr*?2Ub|ehqa>zJV2Y7NY!^7_#DvImAl}QJz^Omvr3%XUjVgF}+5{4w-_U zP1^XJ?XZ2Df4>F`M#QUdE4NZ%UxmBN?DjZ*B_e}k^!_h5SHJtV2zO$yonZRcife68y!JaAKqMDz=H z@a~NJM7b*-xgBKO#C;A7it|S|gZSJv@tI)LWIHsYmvOiYmErxM7wGbo4Mc8CKVXVi zY-_3x^E@7LO^by1DbjO|eAw|6KYVzB==~Zb$JmbfAC^ip9*YzF3$0(la_4F|FlmQB zDwwVd;`2U%ac>VJxAM0nl*7CgS>Mrt1Q{~__75;|xdwK+H5Cp8ec~o7^U;PjSsLRq zOzhb{ZlstC#Y9}_=X7J7DaJHoT^yJ{+aGPR%>-UbBcR+V8gcsKiOd;!xc=uer1l*F z|78w#YF&5$Aw*b3U4^$GQv#62N|ywYb^Lg^*7oCKqv`pzA9jJ+qP0`yz6C_h|T|F&9;aw($3?afefYChk6N3uE702cPV! zP^0z`smO>2C*{`Q?JFKTJ@ODG=1J`9uStW3g-t|mGwWjG$W!m#dV+IeV$LW!1@6w1 zhxfVuXwUAWWcRl*aOs)5XhtOa9nFje=a&d?nCE}Z0B2Tc4v_Zl7T|VF953n< zBQEn70t?qsSi{8xcA1>u&#Vw)=9a-CdfHvaIauBq{J9_xcWVe|%Y3yzz||-c?R``R zd_O(`G407nV(bM{gMWdytVitFs(4^pn&+r!$uigKMailb9TE!{<8y&Zv}`E4Ye zIYF*Gbh2eQd_|d?I&ToXX4y?6%cjBIe?I}2DY?iYC4vOZ6@wkEdf3~q8`P*|u+$Y{ zheh+?Pl7##H_TN@Ux}A&C29|6S;wjha9OKAvK4p$!yHlQb@(`1#By0De$jx>)7wyV z(srK1_20mCp$7I**a0V;)dWMSZ_zt}9BmC+PSWNi;l|oLATm0gKVM&npJ#NB)74p< zaEg*L^}H_+ZJ|Fhu#N;@w{`-l#GNRx?Go7}p$fh0no(AMJ~wd9d@x2K2%XUngPZI3 zlY!0~IAR_bDxAY)SnI^UtV_;)vUe^G)Fth;C1y{++HWO%Wn~QGaJe~{F ze$O;+KuuRnU~^p|n7-#VvTbc8U;SnP!_QjSdDR#o&Gb)i;)Ix4{y>|y?p%ex-c+Ju z``Ei>`FOpLUcC0Y+#SqF>UH+<;$nNZA;`Z1TJlUaz zJvUthD!Q)x*abqp(1273O^+$Y$A!6KwCk!4KZhi#C`tAM~d&L?l_bkLO;KhZ8LP z(Wv#8`FAUsziC?pijz+P7xcda^+Wg23f*oJq(2C(PP1IuL=~{mYZe%`)WzPLLm{WK zh2Q!{s2y7TF^+B+{S1%UxeNY`ze#5NjYqp0N+tUEY&I* z2lu?_M`EKw$QD;|I68=BUw5g&?zJDdiFLx=+;Y(_;&${YK3H>s?BKp5zAX2fFYX6h zrYX~|=fBYOP&vwHTEUlnThZAe9bk947nIBiMrO}Dh~bL~P;=F96ko$3kH3q-#!gtCt`AXyb~*lN zdu%57<{}PXC`Kb%9Zyy%s=+-4&(Y}n7&!RO1oA+rFKP@oCrRE(IP14RtZwoo8NQk5 zpq4DvkWz*=U>myCs0i&gn87=@a**1*7?Q}c^R%Xp!T|?6L2+X=Fk`;Rk#HHRYZnT{ z`Br%E_se8__d%l4D#Tb<(GqrxF#4B`xwcXi`W=cuYYMeUd89hrn)e(9NmPP7ehQeV zaTlF!k)T}@BR~hs)1I!ZOCq1#;V)OQ{+G>O({Yw)Gzl?QV~V<9n}V40ji+2#b^IH! z&UQnk>iOjNY*Dy#FdV&3xW=C-tpO7^*CQ^QgMKOJfl0%aXm#r#nP?jUbXec+Mwv@a zO>TGjLDAO#y2z6bmywq#`gqG!rqiobf?s%BQ5ZZ*1_dI}$1fah^?S!{`V|X`ZResJ zy399yOb))9sfV{#oh8|)Hvx{SHlF|UJqXqs!+#wtoJ;lF-04b&v01YMpk9v>OlEsi zR+<~hh!TOPSO&-^meKJftQ7DSV$h730m5tP0^&18@WXv0d@ogBV4<#sYkq0N#RblM zz2^dSFF}?H$PJo2PsUk{;|vydD#74xHb0Bp=MBq0%Z*w%CEX>BNHEiT}$t}TxK_$ARM?h4@3o$l~W%4vKjGb4Y%-yi= z5AepvQ2Q7=n9c4Oz)XN_P9%|Ywj6j;Q6DGryFuYF;htms_Gd)uV{L|V{*&iFY`KlGz z^7k!j8>?3?=$nr?*j?qA^&6v(orcd0J;Ze4isRc%Y zrT5-|r+NP9ir#r5maPR}F#hF`Lq4~z(F>eP*o&rh9E0@^bAV=~B>uK-gzRf`A)9}e z;GpECuvKm{X>dJ(_P&;;@78{xj#bqdM`_bv9|qW6YYwtMnoe3Ci~z^rFr+kw;i!ZL zT(GeoogZxicdyR}sd+VM{jzG3E4c-%yRL(OxsC<-lK`)5iEzia-6l^h|AOVRVQ5^?9v~L?9z?Gc z!_C=+MIpgHVAMJd>}KHzYwv95FJIG(&KoiBn~@RGOA})3s9#EOovaXJUy1z%qfZ}0 z4Uf))vuA2R!}LTn>PsPMEPV^cF<(IR(;;q?#zvsTI-4F&I|B2MB=g%OS@yVqL+_i0 z(I)+8`0%=2Fp&A37Qc%}I@?%A*%oE^w9Fr+m+`r)F5U!bOsn}{FS$si26R5mG>7_Y ziNR?}*e75nLvXD$DsKs}K&XYvvcCwNA(Br>vhK5%asB`i! z)Vo@aZr;k?aJfI~JgEyp)jokwzPnM^_E+ToUkfNT=NsDJB2AQTNW!R>OtZbh9_DOP zVVy(5TWDzA1Y$cn8_Ol7a`U%$l4;pOp1nWEo+c=o;CGAVDP5`zCteX^>?~ao=us4g zy0|BZorgNhi+qkQ24avHIU8^$2=j-3uG|b{6SeWqE6qf6oFSN}JzF0u9(n~V6Jo%w(-+YXmW>%H z8v&M{vciX+TqfSUeZ*Js5!(MrhWjSe{x)s6o?%!rdPTL}5Z)D2h7Q$>rK4fk`{(px0L=>CZXC zV3e{Xma7XTH>MQu%JvI!l^R2;y~G+f%-#XZtkmH9(yd75lpDFQT@+S3g`!$58*o*> z8i>6-j?TC+T;=`%p>-m7!)y^!G$stVvd&HYdL5{=_$BXPmjKPWBuj5cU!-%E$vC$u zI|GyTYVaeQUA4h|-eE~mX!|S#J+LC6Z)O7+Hc3EDUP$syp4aO zW-(TK%JfJF@=3RA7FszXLlds4!3*qeu>Y?z7uSz~&O1lZ(YrSAbfN+@6cgS{EsS)b zRlErf^6mqg8m(M)E#bX1>%$Y$#`H+-N7#+@>q}ClT8XMycV1+@8eCNEj~aSBnD_cE z^TlsQ)86Kh9W(S{=$J zgS%j;FoG}oS?B|@WEuweKbEe;ug3q2w|A2E)>4urGwC_!JY_{z$lhBwD;d!;8cK?6 ziBPtTjNJQqLS&^hZP_xSWRKtH>;C?M=SBD4_jAtsyhqnr;)9TuQrS7)!@gVgk1riw z@&c-V&7^)7TbOe@dpxVCrHxn43SCTR!_!xhG&^M#hW?lZmzHRX%R~RNUaRjb=6=2? zcHcAt5BoZ^C^41x*Jw*xogYblX1B!W1(wqARZXDwAb_Um?qDIGRq%!sPp>B@$Up3} z#-g_s^owVud^S1-bv*wt?s_4UZA^shJ2qlrt_Mu)SaqRnxDrcm*>I20g>j;JrIB=e z$S;`iF^E3pJsu=#5>;G4Pkg}l|JZ6;9q;1<+<6Hi@U$+#yR%d~+-xm4jj>?<+ z%d4X#|D_kiveOn)WDQECKlwah-U~Cvn_xx@8C5d_W;0L)$ugc=JIsf^y+6Z>N)>VB z>a&GI6XRhfzpD=1>W3vKG!-68-}6o=p8ZP}?CDme9%;}t6P#tmIqg+Binx1!!LT5X zG8SzC=WAt9YM4gB`KMXw`I~ULv4-r0JA$x(CG7O!w_x2^47T-9d~IbRMsh9mpO7qO z;g~@=+jXQ(>gH%$B>Oj`Is}}7y)(Pg0pQ(>mmTonhAPqxO_TAJG z%|299j@u_iYHDjt%5oC*9sA;zs4g(kRC#m1w#P$}8+%Y3{BxHuk9V5e1UiW)78*#` zCYj?%{#`v)kqZwEH1Jf*m9#1`nccePiV-&+P^edbsL+@UTl!2TmBCt4FG_{0W+vj3 zr)6wg$KUeMm&xLy-sA95T_?8bK`ylq*OfZFF~=F>!fAL*KKn$dV{A}7y*NCSwGDN` z5jS~G?Cve#IcoSWLIu>Pr0v z-++O&4%9PUOImuI>tk=k5iBug+dLidY;Gl8GPnWD-{!%T9(j~m@SUknD}ghYcpi9> zH`^WUBA?AOrT@!(8$MwLGr!VEop$I+OB_9mbk@2Bd^^1e?;3rDss1AQ^*YH6!qo9V zLL6;+y<3sy>xgA%E6Mx8Ux?a$6Fy$QLF>Q#WZTY{K!|mJv1H?E|2OG5Y{+?z|Gf>Q z^Q}FL1|_=%e4Kv^3yzp$_xEAcFFKBuVe>=RmGl15A)ReY&R7ayc zHStbF9LssS<-*`qduek!UFr7wuF?ta53=)}kNYCbam9u(nz^PA+mfq>x>sV!@QxSg zzpH>LrAquXxX1mHLsi7x2mdOvZf3*6lU(Ok?1H>c^upZVMRf2O?=~H{PFg%#Ct!wA z0Q|XPj^9mX^eePLKDJ&J6ZB(Aty>|al)QntJ+_gKF^1d60g!(v?oATc9jLM&ophg&%)Z(6~=DIb#P54zb2* zSvTm_#huKT)xwYaH5AaC1xqG<6BZANqG#s3Uz=j(^VE~Y-D(YNeEDrQug`Ug<(XZ( zy)DqRP(~Ae4hQpzuVIJwG&Y6rPUaa~UzFIt@c6)sAVwWk9_u>T= za868R$@Z7p!>aTygI;CD2;*Ko0T zDrL;bWOWyuF-uoDmnJ`ngwqcf(HV_ZxUFa<#0}OI?T!Dks1<@d{pSF2*seM_w84ap zn2}0vzGzFM4&RX)THF#l9k7%RD?Wqn93(TI`>M4Qc!rhT*a{1F+VK0k2mCm9tZ=oZ@-Dw*%PThL^*Hg%Tb_rkt%COkE9cTY zLp2=Y6-#xy{RDYUDP%+>l85P3T%leAEuE@Ke3r$WyfdM!$z1I5X$L%C7~a~=SD^umR2&2hj$87=*8z>Z8)#dzZw%32l%s~@Q1gkh@U zw%+FoW%U`*BiB^a?c;|Rw>-GeeUfrU^9x)# z)2d6rTia{n)mk$`$6AnO|G7_ev%bx&Q)Tp>CHC~ zsXCc%x4X##g4$qRbrn^seN>nZbjSXK9L4i#z47YRAQvb6|s?UY5_cSmPW9f8O0$b?ehFKe`Y5baAkTpIW*594- zua|9SaRw}VuEV>bFS6~%P5!5^C5ttd<1qYwYo@a$m)iPpjmj8n44D&7?(L0m`7{k& z9~eX1mJDQd`EK~}VKpt$+yX}i?t^!H7B$P{o$PoSvMjoam0$AM@$60h+stgmLARYS zOt&ZNY*b8bp6E!|8*YPooddl-q$PQr)ZqHvXtF!df~lIjW67N=dhd4=b}h+=F4J;p zN#Zy5xAkM_btgzHs_?=ppX!6G?_{pkX{1NldeX44uh8FLpr9ki*ohzw z9CKs^ZP}Tn2)AvEJ6qS#mO0!PrBMxI9$ljkIp5h`iwstN#a5gUY#?3sw#G*`GMaHP zj;%SYjxC~>^N#7e!e`tKHyxG!^g}asu;oD&@r-5+)A(`>0vh?9$f_A;=a2H=vqO28 z_kH3i+3}fSd8_&O=dBgmo(TKLqfVQrjzxOQ$+T@dNJ_X5Z+EXHe|??{rYW|!xlXii3qb>|8QQn^N?Yjxu zOOnMiHyhY!*=5$Rhmt$pQece--^j=`a0I-+^%gdnO{U3B$Jn-TcU&G&O}!pXmj`>k z1;0BFX?z5qd)1bJ>%2NTaZFoU-(E-XZVVQ~t}cVHZ=)5be=29uBw>m)@AE9N@oY;e zXSFp>%94@J$wW93_!j=APa>B|8#t%ojx~#`Y47I(q3lTpI%?!*Jyvbp}Cp;xvz#^ z+%uK06)(Se)D=B1-=RbUNBnSHf`QU$I#6x0G&$%>WhtU7dG8MI1HuY~hoEIq+`2sW@EM52tu)@LQio zmNNG{byaYkf3h`(?&G)ev(~Um=Ovh=j-|j}S6LGOzRlp@w~z536;Uqj&`{R`5{`0Vxx3s|- z5#e;Hs}Y(_S3`52lQ1wah@BbV78@dJ=<9+lkaKn)s0`jg!=tn%lj36VDeffpF5A!a z3QGNp2il4%`p)?5WjA(kR57`5|Mir!fknv)K>^R|FT##}m7womd|<<9)qQI3FWW+%I3CSAoM!J^Y)`t z@zdT|X8zb#JUD^(&d1uJ0nc0b4?nl2XrN*EV!A)RO88o_A38lAK(3t6nSJanbamt% zru~Mn*12b)^B7C9ZOj`8GE@=fo!U#Ic@F=;w@%V*-kbB)U_OQnvco;c!l-?1ALi0U z18-iBq|S%k;Fj?-Xb4+NDVM&m0u5apxV)L(<$YGjH=TkK72a9gV2OG2)_ot3j_DD)gr+^`FNaM@VrT zC&%Ttj*S}J%pPouq4cd~}`-0T_)GhI-iItT7^eZfk>Otz| z8`(VGZ#5bssr8T;dE(~|xRvLGmwE8snE1;uN%uIpc^+kTDF>ka3$BL@umbl^CjL|Z zzq7AZDPT_;#)*U87)iT$M)7;QKpOpIB^$1@f z`9U?^iQUES;{k}+uP=W0O@}@!@A!vJPM`-5wWX|w)>2;W1yS#dg)~vkS<2!Xr~mf% z1=-v?&+kOX3=CNtQ5`#LE+YB(DPUL3_r~igV*RGGg$ZL1KtH*@sAA!bCMUZKF6r-S zL{EL`mX-?p_C$H3caz&;-7p#Xf6h^q{Z_-A)e$uJMH^4VO?PnndH|k4H2UfF6os56{=kMUwxbU8gQin5PklIy< z+|rc{GPI=7l8$(HCEwqpCb3<`p1AU{nRsNe2|isv5c*xurkF##Cu@NNXbsL3ZQ>^| zHg*-eZqf1Ijp@4XeKyhWJ59{glk7*e#x@6KWbn)yoaVoSw7ikD`Sm4s%(x4hTi&IY zRZR-jd4C~D{~-n0>R>|2A}Cp|pr0b|@(#~}@k5OR{*KXszxzIF8RSYaU!+d6Z zQS2X~#K|LGj(BZqIBg0s!r1OwI3RQpP08-fc0cKab|1Nhsy+8(Za)sQ&9~6@C+gCM z%+rv=wTNypam*++U$9%i=eLf|_@QGW~~nW3&^JjT1IKhF;R4<`rv+=V+I9f<0* zB>8kLTs%F3+}h}}>wY~jSMMQ>=~Dr=8kgZlhg@VN&ALeO|+BN`q`#U0(pvr&(1Mb)teQhq~gtkIOw zAVf%{*4;m``+E#<%&P`! z>E58|cI+(7=Gpkk!wu1MrcAhBUqq&Rb)_q<9npdBXyKIw@*!(A@RR0zIye6~7_Mjl zt=8+PcVs#X3Fe*b9cxItc_<8(*9(?%5Fd9`lR_3{u)iELUux<~>F9_}%lW-Nn9rO; z)zSA>IDNY9f_46`IK1^`%Cy_UuIK!Mn5Y`^xRC|=dTpSjW*H?v)#ACEKLqnN1H=Q? z`E1muBP?U?b*}Nyl|s44f6yhaNuD$UBHJ`UmdQAJ*7YzmJgSB(-aaBVStoqbD;eBh zl+mg+KiR7Z3c)+pM(i}!A1WucQT%$TydQ0M?I&eh&K47RW4ad4!c9CYqcio1Fvk89 zobNG)zsu6t{6gqAevfLy$=%~Bfr$5PU3;UlK~4a6gD9I<=^|C{tQWC?${Z%BI{h18CR z!`E8k*k500h+cl-kgI1Qi)VeGd))#37NrY!cD<+iUR>Kb^rJ$hR-YQ&wIy3;M@%0g zqxE`w6)HSe;po=6WNMrW-HPfU`TJ@zo_3H8<($KjY4_;lh)al8Fmh^l>~Sbq16f7(%-L(VvZ-;&nyNU-~pZ^F%@uH;z6 z|4(+^aL%bp@;^P14d$6n<>R?GN4*>}#ECGE=NSLTg&we+#J;!SxljClw59tk_Hc%B zPp_|b#ufaTtqpD9P5yfr+-n$R>qu;Qfjt(tI7>52OBJE>JL8|%rlQu|Za8J{YM7Lz zp!A7)lJgKvsV2ioT(`|Yihk{kN!d!wEbXt22Sex6QrWlZ-Zw#`rJcC9 z#+i2-d{!(Or^HWJ9oM3g-9Z8GUS9-z)klzM(VDh#-fUrKZH&m9OF5}p%+?)obxQo~G0_F9jb$|QaU5GxuZhVMWMuT>rr>bu1c<)D|2osv z!|ic=lZvQc62mluOF%VVU(|h61t&Ho2}=*`rL8g{H2L~`Mmdhr6bJcnT=z+ucoP=-!je7R+zZwJGFcFO|dAj1oU`k$A9=a)M<~9 zsC$v1P*>6yO4;8BhsE$tUxln`F1VBP|G%#m$PKw>9?E3&sQpoRlEUx5b5dx1aT@Es zR0A9L)sWqy5Lhw_{R6(OhMP`56zg?bL-T47c>urk`Bx(IS*zqieXqG--~q15j5ZeT z&D6qluG82b?}AQCy)o&)bsEQU;@}qzbX!nMyVmZ4?Qc3k#7<>yXXy5}@Z(327<}az zTefEp`?^GltI(2bJdDDr`N{~0HTVL(jYm^+(*c%O*akJ1G15;SC{I<<#rB$y>0D|j z9DFbnyrRnZ-S#Jo8T(sUx7|XVlieN0|It_UJFN6|9_iUr+B0&tIJvH+r2oJLXYu)A zomLXm4rzi``$OrIWhzsxb;K;**|+>$mQX)sBm7)9pT1Yd;m!+3z+JtOp60w_Ch32K z&b-%k!qHraP0mxq1f-IBiMCWL-zT|;mWpkot)%ww8?1J9<+%ar?8P=sjJ^{_m#!|7 zKeD(2FZ_1XiS4^s7pIbcojA!wmY_c^%l}!LQU^6DVinWU9WTCZGLjNHYhnjGr05ZG zY=c}AzZ%KtLuGp*_Tn=*bTys^yc&&Tm^x13{6n9hT};-m1Y-Gn*~c~=&S*{+HiOdV zo}y_axpFK`{1S*=QeE&g_gTCjWXP-pExg(!qejhfywhA875V%()ibM5{Zk3}e%2Rz z&GN?B#aD#atKL&;H+^Z~-zSQ$Ee!tU8y9cn-=%RfYT>z8F+@cR1K04o(wnu=t>GDr ztc#}wtM{{eF#gGPt<6rAPLMrdKH9lh?wV3{ct>Hdd)8>U} z{C76n)<=0)DtPRIC$GsUX)Y5CtxI`cP*)mrT1)zz?2Pthh16nRZ??Ll8eVSTS&rMw zz%O$;jOIS~|8)2>f`#-XBG}yTEcQRDtGq&r(Do%t&Gy&Tf?4{?;x>c2%Wku zXFGQ|;_NNw=+e3}h4s;Hcr4aT+~2-CK8;KO^OF}S^|y|+?^{nObek-eb{i)6<*7+a z4>*b44;x4Ye_inIS3Z-E&4VS8n)p6FjJB*@#=fOHV#gHDb*r?4p;y;J*JP!3)NnDM zSr66I;Pd<0)8FopBm{|}Hja2$aaB<@JC~x=b){ZYU9m1PoOZ1=!lQh~`{pjA1$M|j zH5`Wm_4Q;{^_>lCQ39bO^u-RN;`r?OTX?(GLQHYBN6$lV6%A{Yx1^3∨d^4+?nv z_96^5c?#}N9O(T|Eh*rS4sPQ--nmYi?BVt*h~A~d&!?t0;OTL7Q7U?&SW#sM%d*Wy z^D!b0c=bWCk>|@@Q`48m^6a&ROS;kFI|o>X1JB3i-+^T(HYzG?2tPa4P}~ll({uPS z*e*Rv*MHQocD^@Yc8R(;?B*PQtwblVwzUy!n^Vx#%$n`Cv=h_T8c24zZdlK?B4yv> zSVyjBUc!Hy2E%U&FySoppB_xh)@eykH|nGM#k=IGHImhve}kAOtwo1}Uts9g!$QHC zz2rJZSNd~AQ;PIe-jb#*bi+$kVN^M^FEa|)#nvylCg*`8{JHlArUk^)uv;&g$uDcn zzxIjj+kR3!$$ky@@0yE09$Vrcmm9*6N6K6Lq7%71&*-2SvEsAPXE)CcFqhGjCk65X zCtWp)@femj{~(opqfVPN3@#oG5|^(z#-`S9W{Z=qQ|2Ci3+wKV zBi_mWVQE6UuW;}Ea9UovpY7aYhcD8P(ddQ#@>X%#5Z|_poX-AWOJCVT6VF(le5^Zc zKKN3;yZzgLKBfnH-crj`v&Hu&#!`^0J5DH<(KM$d$Q;rP`$C5CJo#ic>xU!mUU-T; z+inw%_T2^*`Sa-P^fLzNCQ_cJehp^d+(D}1b{44h8n*IYiPmpipxN$< ze~VVi`_YXzqu4jk@uI74OR3IN8?!qA9lsXKZffhIE!UE*)bJ8^s=tPco^g~veI&-O z)IcmOrJI>sSy}0G$eLg(mXF&8>2Fen!(7kl`9WK{lcXv6>-vblUI*gLCvMot?=BIp5OZQ?X)-b1yXU zF%xG#?S|E~g=?$}xh7mkDjc2weitW-{oW51T+?2$V-KCgwYLqVFNGcmwKDptmnRG8!=|icNj937$7h`FD#?t}29Ltyd)Pu$TE9OoUZ+6U8RCPS|)VQPE_TN2}6w zrH7;1;m62uT99po<5udUdqo)WlQZjZ=K>t;zmAf=ePQdr*21B08lrboBs+J%2ecbu zDSmj*=je!0R^`A%}B)KgZkA^(GC8`-L#)WEgeP(qu~u z`(SE84egv$3XT0AL*#?~w9DulbMJo-&VExD$Mk!tnAsD-q>F|4(=Gt_WS>=}U2URE z_WIJ&{%Y8NTW2ckmCKHeHNd-ee1FW^s2H_05c4}$Qg+E-&gnh_A?P4&dT@tLS;PC| zY&FEmvM_(a7r=KG&tyB1h_{R1EAD)^75j4?-$}!E7{KScNd0(rW0nD`@b9@%(@kNB zhXUqJ3MSR9T2hZb#@NN-F3BQ7*#@3BvU8uKIP2M0m^GwaDB7!>KSM8Ou?@S*#YxU9 zS@4N3Os$}!7_(v?R{r$BXcfLYZ0gHyk1)XZCNjD+*%7*AyoK>|q6wqwn0ZZW^qTaM z%qkib(aXL=>k1{7zR3F`d{)0AALyUWJhXy|%2>Puj``KV>Vlr zv*^Y(?eMn5?@H&5g%+xYygMhHuH?AjjpELj(DM@MZ{5tkHiTl%SVu93XHFj;I0#Df zl>Hik3t}MPeP2;m<0!K_l)`KdUZ>6{b)|~k?Qr8u8RnD5Q zYmKwCeP3^R)x|@gcJwx-c>Q40hly~QXJ1V4=mBqX^W{1ll(+cpADpB_xe`Cq_qD^z zZ#fqANrJhzzrxMIL+F5c5}WMY9u>dOQ||3uLUH$O*bp(7HWtTXkmVt`^|+MIw7S9? z_9FC8un;$w?}rr@BNVGcmAa<#1!+>up;B?|aVzP|5*5rd@u9m5*0GRC18moie|E8v z^2DMa@Ni}V9UgKU4z;@lUj}cbIrlcR!Q~(QH_uV#ED6c(EI(4_7#hASj6p5>_=7H8M@!G_lTSyG5{7QOMNJYB65{jx*~fS9O5}bstYt&_03vEwV4uELx$~TpK89- z3(o0D_uAvFTp67w8#o%?1dBTdQ9`FPtaIl!cvXIkobrnm9aJn){m29I)zQH@bvt09 z^=WF$JCq#bmcwnH6@2su=TXM-JnLslTn%^i!n^z(U6hmuoo=+?JAN2>bFO0IX%#ej zoJNa2{+D6R<5XHc=nI?l;yF0?QWq<# z7P3~q#=^lVmg28J_Gp_wRq=Btzbkd&8mdpnrD)IzSo$X(GW$J;&UQAW;;1eOF-AD* zR2a>+)MTD(Rq(=To{`=h3&*=YgCQUH(6Hb}R;tGHX{}Yok3;Je!Df@-YlgX)I#@)% zcJYd$Yf8Kwtf`Kx41CC0eIETiJ|e`=}c)KIo{f(FW7nTccGy?|YoUxW?2 zmDu~FWCGJp~(~aL+@d6 ztEJ>u^?+Ia^~4tT->7faSH;6wx|qJhM%-CshsT;)!kY%AChF?I?rg&5!=l;MFT#TZ zUKl(^MsWP38*HC@M4##!U8sSo)(aTIi%GZ!>Gcot&X zUG{t4C>AvS;6D#(X@eJzIxi#jQe(lZTT8t7O!ja0zv!fjTZSbNpU#;^z&Jc~$X*1y zdKlet9L!v<-2K1mtb#LK>zk{(m318!$Ch)h;NTIS!PTP!&S)J@{ry5=_M|2_Q`ncD z9NEEQ7ptH>_gHC7HI^@OGQ}f{D#_NT9nTFq18aufrd~I{vpuh;!T4KN;>O{A;8eU! z-nz2>U)P&@gP9~W%@)shFqV#d^+Lm9CH5{I_?7pR^ru+fg=_4lf|Wdn|I_|y!tA&E z;27WOR;k6}fltREPq<1~ZYh|~lgUt9Y#|=C%7p-Z3x)T5<$bEV{4a=?+f%LiTDCOK z2({0Kk*$8D-0SHtsEJ!e6PvlOq@o-aEZIbUrkN~clsbkfOvP$*XV|^eP%!SN)RDHh z`9bkw=LC_OTS{|m4e`cB__zBD%|`e;QbtFncnS938^CmV6#YFj6ayMt;029abYuD! zHe5p;+mAODGiPsu=^@vJ?W2@8sgWa|u`UkWo6{JG53hQm$ttdeJ7&nvv}uW3xh~zb z(>UnY(*_^yeMH5VcNK;%&_$2^Hlox&5SKUlfHbFpa>f`)b2r+tziAu9ZI#7fzV(EH z_bUJ6R84sA(feo_tzN%Z;XJq{zB5o_@7eaxAk`$CUhLk?w6iR^x9}b{B~=N2x$3yj z+)ON85{*3@f+72ouBff^myNRP%Jw836j|rq_(aQ(T}sLzPo4uj(4hmq`oT3tpO~=J zuNJn4`cTMOb*XXhUuge%HJvO}xaaQn92*!t_!ErP?n5p-)3tj4AJCq=n#S92 zQVcw9gMs}Y)22LKtpB(T?k+k;7oPoLvt3s4epzp^O@pg2%b<+)Qgar2zc!G@*mXeS z?~7-L^1ybg5pGHdqoH-n*juYV;O)Aa#+_;wHVoVaMLbuz<1sDXZGIV2TRf%?X<6*F zYbQnDi@DT}&!XBJI-tjva9Unwgm&|dP=99_wfX`~)AKhZ=B=VuZao3_7sJB~spMqw zg;f~7hILcb#f_~Zn3lmrh^sRbvnSbNwoZtmUzQSYT^o)_Iel~j#%QjD+{Z5`?6WnN^#M_QsU$-xIC6({bf~<`d z@Mm2*oga0IIZkeZo}E-htwA&V3ogdNa6@yErX^x{Tu;T0*><9FIoFz|ER^g$?ueR4 zVzIlu4_@K7)EOAhy392}43UvxpIgEi-|KK|RWR+nr6twfw8dye4ejebf_*w;i9Rk) z;%UV?`Hwf)n9>MWVRU#8mX8 z3s1`w5p$1{ERNdB9f_lQv5)-^k~;4eG2G#UgZcY?ZL_iP z$-orb3<)RgmoBK9qlSAft)imQ1KF4gTbyx~_gebzf{t}_Ky9uPd$(TQ0_P8LKcLQ5 zCg+@6$7|QApF&rfQ|5#E7U48;WGHm?`V6BJ0;wWuD=XTqiX9azsq=^ya-WvgIE#1s z7(DdA?!zy_^`WISf8RIuWcnJOYic9*80rtbw;RaUS1GZ#kG+o6`|WHo%hgzVx!DJ= z-H_3kDM^r>_Y1m=?oanaRSt~9r6)l+}>LUbQp9H!s6z zz=TM7k6(Y`tVujMgeOkFH>g_n2VOKIII2vh8Qcc3whiYJ+k2a7$dawVcxLZ)ec^8bsz- z(W-^xVYyemaA3NUL-^ZrpW;SMl30EDA=?^N$}Y6`5%qrtVy78C*qAJ%(wl~?p}+)B zUy)I}A>*L5zb(Gxna_vEZ!3&h)&f;~S%_+70^U&zh8M=~$>NWm)O&NjqEGNf(Y5>v z=-KU2cs*D03E2rgXwP|xn2NoMfi)&r#_@CGk`(AO<|XX4nN6kbGFi(;JA5|eF5NV# z6as?`uuG$<*sX6g-XAW5Wxl#%zZQSkkxgZaj~$MR)8_|a!TGjqYh(t^;Ms98&pP8X zt8khPlAt&EAvm4rKuL9~(qtd5Su$QpFXeiy(a0Wak}7HF@^a`@y8{^aOj(rbNS9je z17p{YqG65(iw&ulqjyK~oylx`Jv))fUn}R~Wsf>z@LhiI$h3jkIbR@XV*qWOlFu|h zt6_LfJnb;upm^e8k8XV`sgdhn?r^=7+Lc3eIO{u8b1MYvy?w;y>3%}tsC-t)v)lvi z45cKo3%+y;r=*{Gpjcyu^2cG69Tmk^mZ)KE-*~Rw{U{`zItbklPo?XRv?Nnk9`rQ! zF+HoyV%#DopZzYE;%Dee*NeKK?s}f#^Th~jGR^P@*I1tDhHS=3HN377Prp*S!<*U) zXqTNz2D)EZ6Ze5;%v2YfydzkMZ5qTqFc-Ur+hOSZ!EzpyM@vyx@?Do9RSee&5cOBW z@6j)L&X_q>eEGw?;>>ZWDd&C{YBJZWYPe=x9GSmd3@#0Cpr-qFYWe*oTl3@(Bp9iP zvMrAll^xPy{TefI{$IpM6AyVS&CfIg^d)CLpPcn^qciT?*^~w5*zR{2UB9wXF-%lL zmwU04ziK;78CC!GaZFFhD7ikIp&s7V_ycN9|zM23vDTl^XkR?Ht|JcIID_u!pGz+*2ZzJ z^pXQiNm6PCtos(p#k^$EerbDF(X$J-{24~$zVv17`7=}bGp$}Z!o&x!Ko~QPUaz^q z1|M?7(QB(|15_)@$P7pRG81F$EOFE7o^a3YBK>{HJ51*n$y;4X7RzT}5u{yRa1Ouw z|H(ZgH+*1@J94-OB=#u0y3D&6N5*rmU^UY!bHyKe59qxa&%v9M=)b}|30_;OF!Q-Z za^K6zqU(-nXg#qLn=nf`_l|ts1w-%iyeX4b!k{1v?9Z{+?w1QTb1(MSdz@FS@5h7^ zN0jGR(~sp@(0a^LxR{~jY3o}Q!PAP~qOWk6EzTPy|LbBaZaVIUQ9FjSD-G9aVI}VZ zYugpII)>BQj8OP(_Q^( z#D>-EIDhY_FNr1D<1s?QfRnI~>(8T1VzIjT0u<%TDZcPDJFz|keta?)r*_{D0e>!E zcs4|-F_`8#O0pkXDs~%hCGC2thLLUCkty%+)ShdObzj4%G(A%Omh1UE{h~?x(M7Nw z{u-{jZ==nXTUd!r4eW5|d28111@k}Mgp(_jI9$MIo(}8%sQ1VfY+57lY2w&eSn4Iz z_4^9uSrPQhIT$N=AMpFeavJ5agSiBoVw9GdsO7O8It^3@c@L%j-ylJfU$RRUD?2}8 zNhiAC&y6zL^~R7f8w+gI4yW)#G-p)g_l;|2dhmFsD+z8mcE?^*RQ{$ zk{Ue;12-u8zE)!Fx{5C7#<`|npZ6-%>@9GWemHq%ra(sU8(3H}omA~MuoqLDa6oJg zeHnL07-{$j?m0asn|J{q_gD>1U6mMncxsw_@r7Vzq9Ajd9dh$gV@|`CJeU8V)k8}MPnU9 zX~(wi`0}cZrr*tjwofdvdaaUk*!M#ny(h#_O8r|QYi2(0w^d@S>-N|1An!4inC@cj zn-48Yn)!efK_gMYsMeVu37x(N9r;&Co@s^Vn-r$g#Gjc95$ zt}}Riz7M7gQz^f!nXTKck3lar#cNNNup*$o?c zPnS9-4O>pvMsi=+oQH5{TqemQSl_*2-Z_z2X^Mb*-hh zkM;rjbb>#ep_zEUE}yvU+i^UiM{c!xc;2`@BHmt zvD!rgC-N=;O6bL2y>Lel-siqBU>7{2Rp8XTjCMF^OBOw9pp^9zdkj0oqMgq8y9e5c zKCBJK?Dl6DE-U$7{ae1+vTHcCQ-nf(!B;r9NuU(9OqRby9n*4`Q-|$3a_ebruzpD; zy_wJs7gg87#B;Z(lg>A`_2~h4ZEh>>YcIgP^~pWg{U3WfG~Z|aeddTN{fwo_mwmC> zBb?@5OM>5f)KQieL^+>VF)uzl8MaETQJ-3NShK22OX$q$}Syuv)X{&|z9F>CAaAsHO!ArypLxs|&Owt%D!@ z=Z_2$J9(%}j~}Dy zXHOjMv4ys|m?G?eVU{K^yNxm{U|WfkV8*>~s(O#u<5)zUgT(_KSaHqKjkxF%C{SX2VLZpJGX zJW%=wHq7)zIxV9?`uh}HxQF*T=WtGCrGU%a_fY9Fl`3P>Sy#~=UGG)Xq0(|;-L|)Y z36H5S?*lUIlnGPJbj87Ue>1&~jsE&0g2ni~AHcX#hrJ9}-qbE@_rTF{;S^dV39QXS zc-6*(oG$%j5s%fdRa_Lk_R(ZF@4KUzRYTXZDq$?olZxAuMUk4?QmEoOr1$9|#>MEf zzz?VVZ%nfif9?xH=dxMsml}6vaXozYC|@++qnvwBzW)y2gOGfZk22S3YN)ko8J%!V zRV?o3hAVee(J`(i-*f2{Jc>C))&0LStGoOTU8uxlc619nCOV6US{X|EyL~bDw~XFs z9e~J(R#G8W}W}%~pYRzh5{G5d>qR$?9YQ??zJ8f{p&{_UZ%lO?bR9A9nh?e>e&{L?97EcTTS8mB!Xf;_OK478M|=8IvS+E<_@eSN&o!-5 zG#j4aT4FP?c@E;_;T?pn=arZ|`_DLO{BzBK9L+%9i>-oxgPiEu?M>__*ZI%ox3fa^ zOhqjB1rHgu_&;AH^t%59UfoWnX>AX)3zaQU{!2w%WIDrN!}ugPKQ|M{_fJGipD9Ae zH+JGO(NH?$+Y_fd^4%>up2Z~Dp~F0mduKQ=@uw0_Ebl{Bn(ESs^7goYdo@)D4`&ZU z8X(27mO8xH2Zo0NK{Z>6&&E(KSij*p+rd594TGLo`Z|p2Jo_=DU3QqYp6g87Izjrb zH?X&KG$n^#WHWBH$D5m~Y2LhQ#UXDOJk{G&9I((FtG>>FFwcv$@r|x@_AP(rq)ag_ zvr3r0uqU>ft;FY}dHmnGONq}GOEht^+A``kE|z)B^TMJDHRQT41Uj2!L*yS#ag%ug ziy3XmcE=y2^E}&O+Krz0p;kuQ0$T|_gY9wa_HbG;!4>_~G;zD@QfgaAtY-!18}HT7 z`h~kd&tfgeyG4;-e{Jc5XC2fm?)*tZbZchp++`#(w)xh9ui)oaOmV7V2M=UvCLyaxGa9`y^STd}H+VVWD zdC$(nzhdwp;CuichP zUgrGWG_ReMbgNXX%eRuOK53$>!ksE)3G9)%9gg9@yZ>-_&P+9&+dG2Z%_xM>)^DJ; zK8-qDS;wwMyo1w8+bdis4p)0#_?gwZ7LbJjm>!R4(2rQUaGs};piquDCIfTC#$rj z;qg0#bxotiwT{P``LdoE%ekp}S}j9 zxGt`npI5h%^ifSZaC4jBHNZ;DULAxlP5ha~FD2)2%K@;3oZm94 zY~ais6})*+pd&qwuoW9MaaqnHnzuMv(LwBp)A#W%QSLjr+w(H`yB?wub>A4cUI*7( z_M+V0Opq2A2)(a)i-X;dpy~QWY(cWK=-uB?TAdAO-X@&VMjU{<`3~5?wVg3fqgW6A z{O5xg(ap-ILU^JAX3;cC9<434J^c%U@875I3wAK)!zW-6(-)WDdIYvk9fk2fbE!5$ zS2{WcQC7z_LOlO}&?yHr-=W0e_8m2GXuk+*zoR{L=>Ht9+VbxBc^_DZk%l-uw3&?T zrm~}LPQoj$K|PaWjElYv6O68ME@FtTB*pcW2B&HV?80~$P+kuOWK0=zzOaYqT4T_E zT7{FEEI5s88jmj|-`lgG<+Ts6bHO@V(xH;2CYj-=1QoGI#uG)|>;mYuOJDTw+Zl)X zt`jutn`l-?&JTY;=|Z$tz~pCvXvlfLlm-Vn&wFb%rPes1jf{MpG8JP?G;w6<0;)Qn z0b=Yk=zk`G?oY~Ni9Ao^+>?iN>_%_@h&2T;@sz&U(JC7Kb-MU-C@dec|FeiZKr>aQ9>a6kfwX@`1*o}=I`wMhm*ODdQpXPDi z6Ds!7$z-mZ9qk3D<1)q9hJHN%7BH)Yj5O!>WAc`c7_pPj7(q^u`Qa^G>lsSlM8>4l zE?BUG&)Z40ih#iOxRYmb^l-JnCl6M@tbrFPNlQz%$zK)5PI)l; zxQb~1>L{~c^H%Wv(oYPubi=l5J}cBBl^jL;ZisQEG8#X!l`!GFBc9$IP8$}vaz2=M zWSB?LMje4!?T^96I7{*Ev^p4q8L(w$6gh@-PSvIWR!-*G?3?DZKFOy9?=ov~U|<{U zbKICkI^3Y0y!XdG39*jrE9$gH!i?v?pe(ruRjFmL8`_!(=N6FL7kr(Mev>BD zePQKZ1u$T~zBuz^TS&N<=-=~{QkVO+FpqsfB__KpM9jAgr*$8aV0elao{jEJ{&VA5 z>}?H98oGeA_YV?!a1QrWnT+PU#A2%3CCI;!OY?7Mvq^0VpoaTg#LTT=ZRsjRrKi%k z7CO>q4>Re~x7*_T6l-aJKW!W`(T!|mYuNhzt+8B1Mu)T)%lCw+1q8L$ocvn zjy9*#x4IOz?9y*IWqXg@XEzAhO^XH35;?{=X-nfKzZKTk^b?zFcxK5HGYpdXQsMVy zEYaT)lOD_HW%~}og=cEmyF8pyQ#mG2GU2(g$0+ziJlmi59pW>2-}J@_5O~!ah7D9| zB>rls!0FU6;_0m8Y@|M7?=4(!(6t3i9`A@fTZR)e9S<%CtntvAv*et!s_+)q$vi*w zkTy5yqf1c=ELdDaD~o@zb^T8WW1m@y(zgMy{zG3yTq^?_*j-!d;)OWt63=%X$a&~F z-1p=hPGNN^aPibfxVU)?jq>E0m;07DYeE5KcReBW%~M6!r;n(QOhB97x$s+CMT~TP z&rYpr6vlrYBu1S6A4^vrR@3^no9B^6l{6?xNkpaA^SmoWqgjX$CE7bf#-bEOsYIEF z6w*LtCVRhI<|&kt2D1zqib^Pb@A>WTzjK}ITiC_5tzkf9!1J#a*S*4e>72T!xJuz5^2SxdMZyNBshI!*iZwo5p{D+vgs!7U^^JrDYa*%pWVD)TS{Gska z?0**0G3>;fET}XP%y6B`92`B`r^JO)1+&L-- z^^cr*Z>Li@$6^xI&9&m|gW367(+l7AW1nA80745ZbYod|-}GbY{0&N|b9NbtE_%To zSb7s`t}Y^@N|hz=*u116XdX;Mz3@p5+sh>D z;50|(zhHae>QhKTQwdcLMv;KIgCS?o2N>y{M8@y?M2}UQU{JdZ&oxHT*ZV5KagjQ2 zk)n&PXLfVKhtfG&VlhY}*R1HZBtIT}GQPsUSvusgP6yTgXN51>tf*b6NF_E(cz>sm zD9JB^(BL)*@JS`k8IP#j&c0apuZ@V;REq<@+=OG>)cGO9N8s~|H@N%{QhfH^%DB6{ z{-pBAF4{2A8s}KDUHQmtacmiTuGzd%OEcj5l2@RfxQQGQ=g=ux%9ua(1$m6#o#|*%K?w3ir$7QkE0~buu*5}2O4KXo)D=aOM zu(Pm=#C6dqXju@-cVy;rXBK$jDaJW3v%Vx6&UEr8FS6PA*J+sTql^poEhBFJYbbB{ z2eqc|;6HuS#K*_;JU==}vts@(It?WsI>{VBSD`yxUkQuB<8~hip_O z^YXlK0(%B6Bl~bF{RX0GqL3VpABYAwlyF~R6mdK4PG7Cw2aiw25XnAeNkRBcFdw4M z|Hb9>R#`h&Rc6Sq{9=il{5!>)7TzbV25J&5-7%Oop6%R85Y%S%K*8WqWMOm$J^Dov zh4zdaX_pbDeXfSoYp2MbV^8Sw(wlHOM4eyx+78z37I_METJWWlvSfKoI^8pADQ_}G zS5mD!2IqJRNxNwZ6l$s9nY1xviN_{-FhCKP^kLWwzTA>Nm9UlVXu@6MF)Z>HgqG!! z=kf=s(dC=4jor8Z;jnu6Le6uqbT%%qRKZg#29l<(%~aFS8vn4pu!H*=(NN|e&zvP7 zL&jbJ-Cga_cOcvA4cJa2*U97Lea}eg#V_3L(MeqPSgAg3$#X+Ikm^eAb*!UNo2~I5 z^Onk54&~h4lVT2;XQu1MNB7F$*SnK|b^ajp@CGUV`2utzy%w#9%cX$?G z__BoBW_qDD%PD;qtVO>xS>sryANw+KE|eOXHOpFl7ns_d=&j%oDNjxH!Gj8XE$I|MQw% z`}Y$vI)ccMj1+ovwK=wGULvc%oaOv(x!_GT#;u7rVs?8GG_LwV`e(nQQQaL}R${oaA7pPcb$1KwnTHwLdWq;u^5kn9$w^*!eG zKb_2fczg3_FKEAZC3lQZ(jo4OsPm2aI*)A;&wAvByI0o|E>;0!ogYKXxk55^N*C2W z&B{bs2aWD~IZnp2hpXseKK)z!@M-^XRJ`Aczc)=&a=Y6LTN%IIXLA80s#{|~cO-Fh zjirJIifH$PX*g{fISut&;F7(Nyij0gmfKIDNv4>reHl$R;w|`hL!DQ7{Q`oLlezP% zCy8T%s)Revyn@|AQlF=TO24ge-|I*+q6VoXRS~V@1mx%IK@iJyDewCwlC4JXXlrsG z9OBbTB4R`6Gw)k4 zW7f)UuD4$Y+5bjeg6Eij$J>l(uGvZLPTOL)zkv8gWQ!|)t6<$OrX{<;dO6!)LD#Yv zGTZndEn3R_v1giyx@erIlBgQGW~=e%uf*Wz(T`|y{S!WaNj&aP9EabSSLl0r0)6+= z7U!^ihq6m0x3%p#WXXDxp}AeubmSo1tZ8C~1QpVvSc3<7Am_X;W*y8?U>>k@>3C~x4hX*GE$(r+*=xOEt=#*E= zK69x!MUO+-9zA|7+mF?1>;%o1VsbP`S<!8%nJ@V6cw<$gUJhvkcz*4^`xXzvSK z+`3bWxBEg>Ff1dIgp6HD6Eg=Q>Rcur+9N@9w9M0TbSl*Ga#ZyG9Gr^yLQb5^p=Em~ zL-QIxzRS@L+y0&u-|k;THqBR+ylo$cBlk%0R=jx-7HtrcbGrwk{{t1aPZyAfA6)6Z z{yf_MVLZ(09GI{&2aJC0(CuQ}w-FyWJ*+u-t>cf{6#_sJwS z&(|*Z#z=-0y90w@#hzaH)i8oIm#0yiTPir!o&7BdG9uJO^e$w%0Sg_l`N9hb$UIHH zpQ@rW#2;Xd(2y4%a0Tl@zv*%hDM*aOoquMXidD@;Zl2cKtBc*p;l`wvN{Svc+*sdr&%dD3@QL zir;Rq@8|q@)ZA=}Ep4YsV{ig(wo_(WqiS;aZ7^hi2!N2`QeNV84D-YOoXH;!Dxsg_ z9??+qDqd{=5myalvmn#DeA%u=r+5rPN5&`o3YiQ0=31fFfeXZOc4GPO(Hdx2+d#fP zSHqU$$AEWuM%E>;e${MK_^4#W->LD1wY$~CZPPW#y;aJR01Iy{j=5cY_nn5VT zGNy))N`s&w9q|0{RAStaOkGUbnWyM7nYZ&iS7ZPzaJp$sjppo0N?*Ygx3L%r!6(l=)`rrztTRT&Km{$7BAs1!ATS{c`x7A(F zuS3dF#MBhg_{=B#`?Hg2Zi5e2wFt?Cdpf9KGZ^K*N0J%?LQ}V^|F3&u-Pb|DLRdiP z6;Hmfp71w*=J?39jmWQ=N4s)mk3Sq-n8$WiR>-%aHFbZd~pi3UR}fwx?&Bs zi#yZv*sJ)r{er7WBAFu&+qhEHbPJW4c=48`<48L)-|keI>v+un|IL3`mDEX zynr0okS&h0)0VCeLft>19B&m2WO(+|H&Ewig)T|&+8-@2UYX$3_lx)C` z&%+@wMVk*0$Vm43CDP2=BHq|U3cPN z+d*y9EODE8DG8f2l%{jIT8vc$Jg%I20*ad8vN zee-4disOd(DR>{mUB5#7%M~Pn3Td!NZa%-|Z4S43fe-fC&hkTIE{SGG*yGQu0y5IM z1U@NgptYQU3~E?O=jYg>$C2|SggV31*VjQg^&3fb%%xSF55&&0;KMg7;@0v6@g<`o z(!qAV)7V~QM?IV8%ldHR{@UZzWX2y}9EjGY8rYX{ME~LTWlbLxeyJxWzmCHANBO{Y z#*nI7Wr;)BGq`Rm&ld?p>6b$uARA-Ad*@kT#H<72oJmsL?o{!`cs7su?+t?QS7mTf znlo7}znz-?R>wP^BS}fPjA)q5U)cU9nV45JKsU?7G|t&aoS6>IXP^vzW}UfN<2bk+ z-IvQ7FYQ^_F<}JV_j4(4eO6a;sm+Jo4?;5AHwAJ&YG8@bi};+3r!&~+k6@p_d$TW> zzpDY7KeBh+6b0+kCSV{0&ZWnx^hrQD=XUp!gWNDeTcR(NzNtawvP8eF<*!DJ4WKQrVP?em4C@wK8y zu2Qe@s{=l``VsRou-?NJ_wDiD7%5h(E&Br(+olk!jjU_K$p*7@&Jj1eQf{-(c(h`< zwbg=nthsp-vXUPX_hn*w;V=hgdPe+-+od35JWu@jm{eoj*T)}C7@v%Du5pSkt$@p{ z$!v>u>Ly_N>KOv!YS1l?4`9Bm1IffpHVL-d--2Zib`WuWC;hd(5k~Bh;juy@KGhNe z6$S(N3)`mPk^22&Sq~|9;mLF=^S%g(-(pkNNB0kYIXV*8W2|>$j20fe&va;Xi&$q# zFBq;)CZ|*KL8s#-^b5!%^F?3jhncS#*)7Lcnss_k**FbyBUuJ}P!`Jnxg~yk$%_BG zL{k!0;E&^{vbndT0FFdBpexJvH#`zcU1YU!yGTIDm`3i1s1js;%_8g9%SxOh^zr?Q z=j88){j7UV7QJ3DTs8U*^Xk5FPx?sxbaubi(ecSo_>}y~l==nW!zLk#Ytq4s(GGa{ zjuf|vp*G6yXS-l$c9zum2Ie$|tn_H0=Z6l$LF3xV$dFK~yG;)5MFzZNwHe+i(}c&3 zjK^54D#12ydjEbQ->hd1{YL$UllQbq{}b)hFu@Uf8Loy6P@=7WwXvaHK%U)L2!<1z zVTaiY(zE{@t*{w}2V8nd!ibmR$VwI5&}qV(ZJvO8Qe9wOZ3ju1tRc~j9YEujX7R7x zoE|z-@Lk75$M@Aj=vbQWsJ|vU+>B`jZLX4^*7m0m`jRd~=0$ z4yGr-n|n^YA=f0HQAWjfbWVR6v@J;@J#)MvP_YD_SjCb{zm+8=j4L?nY{Gl(PNGY4LSR^g zA@6>|632g;Eq)k!pM>eENeW8>@C@6*k6Fpj}Cgh2|UOa6&sEy?e6O!-wa(x!Pfq}hjm%1z-Q(9iZT=`tm zvhe_&zJlpgFX-{dzU4uS;}fp@Xc~DuP(`9xJ(PMJ$mJzR+NiRN3i>&ikuaAHwCtcG z4i>Ppp8i_VbPXMrInFpkql=*bLk2IUC6h5%ljy-_6P&x3_1slj`a}jh_i`FR&#k+r)4l`{oEOlUAvjdXI zbaPT3$2=W1pK3Vw+f`^=@Qf7Hb<>ga=Y!5ZBmQ%aA87gP5k-HNYBRB#R{{A;$ESUG=!zW+0#GaNbm#_eLtS6-Teo5Tec9cPa>yO5QrzT^!bX{aVV2k z0^cm|kgBzp>5T6okbBsWU%{8c?fw15p{I9}>yK3=6^8;)MIa>Zo3C-9kK3RoOp4(j zj%cGKn4MK^yTz;Cc0<~i%|s(45iA_;g3PBK#IVmVdg9JY$m-uq-ndcmyT&;XGm3e> z;>O{CdCB6Pi~f*DO6rpQ@Bn1G1JZoZ6z)#whNoNX$u>Ah{n+!OuuwoOOp?U4hr1!> z&Svr%j=@rmS8!s%Q8Me-XX@_4x|Z5x_`qpDJQYsP1^H_R{Hd~CXs=r)UUSWg*Ic0~ zsmu?+9M-weZCD8ZraIy&bpe@wEtcjmjM~ODE&pM7AN>a)NSRJR(nHl*XF=xuYVz#u zZd$cQ9+O|`^WXb_2Ze@T+`Y$A?c9Rj^XZE2$9#&(WLh{N5DgWg$mBmd_;;ZrE@4`Q z>_vp~AGLAXQ>K5IX9v$`eua~X>&U{u=hWBI0lSv|CXo({>Dn+A{2OP&Z(eSRbXy;I zExbi6Dpe)2cSceDUj@AHcqb4o$R;}_I%-T`w7bDLjq?kk zxaA`x-V%^$%gg9tFGnmK(?+WLR*N&kH83e!n$;6+H3^!2caZ7`4N0GG<>KW=S-c{x z18>$-{PwI7(N9XJUt5RaUmpPpEzK6s9orWb*)@%{c7SF5M>uef`RFCP=s15<92-_g zZrSmkW|eAKA=2YR7bK(Q(iLEwp~WAv>ZLBn>cj^x74m;SPegP4?bxM-M6WkWkELNbmo-btm8vXeX`+q`@?0#@pkKrq5%w&c{B8*fKRV&kOmDJhZy7~~ z8-9bgkOd32i2GNXp?*v~(b0MVYtHAfy?F^4wBk2)nztL?G&=FFzhb$6GbW)u(}cL* zx+MBK)ERr(9C%?`2?$>GK}{>R%Z6w=!buiWUMG@=&9boL;7!k_`&<8~ZT9~mfqoU0 z#5QL;&CS~lBZmy*w;pBZIg95ae-r5(Zc{V~w|*0l*v>xOHm%{4a;R74NLJcyqhnY|mRG|I zdMC-8T}Gdp-Gfuvb;Q zmjWxySXaf+F=W@IO;k<2FFp^K@+Xe2pWq+(l?_E(td!dv+QT{p%?=l|gKipRK?TdrijOx~V0Ve)p-5;#$MB!T^ zy>{FbZ@#J{reWW>!>uLU&8=7Qaj=qv>mwE~y_3z~+ZvBEocg1C;&5XAVkPy7a>h8O zOG&vil*{U5^Y%M-jumOu|WZ0y6Kd7G1u}8PBtQ-+!5DQCnFz)5t{PBo6j=Vs0|!|AV{la2^?+;R8<^e?+kRxLbF*VV+s zqa;JVU~nl!8eb7vPDOkSfh3V4vpsZ$Y#*F|L7$)4_6<%yF@?Er zq#YA-Ekr!8{U{&v#FFYSo`xm=gd}*dE^gg80w=05jm>sKr^^`N4VIM@m}m#PqCP?J z$HnA?%ze6vX)la5e~^RA=hHzfBmQrjK7aI#DGqUShj52mWX%ax$^EsS;!83`y#6?A zcw8%kXC7<+Z=ZPB!3B@1N-;e59P7?t{K@yX3!(hU7cgsILe52$(7j$Rn3U2+rY@)! zhj%W9Gqyj-4^B-o>qwKxEO!_0rdtPV8kI31-;gBcr_qfwT~Nh~X_#+hi|?E_z(F-^ zmt?;Kbn9Cn{9gnaosda`oh`8IK`mK$4?Sf^>S6yX{r~v^XHMG&xe_hDJfWACIlK^k zm&xJ}n7QEPQ&X^bJoDS0O`wi72d&or-lsS$@t+ zA1Y?oU(BxmA8!9S_8Thxj3LXiO6Z&M@@R?)BzjANc!7R@>^f0J?hLMl6J5n{;Q49d zd8&&R#b1YvQNFxQP$u`}-&Fj;bkT2hE{i6MUGN8cf4$yO0#3RH%+nD`3^b!@gN+={ z9k7WM#s1?yZ>aXv`LrE+dgN*88W9|98^fo`Sz$|(jA)TZ5wTpQDw#ZJ8jkz^A2-;S zdm1_tV~$9%`kWc_`>I2Eg(p5ggkdOFYJ_ND3b@odfH7yOlkc z?z(XR^gdhg?VS#&C^8ZmZM;vEELpyN!Zf5)gv7yQCcH3GK!xfdMC)!cm5(q$c{X3Y zc`hT$4Uom>6XMCPJ&!=;XdO(Lwu3wiJ56;BYGGzX9dVIYfQ?!UIHf;QtOoySxRL2S zCT&lFR9hXKxzB@WK3q#zvHam9uJL4wa}0M*V1)s< zo)d*ocZ@k*4ndbhq~=`-{pOSjds+y3ybAsUw`+2Vy7yN);)4Q~@08^?=l}G~%|8TJ<{0sh1GCY8ud?TX zHfw(E8ZC)T%M5H}JM>o*3!x@{6zVhouc_e%YW&X#TZ#q5JEM`iTk#a;%LWpOc?X>m zXN_;OYsg>Uy_86dF=~T8Z<_ZFULAFWt|lpN*Bwgn?A(;XcXR60M;wIfWTMDWmci5c zbQFGPv)P(!ga&&UV++IWIs5HcSHfp7ej7@v&)=dIWFRUz))K4j-ZaaXbtSOwr2l-} zzqbd%-sQK*>gTGG&yjhaLFp-cLO(@#!^z?NLE1zzpq=7oSF~c+|Lm_sI~t5pnZ2+7 z!|fk&txyoUm_+P6MYr)bSpK<&93N9I)~oppKk+qrbWj&(&XniA6{qlqEUzFKRqfTQCjzGd5%YhuiZ*zQa?$a3cRcgRVPngUU;4iPI+ZoSXR( zUhBOiA(p;av3WPpW(|I_TQ~j5U-ukr8^Dhr*A3q8LHLnj>Di1#y7q%B=I1ipZmHx( z*tNp`L^qOL(oSpa6tFlVjvO!kC%#Z^gIkW*k{_1Gq2^uz)Hmf4ZG9EVmA!TF_L>jx z@~B4~v^&$2J8#TuJ`TjM;u$!Vaik+NeCVH_u6X4P%e&LD0^Y6%7NmQTpzzc5_z!th z>fK0UbK}G&q1O0nQ#HBW?->l4e*r35Pm^5@T{JGR5U9YMPwBgmd&39e9QJ+Qw!18v z^UoFa7>1{vEP<&J#@H$=r}Dy{1aS60$FaARelg=upOT;urD`=x?%lA=D+r~VO~jN{L8xJ{=@A|<}ZkBi6te% z(csuEf%X1tNt6o9bShxHxr+=RAJ1?*<_NU<=<@|j2Vji|J$3#cx1atD!iH5s@+Nd9 ztN;aE&}m2fj%=a*t{dag?aX(qC@U(zA&b>_)|1Mfdtjy32(!}DNRe?7RWyDJCu^RQ zeIFHI`0*I7Pi6}WQk5kFxBH$!8PoX@F{~rCJ_wi35)$u+DR8RO7-e3LB^mn?=)FQ? z)MYdF8+$))+1yTuWt_&zym&mQ_5mO_iwwP&&iu|zaJxu~;jf1p!uKTUj`CWf92a?i z8^4V{pcxrjxWCMlXv%G%pKrQi@*2hiA6P3Qa{X`^JDVJva1kPIv-f+^M)E9r165GB z#ZzBuNl(}pu0Du$i~ET%vr|d(Feww3yQ}bZ=S%7RQgeYvXLL1W&Bvf-1 zjbdIin8rMJzD``axF7b@jUu-!@-Z4@YZmJR zUBK=c#@C&9Jt59ab3=2+8}vJy28U+JB0TdZ&dTw$$Wsne&%_YjldHMY?sj^UkpN7rX9`xYYH^e8T3R|L}Zul`+mfCdKoz4Khv{M-!8$4f7 zLl)23ODA;Op^v5&zmv^hlJwyq(LYHV4ysDjCTntXBeMCTUVWBDGZV9wqR738y0~_u zD_$^>;`s%|ez^6gfV5q;gUhLJ;Nyo`Wbu13Z4cMMga?<&A2SE~g8et?qP~2kupd^s zPK7N6x5xllHOVQ|T2wW0A3dn9oz9wrkDUP|SKgCN2U^ z_n%NHUPwy57Si(7L(svZmb}_rF7BiA3l!hHVjR0JHufaK@3NQV&)QzP!Q%nf9+J(k zIb07(d8*j&5B$aW@YrA3V(*z|xU-7oqfXudvftVuIVqH^I+#Y?n}(n; zrlB^`)A{zZ32?CH<5;p z^*~kj&vL&jIaR&`wgtJ7_50gt@Nh-Ml=Z~q+i$VU4hKBB@fpdlI}Uv}p90_3L!|Ma zyd>b@M6PS65$`oV0MCZa#>JD^T=dF^`mXgrue(g+?O_GMuX};jR*(_t#dJK=3CmZm zBXOzg#nnX)*p|cc@IxA4gSrG>K0HmTE_G2y^{WsP#JZEZL%D}vX5*?i%wHdUS!B&T z3qr>CYV|FJqKBrK(Hlv!H$_v$9>%TlYssJbcJ7o@t>^n+oBx-~k-z^pI6J>32Xgk) z+r47g^xT5?_@{{3g3q3>qKn9Pmc5x_7>wtcc6V54U#?)SCtlEqA{UO>p!kX@cD#us z+lIT*ug~PMqI(UAZyW^)%arj@MkmSXokj=lErIg;di=i+=9sUf&Rq+>Pa4(LBn=6{ zcw;lm;5s}LlAb7GhS6Y>_hbuQYG;NXDeSy&C@ZRd!a9|-SCdWrZAh8%5~iIw~b{lE2P4*ToZgXdklF{ zx`}4%nBiH*bDs0|Af zV%n3xSrEr|eE;z(d$gx;*XH!&AEXY(i@L!W%6RqT)3xbAdryon5)zfWAuwTxJbu2s znq2%gtbBfq1KwZwjC}A@!5b4qFgCXZ&-t4UYSa_$(cM)3>wvuxY{vko? z>XHXH=i(^F&$x{>gKjp@KQ6N*bBnTQ>?(7dwV3SzS0{;grYKE!a{N3`Nr540$}BqQ!V@${Qk3Lnii_yaSyVQrsd+~Y!PK4P?%q>oAnsx$uNLs21| z(BW`5>yPME+(2t3=9t2CT)tNuIpg@3@K8H|Okg~7=t~E*pH)S+8SSS2)7@~=I!oS9 zEQ_}ePKCE4P7-I9X+xhH!bjC?eq*gZZGRks2iP;XjA^P9BpmK^Vt!{Go}SPjfW?dh z|5t4XK3y#!H*O|bbd&|Bni`{K%O!F-dJ4%7A1?|SV%kEsSP1xX5>?k zmBShT`HUE5T^0XTmqCSFO=O)=8>c8{KxP=*(Y)!VXjsNMo;2krk6#3h8`W^|s=j2G zb_$Km1bh<2_ICqzi|d$oW*p-lEyH%er(f+r7R)21ms06gYJ@(cFOus=tUWuo$>7MG z7ewKS4_>z{h4!f`tdF&wnj5|0Qe?;T-z(Z-j`?hy>>ojTW^JPHY60Ic{fR6*;?{co zflgC5GG|#k%~estiz%zf5bX}J=KYOmRAt0hG0o1jAEj_*^gc4mh~*ovJO?dB>iqmS zr^P`Zin;cmM*P_a0XR!11otx?ro`EoUTX#XR>?S!IaV;FTm}u6aYSCVkfs%~{*f2a zq~QE2aedWre0lyEN#EK4>E(A}-f)U^*e+%N01>|~wjHIPp6R)oCAeT(1(JkTU;6|=GZ>n#AFO?=xrcJANxjj6R3pvT&v$)Jg?| zhb9=NLdfF5adgk70eE&f<2;x9ai5r$?8ZtVS<@AdN9VT!=dgqP-k(BulypEz#Zyvq zZwbhxkA&xb(#)l!4yNEcD20#peMlR9`rzaW6H@pgh7M!$(R(Xd59ar^qOS4*sB?$C zTNhkp=O;z{EsQ3|H?E{Zl}6z5pU=pRGhew3mwIm6udDy#TdvMN25G{7d~Vbc^fV6w$0VitVWdU@^WKURkq_>H22+C|(B- zANWDq`d$!6W{bf)U!C7~(v@Mt8SbIz54q&3E*WLK0QJnII6sZ$31li-kW<_)`n|yt z^VtmWZEKQv+XO`{c@RbFOS2$6{U;QhNhjsDk7@ri?99%;AjSipcwRq6;r(lMzQJM} z&iVRt;|=uCTOtVz`4eP){AsHUwj z)A|;9P^K!0zCQ@Qyj{S5{r#K^a8SWDREq7j4|rUnC-`3%NuH@SE@XV&e>3?S&rT3L znN3ue9HUQmnWNa|GTFiBiub%z#7gTXQmCzsFBcpDkGWE8KbzRb-7z!f>rLjtz1yl- zAY-JnMtgN=qU9 z;$PCc;5E&(><JD|8~0q(dVAQi2Nv@_TXtFH@4@9Ia~7QPpry>cZuuATm7 z9Vq1LGEzOSRqX1Sh+D=Q@!8uyL-4nAaEs|BcD?*f<07wv0rO{ln0#71%(|8P&KdE| z&;4=mvIXcrhs~VmOPksCDZBpnl~ybljdkhjj3%qh^J%L{31?(3BWDwqi;q6@MAtEm z%q#Q?T79b_WFym+g)_gv!RzpAnmV5u;mt+=S%6;bT%U3OvZ#EM7w%%%eu?dgqW4%a zZ*wHEy%9~PGXJSAJ4a8BXyMLfee+zlI0dwx%F?>^8rZD(k@WN&q8SV;!z0yshn8l@ zR88j0+@w7DIhRljVVdp#@O-J^7^Ekpcy52(3a7F6#rsq@x;RY{^Vs>5?QXDyR1m5nEBIK{uszeScYN~gv^O2nCcXo_61|!pWZO`k{W@ zn zh4h%D4=$@QCXT&p={R%to33RTZn;h*Gt?S;tJ&@&`6BpCQNq@$C{m;lMN4mZ;3&lg zk}$Z9n;7(->sch#hi~3i29LgUlUF9kXl1??q$LFMbM>7uIm{j(6b=6$-}3sl7ycN_ zc%j2ioWJ2f++ZC=Qa?_>+lh*}oaGFMqcau7ZNY2r`tiN*j=~`Jj>x-`OxEpFk!Y{J z4)5L7`J$2YXm-Ijt~tPvPj;}yhykIfX&@wT_c1(I9fP~G*=|>H9t1s8!0aKcM_`0~ zxmEH=Ja)U9EHhO?uMFm)IDeYF4tYqmuUv;|OV#;-2BSfLZIkEH#TvwJi?SqsLMRR( zLNc-CgxF^I7>v8aX857$P@JWSBMtmX;^9Ops8+z;16jx4<;C3j#hX#~s4+jeC=ne) zZ-IMF9?4MMOV2;M4$<-IEC(hRrfdr5yl+b9_9r_+@l7iGO}AEXPotD@?IG#hzTln} za%^rt@~&Il?4^i{*mKc-XDPTncndPNo5{#qujzmz{c!U9UNZMI6+aqt1MDl+`7JM8 z(K-1RH~h+9GVi9kWY@w_+%!i>s@Iu8p0PZ>O*1EhzGu>=Rx9jYCm^E_B#G7i74b6L zk9^y+3kKY6fMIfRWUBlXdWikjLmHdNi|da)2dX`W!%lkqs_~halNyT4lUPnpYawVn z;?cyAoeiruP^}TxII)5090oRVKf9X2-zk7BOKztx>kRRPV<~Y@jiHWNUbs5Zg5RMa zi?u@|A;|M2*>+!5Vl-qS<~v3a{TsTd^qR+R_IvFa#nac$tZU}Efb8tF1DUwbkTGo% zNvpg-A6;ZKKyEqdmLE#x`?+9sI_oH0VTwBaQ^4iM4Pql^T?VtAL520Ud>iweyA-a5 zPA|2{EjGtqS;xF5Y<`~oP>HTSV2k(I{Qo0;5gfhT2BN6RBxl_rIyl${i{D)#q0jTg zCu7ucg9v=zzQu`ZoF3XK+oGu8+<+D1$lbK2lIR{!i~B%vM#%h&QzHI zq z@G8U~$|AA*x~Ryb8kWpf=f|X;7TZ)B!O=ek{O^H&m}?q_*BK`>aHlVodp8cBK4bo% z94qjSW*Wk>QKZ@B7;W}eK?A14oHkV`K0Ket&HwqxB3{5mwI=XiA;s-}?AeiIO6TzV z>%*|~GxN~3UKYt&d*d8y;s1L2+*NF`NnSwoJEQ3q_Bmg$&uQxRnVT#$z>&+pl4qBX z($|_#A@sdE-+T1~Sf!rg2Cpq5>kCvR2iwE&{9?w9|LV*A$??X@%R=%@VuPo>Y|)+l zcKkaxD*3E}xuFbiWro41fcsz^wvasg-brUoHNuc(t>kLmL~6G7H7HO$e*PD8{Pgr8 zXB#5b5RM!fj)G$5H}{(b+t}F(4-aJDZ2}!W#THS>_!8O zW_~(Y&q^a#{wYh`j)X&c{X$+>qma_g2IxD_giJXXLqm@P z5Dbg`_yH$};=K=p@y1doGNEc2UGC+L?GsoITZI$nlrad8vgb5Q#|Mp^RPcCzwpR@s zMn#szaPxUG;VV=mE2mUL81v&#+&+(1v>3q~LqopyhYgmMhT%R-AqkXd)2~~+an(L{ zO=mX$@G9sG0%8zkU%p1g6X(r&N|tU_!m)erKt|wUvTooNDpq+1F3Sw~vJVqro1GSy zwOY!DXO@RywS$o4$>xjG1l}0PxZfWp>9Bse4tjO^{STiv8#7N9%OSi`u$YTwKd-{e zXXL5A8_Igrf>+-HQr&itD$IKYqm}gd0q(`nwK$7w&Xwv?4#z}bFq;#U-d1o!g4Hm2 zzZH4!%4Vl6c9^}0d3k($#EYM(VO}H4BL1`#nv`2$=FCmRWk3_PsW8LM%0Gyy_`LYi zd0o(Z_?PrlsY{gYBk(ojf|}CJz`RERznGa3nKv2K;hG)V#|X$%nk06vRl^jfudZ3Q z3(P9sK-h?Nq<`~y+RsD>%MUaX+mc6~f3AFi#c_JPPEIE3>N!IAZ#}-QOh#gm7J;8; zv*)5u5qP+d$A+1aq;&QMnmds7zuaT<@Z=`$)caO2dgD*#%x|Zg>&$W9q7ve@XFXkb zbTYnV{Yr^DS>}315?HyNBqOR+CF_v7j`e?{Y zzFuY?p9pMvz%;;)o9W%TKIqKecRh8FSXK?2ulkK7-Oa6(^+w`Rc2=6={Z*X*bsVPc zt0M=0oPghpZh*~_ERsI0i}qcuhf^a)@r+lf# zBp=kc&oZblSi$$jJ#fRxiD>UXMAzL`$AIXBcgoN!qWwpFa6Z$>xo4Nc({+P! zwHDjM4q8QXZ>VDo`wUJ6pSj(6-#t&PPJrOHcCiea;mU%qq_O2FP1gDge@FM@Gq(1^ zhSF;8)l}(DQ!$8Le+-+KWc9fIZoc@qf$`N{HrQM^7|*i(PJE9W4Oi5_EpM4__L39m zXFrA{(@-+$SO+Z*GslacTFJOcljzzl?O^L_!2j54fw9~Ea)#OW$xv4{iGAS`blA&u z&JnYqpCX&#wwMvK9c$_ATWsIP=GFW;vZDIy>S!Cy{ERHOsZZG(nDKNqdAA~));v{5 z<>}SL(Nq@BI#TW@>tOxMD@!hCPKO-@4!loXEv=4Pf(^k!QZYXjeiZk|<~Vn9T4xQt z|D1Kc>|&W$-~71vMH+aQ%|A86H{l0AmIu_CPTKZvqb|C-SOpEl(`E(8jR=FlNa;?~ zYLgLu)iNQ0;p_~n>w{c8%lAlLCyI2m$K6cd@?Z9dwK?lj36^5@g&}s>HT)8p+kKC- z&;P@9Mu>2=tFmPKiMuQ_{}85(j5J(9jn4R>si%-w z);n>J-rM6o6)9G)+NqAC8E3VA<1p%a)CLa-&y!=fJwfUBSxA-HN{0Vbk-TiFfs;$+ zdG+&CXs3fa%qw9%KAUV%g1jI3edj%O57h9 zF>foeZ77E9&iioCVn0b3f1VmM?_QUtKChua9zs?-a4Q!|=jwTpOPJ<> zI=r9_d{*o61~-afA9tQ>D&0wD)~QGw^#n-Y3Q3peb#7-e^8m(5aogn45Zuq^w54%9 z;-dGO7;{)US0{&mgJUl?l1Ja4(>?A^IImHb|E_mkoVQ5<2h1|%EuID7x3@zeD!QAD zb=HtroQcHHDMHfo&ogPs9lgZ>OG{M ziYAhRGt|u12Di>>C*Mq)Jw<1G;P6nUbDOdgyYBhH=s-PQ&O$~~!alzS+r{jfUIdEv zet3huXB&ez(&A(XT;0iZBZr!}z6qV+|Iz<{Gxmy^)|g~pLWay)Ps6N(@%?rS-iG-? zdJ{6BnPK?LI;L~mup0LF8OFopEgrR=CLcy?-<@a4o#+ zVESj(LatwrCb~`4BH=ARDcJbqOO#^!r7%bQ%{&FS{w{)dEDxb_pAU(+zK2#EGsI^; zjYQ+97W%7HfXl6yB>Q?VP5d_tzJnouY{?vWxLgx=-_az)hi#z)GyKu%3iDq)*exD2 z(Gh2`_iy`chUY6~@#CNAWSd12UD;)as+DJn+IoPm+2ACh4H z61_o!VVJoQ|8n>h_~a_UHSGP^JDy>Ci9dd0b5u7AUZ=q_ICIcY@}d3%J^xAzbD2Kv zKWx9fNCtOTCzIi;C&8nw55Rp#7SYS^qVs06?&JG1d{W3!@xh##FfM>)x_bHI6IlUz zG7L#=^QGO*{&>?|NO&!4Fj?{s8nYZodhh|(53Y^xo7j9fC`z1lwHLg`BoozFER)*( z3%tuNBC>1SXe#4<6^n>D0~w8EZp6t}O>YOcvmlcZ@$7eMMCC)*oA$KJ9&R zDcoW?f#U`<&Hs{Bw9!=?RoHpT+pdLM)<=dD#3V!E>VM*B4}IKrzmEJ6@1iF|ET!*+ii{q?v#`vWlcyO8`JN!J;W^rS>AA`lA{3D#$wK#>3**JT<84G zZ@5_X0jH04;4?M=x&Bc8XqE=dry2bJ_{o&a3Z~VqtG4?kTf^$ApO{}dnYY=>fVqXf zI6uMyVtVMXT<81f_D`wE#4(V(a|5xi$d`S{Py~%Xrg(g1B<<+?!;yH}N34=Al3$x}-sRffg2WbPwJaW*T?l;d}D~VAUAn8HR3Ux%Vw# zo#`;lRA0sK_v{bH_tUIu=q>ncqwF43X4ujh4djbI#f$Io7?N&n&vnj2_OeI>HcC$&FV4kFEn zbv|=0Qin5|^ndO5=Uy_Mtl;fNoSCyjxauLp4!LzZRI%tPCEqs=f663k2+i-?x>lsJ+GAMU|GH! zQ7J=}L0Uem*W8G=l@y9fm)Eh>JX!If%VfU8ZU$R1*FfAiiZGMa0br&|zNXC@e6-zI z&>`$Aa?V`VkMd;>&8Iq()vqA+NE@4Wa04o>AZ_^B$1FB21Ak1)<*G*tSg*w|@ScYj zo1^O~bQilYaMfE>Tc#2(Wzlg-&*@{~-r+!WSdz@5O|)U_+>y9`U<{WG*8u;o0XY1{ zQsJ}mKbB3}nF%%TSe;TeQy+N{7nh{-9~sgBVS3`$pJ&)b|7U{VqB~Nha z3&)=RLd{e8lIG@apnJer46E~of4!aA&h|E3vQD*Vz}o<@qMb-$qbb|gA`5e~46&+i zD=)O|53jOGFY|k&WQC;$Jh%{mEeF$>`ocOUxA(tndVVok7c3q<$8B!+-5L{RK`xK- zG#~E(w>wi=!c<*R+ghq<&!|9n^fC}%?8#=k=XitT`T%_MY%P!5+8^v_mhr26O@0f1 zSd`XSOfDildr$|{-?0&U%?2J^LeJAtU$n4kX0t!1vfiVpKd)CR+WBA|^QBx5%@a8i z;DJy$AqeL>YeT%9H;f!jGwfB7clc86r8)iXL>u(Z|47I%9SJW^__IyL_4O%=jr_9ER*=tKDYB{H7YOCggr|n z?0`opnmlaaE_u=H^L+zxk?U+WDM|y9^VLuZHt_g2m)^6xPF8 z3SPI5!@m`=+(nP-N#+LJxV72UWWEV}5?|uD9wR}bSjfWfJiyYZJU-icE!(SMC{|is zWwCpL;pY+RD<;JAxBVtS=39DaZ66Cuc1XcIO1nqECG+H^p>cgY?lw*%?a#7GyWZPtcj!qC)pirJ<-Y4|X712%^ra3P#L@6cA(*xZY}yj;;}&T9TC(H?fuGwJ2zErjUk z!1A5sku^IOR_4+^Y0w7zHZF$m4KoG#>#uOt%a!cr#W;35BMIMo5vGxx##W>Z6dPRD z^X6&B@Fd6x6C5JBTGe=XvXQ(LzC;!Vwb?@jy}y?*pN%xqhIA?F^UwKnor_Yid|*84 z-%Ax7Jr&rNCtcW!SKvoBt>hnGj5^HM8SG#|PWIvz%Cm4@<_Hr9+2h9bEBV{l39yv* zWpNhv!Z*t389XKkb2g2ErJCB{^xYr#Y_aER??|7%WIf(UQDXTE3Rv9DINVh%TZFzE z@Og|ey`8K1lOr40kg_QX3FyZ+>Np(50^6qy>v`md5#Z{zQY>2zrbokEw-;?sW7{Os~N8|L`SpF+X8>$KeaQfY)!m!QlY^!4&Ywx)vM-QZ>O+?M`v5?%ykA46B z2i-;~7dgBP0R=kGeQ1YvW}E_aH!;M9%&q*FloQCGBrMc8L6ZGd7aFgT-moN%)lO?< zl^+6e&aSgO?Xf9Lo>75U|K4-k8KeP2RQ1GZY&#sgkid>oCgvhfsiN<0pfAXAvGH~nodbFSH%A?3reZ<@f zR9lnHt{p$f+M>HM8Lf{WVrSkC6wBY|NTS6sFb@nu*LZE%v1$@5oI9lU zNe7W=!>YAgm~oK@UUxgqe@>BwB~RAl2fyEvh%LsjBb>5UBdXYS<1?(OA{UGA{^7?Z zhuP4Mf#MXSQ^MU)9k{zm<3B&x&yyxY0^L~;ycGD@4TE5qS0D-*ic(ws&T87-l+0o#BedYp5;feY zvw_Dgn+y;4QpWVJof1B95DcMyxav;|dv;w0PLCUhBcfvYVHH^zbT1BXq&B!3`dC7Q z)Jy#OZ3HB0rm&|fU3LDaYbdnQd25c2=bCwwA?Q2xjSC(Nr$|TUJJkjs-F(YOY|(>t zdbB(9X_VAYlz|G(INZ%gv6AE}W@NAf73Kc$scQ0IUaKIgPdp_l^GId~d+Uok4LsrH zyAVL)Icr#Z@%E<4U`qZu%V$_IcR>maW>{n5+nwC!v>wEH5yI~2~7-;s3w)xtG@C&Npc z>r+&6Sn4Gwh#y8?g{5J9e3c$-%joLoJ=@J-@{0=cL)*@?$lvVgQ9ZF*=MO7&vSjn^ zyL$L3cSGR>?cI7V&=p#CPXVMpDsoXDY89OzoG@6o(L?#vXnlA|wJ|H+o()>^j(z>< zht79?@gX%0+Qw!@!+(WaoR&VBg+4 z{fA}s%9Ji#-lPXFFVViqu9&UrkO8f0aX2_Gi{HIz4$gJY|I-J}b*&dtEE`~aq(YJY z`OU0xyp~v>aDjt#7-&WZVvn+|Z1IO);F&%I7cLIxYkxZdPoW-coVRdxgFfgT3B*`Fz;-E83?$Q>v_e2s-TR@x;@-4UP-W|o5)qIHNWGHne zPH9PGVcX(CP)OM9df$8&vQiJOkWbNG?#~CN&|Z6NEXrjk3lfPc+e`Ldn^YBw1e#&z z3}{8yX9xLM^*wA%hNXBlT?H(r42F|y?6I$L2=6U51?;IWau{weXgCdqqxM0lymJgJ zBrlFx`hxCleJifwW(4?+baIDXniTsI&3VLot4D?+Utqd zAFSY7N+@|+5|7$ZlV2Y(1? z*y+5kU1xiG1o##O;-{lGgdtniAorvRveeIfc7JE+M?Ic%_YR4axgi*wq5aDcf0j7; z6KgrK05{*h!AnW^6im7pMTLWs?#GSb^cVv%(_<90E{tQThdWVMTD|DO*a)Z@N1R*d z9<0?+38rNk-~x}W{NiwDm>wK}{k0P$)?f&u2~+xi4L=c1{ za3BV+trl!A%fh{h-v4nF7m!x&pg}Aym$>kOa=js$yiENf&d`qK1T*h<6!ZKQihjG5 zF~7HC#Hm^jB>hjVg5x8C@CDtI?|w{$(^SL%4s_>e`G1}{>9%g$u->8V%yi0d%zts3 zXZMkV+kawkj?FiT3wZ_ap8N!HQ5EH^=CLdNFQ8<6D>tt=%0e5>#BY~(3+Ju$K!&*G zgX(|rjm182Duib0ISRaIhYPGGEUWg`B3AM4FH>11;QrNJO#56(w_$`K z^m>CH?piS4yOQ*hWjI)~nZIn<$HwdGi7DQ`Rm@^SVKf;CAP;23hQ@o1S>9B?}y1MZnX?b{7a=Z-09v^ zY;jSbet8g68s3GyTYIkp8zB(y#p((Jou|VG^&mXEkMJ1_7pNReJb%BTeB~V@;&KOK z#wvUE&iWG@HpUP8+x+4_ZoObiDd~|rhH%wH%48X>CmNqLhfd#Vq;+|K2lAAQwvUR0 zMFWD+IDZDSd#w&{hnnJnSF8979~Tg!1906X>f5Inf$c@wUyLkf!NFhIuceEzXnG=V z``C;2trd7~oGd$J@> z+?llGwKk;Ty0TR$_tIu}NJHd5R-veyV<+3T{x|lqIKU??Imvo`F%u2ODM6dNGpu|* z;6Ki}%-(6xgP!f_7<*yPxgqe#IS6$mV<7v1Av6)^=l5BA9wA3s$T?B?Zm=9H+gHRc z4UNRA5&yWV264L9NsB7C$MfB#``Cp)x?;p>D|k3)6(f=| zjV7*wkA&lGFF7umuQeUK-v^>mT{7DzV*(%BMxpweSZ)w+1S8vse>HNMutGr^{6kk` zasTJcBjpSGtg;(zMv>=0NEI9W;~84ZtYUqEz9PaJUQ1qWS&q-~`E)Nk-tEL;Q#8G2=b>ekiz2O3ROD5Q#W?Gd;i5GVOLubksDcX;<1VmRmS)?lHtguIf6Vxrh?W_r_$|`g{@oab%gnw=LO1q=(49|lO2KPp zx;vlU8lQ_dd;H;}b5F6uJuSq4Z}$khj_AUHOjT?w|HeS3S~ox zGf=*Wo#XB7(h|T)D^vIc;yL>otwHPDnUaJHeIcguDNgrMf-1|`OzR+Jyx#x7PZnNa zJtB?76F26vZWnZ6D{|M0i!r8#8b69(3AGg?@!-|d=h(~j-Fu$-hkoB5o zy@&Dq)Z-bjLyOMsv&Vw;vY%{GQg{4n_K^2pVgkKs?{GH1QDU&1zJJfvSTqP(L$~)V z@@Fz$Ol#tbw7YS?DJAxbJSgeC?JSF+*{X(g9BFMcpeOON(oc|w*jyR-{niTGThjQI zY!f(0GrsfEAc^A#Sr}{+iMq?yvIjEnS^c+U3~#*8x2LPpIg}C;_PPjJ`_8f_hI*oX zc@`+VngI_@x@xj%!Y~N!OZ!l*a2|KU1d3_K{6FV#<6RYDRkwI{Z1Eq-JePi?H7&>R zSE>By9tSWu(Ni37nLN>TN3+75Z2Ux736ZB}LS#G5+86r3jPt`_-z?g*930A(dQ<++ z#I7ED+|njiVCIJfkGDO&X^TI9=s*PAZIOo=LBzI znmcL4*3#~EQ!II-%E8{ftI;lh1&^I=3*Gxa$2x^THtWm9^8#@5<<*5w>s(>*{6MrS$!B)sOkk8Md3KoxaM`W0pdGaedpm6wZZ9xk z7dx)O|1%dt=PN*}=^s=dbddM;D_}XDW@4WON-#2i2n;>jReRGrX23Xi$`MPn7jCz@ zf=fpr7Mvdgs|T9EmDm30c*mZfryafN+z7mOT$=rgy2%X2gkkRd79ROP1F~+&ilKuxFpquNU;^IMCup|yEAaEB%w^Yb zeCW5A`G0=S7T+Rl|3((yUDd$Go4vpZPFjpP91+|dyRdQdw3#rlj^-n&ZLD~*DX6!O zApi3i{`tNMth`75md?wBwlZmG9U6vE@`Pz-eqpQ6rQzgho4JYi2e#?kQ@m0a&Vu&z zV?G^m7Zxs)&f&}tMr9W?JI!Wi2&Tcy+dO3rw5G6r+w3AfA&C?a{YX!;oXH- zxZzqOkW4DT=}n1}_bP4d+?pD!{-*;+vy<4Vl6Pof+0Ls`4{eE0c(U~hlQU3;K_7J} z3uzO7?DMG;t6`9aeEuRRnPyg=Ml%XVHUVKR$y zF~H{!e;D(C6}VW6OMYbv8*FqyYPb?QkN?6)ew+<>ka&{k6}abn_MeaFKApv^>Sh~T zn?4LXJ|yy6FXZ9YkZ?>}KTTqwX%CI@<){{^4B1PbvS)7jnDgif-{y3IRh?E5_ojOh zPgxgSS16;;kvQI9N_vf#q|1oRkWlOo9M%lP@CB*NOI-zeFBprd7O{L)qC6})6NW{} zuU&6Fbb@;dFR{DbNa(P?%_^^)#(p37@Qr;hF!v)WqN#i~)0{I0-qD`%mui{N{mWmr zztkA5no4=-Lo?_}8YS(@Mv1K`4+U0X_%zs!t@-eU!SiI?xT=XiR8oOtpYQ12mLaLJ zxxmIBRS_@!aD~IuHF4LGZesVrANk2B`p%5__V=g`pO%H;8+xK!<#v9d&5XE`U3GYV zfgIei4aKaWNS5FG3sab%j22G!`N$LPEJfor)&=(v!cJUZ4hpKGu6;U$O;$#A1!-~Y z*D;c0&pBYALhtp&92Qj}fIaaI{$G>TyOY-a0QEn+8-xoH`UF31`Oh0%E7l%t)GDxd zkL|pbLM5{1Sc=YPNt^X<221wKMtRZ;=#H5S{@sJ{@8>=+SB=3;chV4@9m=O~Gl#~p zfp})GJ*z$bizWS>_aCO+!(=EV+gpm}hx$Xmus9Y)dd!qQ%0>85A17Z|6`yXArT{!G zs7*A+++E?kc@Bejgc;ucCtWCUH-}4v)k_~PW{&B<*z9-naG3dK{yEtZMkTz!%FS|Y z#M^Gn(6CEiuXy_`+vTDt8qPSuYo_X9v!{wUDidpNB%}wEmbA5ybar z&w&`)EjB;37fxmZ{38tHk(4KtmzzNvVOf2x9r(>US@?BuCAx%l2=2q~Gk={h)N*g( zYa0WU;mvg&u*b_~EcZ(VQ_# z_*z{`yqW97@0ZLW|BygD*qF?m$@^u?h7p)Rz0g!gbC^Lp=p#PMgs|H(6b&4VxwWP2 z!ne=tBH>Hh@2%&7=YFu;v%4^mJXKe=BeknH4h%NH7rLtAtwD>}W8yq4=xvU!Gn@I; zRD`>aXt(mQL!vgw5<+OsJ#x~Yom>8etumU56Sn1X<3!Ir*4%jZk2(3q!|o( zrwu+2cC)@u-{DB7cJ6xF05`d+iVAsG*&{U-m|m!j(Z&h<%pQaWIy2?r36jXsmf*94 zX5?-=Sjv>ItUbwx@^km`xiqI}4Znz23{JUu{3LJWib@>$Z3@H*8-`r-7s+(^}xQQF)5}Qq*{Sr6y0I-qChO2u$T?}+R1KM4@H;HTY32& z%KM;wu3_?INt5|taOTgjpS&_07;%@m+&hMewGtk(rYQ--$##^4vLXkM_m8;H09ZL=#~ALI{(V#=A) zoj4MPS-oOI)?LQjONV*p{$f@~IU0W{m;Sc+mb4^~@b&Kxy!4_UeE)wvA6zDQ%C@oC z7e*Kr@qoAV=m{a-0rVapS z3X+^$C=UuNgK$P(D0A*x%?1|7;vTmvyf{q`?me!;>)t&C`H<^O^EYW8ts%NP^Zg>$2`A{f!UX|69*I5n{+qTVv=H2e% zcAso^aONp?wSyWR1uq>j^!H`Sb_Uw1JtPt=Y6C7Am)7lYK>h}DC_19 zJLizUhvF5M{K69CKltM{2;kF9S40u`Rxd1?N!CW3C-}wFUA+TJs?!mN=P|E2^h~m8qq)$wU{bvtL?jW{^k@bvD6L{;zhf|2VHY3i(Z-nG z6T*Sjm#aoDm`AJaG=6cSs_a_Jrr88O*uj&s=;PnBve$c*Oh? zzp7&jRcrF_i}4o8@xFs#WwpN8t9m4Cy|Ir)nY_cp{%!o{DLrJjmBjwhdCc~=GBp3v z!eIZ6{D6!*j5Q=*f}#Y;l-WJuF!dfYyYFCr?G0?zgGsnfKa&U5_JA3?uAoZKb8d@i zKce!atG4%4KgV84wV_URCBHJ=2#sviD5uX89KHR({6YYR_lV(6rtVPeLcQp{YT@Ic zf9&m*!5Cd!$#>;b?)EV9M##6}g}39N<+`Cbi2r0(MVHvk85uZ!;U7L`YB4kGt0ERD zCQ3d!`9bDxdY&KMxtzN@G*In*Gov57_vjC^`{#tqA7}CSbU9c`xYP9VYKfzhD|~zY z3Z)O!vnl(^n03loe5L(^Z(dc*ZXxxzA2tX(O|&5Ox-4d}cl^euh4Ako?FwZSdFTBR zkiI$)JGL!miHD^j=&B2@{IZ4rUabJJW|U2EX}qLI+%Ood_za(BD#3J<`^<3XK`i-~ zPrjyQY-E^Q+DnSySk}j``9R$7q6|q=#t1k~e|vszDs%p*1+PAi z!yCim_=yw+h#XFQnEn;6+Aa*141Iwyr-#FdKea3~^&-l4JH&ev<{vy)MeLBAVrTl) zK~~?c+J12IBG}+c`h}=6p?bCqR4y>V*HVx9h`qg`&r<3Qe7{O|-BJLHL!`HQQBPNj`3r-K~w5Zt|k4b3GU7^DXG}OH_KX zrIZyV^VJNcpKjxiFZYH&$%K2C1W5)~D1aR&y_Hc2dlmVH<&;O`NbwTSx~Kw&Mpt9i zA~V5t)Ekz&P*2Qs*$;D+RIo0p4YL|XNN&wu1kxh|@#EbbrXx23inkDc@;99SY3L1k zbSDNIeGzIay9L_wK6m*>AP+ z_bhp_{OvJ;dn|@GPC+={-5T!R91hQf0G!%5lusm0&1mXZU)I^P$7$`%{L?IKtZwEr z4p_k?>#LY&YssBkhQbf>0rnea4vsNS3n~_*JIQ6A^po+`AH|}*KOVEt0V?7J<#GJZ z^t~zh}+7ue?{vlE>bIOStHuaybc>hl)^PkUP-W@wsu?XTJhZliLGV%Hx z9R$ZYBf+*`5N;-3>-gl}AWk8_uV4qB+Nb~qAL(~5Y!y~fu3tuIC{{oI&8JN_fbox; z@%lKC7wFe8hdsLDpcz&$B}WD8&$MI7>^*!_&LYU%+g0Zeo$n1c#H;y#o$qU=2z9jA z2;Z2&9GAagJ#Izgu|w(H>@DTHm6svtt1;aEL^$r=#VwaNQNiM@HZ0lZz%(MDl-sdxLRv02?EgEkN4#P*ZE>~N4ewAW~1uJk48X#B{wy!6nGG8}4pX1y@WXDDlafo!u52zMOPDn;V|v0lhP< z+59F`|FaW+)U@yq!fTd9dO+2vM9JLUOW?w3%D?mQ;8v-lVI=i1N(cL~<&WB!-C%nR zI+MvqEmH=q4FR}oSGDA!-Eio;q!P7<*0HF+pV_`O7x7~7KmPAc3%guqEPB+W3rXa8 zzA#4?J$&Es(#WMyMI7egeH6LR)G=_MdVv0=iUf4nM=OKcoJY*)^FBQJ>>{6jpoz`eqAT+3>Fn(rQ~0!84VOLJz&#Ev1zp1M z$Nk8V{4pN`)r1LDR;IEyE&6c#{zTkl7SCm#E5lxWstINluH^?Q*V3aLLsZ=1;ioF{ z=Q@G++jsJ6)h716zpnTw-k3USs{=XaF}*41*b@R$iYtb5E) z$=bjp+5^h0`6}t}r~)#yNAvpS%+fNyGS{ndcx1^dUihvD9BBWBM`|-9p;iCLOUFc% zn?4Bw4b-swW*d5?zvNHeFNJ!l!?n)6Sb>Zz)P!}%Khnfs?O_9ZHFTwZ)1e_Z(fVi^z{4%Y-(!_;Y`VUi!=!?wft zgIlEWp*>);q66c@ez3)7#-aS?w|u;wHLSABNB8yS+*EZqL=z8l<#`Jj?755SKDvgT zlcb8uR%_wK@iJoG=4ST$s1ax+m|)m-@|!Ig4R5Gk4O}Qw*gMe%{48m^$)Bk%oj1^|SwSgI=d2D(g3%%|r!-jwU7%aPxx2VgZ=EW2- zY^*svFwbMsp)Vk9QY!O z4`1EPLbde77F{V&YjuMo{cNyh{xa?~co~$?_dMt4AY{mU!qS;RxHrucen{DX++50W zNO#~K?bLtLF7^HJR-rzRvh7qt(QDmrlH8anJ1G z26Bk=+*H3z*fd=Q*3k^||2lt7MIMyyrK0Pd1Rj4&6U?Hka8Gg!Q>gc6(Usd#uu>|j zw$VTXu>+?iOkk;vYEaW(gLWj(`O15qaB~m!V?w7SZK^HYpnK~1Cx508^@D9X=7pd0 z&vExoD;PN>2Y+tbAhCBhfMClv_;jJs_eAG4@IM#3(WA2}JTMl}3 zr&M7@<20E2?F_Ry{t&0V$>D!b^uXh}s^W-JPcS~U9EuhMU=hUdgAra}+7a+yoe%Zs zWHu=Sa7bDicfPC!!;f{V-o&|DX*E3S^y|H2I5!mUd%~D9yYji zN6+_L_~-3*kVaU|T$5l)_(^qmMRk6Xe+WA+eqdI2!|?afb38&_7wTy?+1bljNZv@_ zzf)ISUzr6zWHhkbgEm~0G*a>_E&y;AY0&!Qva}*ExG|pYBjX6(RBi|3n#doX>ili_ zzCtc#iKo1h<7|u-IAoqhGaksL?rXzZKiWCU=CaZ4Y0Ph1*FIEPQ3sQMNQ-a291_g; zkq7H4@>#uR4SO2B;AcGTYnBh=j&7vQi6YIlodY|6>L-i)>WMPxula7O^IHz*;t_7l zZ#)?XeXkpc!_tTsrn;X+%*)3MXaDlW(K@5CpA1s)RF7q;Hh!@qiAJX|9H zd_GZ+@q10-&4=D_b5kJhO1Z)Yx!8ffK>%9S25=+#eHs0}a}TW-{4?#@itE?@(~5eW z(1m#8N{nSmd?)QEqHOg=8+B<2za)aWfi14~2;h%C1wiD@K*|kw5Rwm!1>NW%^r`TK z^`Um~n|i`MR~-17RCRcBva6r}zVtmSE(^iz*}wT#Eo*2B{e_?Ujo^PnrQqaeT~Yal z6)a3uMPchRv2a*i@HSX_xT)HQF$ z!w(PfIVsvuqgsJ)r8JqrkncjlB2^r5fwHiNt6=4T-*aPV@26B0drbr7bvv*sWCDAftO}hPYIuJ9Gp=po4Ueyqr`F0&iNkF>xJ5mu z<(L3=Dds1Ozwe2P^5^(Cmkt(eK)y7Yo|0!j48d<+4dq(uLT1xVw$i%}bKkV{3Mma7 zeYXt*%TBOy^%{_}OcRIuY~XCYH!O4@4wCUEi8OtF9DV-zwL6$Z{RiuvF$Nn`ckmq3 z4(6$pKp95s+$?Hz;O4LA*xz$9Tx~tiF7|zhv%+)uq@`wfwoa9DZM-13&>!S!22q|L z!zZVDLq73*V#n7As-*E*_0kUQQXlcYj_PnsmF_PK8y;)X#)N+xaNwt@ENg!$d-HZD z?t9Y0O<&irkn7T-?2$N$^ogYqxPB}?4x#Vz!yj~L2AQ4a!S_A$h6^cyc=BaGHjT7` zHD&!!Up<4H>{o}~MO`&NF#8{ixwZlCh9$C{+12de?n7vkSDzkbe{k(Cj{b%#>MRUdO7%0Wslji8~M#yTF^hoAKxAu zFWE|*c^~x+xaIR{W`&h(fZr}`-F=qJ9J<`vePNN!kRof#_5S6vU%)+=@&TJ{16w6_`t&+1jBPv>QTRx2^yYCP#H-a*By`f z@jCC0ly0fG^Zf za=%=*W$Ji{TS@amU>1?Dy}S+K@Ue1S6PCkn9@xjs zGP1F=MXAVmy%rWcYsdBx`-OhDR={1IAUu|74WoR=!|m_@d>lWFk3DG*n@A_3JKTZk z1pZ{wog;AdlouRMOGDYc4d^iclVq8rF`Un<#5aYXSqYwGFIYZ?CjI5!`*pGOfV5~X zX=17uO<~S=W8CAhijS`z52!|1LAFex7x4t{5SHugOL}5`Ey#BD$0awn@kwW;;Mt9M zbgeujeD>|bHsAdGpSO9*r@!o4s-k$N@dSVR#0+08q}}T|E0E_-aHPNiOWp?ZV};{E zf#!v^cg6~z+wH-KG$4|paS*gX3ly()_47ZUOTpc*@i=V04m00%jr|%)c|c+(AFbWM z3hO#CJwV`2OKf4w9DP(C6V4B$21E8c$|$#vD*WL&0S0fOoz$f(%sr3J%s}$Vw+!Sb zEw$m+H_Ar8yxb`3aymE#Ce4X?RUHfn0J?YHcq%(6^RvJbodXNUKANJ4i z=O4zdfQl^AOI~sioCZv!-AWK%QSpMO`2(St_*YS99QbZJ^W9ESeXeO09z-=Tz27VG z{hnXE&E5{4|N4&1*@IiYQi7gZ`l6{;Z`hNpioXW@!WBo-`If>J;HDacUU&T%{u&6? z#7BzAvn|ME+E7n*e)qWyHY`FKOwu;spuBzD`!VH`q&&r=bJUs2dnxu}TvtCosa6%G zuKz;)A^o|eX$91}1!2qAZS25(YZx?-tm;f7xqPTS$dMPp(D3DgB4tr6%p+d(!-s6> zKPj-)*?`;iR`FX8Cqp-PJ@KveSvI3(BdciGj=M#rq96-B^k|V1%l}Sh)(6y}BVU>F z8O!*fs)=AueW1(TPRUX)N4Rw&00;O6F!Ld#e_lNrQ~RIcv0G%|UB7sAoHkOD)?yBk zeX4L;H*FZEd5hIgDaEB5-*fG7ebiEv5wEtMVUJR^;b)izx}1pTKb$9l`w#L5v)Uw4 z%5;RI)F(VSwu2p9*~)aDj>N*#+xd}98OT?S$LRBsZvBc(!J2%Di|$W?0}*-b*k+D9 z3XXDz&pq)~ikkRyl{Xj`tb~`;mtK#G;WLsZft>~IU!rRS-!kI-FSo(I7w&V1A39KU z!yl#eZTSDQlhixoPWSnk{qF6P;G{ok<=XqPBlDzS*4e%|cX~Sim!wPB0&%+PswK~gNgwez4&Sfc z%vv3q*w;gcF#2vScUeJv@;}nzz`m=68HU=Bn(z-s-mK)~nnIwF>abz3BHyuPGUU=d zHA{5~`$jyUSv>|~Mqkz6{(Y85lho&QYH{vB!4iLOJ!%w8rDXQ*m5r zCh_5^&a3^aaCJbdFoQ1CFISziB%uxG9^c$jtZYPttF!Ln`SCuY(l>2*L4{0I*@v(<&Y3$ABzor~~@ z!FB#>kOkByRpQXon*T({*J7ji2wtSJbE_v@(kZYQGArAd%HiRPen5xn8D6YQbcGv(eF zVb!6YLd$?S_OEL>= zc8u@7UwEDw23viDu>FTMq?S*DI}voJpBlz%^ajC!0MZ}La$u5CzuAg!?zqsRoa<)D zKs{x>DTLKYj?@~1>+C0ZJEz;l zfmGWm2X_?|#jlg4j~> zM|F>beb;osC)@u&tiJr3G?=T!p%ZE{#Wc>oxW{5_d@HXU-Nqg-mlijj1U@>5JOTRZ zhGU)|ONHY8P`czP=@dY}cqJM~1LJyOIq7!7ls?QoV?5Z41FgAQVQ!!D85e`bY_+KeM6gCw$R+9&vh7?(PIKxvZnr&YOF#RL#Z0ySs zs4bt(_a2iaj(seSTJJ8&520DCZw&@(>B6|9?Xp8TU`U78BVsLor$Cdp=b=l{-R?bRLZ$LdyQIL95GqPFpSA+qq$Ar{Xp4t4w0 z*$ZR`zr^L|r@}y=0+xI;AMbtK&-V=Ojj_3E;>;Rvm_92U=EqXMdOU`Yw)O#k!YH=h ztq}%(kcM{$tkE>*9(P)20OMo{>z-l5Z=IBZNFfI8et5HN+4n42*oi~he{=h#GVsM+ zO58LkR`U3DAY6#?M5mB{%w%mijH4P}bH{^wMEO8D)%h|rTb6;+kbbZao;;GqpMEre zHH01gAHzADA_FU$*I`1+Ms_&s4;xr|2+IuK@mE)6q0C8IwCAe?pR2T!J=Fr5M=H4X z#RzDpdh+<3BG)C&&e}NAXGJbyI@1;4eNBJ-*|eTt3NwT%>T~QSPLOy@s1A@1PkixF zRv%i)T6~kRS?dtT5jBkMdx56Ud$6gKtf1wP3ZBf4=l*9RAd~RD0Rg)t>HmD-DAoDw zVcS{m4og_8F%i9_spltN)5AQ{e)fLux^yx#2XwbS3YP3`HUv$2hX1eg!^bqUszJ-p zde?Ej%DNYP$*aJ~LEVMv&y8RkbnRsKOw_@pbN}K(w-J(kajRef^+*kMxh&G#2lj{1 z?DiyrR}FOmTSe0ND>VvBxSepMPuEWNz%yAWSQ~@mzYO5}2T>N)y$W=W&t=Q@oM7*_ zAI3pDWQ#%@^l(Z^2iiCt5Z=u3frbR~I(R*d4de*h3kbu zHprAlcJ=d3nO5K|U4hv%w{pJ&W1y(U^ej^P4ygw%Qzh-W(HxerCu=o zjx&6v87;NDBk^a5hxUT9x~BdW7XA6kHh)=ywI>_6@h&THBhQ4njkf$vpb#F z?7c-OI}J*O=RW6cT1hEIDT-3ID5R{6mQqT4@4bh-cVB4_EhI@(C@l$*zEl2yukU%E z=eo~*ook>)jKY;uuG)y7J21y*9Gf;)86Mt{!>OTnxyfaJ*xy86xn2@{(cmGlR4NL0 zG)6MFkPh~0`EXn|=m2+NQqccHDpnRUah-!XJg$0-35`mivbmCNvVVk5SL*rGkJ?zL z_Z#!_4zhqz+At?dm9jcBdHf@P=u5w2^!Qxy8qp9i)1)lBrgdzrQyaUiiP-<~O8)Vw zBz)CN#Y^*|-J0?&AujV7j#r!rndukVr?%7ht8_CDSZ#^#@>D3B(HkP;7r^^dk=SrM zjb`u3FkvEPkk-`-?$oz_b7dcNR=&Zn%+`lKMzm9lv*j;HhiNl21!G^iQ$O8%wx?eq z_8i&5*T0j2(k2N}%A0iYkRgQUksi3*{uguGyZ|hSN4jD$l5dzX8I*QM;U{lUX|98KYY>nWaGuYrT+@?9+0=Q#^|my1UvxAK{sa>jpGqT4(Zrdiqt%GJB)_Gjx9QQJ*gR6Wj` z>qe08$((W^eF~VhLvQFgY#jFemccuE8iQA1H=YmaNBszu3sI!;jujAxuyf=_OuwDS z?;3nyLA#!!B6XWzbh!nrV?S;fTEZbg1#T}j_~$>`?Ck>kS5jYIygh%o#ST)2RAR>0Q`Gf&gb5|va7N4@p3rQFwxpLn zyL-0~@iE|E$HYN3SN`UU3oHnvT=bO#nUr=rdz0;ke}W(IZz#wi>k$=M%cp= z#b>Bz+rYf=Ci9ti9>W*5b55GExP5e|KKPkslb(FuXe0bsyMULu2f{)6|1J3@RiZ_{ zr)4x})?dBKX3jK%Nl6iS+;TNnUMLN>f|Ibk&qm>3_Ar+Gso`IbbGVT; zkGQ9Z6W`QhQYWPWeRYMSO#^Y&ooF5&5(raC^ENBWN9e!W6>eBYW7dugh(BTkOY0-B z-)iF9Go`_MVG{bLD6)HbcbNxyffv)hDSo;dY;2SkX)GAQW7Hf$W{583O(pVq((2e6 z+(UHyhq}1WDcGv7t=wJOFik!Ib$xP8`h6kDa)t%0|^W(yfs z75FfHIUg|394^P`P`@+rOo|?Gb%_oB*fWD9N`)5{ocR7aw1=?1opcG<}d$+%#`I-VX<1i?m3 zq;ffpi9_|-m?7O5?tE4q*WLS$L-*Tr^L9#C7{pSop2&tX8@k!_QdhVR23e z%1#=`>Q}3R$}L%(;&_Mmm^lqvXwESnCc)M2y1}s;nyD0{m~kHo5ZnPX^Y`+fluy1r zVx^#AOo_z} zcI5kUd^Nd@#(;WDHfp&Xrlb z<*g#NpOh3GNVVhv3e!P`?k2s{3fP2s7VtgO^Pg{Y>?X<#q4RE8aHXrMxeQpV&&M5i zYFVr2XLitcHCEk9=lW^i*)Q9t*wiP3MbEwoUTRv$=*MgB1#DL9mLnSYd&#{Nh#y(L1AX{_BCv ze$p?dKX(`|G``Cp`p81KTO!8VREn!d4ux&uuTb9oJJXhZ#FSpq^jP1mVnQRn zJYB^a@ArXQPYh8lWC4F#83a9vmw2r$UD7m&fgSO;B738|Pf*1_buyySGgZXz`%VXyIg}MY;1XNDLV#i3-MD>f zu_>&{qYRK|nZm#?o~+Kldrx}N&=KB#eTI{!Q`fD69cJ5*aRj}Uj%z(#q?=}vV z;8G(Hx=43gJ1mOXN_MhoIzzE8emlQtB?m)y$Kze~A>u|qN0_&m_7oN>P*ih+ZQXnT zXB8LoY0WBVZQOvnH*8^p>d1_;P z;td|`A%gp~a~W0pMf}v$0vZizf7dyL{p$G4Y}NfyP&ms=`}KrB`WJBZ&e`I*cj!*> zuo@3Y>43SSHr5XOj{Ckn<`*+{@Zt#tQLW__Hd9?0jJ>rm*K;Ws!bPx>_~8oQSn(*q z0<7et&@y2@b9esCY^G1b<}Dk!j1zTjZ#sji&m@Ik8WQkub2({sW=Uh0Qxg ziKnX@q3nHC(SjY5AWS_3PK)U|7ZaX85J8=LH=a+<9Ux>!rT@!I&(4v9jlJSfv!f4p z2qjM8g1)HStcxYLTwqpg6V9L<_~HFD&?2V^?>s6Lehmx(jklCVw#k*>v>Xnh=g9k` z;mD$G+gNmy6V|coocEOjnI*C4VDdz)=->t^Yie+c_ZJp&@Db~Lb_^dXe&%XnYG|>! z5oc*WXBJ*o&{M+@1Huyd9sdxxMO=qVKk1U{T_TXziNXktYwTekE$ERy2|MX-b;4N| ztV*Ntzu>jP^TN?=%75K6xsiJZ^Ur^TC;v<5t}&|E(xU+zrzt|(AB6h-1Mxy_G&hS4 zf#}{*c%{ro7!f@j)YYOf_G$(Mtv849nvuBgcPRgF67@HAM&mAjS$5s{IrWY#L63K& z8>C#CI)QvZdW?s)J3`wKEv%do$NlL(81ME6XT6sfJH7~k9)*;dyyy~>uoJ<&4El~n zM)OVY&EW;<#CkSn3gZrrW9c`F;cvHv-VZ0}{QLwzTQB2|eok;QL{}6ME(zrxK2Wm8 z2G_gJ;|59^xUE1|^yK#~!QtafkU15N%^hBFLQ@1siSwKj?Z_t&wSb?0BGLEDFJYzO zC$@5-A5I=w$$tvE(A9bz9RgMPF{^=4SkR605vNu0O=1J}KIe0r@w!+Zr6}6}SsElJ zir~&!!pXS4#otF;0MPUQi}TUia**H~i>B0z9dywdPLVJ5t%?TIs<&d>$$Rp*hv@Vk zHQX-w5vvldxYiL}-2I=T$n&BV#BHaXnZd*VX<(8ci(s@5X#+wdgcU0-poDe`LmVEk zwjfz}t{8*0ID-p6vS9XkBT=-(IcBl*I161+fL>iau6$}*2zom`@on7!L2IunSWlD2 znfGq+1z90bO5UHdMG_oti=c}#7Mu@9Q4U8NTVLsf51wx3Va+nY+@n#t%t^fW>LB>= z>M8n%tH9ZJrA)(d59(H)B?+O;J@M$|68`b6Im{-$ zt4+a<=TDabTSmP42F4nXyl0!2WaHYv8tzbG0FOK*M9GuV#j_(5;KH>r_~v~Zd)uyv zscnCV-+RiXq-R1^2|b^C_AK*)h78#XL|%pBVBnEmgw6g}?F5A9LQ|9|r4|5r^}!fHnT^4UQh8a8V=qBi36& z7oG2iDk@!@H_L;V_Fv!TK4(g4GH`nEdOX=Lhlg6rLvPwsKeowY0Z)8k-%=YaTEqD2 zLOo1BsUR{jo6myXCUqc>NVim`ih@iuq6$H{lzbBA$R_ z{Z4VK9cHk>N}?qF~^1vUkH;`|8%_%QO>l?5t@hSqX6X0{4! zjn>4J?O9y)?MQg>nDi3VH#dL3n_$5{vXrQ-h}dIZG6x16jWd`d4B}85{ zJ82fBz>*Q3cx6v4OLrO$X1=7q@{ZyKl3`#wfO4wk#|b*^qd>we8mGO>fVuLP(9)B3 z$M#|T$RK$Tjii~jPMS?!`ihOqTa0Q3Ke?oq9>|>jilP~g{I2^Dc=}cwyFwB;yd=M; zVHZxACokSbKCrri6Jdq8WPz-0c$z5^& zY!2hjUBIZ1G2F6H4)P)@FlWsLHvGtn>(;m8OM5I%P!?4{i(1t7gNAdz6hP zcthv1ksuRJ-2`hL`F}?(A&asmg3LRFfY(hlYmP&cwNH50Lv!d?cma0=>u{%9@{!eO zi=5kgLv?%#xLJ8(L{7VS`D;V$eL`8ZeUKd3HH?Ho&&h9flz5nvmatYm3MK4{*y&r8 z@s%Bc@vbQVasqMn|`~6s*a(ACm#H18RQ1ir3&sU4*_tQrY@{U=HtiVxi zFf`}6;`Q+fJUVa`z)Xq)xZkW_YuCuKVWHsJY4aMMDOxxyyrdI>qoC5m!#|! z`LI+t=m2q(VoFSbu~?qrAR2Vh(L zMm}z?0&HJPJl+9Eal;4(tH}%h7u#<ZN5kAWPzN5_Q{w(pXLHc;3h-lhB+4Wwv&-k-vSNcpsMq@hA8f1wdP}R&cdxH-aFaT?e5-@rj<>n%c=Ef| zw4>gj)%@mzaBw(4-l#R?5paQk8|JHZCF&^~m)7hiGbMMWsPLphMrn^~^& zFP5|?k9?HdI5K6LCn|8ow4Q8{p#yZuDd8m2%=oIQ;_#bYc<;9bH(V1AL&KvmyQP46 z<=TTwizhDMmd15Y+dyC1hsxcmbPci$)Lq>t;-qc(?+=V~zLST)Mk zWV0NVROqYeftKrM@#}`F_@KHAS6YNHt0HCClc9!FXI$acFUG)~IO3`Pd=W4CVFP8f zD_QR_lojPSvy26ZuLmAn*Pn0H zHNYv92l(F?&Tf~gL9Z*C_)K~!Uk>iDyPk6Fuf>XAe6xX`YNQ9aIiGcEe`ij~K4|u6 z9sje2o1jW6eN ziHb0u&g+lI%ETUOBVp?OXSmF-k&S%*kbrzCl`-1g`P>xcsq3vm!e#Y zR|YyL_d9{JsjBGe`vhsJb#t+hV+u+cr^LTF=4fIl!68%&x z6+X7lg`6t#d(QW!Y=bdSwwN?vrH*{uYa967N?ed*hoGeQg z#R(TxMGq_O;f%r{Xu2~5^Y_H?XP4Yza1!N6zl#v&hLIob6!A7&AFyYm6~RWHG&cLE zahcRU7^HDdB=OS^MlV0ho?KXl#~w*unY?WY+(`Gpme>QrhjvxC)4vORA79}S+4De+ zzDJ*X5`63)Pw=AiDEwm-doklTduH1Y?>lVZeV-|V{a*4J-FFnvT{s3b9iAcGBw>eJ zIop!C4P|$q;BR&=0rgN1te@3`jf?9A8*^0u=^Jw|(BCI5oV!GxcvFKXjOt4rB^wG^ zZL>544SsVK=W#z_GJl3W_n<} z@;bK5{tJ8={}kKCf8d_M5m2@^3J>*vEgVK^NOUm3cfZf`vrTqzK%l*enH?`SRe{vy zl=+Vy;PX1l&{&?#+7#=Vfo>AsH9W?p z7nA2fz8TkgQBEdh^6SOd!QJ1tczcL4cFk+U^_ls+=wu{BNJV3d@mzLbhB{>3w8G=U zV(wRC4-$d2yB|DW+@HFrD(4bMQMHNfXqJF6>$`E@Aw&bN$d%)xcw?qg(ibMFDxi~c zCQmu2MEl29lyx!Xs=Xt@U_NDV8Lwr(3LN0^OOJnCjhb;^FgqEEW8YW0`n#&ap-$rK z_C04ueyG6k#0@xhZZ2O=S>LlVUf_uE9Ok@d39LQjj)Q_{aq}isx(9UP`du?vO{WTI z-cZH+D>-+G^MXxu_U#(?ReUk1FB~GSc;D!u>|#_aGnMc`rHo_z)X+ZQA& zv0~||ec?N4RHPf`Q-)g$+nVf+yAsy&rL8vLGvzEg+S+d966nEZJ78woogPNrgpioXe8tM}ASM-Kyqo@zp{j*?yPz9po==Z&7&MWqG zF$?OiO!f_79d8~nc6}p8l0KFXNrMb8nmwc>g!E+*aEf;8CdzKSJ;NJTK90ibJV!S9 zc00Sd$POdCin$qSgv!e!@adE?@q?T$w(mCeLp>>AcRw^R-Jrw7#WnC}UTH9daG><6 zE1TBe0mhpc;>CUoc-)!@IQEM6UlGzJwXI(8p+9|7>#i{k1rtcIjX?w#z?%iX%B^34fftp?$xNlGz+|Kd9=Fzb%>LBIyowP>DJ~O#bbp$lq zMqx$3IH9)E8wL%E#$wY$U0sYhDV_1~CpDlZf8;g4@K`P4ukxY4L5imM>*bHpTgEZ5D? zTz{&Gry3;xVf&NgQJ^LjgBGRU@L!Y{jHtd~Lpp(^+zugl)fYBAd<<>~ zxXUAdTfl#9$1wGr3O}Hs3qJ3vaqXjK<`tg?Zx49j;Q8%hoeoVbQj!u~D{NzpHC|9c zI9a9ZQ2Z*kFSOEZd}dA&TQpGxW+z9WgZT>5!2f2skvV8{@0{Q|i?J};pUOOzztU!s z29*{bxGjCPIJ}}K9^a=V+URZr(MtzFSK2_Fw0{ooMIN+@<&>Y$J5tcQ*%#V2lkV&A z1BNjwFkpWK2F#nr7Zi6gji=f8yR;|Mnsb5q8Rk&Wawl&bo(5(?9{6+C0bynu?N4nx z;rJBJWymA;J&1PeeY=Aj{G<-(aiaL2dgNv$0rVjl%1;r`tF3is~yD!ik<9K zLN*S1c8cMX$CPuj37454;maJ;z;lELh6MCrS{Hl5r4>pj^(mdpwMM{W`d;4j&J)MW zctaK=J@es0wna+@u1^_+(Z`o^Lnq3DrkUr=rC_%k(|<83+8Y{NAm91D*Q_aWFP@m4 z&)W~BL9v70yi0IqutO4=ah& z^9Z!#@}8<75LdQO%-ACTU#xKDQnXfm!L2S>f}F<>EKW%jtCcQ-s?gEs^{17&$E#wE zW+!GEKjzk%k#Olr6fXAc%j6_wAU@0hkDt!rUwrz)G~zTAeP4-})4zW^?HXo%OJ;!! z>d2#&fOhW=^H1hlFuI6xO<(v3sd1WcV$3^`o^X>FZCA#Z`7L->VinJFj)m+_@;G?T zWglwP!91@Ie(#aO=l1On(oWsju10>P$#gdTo#7waNy9n983#McHCjSi+2F?*yvmU2 zD)uM+qyo;Gl*vB?D`TJDEtqd$!av@OftHoj`{2EnMMd-nQIR{=?_SK^*7S$Dmx%w= zc;@=(wgza@98%NuoJ9na=C(%;R!)rPbwPeaG3toUtUJ#}k4*=6+BK(T&Ej{H)$yul zCvF%!gYETEB|V8U`b;e0dL2Hnf;5eD)_fH|Gadjl$Oja4VJI6&-0yr}Zww+IMDPJg zNEnliLxQM&+P1^{#;D?kc#yD7p*?QyjE&~Tz^fpzMRGN zZONNM`~5LGapEbD`-2vJYljRIn8Ljl=3hPr_c*TR;*FBvH8dN)c>m|tQj`v-WIWKw za%aiPQD&(9P+2s3z8@4g$3Qb_U_2|5_~D#!;4p@8IO(%c6)gw}j%jT0;AXK|n>x&` zi};7_Ubm@#CwM6y^$KFrA2@(JcPwOFB$n;ei7RVwqOS2sn4c4l}Z6 zbMK%S7~hB9ldN%qgc)^0k@g$(GNH-3KeYCx-rIv=oUPJ;OLVsW#rA%hO>AIJ0-ibC z#Ba&jL$%I#OkM57kNgloxm+7h>n3u;>FO9})QMayCysQ8g{94;PnccI{G`W0%L$sh ztYY}eOZ}n8_eflylqC$^8_F7X760=kd4MGBf3XzL+;`wPa{l1qr6ggMjfpbTq4teCdf#jlTZ^@^^rfW8aY-A? z6~@8lAH+?WI}{hyQ$8)7t*dg1n8g)!Xj~S7^}-6?ZYBY}&Sc^90jC86^U-W)&+gnX z8Ol3$Z*>2M?T-$c;`!N1A~$R5mMjXdU%WJAuB3e}9=a4CENSOol7Vt<%1y$B&a*bngu$`W*fAnTb#1twMO>&jnO*zV#B6WI zpi9gFZk2Be4O#{c>I-+Oq&a;R08Sr_xJC?kd#Yfm_V!+1^ z+(^CZ$IDgVPKqL0_PWHc&Y1v5iz4yv$**FERO%0+nc-*YP?n}qXT`!od-wfZA>$Nei_8m%Ft`Q!t ziibV-$*1q{#&zi|F}Y5de8Z95v+ZKDDy;Co73aBSs5bQf8S#&w!S#}GFE|6;4OTLz z17Df;>s`20<0YRdqmMdPjd-TwIqMkG4^;l>;){c{ulx`X+Oz`=xG!CDNYxL_>6`u4 zNjugTlt~-shs|mkJm--%0L}0-;|c@^@&E$`9Zrzb@dK~cZ{QX!I@t274oAHw zUZKqsewX&ch(3}0_v?6gZbJ8hW8;Kgm3|OOd1%|lXF~aEM+mkg-`TA&exgeof^I4Wd5x9_Kky5Bo+`dvBktuyoC z&?oATURlhJ`Aq<0+Oht{`5I*>a3CJ?FV3&(F^?te@1EgvET!Pb_YB;xX~ze*o505Y zm1rGzk)7BS1Q9WI|8m0yk{_pTQy2bRbVWFGG6A-{jm8?ev2ZPa0%XydTNdoZ=Zmh!L)Ntm=N1Iunb5r^NjfX63maB^DKVwYC- zt8xMyq4}`aG>76D5l%3k=7EzZirD>Z>T9!$#HS}$@G?_L*xs0q>(h@5g)Tm<29@#J zSL&HER>MnCFYx-8o_zTdbNo#i)S0@rpgvm!gUZ}+z>@`B-^vd*5YKjdW~8vYl)lZ& z)R(GU#`ZgEgEh_Ve>oYK9TG5nZaQkL)?H@;J+ zp;-rLXmP#^62Y_|VY{Owzvwp!>gYXDxg5=!G9_VJvo#tR7VvjxbwS%A5+%+$iX~F1 zm*jmKzTbVAg`Tfq4<4+1AW=iui(8-|b}M2K0dlbrl?TB9pJqOoWfLt94zF zCr+3!39k2w!rBjo?2WNJXzBLH)jcwJxso2#gmz>5-jkBx`f>@L*wV?|9<(u(*@If% zt9Zj2J#-2CfIlzWz>U$@!6xtkMz){lchna^{0{0^EPpNd(0*{pa$TJ7c9zQugW)vk zPkJx5`<*?Yy;%>9&t>z`Rf8ds?%*9;UWvn&>A?s3j^dwSIa3{m-KmBe|0{fio(iV)_=+QRDGSSKAkk5I%0In0KB+6aOHYYfOFmDtdmr3E- z%bZ~!?S{@Tc;@Q5Q6I#^NMk&#nq@o7fa9ce$`AL=htWLKIFxlzM#G71qp<$me%>;Jx^lA8 z@QokEocc)#kJJ0H{Qn| z)~FKR?vE4K-*<*K+V}m%^GnY<*t5bB=sR{LFQC4LuA^zFnR3z1LOci7T-Fn{j@ku% zU+STp{Rcesc!;<**%D>9s)&O1C&Agi3t+@+I_qtc`L_apm^g*}vkjjGTGI>LVHyw_Ef2h+$|GF&mQS84X-8{?{rQQH_<=wM-gg!>f*5kb+iVzqv7OXaOW4O|R1t8&1 zxv6Tt!bO+K@SU;|3<5JDfINem4wPTo8pekw>%%PCm(4pO!|Gl%GAka6Q`W!a{j_?+ z*DvL0dBl_}-Vwo5&_<~f3H+F}Ha;!uz`-x%#JLYAK?vdYcK;aOd$lt((KAojnkC%2 z6vKk*i(%F*`73w(NJErI8ZJ6w#Vccb!_;{dc(L*VQ=B>j#$UBXaeNf7)zm}N3<*(q z##NzE*&l8aR@-Gearev4U_m-8H*Tapg?mqIz#wEe zEbQTm>X#Dutuy|>7ZWeEJ5rcDko-GmqG&EHW24gb;P}#R+>Tr)30pH$@lB>S+wXao zJ!eHamB7=}TJao-%F`PLVmlf_gn=7d@9@!-!2>lk%mPi{Imlu+8l8 z?mnPfr~Gdwk2$jdn&@tLq99LvZM;8Br#tdr+&<<@yWOe%aAtNopKqfNt}D9vmcl6# zu-7OB)xWp0y}X0%>a_f$p$8cT?hNd{n(jzo(B$D2yb7L-lNwW zVOzaC%p9SM-rvsf9-7Xugt+v-xb5CoABGfAj_4l7hV`N@9`hMk_x1uGI=DCN>{)@a z!esHZFPX6B=@_io{)>g|RKxUuA9&5<9-lS22effrj5|c#%?F$zi?sL4@4OOkAwS&+ z(tf0ArLfW4-m$>l)A4rB7XFTQc3<-=&_mrvcr2j_5BFEYvbZbU@T>}cm;8*QRhRKV z`WBYH>x1pKi@5KKVKBy%?kwlWi|1T5f)|xE%PrW<`jf_KZEY%g^eo`lif!TQ#R{DD zp(k}I5OzIQ_?O?iN=5}Et3ILc5CgtjJPg*@cke?_8o9s$`geZ3^33(9t}!f|O#82d zYL+rh7KXh{#cZWep3q?nH42qjH6)9r^tlbyV>ggan>zRe9lUes7j9WLoq1ZTLRzgH z_S{70;H3Za0xObw2>QRQ~#`M1y$z{aoYWbRJ@7av>3d&S7W9K%J_F@4sphb`^2q$+UCk6G|#zdgpik`%pd z@DYnMtkCm_vgq_XKiK~^8S;8i4#Uc1zDF|7kf#bm453GB?8ZcGlZw1I+6 zz8lTHoHE7|;iOQlA;Xei0f-LRa^vn%QE({CDiR)&4+)yR%i1YzgzO6rucfhVQq_ENb=zp!_RoOoW49`$gliOgRGgK<&-?4kQ<;)NKl;NSvX`ZOmz$r4O564>q7?z!6D zKnC8;PeGfo-h7*f9YjP{;;b7NS!Kvncz&}F#+1(HH{Tjymy4umQQ0-YVOanSCVb94 z87{t7ODgDb@e@^$pob}J}VV)7Uf2oMFZVjmVO$9VAjsnp#R~)xBk;@DU z1Z~1+*C&xe0QGHcUe=AzGo_87FYVmdHc#W$Go`@5aUq^spusv8KW6pQvM3LyjW4Xz z#z*sCV!8G(rsu8>`xbwND^t$%R?2yb873_nxSce3hSQ*QL=<`{$FR}4((o&}59WL1 z^Ci=JLOJmdKHnY1tDGp$aL)oPl-tWrdB0$LD3h%wbOV^X3+i`~HO!rKo-B^=%>{+Ao@hI)iwQ-VIN)_NI*z!< zr`jk%%Vr%kugv264!gk+VGsR3vixO%Xm@)fKWf_#Qa4oK zE@vO%w6_LCIX#2PyGnTUZ92QZeZrY*^Z2N7^j_C1h!T&>L;Pd|$e7d{_5LLBiO<|% z;ehcgh>1|;yvaRMA`p!copnd?<%3fj)y_zZQj z@N3CJZ1tMKPgnMb(bkn%Hz|u<6O}>Iz)d(}%W-Z=-<@&44)T7^VC&YZf>M$!;pu4} ztQrIX?R19j`6fQb1-M50Q$A=Ib4zJwVMW7m<>jrspOh?|f0l^99~g;Gxb=nf8;`Nf zMGc~=)G;!LysIH4{NQd!ru#67?j6vYRkfqjzmTi zQfOq3(^sM5&G)>fNe>0}H`x3UpP(D0=c!KE6E&%xPwxGRcYcSR( z$q8PcZ31h|$phu^P+UmbW!I|tSbs2!y<^qPW5!Z!lRL-zFH^%!>&o$l$1Ns~8U#6c z-5f}ivKl%x%8G1utt&}i6$A$}XopL_`Q>4ja9m~_{v5P~KYeEcYR4&uA8`X6(jSHop3OgLn}P)CJ>qZ5FxBh^_TuDZbT)g;PwaDp0(}+K51h-7 zmQilH=ojjH%ZZC_>f;zWHIa^GFf6<`4KAD_A7y_-ShM3xoTMUy9qmz&ItXigFuq7G*xL3 zAAMc`(cCD!cCb^(@MvXHEkm%Z-(?;&O9q~vPQY_fH^mZp10m753g-*oScqi9Q0m6#lHW2gcTyboE!fFk2E1bZMlZ#=W$Sp`Tort?+(glIieDN=$A8+%m0x0q{CSMrfnq-Q2Qc?EeM6NklO z+oI3xie?YuLw2H4-xYlE8YBE3@E*@Su?CxsH(_@3ZajbCG>>?!gR@U7ifndfvJ`7& z`0l5To>Hf|)J}j+fsuHs&W;a%XGVEXRr<{T^ExZws$x}rLvY&`E@AFzb z`nDOAAEpekq!f0#tcksS>W|LDH*nrlA5@>5#@}cA3L646;Qq04SiZlQ+h0||6;}0F z`YoHkjU{~@Wr!8cQ-T0nBgk57fuSl%y#G#wrfkY|b)F#Jf65$^=#1O=-)45|w;X6( zkHnBRzrzxBB4X|gXRKLn~)=P7kk2JsStY&Gt@=)_F9(Q?7<=;PM!CXCK(GtBY zOjIS0MQ3kf{>8U^mzz2c8}bS34JNQtD^$TWQyM+yoa9F;f+1I%`gU8siMKByZ^ecv zoHKtIo4)oJ+cui|E9E!yiSlyb&?62vJ<}K4r#V93JCAXyml}*9{X(#DCE7v>zhkdP zd&@?AsJoZlTWAE@(cPT3=f_|eWlQ`_V7%Chyc;J;b6Yebk$sya37t-EDB+gNrwVeg zVqP3tw;XfZK=%lhi`D4jIuA~Lu*ZArR74gRCV@{@6O8XwO}$?qc*lScxJze^%BC+u z&;@@%e_R&(Ueh5Cduj&$lph$XX~DNrAK$k!}#GjdYF2gItYqeggJUM;XoMmdOXjBCEf_bdr=;E z=xqM1#2hL$qHxJa8MZWnkCG!Uc$ESy!0;@z3rSV zs4j@bAJQh=;$Auoh|m|s=ShR#nmLg3-4+8@M)Nh5x_D2%74?=C3*LK!A(gZ`fAReL zR1rXA6h3^>DZJYCleLCAVfsP3Yp2OVjCL&I&1>RZy`i8GScL~tzp<#LYN-GFF;?>o z{^{XDSWx1LT}{K;$nU|hlXx~G$$rJdB1JGXo%Z9fk^O8lgQt{(ckcBH-g-j@4qT7M zhpX@rw@mtf)h?~ir{Nzg@DPSD9j0o5;DXh`23FY zovxIz-9ODB@^b_pj0oZbX3M}C{b)QiT$z2gea&VL>c;SDJw5!-)gead z6U-TUhHpwCZQCYEk%ZDp9`Pj@cF?)=7sGLa45&;n#~G(q@LnU#;nsB0!MZq!UtE=j zX3|%59Nflw9%^C_mM_PF!^jyT>q?*I1Gn5TJGQ=&YS{j@P=NH9%WSejF0F7-sFe!66 ze-dMi*zx`!2XdtPI%G-j!XbN4^7*bBxZ}61NIQ5j`*=kG77WoKkLPi&oq+IoTsMYG zl$t}8VHE1k0XDJg6Z_mT5vN}}!C5W&Q*^}`=m6qtzN&aevjOdruJO99+Nfr%AUdIT zi>3EdhI_ZVal56j2(~(s9y0c|m>n_)`xfdPDNAAYJ|EexL_gfnxQ@TfGzG=+#c12= zBz(K20p@R?z%8#!e6W@(THJe&=g%+Yj;nR)oFVU|x;(`0F@c9id*jWo$=u`52=Jdr zS@9z$h@E6D;mQl@>LuLnUnURv2GOWkmd9_@(|IR%0i}}V**UvmQ0pO&opUm{xH$#P zu6p7!mn^Z+*c0ndsfpgi4g?cRH#j(X1ZoaS;$zp3gvn-6=r^Itb?6vNxIw(AEw5(3 zF3N-R58|fY`}42GcVVLHI&6_U$j=Q+fmGsEwp}|bWK^laggPm#;wSjUA)&B??xZhe zzl%@njsl&_QK)`;81t>{V1MQ~;q8+}yyp=)Fft&W*nJ&wq_++>{&|M27M$ycrNCP9 zpXzz5u^D4bV0905yp%?})PteWK)koo{djTQ$C2QW)`@W6mkGZYfr;YpL9^;pjgGCPZD`1bgHy(D#VOtM= zgcCoXV1juopS^7!)Kb5vUid+3xr zYj+iLkHzLtFBgvbQ|d&jFJ)lDGTQarN@A84uh>}KWVH4>#RI4H!D0V3qlx%KrgLEg zh>7W<_NS%%<0*CY+ae`A7qO+}tXv4BR?NQ;L08{m8~oAPpDgdeh(yo<~oj zwYMZUOc@DcS}NGMA&mDvi-)s~UZ~+5RC4ON5#BtkB77kh3_-8wf);TAwmUE8yN|j< z&T!&RSf>lTccsw2>K`6rTqFaH#6SP;YRFUPWPmKGLQXaio}m%~lS!xVwP7Jo8M^{b zyLe-Iw1FUZ*gOb&NBTY&2dw*%pr{jnAC)h`+g_ zrfbdNi4A$68D{fC^JRg&8_{WAzQFf=3>$XsUw!VLtcjZ~AK-%k1Fq`70;-X?a5i!5 z%!^TwGGHh!?per1-{!#!()>E@j}SDwjE1(h2#kGO%XH?OgTv1-RL_~gHxHGC9i(6W za!!%u-+j$Ib5n4;(N})kUmt@;G+@&uXZG^08n_0x!NZc%yggPCWp@0+YNISJesew? zcP8vNH;NU#k%3!RO|X;vYV_V%K*F4G>YObP(xi3mdw(yhIQE?hUS#1il^iao zqK3yW*5X}{Y&Pz{!QiT;gpDz&T(m?9*VuOB$g3J$tZ6WCY66}*fD)tE^Zl2Mk*YoV-?W6l)|Ig2kQesZ zJA+p!Tj0$&9pN*L4Xids3Bt_Pu#TPJt$W9SO*H9lhFf!ueU@NLeTYd6kOxsGGd(g9 z-*poYd6zldxpe_gesmV4YF46D?M9(Qi38>;B*4>r;>o)YavCB`t*ZCkItfhgN?vQ zRs$@b)wc!6^EA}5)$j_Q5K*De@+;4bZFhx!k!a~IG^cwO#zO(?!={;KN_*rx@ z!xL7JcEhA<1Uo0+%`W8(!F8eAxq&I^z+Gsk`Au8&C1WI5j(>;>2^z4R?yLc`9-;jm z5ud&;0TS1EVbdEG7UOIJUiVdT?vhk4r5p+aXiq(#Kr@vBA=n>;4qlyrbAo_!bK0-h(2si0KUNs3*PTy{`p_v z-nl1#`|W4Zq2Nco>%b8o1qKf-VW%YFx6Ar-%To$qPrcTr{$tqd=U^w-4?5z)NGQ579GiV2?> zZYc3s7Yah+qBxH)XWrx`_?nH!Ne7d-TBsEy)cvdBuyi%sn*XoIHos#6`ueAl8%!hq zo(7(LQjgOEezSu?Q=n>}4W21k#7)nrVL`LF(DZY&;Ar24@L_5s4pmMAIa?11Bm6e~ z?0kNS@+Mxk(%;=uY}M#b?4zA8-g2zufxr4daaR#O)so=IMZ3WE{*tuV|Zf;edj5JvC*02>3r*z*e@j%tPfEC>E} zwkK#(z5P?e?ftu$_t?SMb?h|v{Ur}OsWz@ZP%7G0FbX=dAE8#|NA{sn6_c*lpzdPw z#CVkeW_4b8AZ8@{e18EvQXnsMTiaq;Z%?RPK%Q@*yV$NLmXJhu@t+#*wN3$cehEjv z!TEx{DG6-XHbub%?gEz zs}b1pGD6UJ$rCg>$g@$aj$M3Z3FEXW6Yaqaer6?U5+4y)>X;%sbgY$4HcrIc_zyhQ znKEX#G!Vu(f^B-P3a_l2>772o>t0X|H~N9CO{@7#+eL6_4CMZbF~+PU=-oTLpA{Oz0k!n6*n*3W;~FG-k^N5werI0E|p9@Tpa`wnrPLP!oRKdhK)Zc z3-!cHkwD!VzP=}Jt;0&TOzRtyOZLUz2R8AQzLxOb=sZ5Quobv2(uBs`e>MDZbRxK4 z@I(Q&i`rjl;!RCS;oBH-I9pDckL2Z|+7QPhd%VG$W{`|~6Gc|7*08@n@dQkA+2qGc zusI|Q1LkCMyQ+aOtmr><-!8*;mAHTs;m?ZSl6a705=0I3!cFn1q8nP~IKfXtI9J{g zc2EwuyY5K*PbQAHukry2FY{g7;c?a#A{g?gwpPQ&yLTcxGEo* zbua?$UXNgpH}O?ckltG;Ew?DOg8hNix!+0DbcZ?r6r-g#WcaghQFx6uWZcWz3Z_+V5>^~Lk{6RTQ z@7I;IzYc@DR1;Rjl`|JlN8k%4pUxRL&y4d{MsgS+NhBRx7c$t(2>XNUx?Sy7QpBv#&c`y={#-~AKtv6&O zkbgKV;5l?A1!knf9V*StqCc^d`@HaR<8?m5sy~cLIf1d65(H8oxStL51^ zMj1BtCG35^A)lPp&C0e>&XLDLcGs{PRPSs;WsPe7WiV+>BLCI)1eY*S(Ip)0r~}u2 z;R9-yNe6woTX3ZRZ+2zB4ffYR&5gp9Ve1UyI4PBhQb{wIGif#6U%j1a>1z;It`;4K zBoikg2`b{fa9!X?*4HhJa17$r&#*1N{J{reXyyvKv5Vyv4T8$0#1Vb8j<=~^lVH?mFZ?+%j_vO23HCyJOdYk5OKFC~ zn2!-im0NIh6nVMYMWT019XmG28s?i)FDf;Y52ABY*iKrH3Pomp;|*Ib7f%^&Z}~&= zKFaR8hc7gTvar5tuxR%yco}elUmLH8X5YSH&D9KU85#!K?v$6*5ye#RN<-vFL$r!s z&Fy`yAz%XW+|q}M6rL)B4*hN;#q!w6FfkBL&B8?+$iGNZ6Hm$2w$IMe#)=U<`Rac_(0<|u5!16K{FFcPyMg9FMgzgLdR~5S6s}Rn-n4G zw-Ub1DdaQy`M|*ERL_rF^WY|HQ0_xL-ZfzF48F6wGko!U_Awqn=cJU*iMy-3=$X?^ z{1v!f=gLo*3I_%tVV@r5`zDRXuzy3)zD}Dc}}74@Xpo~ zom$?ChMd&K6K^GiW)b4BQOyKmJ{uDVw1gj7`B9t~nAfYqyG_3!%fFDvo{0o$+6VPs_$*Sh^`l{k z@~J(c%WqzXi)7PniMUX| z5KgnwgI~wo#{TMMfzQ*B$Em>d8TzPL_z>qjvk__Qq(I&eFPykFhsE~&0gkU8W8sk& zt~xS`w58-(wC1Bg^VkAGqh~rRT-GD%3buv&kHYZCy8c|Bw4%ppH@E2BX!c+QWn@RM z#y1L2`Hr)O_~g?Qv>CKcu;Y>q(E}rlvalxc#rThdyd2kH=^nKkqQlh|$5LoA07~ZUyUJi(pP1?gLJm@=-@BL?f*($OIFrbzhN4_3En;IWl4 zJY+^PNIv!a+qWNL{jsbuFe(GLLN^Q41kwH{nH#YM$1X3>jy<&~KfAK;uN@Up|$0 znFE&|<_8_bvCO=AY!J-mAe@ntvaRD-*Sk?PZhG($IGq=^#d_;kf6w z@WR2B{J3rk82t7^ZKYA{+KWgKBOG<+F5BXU34Sn&=FkImyV!I`8%TW{iq2tc`AvOw z82*5KYyU`5(b?-&cni0aE{b>94on+n*=O@#;H^Tr!QvWl;LjvlHP~= z>AYZoJsj9fKL4%5L}|I2z$cIwy>}k7h?ayQt)yYE-o}5g(#7+0@1pv+jclm`$ zMjgGC+~mD7j_>)3N#d%!xpoQsEFf=u*Bxxm5p5`sw?bLIg4@K|!`bWPzuG<9&2lqk zQJx10E(ScVA(8BJoof zO;dv55(>0SJ!HAfzLLcIBB;PUzMVbL+6PLznmyxdZRQ!hjti}-ATMAX#!}| z+5S`8*M72x_aDj2f@=Hb+uvEj0_4d>g62_h&5YDw#DkhM6+kAFyk zeJ?z5?Duw&#S0xg;<65$BzkgcC@4xtpcLdX zpBb9)T$;S8{WAILJmNK7O2s2W;=ayeAgL{l4y{T2onb0GA)W8hvQ&}XlKwbJM_HKA zWDALlM}sl>ZTgIl<;GzX!IbovN7bLWp6MD2j&o^88TE`6m}$Y9k>sIK8^HHONG`I7+)nwbRj}nHML53f=o%(_@*YI%UMavB%xc$-HB?7HpOvOwaMS zn_I3J`Qs&HtBE2w_95@w*|o^#S%`iN)Wh7}Z&B=pJ$$wL4UWhD)$<3G!Bi$9t;*Yv zf+G24g222rtRhT`2T2cwM(UShp7iJaC=>Vf=WskA7{h)!OG2oB8fIxf;Jb$RMbpI% zSpF$nu&huCFFhiCqU1F`$03@0(nyCm+JT9!A^)^^9jwVa#77B-!p0@xDDGM>y17FO zKG8W}5|GS3ooQvW4u_)nojhKCR~PqK-o>}E6>Ru(A!L#7cZp~z=jEEXu1_zP&tG36 z*|-#z(R=jvQaM}fG90$-@PBu{o)2pyw}JIwDpABsZnv zxC{OHtqd)U*i?fLy?(HyK6ByfW81%;D%O`ZFxR)6u$UKuWQ>8?Vo~VB)8O`h6QDMV zvaQ!I;6}TK!p_&UyK$9fH)}pKk0>EV_buU{--*K(nN(CBd|eb$<_9MRs^id?wCh|* z`;loaXz-$|WJ5o5T)$RDc=22?=nP&8LB#bEhArW`0TaQG`v07abU|&;Iu>#5^51OG z63~K7`oHZr40+6XF<5dt8Es-`vCPG{K)PZb`MTfWGwQVPLF8)`?{`vgPHiddd`dlY zwFBR~eIiKHu2cDTx8V9K($!ubi1|}b@Ee|5Af8A$q0`DllPOR3!|r4}1$0NKi8+X(e(FFv68||Mj}7yaf~`F%Sed(-KWiZ!q?ppmgeZM_B+_Iw|Y<;I1vAHPT+dK9N-@9_+(w?xXJ#|frOt_ zPkP&#qofo>rl#Onn8R1z)4{>2bvWDI09MP?z@CMacYnHwpLNm1unWI1)FX;%JW~SK zAUPZsa)=Mu=?~>4Kzp7!D6Z~{d1levVMzdJUJS>cNs~n5B%NS2{U(2E`0G15U~V3U-7%T`MG)O_ z6-l&5ED^{J0f@GjLJNl^?whZM#nYalMU^Vg>u-h=pDGGR5U0}Upa=X;M^rquj9;t{ zfHay}#+p2Ft(fctd%bBFllY9)&D4bo@o?O7CV=aCOM?EzBs_l0n3e5OL*vgkNMGN~ zRUCD2cSAGEzZ}cdR;og8YA0kjAL7bSmVuDw(`@H2qEeSYShXVp7kj!espk@qphNz> z3pet*5M8*UL^H3IjwsEMv=8GG(X6M4>3V1qfA|(Y+;EoPnxumfO0Uu1e?J@aWB~LX zq=J4?Dg3QzENqz`fd}iOMIBCoz^I<*ZHQ&s?_}ZRQ9I0@naJlVQ*Mqr>FlN)cT2n~ z4j~b%kgb-3lae~uvz=X?H@C-v zcMbU%$lYMuQy92-PeRMK6du>#3H)UuaPO8af-S{cSbyn!&{i+tcyzfWJ({Ky?c0@%u zz<4&iEn5aZ#fYbIdPIp>yvStq?C3XXg-X}cV0Ct@w^5%d~M zfU~g`>fSrfRcdr0_yqat?1x=v>jpA$HC~*ki*0x5E;~zJpxy@hqD&Bmk+_jppUHtHu;<9~~7*oN7v zpc(rF`m`SAwo8>zfAR<1-J8O-DZ}@Wf*wZAOydT39ARs2IBwH(5XGA5L6O71x@|{& z;6_!dAyYPRw^Utx7Ey@d7l{abM{dZu8^?@ zrm9Do3zp=a70;7ooc?K*fYX8>l z;z>8aUv~!%xJEeSOD$Y*z8kgJ5~eyt30j?GF-i3xpOqB=SL-QnPTq!x(s>rrdCpQt z<~FXA36Pm}vYKH4Gi|41>R2;<2sdKVRC7OPwyWA2PZSdQ2T3 zo2BsVy8-Zvu+u$rn?$;Oo!}sy!`C${S&q_AHokNuR`1K=r#8W9_y|`VNZ==x3~}5gB)=?03RT`JRO6CvOsv=lD!e36x ze8Mkt?A)s;YziF=)nB|o<0qhj(=s0H69np1x1D{SxCVV60p=-$Cp>z_61og1e~|Wc z`hk4R2q~y#D{;(GLuR#18_&+WjWzGyaCt2)oc#MaTHf(sUlr9MNxBoFE+68rNEh>U zJ^2{4e-UY134-SBG|xu5Fh37T@Lz6$C0^^fR-*w7r!)Cwf{y4&vjpg!TaG<$g=|il z2EO~R0*4Mi%^gN6;Vh@SX!3j;ld-h~)8)!I=0h@%dmInSwA-3CG)820F$i)AR~b_l z%eoKC!<`&kRFzuAOA-y?0?h(NE04S7Qx=c<)I>T<-|5pF%&(kUMdW0QmFbl`96UW}L zqNW*mWyv{SL-$w1qAL73Jyq~yO9kE>wOx2JZ8Bb1s){EAKB42#tK4^mHf0&92yJB^ zv5|rDaGtU>3e6AkR8xAUiz(kKrCwAx)ex4`yK&or%gi(tt19jw>1 z4Soq_OM{4Sb}*9kO+)+e?KH>ErF4^)mE3hE`ifEIcH*5`5z=KK) zxRQAvj6cwUVa8&jJ-$}>YLSZYV^=WDm>&=8=}u4YUcw)*3W7e9B5>Tpbb)K1&FshA zf7p1qi6LCgCOwXf5$BsF;Gr&g$88N{%a`AThYK=Mxw@3Mb!y}Cx|isG?YJPXT@j@e zrGm1@Q15WQ zpv-bJD-ZqGV`q=mKyUpD@+ws0X5?)!kkRhj-i$|&Kb=<&37k>z=(7J0aOV~3Un&2N`bp4 z(4AhQBpmYG9s-*6K(pNpeX?V?({opt{e*hp)pOkJ8u~zuHsL=rJD5|uG&Ecw547b$ z+@E}{ukNeDwRGp)?o$I_9`3>)W`+FJR2|%!O}x{>NS1d+8KS31V~p~C-kCoQVyh@u zdZZ2SVWh#KGh8wgnW(mlbuV(kW6`_$Xf3gdKb}W_e;E0Z^r)xU0tZ8AYFEeXZ7F=3<8)9VKHmG9CXxFTH~2+3#z3#=4&oPkq?JEtdAQnF!(qqk&b@1H6Tc~L8hPS>l zzys@A2+Q(i_fM(9rjzfX&*=SJ+=sH64w0`~z6%@BAq5gE2VmN|Z0_hzdKOFKvCP*I zZTuz)r}SemZ17CuB%)E|M;!p5blZkKn@-A^lx3fF527+;lGI|-L@Joj%gY36B zC5TJ&e$F$%d=u5o&#~;`R7EIWI~X?{S;>X zvmEOX&s&NPyBnZR{%edqVGF6d%i(a}gZM4_1fScag&x}!g|}R@+5XH}!OrJte{t{6 zbKOAEiEuE18CU3`%wIb5YwwO>SG_vehsddDMf@)5CLNsE|2F z6Nqy^tK-**&-m8k8aEiP2o~hqa$VvO?|a4#&g~%WKxMt??IUAorZdyLC7JmS?_kw4 zrs6x;&g0z-QD2-m+jckDv?u}C7b~O9^$;!@s*6r3zwpG}btNa?jfA}c6YxM=GG8-T z09l01hQ8V&I5A*1lUmvK*SG4$aA}wj6^q|34fxOy4g95Fj`MpH02)uXI8Gyshk- z`Q^Xn~>Fd`Zs#!h77hi*YxXeKJCl<^k_G_kwvDUP3bM3B`_ z8K;kz5?;S^i$5@%0aIxYGCZb7a6-L@85{M*Yj^hZJL$#{oJBS8VwvcOizKWOEyZh3 zSF;C{yM09b8gA5y=Ksx7#rvW6u~n^>?L15xc9FEux3#=DIcWx5Z=halVGi5$pFQA% znP`3^o%g;lh9v40RsNPc$h8|F4omDg7fo&vax!1FLdp8hvh2gB-Gx^f@#$YvoJg&zou}@lU ztT!VNhd#K)+s~;&(71cxbNm3G)S`^}m2U{cO5&lK+W0O}LAda$5(wp$U`~w|>fBG} zIc*H|iKAsP+d;Hy7;&VDXDHl}#|B)IfnO97HTh{4Z_^@;@Wv`Mp0D3ACvN{ko)ODO>7;^tlNbTeG7SafjW8~`+(_*^O)a96;RtF zg&My3ykP7sm`C_YN2U!w+6b^8FM#&WN+`@2Y zX(lgdm4>)+OK@QC8Nr#{(J;(I>hF#+{)j5t%)X0X7Af%mUMb^f-iG&z)WME+@pcQ{ z@PqLZ;wJ>d8qYs@yH8wI-XT1oKBUX8fr-C1g{w51FHQ{P!IZ%iow5WAZ)vk>!Bud+ zZzi7omdk6_>7aW?1KRu;!yd&E|KwK(EcMLi%5xRazNHthsi$&7h1u|=i8PX3E^JdC zWeLqR!z+*15+{?+kAFCx%Fz)SUYCM5f+#%y`2gEJSQ96zTql3j6a1~73Njta<36{Q zO)<3weVc#1blC(2bh^=t5C4KpczSrvxj1TVwH-cy2zw9~`0c*?IN2 zTUWFcoIe?fn{SIjzKIc5cGY5hv8AZ0#(?rzUSVbYV0ac<0Xwn}V5Qs%{_Ps!U2`a7 z%Q~Bd=A;U&wAZpAFKM294q!UrHh*fh_mX}fMZ6u0-(%P_+m9^LZwk&cIK`KK)5VQp zxA5tr6v1+HRn(|`OFmR3ykmkE8uybImeH2G}!tt|D;HZIE>`a=F$07VDWku0DaHG%uv4fCV~XvmbK5N zneXT>W~S$egVRrQQJOR)>|TuJ!_JGghzG$Bdv*LUn6le;Ql9pr7Tm7$vqVPXE7Yeq zp=E9>mo5s1_$1Q0T4o5OQg$%8nU^7KoNVbi$$oJAFyY&yjkpXwyI%4P)XDc{mX)_5 z;PPtnb;H#?Saxf6!Ci}(*))1R~RA5^hGQ(72k zP+r{G91J^(seZ=fuwXMgSbKajZrGO057_sE1H>2lQ@2Oe>|&=a|8WS{Q(vTexRg9v zmAIij;dUSy@^vmcaHsE?7E6HG#Oet!nb<5EX8j&pbce)M%J?VpC8WJ4nyM1K4FL3%d5?+^3X8y9If ztGgI?nXKlIAL*mThbojhwvM%hxx%G=3V(H%+Ev-&;6HF__BGGp`j6v~OKAk1y;RvTVI(RyW>l)2V~ zO!>}t_WY^?D!kav32lRGG^b2|`MJdZeI@Fy$`CeTBlrbcyk(e?;{10 z>X9h(u+^(|lPml9RuK$=knLM^vvU3!hvF zi$1)cCCt;n9bZc^`1LXF;;D*Ni|g=l*j9FCfGv17Dx>(t6n?Q&5j&t4?KeyEK|b@~ z$Zp~+g~YLShm^s`hI}vk#qs~j&B4r^^l>%E-GWU>i$pbNyoDH?S~muRQY3|2kNb=E znf1XbIn7w*YYRa)Dj@hyKF*tUoR5~%N8@Zo;r+O5Hfzu*kX0w1#!NFl_L({CaHp(x zT@O}~^@Y8u4ZuEDC%DHp9UK#XgM4C>1a7xhKt`uGRvj?ohd=9Ja)G>XW>r1Y-K+qK z_G-8`D380Z7zJAi1DVlTFRCmx2UXIH{HfaoJ3ljL(vb~6x0w%{ZiH|2YS8cVH5RlH zq34zo#@?LAXUVL97yjO;Ii&eY*$^Z2j8qZ6Ga`@V$D_dQp$|4MPTC-Gol?~NC; zh6&u~&V|52^7*+C$}48LLs}Yn2rJ64jeCBvUB$yN-RBfHbeDmUhA<4fa$3~bXFB}4 zsQx#v=k9p&y&3)(n-x1s))mA9$a!Pe)_k_5;X7QFZNk+PTY1IUc`#{D1U{OSArLdl zVa=}pYWRp*<}hUo@qYb`_^R775POTXfx6?^>?1c}yjvO`J5bEuP0_*M7oXs;_lE_0 zZmZ&T6G@?da3z-wmEH=<#ANpF$YpE5hNuWv`0v=F5=J3}JmK zX>4adbrkdAcv&Ngd*=4RaF5sczWX^#e?#|=inP#wWO;Gg4x4}01+?$a z#`9&X`Tf)8uuYEogfIDm%)mWt$xQ`3K1R0m!ftgu)Xs5QlOnGpKb|w6>+#)6aR_?h z3)#Vzm`7M{Yl8~*j*$?4_mpJIB|>2Olt^50wVsXWI|`;qgrnWJnfwKv4Ldp;ZcCMz z-jH{!!Ero3*DmJ;W7Kh(tq8jlOj$`e<$|fzL-YE4KBIOeD3E4NG4_S%d7UoK87?o( zxuggS7N~-1nI;Z1P3G6DMuW;~^54jF5RGxLgo{x$Grr4XhO6XY+S@Q}rh2u~K^NaY zEXPrXne0%oE0}(g#qifjT=D)2P;m9at$V^muCYdVWumfB(03Rd@-~IDDg&_R8RdG< z8v_mWoAlbvbu;R32{#Dmc~jHD(x=FQ^sF%4J9-?y-fM(Ue5tvKT1 zL4G|b0eU8RqjleFf=WB$-!O61P20oo3+BUc;+INZv*8Y}$H3!7l-DdTWLcBC*&*AZ z$eOqExy^D=BTfD)Wgkn5duuW4{c2%Wwl#h#Q%7A>(sYNM;j8bg1YY5V<2Grtannpd zr9cfQ*3n%|x~Cn)YpMx(C3NT55RI;+|Df2 zfT2G`a7?j~>pW7!!oWHl%wl+qQ383qkO%t-Pp0Ya7IBCKdZk0t~F4t^Y<6s zUf}`B>Ooz9ByFplyf8u zrp$|Df&AWEdGMp2*|$W4?UXe@o7S5+dUP94l+ePU*Y|MhAz+uaDSKjL3zXmyevGJgr_Q(=^KiNxu5BnqC)?!$w)iFrEjJ2%&idhmuPecCt{3XA@6YQN z7~rf{1!3WvyX^Z1c^EQX8S8>_d7e0B)})h$*XEAMX|ff#OriUtJDJU2*2y#j2@e^w zkt6LP51hY-%f?@3IDRbLIjV_qo{PD+egfzvd*PhqS66I{j8R#nB0TXV9JW6|m~ePB z2KL7AZD}6x$%OV7R$B#=@(!}nv#o!5CQFaVgU+ikjH=e;QRJ`wa`Y9H>S<;ojY?RM zyAdseZ}1Y$1SnWZ`6&j&1g~Drhdsn!UDXoGW1o6JU+Rlm2FNhm+db^XxS=>g>Ld>= zkcVjE%wM~AS`^jW;ww7P|i>t(vU&frh#O;qV;+2{TaGNlePx9l~+c&qMc~Tmh zOJCvrIt?*xLL;h29TyZ7DB^JZg{H=3yr6Ia_$~QY+v^&|D0f~TpMK5duWnev$#sN7 zYF!nzklyDM@qFahrcwTzI&nfvNTWrWblQE<=Pup#b!9{B$V^q4@wwrWhIuQ4Z8w*449b2gbkylOQxO)N%#t7Im(+YMU1W$|)U65ZpgAn?2=Y6`QF62jZ)m4Mg92+ zRh;>;3eT6k;%`WglSukIlbu%u_X%T(-`)f7Ja+T9d?7r25snS7ZMdzoH`ELM)%F4> zF&J@m2-;L_;c9M5p!Pis$KLr^@?_m@bUlJ*ncoCu%S|Eukp zS54trrz)-)pUl%1E`kp;=kTZ>&>9jK zkNj!U-d4Vr{EJ>BKR~}gAzP=d4w_S5gU_y9UP|7^ zU%I+b@n#}Fe?AOE-y-mGiYsdgmW4QZW1L-=(9lu!=Niv27u zUISNamf+l1N4P1~`9l-yarVM(%-GHzY97$%DyDGhK{Qj>b)kQf7=Jb)3_9sp<+xi&KIM-zk-k+*3@#mX#9>$4@vH)f%m?(t@ck`# z*k=gLyPXJkZM@LvK_E|kMh(HTA0jAao@!_fke?wOt`RKDDiw8{v4kOPpdsKNZ6m3 zQjW7zzPxak^&J*fssKeAO6aA!o9oZ=hS>{f@8EJr^tHwsJmyf}uA9Q-qrbAprsHrz zY&I|WqJyHxS5dL_5-TpB2v>LO{LNNQIh_bI^u6$e&#No9mHMH>J@Wc%iG-D<5u#yG98z z62nmE;AxQr`5;B>ssHsPEE%qc`KgaE_;GuQs(liyp@J`3`gn)c6~vCXP}N;nseU{D6}-o^-p1-t9F^m_)o*Sqb3~^RnW`Rbj+-Bku0A z9QI!X?KMoNqcM3rHf^+q0^*)M8Mt3yo^yzu)%b^*A6ZY_j90~2>MPF|W~!r>SS>#I z+RNHrk{8@SJ8V50$|Xrx^<$^FFzty1Gky_9b95w{cGMHU-Wwc=@AM}_*(}Q%x+IAA zvO$Sud46EdogOHbSi%qAQOC9sS8zyQ6SnV)8VrA44WFju@i>Vj7&n#j2j4vx<>YGO zUP(z|kX+ngh4$c?B$0woTs@72k&EvhRR?kPW&19bY4ff zEt-j!=}t*vk2(RgM#y8|2`T*Gxn<(!bDy6#^@5NB#a(B6kL|}ha&NR_<6a! z4=fo>UW?gt-A-S&hKYo|#1DSQVh1WifB|u3m3(={epPf@a0zpA6yV_xs$G>;*mK|& zcTPy6{ku2X48A6aFjj_>Nk5_B-cH_rb`c~J4zJg3!>yfsU@5&Xo_0c3aJ`qoLOV31 zId?DR^C}SzkQMT&ME1W*%(P7rCTEyqq_-M6yH#U-(h0ti^ggF1d65shHq%z^57ERg zERsv%{YQm?F3qIl8efUz>HF`nAsjZv41C{vx9g zUvO2VGjFknb>AEeM;C-)l3f-Tom2zuiQ#B|{G{MO*jVz4k;G)WPdBI0PT_PFx}BEc zb^DWHQ>+)}Y*@us{hS25Ge=<5^hn-T770Odgm+zj>KZe^55(Gt?`Qp-El#zCr*p|` zt22;~d#46!#A94(s>x1E>Z9DsYd9>gi92R#Vc(B+7_r)oiOkgD$;l=d(wW1Hg&MeB zUrbn4oXW?$M1kQa;^Q50Wy#T0P~RBijhxl|&JJ5xNb~P;ZC%li7Bwg$Y&JDxKU3YV zfrs3SQ6>2>k2&bdG?G*H7ui+*Fqgd~=yv0f11o6R&{$#RQ~abTwqj-?mPc&oP^bT1_h z@?H;?C;pSYk{^qMRuypXi#nK-U5ay~mkZqbRN}oQ*+NH;vB(xBL!}Ab-Dmsri5gnC z=cKrBtlJGXR9_LqgA_2|a~E${_l4bsG{5Y_h*+RNZoOA{wlEavC@lc9gFC)P*4x?*N90LR9w3s1aS0uRzhg7$JD zUT|H^P0ss5$2{WeuG=b@H}x1hQr`M^2bvj1nL*7|H@=d)#b9;36@Lk%hc>Y>VO6mC z#s+M>P|oW~&vns*a)>4j6R5wAfHTDFm`Hj<`(j^c4kO)}mkhJ$F99;rcIYT`oIe$+ zLHxddeY>IFY*-sc`~bqzo4@Me0;`AUSNOJMJN;eN{2oim+p_7j7!HYeiG_1o`P;5Y zP$TWkiVGQntyTH#!MRI+IpO)IY~cstC)W=d5kFZC66nnI_Z!EI3hqGt`V3rhmUH}N zgj4IEp`BHsz}>)Hk>b5u1CKo`HoJlXP5J}(9uRhxO;tBv0!2pw8=%1 z&%0G@BI7N`WFpFFe@uTx9D@ z-goH|!VNy;MeV2!rec~nxF(5fgp7xH(hlsjcN9I{Z4bJ159W^B#|}DbK+T9SOuvxE z%SI~Uw>PJ;t1^a-)Ef!ymU6gaYcgLSlLBVSq(!w27b!*bBfkM9q4(fn@IOh{9Zz)| z#f^;YaqW?j5NQ*2?{m&=p}iDsB{D-%A}f{BP-#)29V(;{_pw@%2HM-Iw3kxqJ#YQj zAAP8Mf4}pb=R0qz+CbAXE9_2-DTZ{TpkbANrc)uKZ)kXnllg?65{w(M{QUlPrG*zVKUlUpio>4e@J8YYpEu>POL>6`4H~$o9?PTUg4@cFWGOs zp`ev)j3vII{KC^P7(qKgoVtf(wdyn&L^_#YOZGF5se@o+Y9N}=Pv*J;0aQ(;-ou*H zqG8FC;EIzh_ShfC8>eaDglktQ*R%)!K^bU4_OGynYXN?xz8JwU%nA?WX=B1ciSDX) zZ4XCuOqm8@$>bxDdcxYt12by^<*3Wf;x$7AU`|+Eq@Fg@752i?Iae{i@)cjHOx~|I zjp*TxY{*Pm#A=dI*xLk3g*I^}-b=Ltn81W-?&g#ojv>nTy6cB=~PT4y3T zGmm;qZrs2LeaxWcX#%YI?uMuIXYr4pHSznDU$~Kc__tK2Lb_294sGqt7u5`g$mn1k zdfAovPVZ#agT~-Hxh%eQu|DoQTR~p?RiZMtS{!sfMci-Ic=UUc07JjIVOoVH5BRQw zzp|vo^JiaTogONXy}2hAChy?`7EOg8tN+b#|9yku3O(no0~46}iyurzx?eu&_FhRm)EWA$i5O><{4*r$o?-qdWm|OPP9WZ%o*rCU$cShJ*Vli!4`+M+!pu zDVzqqB57|tyHnJ4>JDk7ugTtY54|PLa zT_>9J;}C1mD}jB_p~#iVgVX;|J#sB6 zP)_#&WxIi>wl#o9k|*(J$Zs58B*omRKkKP?2;N_lBq?R^9h7Zlk^TsSD#Q7FeSMrb zM@F1HN)8%E>cQ40T7PGF%8TjXO4_7_GaV&0&W@mRk@l{wne6cs9ni=L{JWp~uTaIh z^n84Kb_M%&WE4E-3TWXK&vzuMqx6x7*r_4Sb9{QE4fPoQKf^!C+rr>KmVdDqrCBpz z59xeXy;>}s;@}8&^zKw&f6F|(bU==>_y3>a?6CkFZj|CW2Nlro7NFU#>v&*tE1xz{ z7duN^(R0~c)@@7KAUPjF_5KbX7fD_-!fZ!}I`E_)GvGGe(@%0S^SmqrPZaI&&gv~Z zdaW)jwEnlBPm-;}4b8D)oM4HvW3=#b=~Y~9n#=V&^lP_hUZvm;l>J%d}R(g}qkQ0NebBFeGsoKkJ~1lRG|OC#>XYt0Lhk z`OXXtgsgj)GIU58VeeIIdEQ({s8~QA_91$bxdnRgA&2tV3$od=bOYQzrUIju=kiJ^ zef(p8>#tV4u+tH$)+(d($aubv?!`}BeqyPm44<+%5@!6SdtCD>mf70~oW|H=`^hMt z@YxYATarF)cAoIIygrN^5R6TWq(F&$E9P~jc<`#e#N1I2ZFO&A{Wde`Y^#UgHT&`V z@8jInQX5|ieqvi)ENfh}PSn;A&+06?Br&^Yz(9M-AJ(+u8--5Lo9<<|-n+8HK3|!J z5U_nz29I_%M2B9LsPrOA6td7ujymUt%FdLpx#}^>T`uH{DIfUsPAPH1ry6Er zpaMH)Dqz^KU3~e?8L%agviM4GOLWP15KrH=^o#`NbGDnA@G)q6U;|&HtcguqittBm z9_vf@shPvn@yUPy-ZEN`_R}`hwNEIwsp^ATu4>}diouXzH6Fa2M&l}N;%*Aa&*e*5 zPgiz|gbn%ZXym{B{F;d#*i{Gq#a{9j5byS*2<(RUl~xja(pL*Ne>;a}4!+#E*Z^yi8}O0z4Q5VR#L;fuIQVqgg{1gM*kl-j zTjSE%=fw=%)=$UrUa@@IH%ADiT|H-Ww#ZT@p9xMXp>2{v#me29s3JOtOUg($wN)MO zY`KW@2Y+Rc?)bv%D+5q4C4f(;H^Bpk<;7cOD>8O=1_)`Vx~Q{|hjux_b^Bm^`%Z!1{Nj1>N8%(Ts6|#yhlE9L{9zS&z&0R2};akImg*zcgSScCMN9~W6d*Ig5Q5);TDZ1aG@ zv_F6A<0HI1)d}t$491l1x9qL19{3dp{>5I7(-}JEM>%HiQ-k(?dU#jqCKj2!t!JzBvMv`cszUK?fe#;Q^NjH@ecB-NC znmAsgO&wTg2vrMo(r5>fG`P4c1x=r{ZSQ~cc zp9A5wL;RzxCTcFdh-OVoxpK52X5D{@m4jcgY4eA{?(s%ApgV*c++78c^qD{P@Q@T+ zd%?xolxcHeKhrNA226@NcAb;C_e(?gL_h!k*}jQ(OFb(YeA^VuQ!@#B5naONA7%LE zKl->bqYV{SYQoB8p75fN6FNx(c*fxs>=Ugf_%YZo4>qEFX5bi3OrdEaOPjbWrwG+oWD0$t!zUwTj1nH_B0lC6wY(MUAp-8cO8ySJs@&3yo3hh)5PXa6L4{f8evW!aM6Vl zei;>^-!lPbkKD_rYq@|tVTJ||sw5$Uj3Dq<5XKoLvC0}vOwKw>*-DG~+I(ZYHn9ok zN#A0g-;L0Efvh;^ef5QY!v(msud3MdiW4kbB?k5A>6jiD%cVnHAdv9kj8oa7qGd(Q ztjE9XlsgLA*gWtYu56a$hsuff?0FG)J^sS72L!+ZHt=u8cucAxJ|8F}*6EgIM`lz0 zWHjZ{EL+Isy=emVjtlY9r9nSqMg>{9W$&o2H}A~!b~UeDXqpR z{8oW5L=(1-*GKsi*HP~RtE*B|FLHAdJs{Urum z$YrmogEK#gyckxN!@K;VsW0(Or{sekT$9NIOWNx>EN)( z=TPmpj%03-J}!5?j;1%L|F%sHquUzMU}pmYHk^HG-z8dBu$djHP~;IA zbKtp45U!kW#UG6mffen0#&g_Q(d$m;@Yoqc#k={cfhM@{UIqSgSuM&atHnoaH;B(! zj76P48dy!*46HiMi$AL1`?`>wbR~|vL>8~E+|Jzx&V@G*=-wCJAaS%8K{#Pk z!_yPk2Fi!A-A{D{!X!Rth9;gIS3tdHIZTDmfn`UiBblhY`o0<5EGb=t1#ZCqcSGSdtz zd+q1ZGNw?_5%_oZZWk=2-Y7NPCkB`o=?8}GYE2$eTTJJH{SZ$D`YrR|jM{Cy$|#9AmZ zTZu!+OZBBz7rzLup_Ti7kwc;eo|*Rn`O^|UZC6h?_E{S@hwS0u?14-$W4_3C2|9UEfyS9XXnyRusYksi9 z%ERd$Ji~Q54DohD8NO{bXWJiX!dRVZn5w&nm!DB5zjz~N?+)N@eN^$@!hP-+{1cnxVqCcI-i^vvL1)W6wlMqa1Br#Uu+X@E}w`8{)L@%#H1{NQR`R2lUI zZ*_aHFCsPYoBtZVHE!jnvs6)cpRD-n@=AVS;{upVySKD>By%;CheIE%kgeOuKU^^b zKOi3P^~dsY_S)E)R6~B-^< z>H>HeK{)QEzx&9+@AHr0l_f&!4w$>i3{HL>hwC9bnu z!khh#F=bvGipA~B?TriMCK#Y)Nf71BDWPwglz6PcOUddP3*q7Ve=}JjSqOQnmtxT8 z^?V^Whwi1Mn;m{eK3Es|V$CaU4ke0L%P7ig) z*p^@}cGbYly>jBnsgXke{R=_5k#YlmK4D{W06xy7T!q84_`A2}F!>bC)g*0JE~kTa zGDWyM(w(3p1am4%7QI!2Z6eTy=#SF8=ij7e1!0pElB>epVEp72Rh! zQ#8QuqCReTp1{kG0qi0!)h1d`vaQV=;ttXN|0SEnYmonda@05d&f<9701bE@VI4cz zF{=@9D@6&{-HhYAdTHSY=?}Ov_=lv_OBZFFmBmIsG-1zdGpOUXDB2y#ug^!A?nphD zHF-is4+}6E`)^iDZ4uz?(6iX!B#;<-8KNNfI=WBk1(Qc=;N!?fwD)e|X`3`~j{jTS zl^w>MZ5F^+SIRoxWJS0r!oqWuqqx?MshJ|OoQLvEt@RI^zuyGyw(jFfQ_Ml( z%Dz`BP)PVt{FJL;JL3pi?L5itL+Q@x zuPdIM+LvjRpJLCx7ysoP|B%0F9C3n+LQHtNi3N=N5`-5lCb6#hbxG1{&3eWM=lmS&~FDDjxZe=C=6`^at20Hdi<4OAfCX5V1&Z{I5 zdejlqLA=S7B$hZ(3ypW=3@@I6@RDX}LTk3@nn^j6yQYMTo-0&*B>rWCSpgP~mgNU%Mow_4 zLDw~3nDHuqP&jFikF%HX&HHt+!n+ggr~VYpS-t=^6PBLyY9ZHHj^I9t-s_2~%yZ{2 z=0DFFS9_o4Pl#_SUUwe%1e>s412jQ5q7o*x?Bec58u(@e&F8=Xey(aI_>CKnOLk6S z98Cc>((dw#Gzsq(K!+jS(~X=Y;oS%u2+yq0$YOP&=G0qCTA+v|K723*gv>jGhs{^8 zU7F)SpY(wfBjfq!Qg!M}YQPg0en?)=Q^&;U4*b|p4{CneL!W+T_?mRi!NP@<7et)h zQy<~7Y6LCXTiR0IF_oF-aQ`OF|CmW!Z<#(e*_2?%PGyjg|6=;$Tlg;dHE&*MjN_)X z;mUjS*tE0C@I0awmOf13K0j13AwpI>etadbnY<95BoJ3JWF&iPFAu(MR`{HF`B$mt zz^sF?@&3nh3({REv{hoQ=}|tWoAx);TUeHm&VqdHVaP63eEvI@JLL4lYoC8pUf**5 z)t&r1(d5NTk7auG>M)`YalwD0xDs`!*{ux12Y&6sQ7^P1`B6R`x60(Tk+geX;~1v3 zn2T4NVpvrhj(OY84xJeR=amf59fJ7Y_evOZsT*CfRkHT(Vz^9LXrA){CbwA(rlA3U zbt5W9R&apy*qvj~h_nN}Akb45^+~TXeYh5;U$4M51%D)()Sq}x>K0l|>_NDNH<$-G z;nI77T<}N}gS6{Pp1gX7708jEA%CwnyV1)K zw+y|8NtMpb>4Q3ir`-bSk=uAkfhrz&(2833gLvmGBOLooRs3Z1bG9N!1Cp=m;v2Vk zZtOA&eCTsna#~MP5n=@kXh%}DKg8N{wb3&pAO8%^q%M0^wCXO!Pbb&0wOR~(jQ(L4 zPD!+v4QNNvx(||PPShiBs3dl!{K5;pE#aC{U-WZc$!C5Y1zldmNB_wa&U#}7QS|*j zdL#wsTeb1jvwU1VRZDWa2fQv`q6Nct;xS()(6Ce$;5VTpEls^4yrgfnO|V+fZzLzk`o7HpljwN;I^M5!IZi z#jt%z;`+rSaZ8mpc3IuUwGpRD!?T+DbjG7pi!qz!s0u4OrO+pDD<91kgI*hb&UYFl zPCZA10%=iZN)niDy9~J7jlk|B@m#KZKKPKX`~Unv1r>AT)X6A%zqUMT%xXA%eHoCd2FABJA!P#MO%y!(+nGRzsR-V-{x{Ubg?;nQQL%hRdXV^+^=)i<@qNLhp^3 z7s7c3<>#!Q_zaKCx++qh`G>NPUf~{xcK*C}F{Bd)()XJ@ySGmY4rUu+ztTN?$BW(& z+JiIz7YZZ=1p&}qrizw%q5RH3dWLu0#F4_*^4Jr`ING=ckNG*loky2pi(xkQ3OdGZ z9`?bX-umLLo%U?s&oeA4vKUgo$ycZmhjr@*?a6CRco#hzXX)Aae?C9ma0`~nM5DY? z5r0BDK6B&CXnkOx=;NZxc-l5q?CTSYg;h~df|XE3390cFux;?aS3u{p1Sbq7X) zkaTEmAN4MrZa2aM-fCh|i!+pb9S2!y(^1PTj!&o_1p%g{i~gA{vbbHr#_v-4+ecgz zEx(;P?3m0<_M1U5<=~Ao zjN{IGmOwTAzdXT7;=gGu{3N~N2BR#d`>7A)UkgOr*d)F#Wg`6UtALt^;(5h24ZPj= z7ET=1DcLtB8r-O3Vsm5y>lZN)q&Jx1?j50gpSCY-rrlJs6!sIk-=ML0mlJ9a_J z8V-<7J9E<{E;5RSert5mc-10SFRPEv4=-UiJmr<%+IaIS-A|`XWX;~BBT{<_3(s%i zg^QH&xy&z|l~%%i7Wx7#r5?JaBUz5OB3x~?Kz)Y|eCS4Nh^9Gw-sn^L@ic9ekdN z{f9;heTc`YEeodn^QWv-;0ke+MX)c{lix45fv<;Y7UgL(;X-qqvgI~%ut)Zv-K z4UoA)-A0x%Fu2YgKWX2V6fW1r4Jis@rI5Rn53dEkj{lp(>yL~DG4Wrm)q0Z1N*hq6 z+5Z0=exIw39m_AEOMl9dsA6!TrxGR}iQ^S6F;M)(9i7~#NmgIh!-{f65;3U5`V7i< z{ceM=9!KzwMXr!XxbXqqQ^KwwTaY46>9RkRqi7HfWv05Ah^}$3PYRo0p%xA?p2dyXd#)TJ}<3ifhIDLci=FoS@lsYCFFj9Svr*qjwh92s=;LVxjX|@!f2avwqV+^}?H&>vxi}Qe)td z(KtLc-)+M>ZVS2Xn?j^86_Hxj7Gj+O6i077P zqd}AIdp!l3tm^SX$fItpB`M*&cnQ`0IVp>K^*m61o;sukXOO0J!AT~SLtNqS;V5^G zI<|cLpgo1S`{*>0*^??Zk2D_tV;6f?+CU)fjW)Fc?ot^Ij}mmz+}oMCwO@zpl)>J- zxRhJjYv7=5H*oL9Qqd|UY5bh<5+{|k@q2Uppe8XG9Ss$j&nGE}o@Ib?yLa(dBWz$E z;UQL63M6Bl{o&0jWjxq7n1{IrF;F$ z+-ixHg)IynMEN$^No?%&X!wP?c*BWHiad4D`%xACc*ohRl4yu0z3Z!kdKZe87@@JW zig^83N9aTO;n^!@;M1x&9_i@{j5x1(gAR!%f39J>Pb>Y+;!d-OfjecosD68%WZOm! z6znP^KBI&6^Suh2yS8DKX%%0vm}co9>ehKUL9{5<7v2zNSmo`_Z>@BN^}dv)yiJw0 zE|UUi9)i=oa(IO68Yqm=#j@0R(Xh!{pqx<-62F~1dVm)0eNTCPaeh2rIu;6Z$;Xs9 znVIHV!e`<&|KFKwhWUe^RxlomagsFaj)T{?>3JKI#mbWU!bW*I`-+md-`p7Zcuxms z=-m?a>Y4B$!g>vbO{vbp9 zL+#Qf!YUU!r>>B$+xR`R%;^ifI}mezP2$%RV!->64&J)&&AeCZ<9DBnNd%^>V=|Eau#bjr2Oq2eOS$X^nmg@?k+G3<3V-%1{LqY*dJWsS_cCZ>nY2n1OGHj$=GQ|g^<#4KpJhv@ed?FT}kS^W6;g;kMokx~i zq{Y{a>Y3b9Z5XGbgLh=(__G<~An-KZ<(2g%g+uMZ{w(?QCmdpfyw-p#@%_UJ6!<{8 zn@*&=ywcru?6r{?V(pZ0@Y^^pco_@3*16*m+i8-vgGM-Kx{|nnbV+aCTEWwc)~Gvu z1@BE7hO=2Tua=(@`nTFcG4Z?$45VRqOANd%*1-qLk>x#81URRjV~w2-EYZ`)yrg@$ zC+!t~@jVurcl?{-kFV?#Ij1H6%_=$Y(H|af4#ExAefXR~|ZcXY6~M~yI8;TjfeCyK)z0Y!@1cz?<*JliXWJ5!&_sTbsVp&72XNezO1 zyJ1hzX5Iz?Apax?v+Nor)7r;D81WR#pC_k>wcd00MrgE=n!){0kVIfJ!kEUbCthDSb5=7;<=aNry%v2T|q zEBbJbDgP*jDcck(J|7aKy$3tfF{r9L>XkZ1- zJd!4|oOT6m_G}SHMz6+!yJF$;Xm>oLYr^Al)$n$9H|}cNz?Q#Pg!jvpFwcA|-&iyb zfN<&b=hc#vDfZxKPZ>UElh{bw8KS4_;HW7Q$)fAJc<+1_YN%GQF`HwdMD%Z-AFCkz zf0&B6Hoyr+4imwI8Gvtw`|(rFQoiA1*ZLMNOPt4KmT}9@M+TN8JEFm;($&jYhXpqbsVAX!@YXO!PMjb z_U+wMEFgWX21cf>;gZwpKORWYyJ4$&jEk^ zZm)JP5mvj5hc3E%{y)!MPT0ZNPygomp!YH0Kzy@CwKof(j?IBP2p7oGDrot9sYr~8pYh%IuKr6qW!01B#TVwa3YgQckQ&Ea_x!)yS(po6q zb{+5RlL7JeIJl?ghSkFp_&MSSeQKq}t%E~_%gaKb=oabOE<9x>A11=qCh{qidh&|e z{_yi9@$3o$wuIU!cM)#2No2>U`||Fgo@l>2j-T8bPySqY6s(>mQP^&Zi*=O6`HQt+t%5al zF6x6-Ys2}Tv`N5skj7@yDWQeS04SmP^Z#u3>>UTTc{+dh^OjI6v=44TgX6tnBx*Ob)Z!|lg-;<Y8AyiWFnLz7%kA%pTF+T&n5X=PsT(q!%9{9r9Yt%63{p}dcc0cw?2@3 z6E2g}ALJ#3^+il#V{XPm;}RYGxo;-#|4s)t?Bn=)QJN@j>J@b8v01!9W)*IfiH9JG z8|pnU=BCD)*uMEUfwjrZZ)#8Ycuf%-k~eeP-jgU3iTp%At0fa;2f$j&qZZsuV!u|z zK_cY~9AC>N-u7z5Hx{8%SRs4h91m{=?szaq@4~)&W;kDU>? zKF?Ao$?MlsU<2(uioRK_@!SA#vkAlxi;{S)gD#3hr*Q4Va5mR|8ua`whv_o${M{Z6 z?2xI&=rivnUw7%?y6^3ne?|vpt2n_M?Oym&e;L2=C={*{hUVL}L^w-rD*UGXQ)&Er zHf!ZT@F3mhz@d}*Z7)-Nlzkrke3jv`j3r`8J@!?6#Z##lqwDGotaNl|)$LlKn%fLc z(J6dTrWy*$I&tQYb3CCV6n4?hv-HVGb~`{B>V&5FIBhKtzB>@k4*563e|)`;o~6O! z{$_^QM0<+q7zx&B9_9{f%&_76Q?%P~jIHo+1o2Q+{5CC)KWU}A+V(G)r5H$aJ`4f~ zOZ+@4j-~h3hs0!iyhXdB+n_<<9!?mb&P(CVhXQCEnhR&U(zzOSKv^`DpqJe|zKS{) zQ`>H1s7w=!_81Ebr48{xUC7@IK*OV7G3@FSNrO%}lpLgd^1BC^aNA@kEDOMM7nA9{ z9t8fhH(qT%BicUG8#3PzpCz5Z4gIw-E3y<1XMdN7k_2dSqaMAt%7TVp0w~A1Vb;k6 z{$_P|Y@)0e-{d(MF3~gp-C4jw3@CHyNFF|N zs^haewMbJ@g3llHWzB|KAPBn#nI$QF;>83o)o{m3+1rxM+YGVwnwEaI3cFHWB3YrZ;cyO-1WPxBXbQY11e(fPP<0a)S2j*eRoc+9ZmkI_p<>RHAI5xMgCD6EvbYaF=`{@;Tj;#@cV}rUq(OMk4prx;@b^u9 zutmBOcbte3=}|7_{6TTz#<&qU|BEJukGO_<+m7-F)QwV++D^N70sHw<4TAhT!GF$1 z9<(A1Mia&|DyLEM<@Z!bA$}y!I+1w|ATNBd6LBIj{FIwMF70;)Gc!)IH$Jp)QwDvC zZX{p#&Hy!M-N7)Y<>jMB=wppb2c9IZ?8TD#u-F@MhfNp{*9wQF8T8J+P7~c0)v=Ke z+d%ibLdCv@LGY9GoR(HP{Jab0YnnG+#s@644r0 zIV|UGc=%W=53mh~uLYEmzEy!8q%Kig+7FZO?%;!>2f;Veiu^y@uiD=NUw&JNtuSG>e!l1k=2%+a9&WxwQal#4j%cwEM>TaeHXoETT5AsxXT?|>5 zi<3s^u*ttQAu;?s<+g9*azn|Fv+f%9oW6+boYq5=9WQaJ-~(Ir&IZnL~Efg{Pb{!&@NNlK7cax5>`MdVauZ|e1#67l&wL}bLZ^$ z>}kgk;y?p2ZT@6_Vze2)&@IO7ugaj`M-R7@mE+xhcX;M89o&AJdQTR+v7a4UkR$yZ zLjP>!j#29PtLrPCe^kT;St|e%2uHOa#YD17kSZ|5u0iqqQrb`m+E1FI!Jo^YHD1RR z69dJ@)F)qCr;TICmuJ{3llvH0V4sSoSg_+5n_B4v9S2pg@I@^5jZwi%g�wgCDos zxdINlkuJp}jyc*HgY{4cG;E9H%hHE}YXJ3R4Sgw87VE%Gg&de{mCn}$YGJ3xdD?qs z^Pa@%7eBa#Gln&?{ITwEEW{8uNtSWX63RW3|AB|JUr1ESBEY1W_9B&otake}kQW7@ z&hBJ>ejD`-U!+~jE?+cj2jSjdWiV<4^@82f!f%b|(JbPtWNe8Jb~)8!nx`z3bS;4o zvj$+%_r<(%Ea4S-J;Z4mkwTlEkx(oXf>o2AF%)JJ^R;jr}yMT?>dhiQ*GJ1@0u`5^(thEHu37y>S*Bm5NpRR=DW!svCV<{BP{CK z70Rf0SV(!Yaq;|o=?o|!-N^s*{OCqU$fuor`H@4+vRM~-Yc6gh{n&^rs%XAGA1g}Y zSjCUgknf?0n-<0L`FGS&J^LY^x!5Xs->i?x*)rmxmwUpmC_89*X@z1I&P{iEKmcjm zBhe3zho2FGq9&# z?u%G=C0_I=gmhkAvEr*M{>}4W@>lWR*TdW-N*~=CUZTC)S?1EA3BuVwAbQs(KE7uJ z*pYwpcXOkJ@AH6Kn!Tyh64|mCby)P=1@-LdS3)WtUKIpOa{tZqRc~}K zW=%bv69MHHX$bmmi{1c7 z;Iyl={yN;Uq8FB_o=2x!FWAb!8}R30JYMc!#6J+<5$2w^&?xs7)vj|xHkTNzeDlqqMc@XLSo9$7Gj$k98JBU}I#A9nKbR#bXNv4(rhKs{)<52l;R!9=s8N7dJWJ7~AXPLb_9`Y)(r5G~bmxb!^2!5V+!rx_dAo^oYaF<1d#S)_1FcMq^7-Y_|=Msh*f32yiV z<7EAH?2R4a=-RpHH+~MCWg6HPe-;%k7O=(2dN}0}<=?K!yTI#uW6BK`u`M44W5#a#Tux%K{$P z!6=>0c<*jG|I(mKeHv|OwXQ=XJih`iUm#7F<06hHJwV|UVg5F1Y;IIHajsUluqJ~K z*R;a}8ofJ%^;apYy^-`Z(8E5(Z8*qK2QvTA4m`&glP3o9g6$DtNOS(sKwsghbPs5t zbE;y~d-hR{x_gXi?@gY}qnb?dp42(i3sQof_IlXqT8=)FCZ0*}tW7HAG>#n4>OBN- zG5!U7`nHK*^Ho9D_wTXCvV5L*J_4Q>24m%dQLNV`C0H@u5U2aa^LbMoL6`RG%UYky z%~h@=e)ShiI`wdAm=-RWcOIJ-9N_hP4Kd?=BW_xIkV(IyE}o?-e|6e|hst>C_d8tu zZVB&^9|56xv{$FbvE&mbaC3Zr)LOHOZ;5b(B${bUm%kLA*r)>s%T7?>>ONlMp@mV4 zi?C{yCtpFiPlNh3;MB$@_MzJyBJC*aTsef_7^04sc74PRn;%M^NCYVVL{*HALRj+M z1H=viSau?rKX~U13AvP~?UXOtmc9hEp2=VzuLQn*vH(Nxp2rQhzDlCAb+K^7bsS9H zHR@4*@XNnH-j-j?Cl9c~{vOKWn#b|N{3V{CewR91X|^AAbAj!2rfWwCn1-W1POizt zAJ?z(m~lE7saAr`oBOim^EJUo^AgPVO6EJYHPQOR12oZI%wHR;;DdQ@@aW|-cDBM8 zwBmKp<#8Oh-s%ZcWl0}WqA!_b?E-mUNGsKTh+Xs1!#8(xFwHlEk3Xb_>h)(Zbs=To z#JIwkG)1)3jpMO_8YuPUKE4~%B56}I!o#&P;szZhcz@3tzUffMK!-nnZ{Y<}M~D}Y zIxVcpcY%}i=Y|kzXvopUJ3Vr6#V1wCkQwAVeoSZIRdv_}#;DiQh+}TIaqR_qxG%H? z$GZiv#|o?9e&WCVd@l0>gBqH>neHr9x(CcJw?Q4bjeL+(KRl3LgWkL2MJBVa;Q-BO zaTj$MWcq00b%RT2R+G)Oe;VL`1uy^Vw^OyWAT#hA9MIj!?GLPip|pP%8#hUE$e*HL zN4Y&45}EI2b$A);gt>QPI6JFHS?sxZOni*(Dhq%xc)gS)YdCQ2me=W zZ)-jHxy0ct+d|R|6E{V@DkqDJMV5+}a9U8Bc-{Hq7^Tq@(WM;~_qB2JZ<;7_q)c7k z15D$(B5XUMgY%PjaLdKcFp%_zvz8P}!td3=!UR8zmbt>ct^1(;m+ODE+!4;Yn2}e9 zYIRmHE|@r(gy*<9>NP(@yNu^38F9Ttz)nFW`!@OC4DX=l#Fl3G!I7r?_7WF(G@8!n znUk5U+jX##S&E6R$9Z>&CBFYyi^(kqM7fn$FuHn!c&vXI&Kj3G}EqrF1AL}FNvNL!Z(%-UdLp@^{}HY2Zt@4!!viP z&Jcsu?Kdvn$hkF9)#?;1{D$eG&*7fx3Z_nbHk(r&E+;V9A$&Dq8)hIl~??O<;# z4~s^q+-JfPCA<)zSh3*?d6QS=qRBETKDeg=rsbF80@8AN^kLlk3sU6v`_w0ti4w#8LY8S_FtD|#ZYAfA$K4&qz znZrTxAbHQ&d}g)M4GSw?ixD>4sIkI{@QzX=lO6*(G9}bs>$4IuMw8dJ&lEBa&Xj>{2F75 z(09mnZb+KX5zDS)_8C`JQ>Y7H!=6LM?oE8gUJabJ|0CX(D&!$EY4#crU$(26L-pmMi}KZZH%)i!mP&`+^oYG7j-tEhs{A2 z``HEBE0xi_bq&w&P)DQbAMou_Kb|Nyht_@$SWP}|vkfCC=O>7IQeFx_$LT<|!Evzt zx`#JWmi75#g}A?9CNGsU$GOV)@u}(~X1aU=R17yj`@j&cl%tXuCz34ss3O7|YMZrN?u_%3oaL(m9pn8s;jqzT*i#!DteS*4w*=~t7;$__O z@LZ@qM4A7+PYb{F5ZB?rf3296SiI zChu)Bul!zzs>!Rx_lum7J`<$R1gCAv=9v%GaV&+iUY>E3b*$?Nt#k zG0$Wl9`uBbK?3{{vYmH-8Udx`5gT}@P%>nDJ-CkYLtEo3+^WkOe_PaJx1^ZuY`{AsO6cvK0=puf$BX z6GELW)bSchS-g4ad{MU=KGuGRMgt<)WDhmaZN2=5>4z_O-4M@E5rR09 zI^djR*b+I)TXkpRg~%nm$Wjx>8)f71mzP*c*#KiNu z(GwFQKVHHqr{!SWRULe7Ng9+>Enn$lh=C!uvH1He7JS7JQY&APKV~Av!WI$ZpQ z=io2bWBkAYQ=IP!yhZ;9UvE8e1}#%exorvSIAD~n!@)`i=L zEZ|`6V7#NTi68jD;Hn=n_H){7N(Sn}vZ-lMP5G?wRxPv-%Eq-vocL}j>R3>#C;!r2 z=K5(4oOqyzHF3WDjid%vJbsIbx%b7-i9Pa#x}rLbY@mMmV(?zI29ImU@}3resrkNm zEbOvS?u!pB{w|I09!GJ{+1lvxH5=o8c8e$d(8m`t#J}Aj1>-WkAwrsVZN6?ikPpRy zFV#fB8@Jn31h~RWdS6dVcHw_kAxv3HS-g53c51v47QD{F&LcH^0G++h%jV(R0Rvgl zECGDby9qizJNW508hGVg6TUK9!7EbKaQLYXEUhSHw-=a02;JY`uMFq$p{}rmyoiQf z`r`fu2r?4%dl{I_R#8r;F*_4O9vtIy2kYQa`COFKk78X}c3@CX>;lq5ZqmJNp>ZRo zo^KJKj#0x;YdbJl`YU^>KLRXgTcN+sI^JdN2It5h((G{2W)k(qIG^@Im1C0NbxyS9;j6D$NjNo?-t3!mxg|ne~IJKTZUrFgi`E@3KQ~I)!1FQMYL?t zIP7;*8{Kuvv1w5fZ}-=v4!wKWIT2!K0A!@ z%H7x4kv0W3R5Hi+v-sRKL-E^%JNRgAim)uC3WZBzMA~%EnbKbi6{7Cr)$PQJ z>8F9m^}0~vdN|X5rVg#%vUu^_4sLhO6{^i>CwTjYc&jTyhx5O=t?Z_c(~2_CcAg8@ zb~M0#bFN{pZ2=o{&J3Tg>qO~mmkZbQQ^(?fPCVFS2+yP(K%I*)(#MDEDZ9bK?ZkGT znk@YO^BFTtQ^IXK6iV*5=%LNv3@j`BDYi5+z*4zusF&Hn^89K+?q?j$_5yyP$pDk? zy};vDZ9)ay3U3F@#wU$eShbWSdQ9!c@AF!Dt%Mu+1kyduO^uEE`iDIfo8WTuL%e^Q zF-nGAz@B`X?RT^w$vqn)T6Xcw*&29vT?qy}b>>Qe#`vZ1HSRU)X3r{yg0P+DBb}um zd{@M4)OB@lX@z)5wHtKI_s17rNz4Vwit^b93vFV!?yUa!&FLDpU=)khUjiaSS(Nz{ z&No~qjYzeWm=dqWHcwQsYj^{;r^~}9>f90b8e%lvXLnFer{aT*=;kO%VGup%-t?R| zxb!f|bpY|hsf$g~o_nMl;Lp0o4moo6W*cp(A{moACd$0BJLVGm^FHU4;IW};tSs5h)!nmMD1+^01p!613 zKBt9vk19$cMe?D{xN8NyNkg$be+&1d&v&8EU+|&LrfG`+ett-X%)N(r%4aRyPIv#n zmkarSu_l!7u0xA?ciHJz_R#!GAES=@^N*)AaNFAsVn*E)kG^k&0^+>oQgxm~<|?>$ zklq(wJNcWisi4~Bi!nDZ3r7z1gNZ)U_$D%n|47rq7yg$>t9dIPQlW#Y4mU7o)ejcy z=mSMlhERuvE6@Ee5T-=f;mGOY$(54sAVGV&+bu3UI&&(d(r;>9g%0a}LtNa!Qn+cl zA-}#x9~~CwVO#D%)}f*c<0LEK@`HH3y+H$inB2wfxl8%JVL=ciIUA1$Sg~oAmauo0 z4kivE|A{Jfj{hRQuC9SN_54&=--j53Zpo~RI6N9U$hyk zG!3>V_@PslBa)U#<}7Au?uxp2Aso@_GxTYX8@E@UiAN+!jqHDQTfMR+$-2n zT)T-n7bM@HrqWbkIsoS>KN0=Hwu}HuVy}xkeXjwp8H!;kiNs`6>vUb{2gWo#oPDI=H!B zUNrXGQPv=<2qS*0VeQ=AyqtP7jVBYM?`w|O{N`IoO^w8#jn8?C2K93~=HRUZH;aww zT>0|h9kkgp7>X$mHGAA+yixp$AD%;*8e2P@`@~atcw80pQusH|W9{7GvkiTZwWfT{ zy{S;;NZx>^`E2djwZtBwjuk~49(kh*rOmgCPQLWPm4`I2{N^2OkV)ZP7J*>b-wsc{ zY!;5|(S$?WWbt(K4*qelJ4l)Mq3!1z;!x>nuyPl1S9Zs+yMqi+Lm>mL`C_hKVu+DP zo}))tW?}b@K)7_yj`E)|tS;IGmOY+DC1U_pBUL$CN|ya0sSXapVz@8#?z<4 zK;nL+TgPy{>&7_g**W}G6~NBiSpnr&WpVA32>yG!7HV~Kyc*sr&dpZGj=OcZMpYiD z;st(s7-5{e58v=Z3myB(igq296iWJgz^WeF3*72qt_!BahB4%$o@dX`{xPMu(*>-H zl7&f>E!*LI2`>aya?dA5I7OodbuDMIjn@r823z2};SO%OA{e}N>~M3pF2AK|g3m^% zi3b1aU@{@vP)2%pJLQjtRZNG~g)_m207L5TA2t)sR1>2gYLz)M5PfNAiXcg#! zWoG%w-$z{=JFXSs!e8&1=Z9Ko@JYao zN2UC-K?ry#+2I*w@#H%J9uWG(7d3yn@N0c%f(OmXsjqZc`JfR9r%JFo?G+DFq0EA% zEAzzf1CjW$!DnGl+5~)=Adyn9b-I?a)r)$U|S-Oogc#Z$|enzFRRBsmmZ7# zcrg4awZ*J&PORjhHC%aXiBpMx<=N!{flL0)-t}i@!m&K^8{C%!#SBAaMj0qAR27f; z69kEdx;Wa*hsn56_ik1>Lco2lLmr72&P`ZSv6Nk&sEl&N0~{)KnI|3cgw=}vwEwbW zt@$$WtiuFL<0AM1uaUU-M=4roh6_XgtHD({8$@4nt>?&PK6Gr*L% zi{r=Sia$N7fwjL@V8p9Z?l?IZBpET70{Rzw)Rj4fE$?Mf+$`?A!guuoB=K$NYq5C{xrtNQ-88m^f zT^kIlONc2}{nkeCwhB$|MTxexdE>iuP3ozkewlsAJU=oR?DpAWbV##s(q?T~uOy4A zJ9qHp6CMz*=!eM~<>H)xnedDD(fm{lo11EcLq=rctAk6p@0}oc`$vG%rvyxtVuB|o zzC@RvbA@}mf*kPyh6~^Rb z@Wq68IHKegKQP)84wH^|Do>65TqFhi^eA^ye}E^un_;%id6b%}$KHr_z*z8aJ{LM_ zVQO_TK1_4uiA%JJU3LdQjDE~!t{V;8Z>tdxCzPKjhT($#KXBvFGVvjewQy>jKd!uz z#16F0gj6>lOc)%)bNUQLH-jQ9)7Z|=8oI)v1ew2QX{CF#b5SYAh$Sz?_2kc4kzbE; zHS!P~GzDG+8sX?QK0IqZ`EB;fiqtKngg#npVY;$E_8Por52|ND#dzv=3AE?;68qwT zJ2@yJsRZ?u3A)-Kz_kg3_>^B7c31GJDK$w1VFb1vN#ACc|;p-0S zYM{P86SoQ{4yo>_*xdS>M34A2(St?SDf_zla^Wj(gjMK?D7rx%bD5O_o#d zjkbzNd}R_$re3f`&(~sX$`0OlpB=Q(PRgr)ws8B#b?^YBQ2Kf#A4NHlCGTrpvIOMdIia>SIG#=zoy}J-J|?*TL_$} zAT3JpSSY>B0ZQM>V=#4FpOnzRiL4gSzytBq+hOoK&lVRBc4jZ8je$ZJ3tZpk%foN4 zg>_enD{}LqjkVcqP`&0yyk<#QwciLsccx?29~JSV5uqS>PoF>5hXqCHVQftqwq9!D zsl8e_X>$YW%PnT>R-O@hSBCxdhb*MsCEqO}(ph+gkDlZMfqne3_Ld#f)s=_ZpC%}M zDT3eMH41~)mE!rxaG@5RXC$18@O;@ZzW1pXa;FBop?sEot~G>YmtKgTu!EQDs^EC{ zZ|FJ4mFH{wK;%!#_zaI`eU2Ex>#t*Q<(XhUFwg{hj%8wyLK@q0G60fj2c*^R&quZx z;v~yTlr~vY{Hf6jcSW}2mXztxxIGkXa%Q2|`cNK9nOV^%36Z*?6|*1sidlYp4PFfj zCDlJ|!E??38Q=nb^Ftq0&CSNb=%?(2bqLrk6`;{*2Y%xSb>7KS2k7k!Lf?j)xO>eW z(G2k!ym}=RhCiHzW87@{T1A@2yJSV1FCJl)-qdYptV~(dc>c5A76y<0H^b+VuCljt z1zzlPoj>slfwWNKdOYq|?D>o4Ov!B&9vlEib&PPi;u92(ranrQFc@a~Z-#$ae48yj z|8Isr@uPV{XXdSzX1uJ~4i?eAZ{m1+_MY-4+YcYdX}4c-t^)8U7?B3~DGBx%*VJaLQ_J&>T%np6hYkZ|+*SWlekk73Ja+ zzwBt=K{`fR3@aRMgzx*L<2$>>{Iypo6l&?>?$SFwft@KdZZ6%82MxUg!gP$t1XPPqfX32_S`q#3ipu)k|n1AeQt$7Xs!UKMGfLQ zbY>eps1PT&jAPeM8iUECr?BQNUH{X={gR&Qo*ck7lDfZKRrZ4JpuxC|IPOD3Ny5H zQW0GiP6m7G9h^9U{1tn4@)LjNg038O4X|wCS&I$uGh7Pu$47DZ3hEW|5n$VnS>kPU zPgi|^4RaUuut={O(9-x1$Db_XQvD*xCt!%Iow+Qm%zU22?5&Mpko-qz)rjXYn^o|Q z_%kl(vz#xA_Xm?V#7u)|_G^Ydd@~%5c{4WfWeWW;(k2@>R$X9g`h-DWBl|n9h?Rw6((A)$C3cIn zT~4FCVg$&m(mm+5El;AIRCoAKtPJ{(#oSV+zE@>@X+fNyh`F$1lP`Mg$Q6gIy$kO? zuS7}1az1u`IE0Z0%1+uxeNThhAkSlq=M#!tA~f(ZCPUj6k2p2EHz z_3V4-zu9j7!4K@_Q-_qujQh@>2VTqRzZcrGB1htL$R0;?=U2R8PdKEIerY4>vhi=x zz&PTYP1tanySmV`y~`GpJ~az>ozsB_2~sF#ar~PGb?DG+d|Oy9z8EwQN=P^R*g{&^ zA0rIdl7<_~7x76ncTcalh_V|lvR~8nvFhxA_H=(A9kzv^ zpY9JQlj#oFo-Dj}tDT+kmP4KEG9^u0jd0YPR1|#pF22-hh@T{{U{_WvlejK}BWf}* z{>W=SW3v`|tiO#FFB*mJ+ajT9&TM>Ia+QT=%VW`scevBJl^?eAhZuTaO!%(G4hm(U zOhX@+_1(v1U=YSohRA7v8Cy}S3z_;Cp?d629z%Py(`T;XhD-MMx$U|=DkC}81xwmsZH4e(@b>Qwx0d= zUIV_lvN+p6l4r+g5u557s<=NDf8VE#!#!@J(kVIO`ObvT%|o*hV<4{9bfZ?o-r&-?z^S2G8nv?#*S@^DC4@$XC?Hdqt$SU$%4 zk71EYCg2+T7?yOz@v%ygkX$nhX9ekU*S!Kv)szzTPrT2jD;dD5UR~699Ll|>*u!L+ zw>l?36<;)|!?}e^MSgS^aJ&}|Nv@RX3YOyhgEBUg$9UF?7&db0bO@xK^0EIyIl4u{ z4QpFWmn#=vC^o})jY^`pi@NY-_F%a4U;sXUww|}Gum?5L6-Qibx0xKS2knE-K&W~G zU-VdjW4+I#jj{uEE(p-%Rxw6@EoDuITwpZ$y#Jrm(b!7eE0iz(|5-g-*AmZ%tB91+ z$xrfhF`PDYLgxX&yyb`k`1Pkg^q_3vOs|blBO!&c?;`p98v@)r?>xHFzSyf<8$D+f z;v(bstgWC51{~jo=?n6CbyFln`BML`p?LCY&j9Kb^~2Gxmrxfl<#Y`F(9>GLUgZVA zbVEsO`D4I)bOd-JItwk%n6uq?3}N%1vcG}e?z``hj_3h`7B>u!0mS7?3;%p zh;`)gzk)Ds`CbDx)o~m#!Im{GKDo66emtFC$ zd^h!*pAv4^PdzFp#Q0I?Bww}57)RMW!YOMq+1=YlP_6MEP8i2=y@#r_B$fxjt_~pmraiig}ULT{8<8y$R)()OY-Th=eF=oh8#d*1<~l{X46Nytjw`-oDsu zq03K+hU4n>*KlQTJF7l^2lDeb;Ag2U{-u-jXLXJmYc2>sua5*Z>KXk141eLQiP7JF z;G_lrvBSzLP?AKhXcLZ*6d(KbOZs=?N1ssrAR@|{x z7f1Mt@#|$HU}c*4eRMTG)N119po9J^T2b&(n(cJH%Unj~{q>flUJZc6ct1R}%Z%qd zaDWpudpGa0XHSM|;qi!LnA-c2mz?c~^7l%xIp&D)rui-EH4PIjf9;L~{WNh|@h!X) zev0=akD12zmpK31RyIvd58QjC{+`d>4hFz$Ps&`sEEi`gEP%%;q~S=%vdTFdVekh@ zJQ(2HzFVT%d^3+VB4A-n#DtK)#GP(gW3*(sp^s1Oqg2-_MOyhta(}9|QMU zuv@zY(5#gO4<+MyPbl@>94tV%ZqM`Y3h13rx=q9b*4#0kI^6&5C`Tl!qWHg$IOkrm zIN<0e@SEX}vcw&-WD6i7o;rW`#_(I`&G1i4I;Lu`V`oD>!QzrEsvnEwEs3OQFU!Zv zXP=0je(2z_ako(`Lk^Oxh!xOdgfE^E%d|*~;6AB$BFONbMz10IRQY%o5L#b3*LCVjt)i}O%=$QY)WY7S|_7FbZRgBw*u zLB$B$zqd;C5%6}JCYkTccwGE9wq4o6;`T?xG@jpv z!Zlx*;KwB3J?41qk1r42z8T*1lCO2`C7afKC+Mr@k1^g-Fmr$@&Zn z5b|LEzn5WyFj%)1zYSX}n&&ed9kaBs{Z$^SUpd0f_Uq%-&^vf>S2C0BYYg7c-oZNA zSl(}o3L0$hLFdn;K^@-=b)*yS-y6-&Ei{GRX(Rr6OPaS2M8%qH>M**39Kn{@CM9~hT(^+y0zQyr7C#x03#y*~*8k6QJADLUd*4ghi|p z&8&8amIR)_D=GpM%f7;?Zms-Ir8at~{=#oM`&jV{HE0f3qO5*Aw_EB6N~9ScdYUT^ z?B@%WX5XQ`Z80}nNLs|IEL=aOw79@X3&$o@;mK2Xxnnu?ESUeB)fPkVv3|?*U|5@c z$$5*-FyJ6%Kl9A^ib+o3PM*C}H|$xb>IV2UL;|;sn9Q{_Ebsz(I9q1#7na)I!Xu|c zM4yJP!iG34EEq(+e!^3H&o}|jp79E|?%&4b)AV5LJxQEY9Lo#MH-inGx5GwNh~>}; zF2(twzDg`}vo=Ac+bP&E*O|9JF-7@dS8;#!Rc25`%x!~4w4HILFn0=dV)nG5@@zwx zJ8BVh>rcQ@ax3|3=gp8;<%e#wQ-t0-JK1tmX|&3gEV<@PzP{FEtjzx^t`itx^Zm&?<8$qhvp;i32mwkuyRHx_P%uhqZTE~_IBa439Y<$_hvBt zP3I6Fbv8Lv0VF;X<8{hDUQ}s;aY>mtv0A_eYU{!;{VZ5%Kz-u&nmA|FRZNqgOF4Hv z+?G&}x2`>8RcaI9+iq2K`5er57pq|EuO7V8S}6W0w*~w*_~St5v#j&YLfEF@i(1cP zxZ)-=6b?(r{IUK_bF&vrY^HZiQzZZ8u7#U-=3$SxSv>He4t`ovi^=`u0F#JIQ)Yy_ zE|bn#O?)^*NzpX-pEjcLj?m#o-Jn(u+&0-7N5qKH^@kQTpQQJA0X-W>%enZG78;o4 z9ZMHgk+Ua7*;w-GMKg8{}YGUrnt2lG&4mNJo3>fW2d9B)D zesm%E8>ck*@_>tQCUguM~Z z8mW&DYl?6V|H#(OtcMw@dvN)sYrHSqvtKa9Cb{1Bg9uZpeR?{N3X4C1hnfao{2MJ@3EA&8c0v^L{WA!Z@EOQ#O`Z&%=nxz>To5lza1xX8GM}1VTM@zxefaz zb?|fFRq#{4cX;h$98=KIfY|+tn4KBNf3z-wU9^iY?aUR2U#^3te-`0%w_?7I?u!S0 zW#Mmjz4&;&0czKaaeRO=jBwD#Q6H(>RCt$v{iTN?=UUOqM}{>XdcaooT>ZP#Jac** zNH6&}!`c1CaEi{`InV4_`h0&FsQ4XnpN``%)>`3^odwiCazNA6T@}(ZUdyf%!0lZVrxAYIDN$rr-@?O zECo|MZJdHml}_AEmKZsqMR>@+m?=`%hhafI>b^Z$*oS%_+@8KcmkI-DQ}lvyO;b_- z#5(Ray1PfDTuocyE_6-W{Bcwni^m5%EmYsdLA9>jkbM7GMF? z;Ax+`LK9OX+~eLsyhjHJzNLbDo4W90bSppVFAqCxh^=;aH?OI+#8bmFaLGFz79V5) zNPMK8l{@&vjavBfP%frloXz!XO^M}r9}k-oWBKqTP!?0R@K+E&dt4Pm-Mi4lvp_uP ziVN(}r%q(OSUz9U5}(gVM{~t>Y;5>i82eNPKUkACBB_nK!>-_PpGRW#6?%9|p%$-B zl!Lc|d7wtQ>z&@deAiiH#4*yMxq%YGv0q%Eg#3OA;J{-a4a72+OL!wd0lrx1bC`Kp7R)X&5Gw^M`>coiHA7uZW8yqr;ItK9h4`z&ZNN% z0%`yIe?6r7#1bgTA?}B$x42JZGoBr~TGU4Tux}0e7%(#nFAq7)FDB4T&@0BSt9x16 zA6tlaRKy5j2>-w5Fy7}8ZrbI@6&#dN*{B_dR{UZSpNGR@n|^rorXT;%x&)Sz52QM% z!)AuR9=JR|4#yh*<5_d`G0F8D)<@0fO1CsHocfVN4qjyqIV)h4j2@=%_v6PXqcQ2{ zJ+z7~7oQtC0N0VeeMr&<+(YKU_pMVfv~CT*QL_|`6p1rdmo03ysDrBsPG~vwA!mK{ zP@qlk-^$nGj3wl$JXee|)I+yj;m-g4`)IZQ8XtDi7-#qI!0_ayHsgLS1rg~XiAe%> zq|gl215@z9k_x_;yoWpcWud9G1)H(e80w~!z!QsDKBGnlH@>b!*M|$Z_cLN#e`v!o z`bEqmd>B}t(8Q3S5WZ1b5x;9oir#6biRT$FgU6&#c6+6;nGgi0`bgo4YdvC5Z$s2A zJ&!Aio%^WS1%_{t!&k?{c(b(@7Og4A!Lu5~ZS)=qdHot;^Jf;O!yqrf4A;+~p5mfq zkW6RP)hDIk$)(NkVDBHu-sxPN>|%^tyDy^7X=V7;po6j0Wz+Vdk~iI_9kEm`Mi)D> zu1A-JOIxG=>e%^1)RBF7htkV4_yHqzSTe&9-KT`|m~A7`{&614+in&XEv&^_We<^h z%Mdi5rH!|~=VH^9Lwwb5W1K*Fs}!?TX1(4VzTN1CJNIJwV=?jD_r67)CP&_nyf!l& zl|@_X4dLhwD`2}v;766sJpTgiANOUDj+w?zCf$axD9^uV=}A_7ab?FXe9+-t98S8; z!p7SesxlJBUap0S*@?LR`*p5bVTiB$Ns1hY^kD@Tde~s`3-D``E9sfF6f}aV+nVtvu+0F?z<7;GxZzgbAuu*i#TIvNk`4HxqOalw0uL z^QTm|mpI}B54a*8nY12GI(&!TIu~9!!2sve zoon^W(&DM31lYJB4;vzN;VF6fRf{U|!SuV__PGIWCYIp+A{jQZ|6^A4^eT+IBVTgC zQ3+2vNQrW5FYw8x%b?qp`s{w%v%N~Bi?2C~=QofBQZWXTcGTd?=p^AEA@$dN4HP}` zb3?}vEj(CRj$R{<^U`suI9};4P8WHwlcSBmF;WscvtoI?jS{v@qRec?B7P>AdU-0S zmtjpTTk*^kKORcP=j)y5+}iJz(R~h=546Oag%7b!>lNFWGYRa> zlu>{6HhylrI+k_3C2g)iJhN2~J#thdVJt1KSGR)!gx&JfALimR1DmLuhj>WhWm1*q7|U=i!u(6I&6Ltdn&8nacJ}Uk6Q)nWAf_^Jghd4 zue(g0kA_7!-LaH)=Bxra%5y4iUdQ7?H8HjB9_~6`F7B*S!}fulcqz^l9Iq?`&pUJQ z+0+gE&SqCAlJUb~AG3w+4+212_zf=Q2J=*HeLBBn;NrQj#U8|yPtduB{++~`pRzYsE_r>DR-pcw6z&_ ztUik`)Re@#@=dUB(M4>$tPEPGNeg;^1@BP~^j#8hnapbOa9=0p`?gp($a)u(R8^wB z3F4Bm4zwPh%A4JEP@+Up#8logt(%&Vm|%!UzlZWaepYy^C=K`Ny9x2cW76w3iVnDq z!%Yjc=$w3+&PECRVz+>L-YU_;@C5r~WdWY;UGVE;3?G!ChTlF?2ib{*Jkp$c+t(?H zJii%$Nqk?>iW`pU_cro8ZiQ#n({ahLRQAlY0TxSo5d*HA_cRZ{qmH#GtL<0(GS&#= zQ|s{X?~!0#@(FgF&&AClt^C9bBdlH~A$sXz#a{1!&-P7u22TIUmV8ooh4jPJfm@)< zLv<{1(Bf2F-RBNFYwihcvU zFMZ1UllJa@qMiELW7xO#I`HYXB3|zw&-)v@!r^4%Y_Gl|KGzliF!viIQf@`w+W>PZ zdpLPVNpZKP5q{lUgfU9Ao7E+zP+k?*BsTKgAx0Qz*otW$GOQ9>Sh7qW80#pMj1Evn z(MCy;eBF6|T*r;rael<9aA4Pn|5mJdl-{i`x#HRJc&4BhGYifNW$LQ2116f`tF>owRM{8tj(%p?v*6zhk7`%M=Ik_FxTux4d+B0A zLnW^BtQT%;E{F7YNm%;d3GUUUi_OL=qVH$Znbt5xxU`vmZ>x9mlxG(B!73GVk7%(g zNAzKvTqbPLjpGa6XyM&6*(iEy%RlN^V4eDXtag3QRD6Wsx}WYs`oVnubv0aN(uvPo z^TdOC^)OG9@>3EBT?Vdyb=uI~v3z`(CFWG5Vw0aA`&#Y~ixXtAXGj!(eOVLt4ZKWu zq$aV4NEjQP9*TWOhq>n zNqBr&A44rOF?w$qFL95MWnkFn=-L71YXzjdrlN*uVZZUJxx5<$h7db{W#F+%j-*X9C~;P6zuN zT*3J-;@N|)IUu)H5%;_a;rkNR@vL+s3J%TV1J9{qvVA*RIR9pgMp%R5jQ-fRYaO3@ zz!hFwQWvLUr_FCIeRx}b6o#zW%NyV7U zyB=pBd&&-dLMU!D!H=%q{2;wMj@*(FeXN}-RDA9Ze&li5{Za}Pzx|zqkpT+z-cVQwOD9uyMr~`EAUBa>UgxeojMm% zc_Do#Th=Ryz6W$M(}`NJq>6O^alu^rXJ6V&q~m^#RYKXVwK%kMrKo=1Ae=u=2OD-| z<6)zNJkMJn?`*8X=GiBiV3QS$E_erW`(k;wlN!!Se}fVa?D>()x~Qt9BpQ}u0IM&O z_ht;~ED0NVZXXN0FOiIg{gPN-pXW8NDt_Y#G*++J>v<1wnWJ<=nuYy>b;dk!q@;)|JSYw%r zpT^!{m4<8K#~n%Bo<5!jTMom-vIdlEC=r?+tHdz}qD7gVhf$GhW8a(iajecG-Z7ez z2}kWPZ(WD*Pm2Kb>=m)MDvp~ttb!BKzIbx|6>-3m^{{ZjXV~_}nQNaX?rVMq`flXK z56)=gV~a9;(^1QB4bjI>!WOhSB*C_>e#S-|z4}+vKD5R3evwNFnw(-uaj2AJEJ8<4>vpWWny=*mh{K-C9!Ob@)kJd`vbl#P8K(Q zG{heBa~NKc#V*s`)5rWS<}E){_=5V!H_d3kwrR@XphPShzmfQK-(vnKNPzfRL1ex_ z$dsD9S=`C*#HRnsdGj{-V)q-QXeF?D$xvLkk>mY=y=+!jJ=A0c;fsY?T;Acts^)6J(bOgzqYS?!@1wA*P=Av{xRQ;qRvRR$R_I_7@!)EH3D2nI7FD-EX zowK;%g9fu2W(e7k0ZnzW{AP$YZj8T#>b*1h);~JvcBBj~ylPn)MZKNh)0_(k;%g5C zL8-PK9xyf&U;AlPH^F+&_X$(L)42nOWOPQ7>eCmN zlnGF7QYcTDxdvu6`=YyhIa}vJ;AeSM%MIdf zlrw(*hZx<;bNOXy>M>EX!{)MOY(v=?NGzbN+;m@lK5`Azwfj;Yywm2@3Vn#qPlS!h zd$_8tA1UYM^wV1{6Ff5og8(gU1(J z^fHNO)($SP)qWbbrh4%yJ|56wPCM=eIYO(QL7;l$7vvKw)%2kO7C5Kl_^4KK;iDk9 zPK?c|@>7^zbv2kz-;RUTFL7%Vn&-aH@ySp}n_~k*V0j?rv(A(zHt=}#1ELD_c=c0LJazv(YAmy2FGrfgYXOIx7co4doOWRcujBeZ zbGS~f1_pnu$5jp)ENz`N=*w%;zAS{BL@8tRu%B3$byj@vKM$~(P9ELsDJ=fiHs~Jp z6G8$y#9M!wp^5rMyml;tH72;i+4r)4y&`+NwD9NP61={%MqE5k6Q?vb;KXwJeb1W; zj+G`jbFVl5ZlsN}y)vTlHq(R^(>>t|{RT(9l>#aG2xuH6h4-_U7MGFc2@Tm8a8M0) z1!`dHmm2O-GNLS6E@}_!O-1ZeX2FH89Q66}P6H;+MripxBq*8RL|MC-+z3vO7^C z713cFBOySo0r%1E>O-y_6%5gzY;n(rc43uJ558Siz}DGueE+jGV7|{6?UG0*(F_J# znoCc7R`8j94Do9Q>7x6@#ryJuz|BGzZzpVF(VukDYh5{hI9<=jcB$in#yWg^IyzKA8`{OZTnk7x3+| zox;QMHF)6r1`!x8#Rm(h4@F0eTeA=Gh7aU99odNUUA$O=f*HuA`~iEX7;ZI98AHTB zNUL|?k`A84uJp(1SF!A7xEXG5KaH=hIq+k|4IBL}6A!=2VkedRBDCDcgJV+)!`2hO z=s-Q*{Hg?nhl9aX)()?Y+s4Q4Aiwk?S&>KJ1a@NB2PQZA8}RTid|{p$?lC`uQw@8? zz3rAbo-$DCNw3(=$HAacNBggKoo3cte zH&8tCHcOG70)NW?&F4uULtuS~ElS=srM@j=Ts%xgv|1^Cn7R#s7vu(F9 z8Lgyz*w>XCVebPO93mOTjT3_*j_#`ue8-3ttu^svToJAq@Ri+bUjz+qM)>NAANMf| zgPecxDcg-Z7#t)qreO7Dt*yy;OF8v zvwE})n=e{urG)c08=_i88qVsMz=f1C)F98l<*!%5#jrOHRwaiKUysQiTnwb>`&!65t9$X1dvaB$wArC&uaUYuD^>Y;dm7yn3?Jn#L5HmrGaW z!nw1%2L2|?5N_bcD;}z2c1AU_xpltwi?;I()$gbHTk#K&xdHdwD?v4i+cSBdnf} znHESUaiX{BOJ|8%YzdOrg-QF>??u;3qJ!gI4P4IL=7F7qX}tKJZb*A8sh_1sjWWeH z?_ceBFZwO!KwNH?EU{@5ZEgNV9XibBNrD6CF((CCTVw^7 zN$nRl@s!&EwEy03T9`z#@$;?lZNUZ6_x+lkofAYlLq%`&^s&4~Fgf@9;^-z{EWrj# zJeD?~eB2Z=z8XZUhyR=Blb8rYJ3hcl`gSE(9c3)v8pSX4F~`Av3GkPxGIim3 z4v?nNSmAlr6TLrAgxC4>zBF0y)jDwLa1GZ6RWSEnf@?FgE9!3gamVN&T4vye%)Q34 ziRwmJ)lEt2X)XG?S9+1zp_Q%!RgA1!*Yxqh6qT}WpfPSnS|)RVB$+rxd| z1qw}D3)5!2l(hdifj&LzgryDsynVFjkzQJX4V7-ZL1Zn}0^G!#cMeNdA4EeGEOD%5 zC1=0AC|BqPx02sG|EbZXOQHK|hUO0bMs)0I)hFXz`e^RGE`&5jXhSyLfF&*Qrm$(k ztNBQD#qJk=65E@&aVcLmvN?p}rv97lSE|R*Gwpu3_h2gD6|#!@3+?)6@_EVi3xV_? zyoF9J2oXFPeRK{^hGXsvSx=J?n)X}^iyd9qT9ZzY=$*z?*Oz?23%;j&pt` zIzhZejz)8unCe&H!w?>CBCN$5nbUOX*d_)F{BOUH*xC7$!WDObT87p>(Pddx)C@J@?GE#3{E#!H7&?FS=Kg)v5Vd@635M3#PRq+m&v3CV%xQ zO}tzy!$~6x(p!F$(kAZ0bEjfmW|oRbV*-J7kafH2yc|JMI+z zCAD_aQHRs{#n-E-U$pQ(b(+Kiy*z2>vRAao(T@LC>50DT`LH~`Pcr|JU}2_sOU>?0 z$LZ(lxN4h^q`iB&R-!syt5hOvmM5IamD6X9Ie(ZTQ7(>wi+<@g{ztV-U66YN5h@B=d81#J8b&7%gs9?xHWR z!*?ybbs5WFiTyc$O)>s6sh0e@7(!h?xI$_)Oym<)khteJviBZfvB#9?Gs+!n|@3Mveb*vJ6_1939g9T7ts~F z*N>+?4yDRY|MvD%rl$C@UP=0@3ux~6)#6Sna*^UKpzzWh^(*7>=d`B)1Ky_lsf#cS z&$xGM2+bEccgq3&Wt+PTCP}9}xYjkY&4TG#x=3g&B`f)#fnhYt*A3mbk92Mj+3@%4 zSHdoK5}$3_13R`Q;%!npns&|*a}7_zcE@Et** z=Q731&eW=Hi6fg=@u_Qks8D$MqJF%0UO!luo^RhvlJIT(K)l+)Q(j*xd55JIoSuMDW4>QqaFilU;bE(gKRcOO46uayxOfC+?B{kpjZrc&1%;dZ*nB5Xy0S*0t=IDU zD|N)$<>FX#k*q|#<>M^xqR*7q%y_#S8N4uT+tu@KiXJG%KRCmNN;I*S4%&NT&un=* z|I7>)9Zq1|0!3M*neYb{3olcOG98Ht73@B3e41^=CkjtdV_7zI21{9{O`hc4(J(fA zu^eyh7DmVY{>}4);acb{lav1Ne8QySKDT4FV1`Bp@O@pZaML&eM=NJb9Mdbr4SAL{ z(A)}xBDDmI>NG0-ck>;E-LUNK1^9l7W*<7(lEc^!WV$Mf_g)%CQh7HdR9uqzi$0NR zb>UZ8WkBhLJ%wIkkCkeIcT{7EgxB#f4UA{sKHnm>{R{D|?`6Iq&mIn4icy`ktl;^c z?zkUX290Aq>8^bl9V^{|$-T39jQwWn*v}m?a$%CDl<(~4=vy?`u$6as>OQMDOPb7=NdVEj%hZdHWtmr;jiAi1(J5YE_8Hvl)`_DW%Bq3X%3|jKx>6gLEsb zhH97FT=7U48BB4*o(}IMHNB0fucsnxS8U;nxBHMp%z-MEi?SrYJCt={B0d}E@{OmA zkRPAeL&dFa+Kc1cuBfW~ijl+Id4}+lYcz|lf&N>V?_4wV+k6}g zI!xp{Tx_wxAq(op*(_|lxZ?=cx}xMjp4)A~y2-CZ(8n$`UK&OwrLJwedbx!ru5WKA zb)DXaHE;RNPLBRbQkN#aUg#Jz+Q%VeXrs*7)E+x+E@7Bv1CvXwp<9h28>O7W4Ft2R z_Dw#P%)Krt7kMlBC$30y8^$+|R>M}C-}o4KfSIi9MteFdLHBwjuc;Ru3uf`?xIvXI znrK4dM^osJ!xldHjCi99pYx;H!}*sHYIyhiB6bb9%sRhxCCM+r&Eo-lSL9~uI>rsU z{Y+#TA z3d_D#$=)my|81*s+xBytYjY?eO%MIPui$IC3eKwGOGs6oJI`%cOC>R)t5NvY0x$Ov zU8%x*;MR^*rx@YStYmn%6mq}cwlK=PhLYf6%(2v#B46L3qMK1X@TNK(Czru%)j@vn zjSf1_e~XlWt1Lrw<4#lmx1Z}|tfRhGtMJyTsbKzr$FLYaL#lR36_-beJoJ!c3XGv3e=~gkI*}1DO2*?wqj~#eU1U0*#pXnjryJx$TNdcF zX)o)>sG)yWF{b>^k=<^ui!FEGApfrsHAO9?gO<`ZKVez6FTHgYom}b{B>Oai$S>tk(Y2Hs2FuoCKw*~8M|QB}_utTaOAy8Ea|8S9)P@(yq9 zTJWjsJFaFdG6LzVU|gxqn6V|y>QCV1z^i<=c@NB-EN1u(E2ipYNshM*D6u?}cM+_E z+&iLs;;ajwCA>X{ifRy_bc%J74xxEoDwrMP&*Mr(cU+fmsGoaG_PN!UKJF0T!7a(` zW{?$9hQ!0^*?#`(o(U!;q@e#)f2Q7V1r`3+2`8+>_-t_#_pHsv*z)T#D>-ev=u?R! z-JYbPMW@*BuhocL0i`wPgcrPd5j+=TYsmbHRB8J77B)e zVkYK@tcgjcw&)p7M@0KV?y^)}+`%s4>jJR!b~hwWKL54dI<2L;_!jt2Z^>0LB5%PK z|Nq>My>5jQA@NX{FDkccQF$+JWYdElBIv_NUUt9~w}ZM!oj&Q)Aj`gFo9T$!hIO3R_khoV1Wa3(z#f^b zqP_!L=-1Y%{GpCMEbg9z!TqrXe5@IETr9(N1tjaxOU57W=TBGJs0`AyUv${=dsc2O@MB5DHHU9R{`+6Np z<1R_IhnK_rSBP}#%{^d4L5 z3AtxC(emF%NxJ6;W?GxoHn*jVmCR-HleH+}cVp z`y+Xzi4q<=e#UC4D-Ykgo?NxWon_G$Hv3a3B@XyQ3!9T=3is_WVRRN2L}jztiw&Xc zehneY`}5Q{X=1F%YgtU{OeGh~>ErgJIO1}J2g2*6yj66F zs0`;eacU^KaS7r|1YYTro(FzY#21BU))-$}_e^k>94B)v4{L;LCZfmAcCxUOS)Kz$|LLR#=bUVP zn!IT*eflW&a4V599GfVzvTj`Nmf#D`%fs*3E3EPA8ah;^jjTJXdAAd4P;M#0;bYmd zT}66`6dA_D7RJt*w1|Q+DiKh2ng&Nxnl6Aw4An{Jbx{l9f-WrC2U78`h z>~Gk1;fdXIx$Fajpoyfyj3IrB8ze)89noh7y{gUHX>4irqwO zL^iF*3vG5O*$T41LYKI3mA{{F25C_$Ozw9VZ#qkwG(4X=zlz|Muf%smE(Za9hx0qL z^w4K}HB9T$*raA>+FPcAk7Dixq$?vO=My&0JtC{~>w(Ohacw?Bx3unp<8=~mi~Lxi z?+U^a1q^Zt<%dK@vt9K?+-kTgQx#dE%9KhBzWs!m=Z~gNP5Nj|UCN{5buiYgo%E8Z zvs>Q~NO|La(BR4m1OgoDno?{BUWO^v=$dTw~ zN!J%tQo@-X_!g4IEgW>v_dz{+6{s^!k484ew~CtNntAb~jkM(DN^HHQ!_%@wezPe- z^f*>Cr`A>U@Tu@EukFKQss>`QP7U@yxFYcr?>xyff2m){ZnTWhMDC$dD7jVe%3eAc z{;VEvPlmHeTTLjeSpjA)QT*}!jdWCWXULzqD7!aZXt~)xNK!e2hulsb_KFqZ)-pXdub$5)QP#%J;YG;P07A95?(bxpV$ATj+F=K87k5>Mc}8@sLkg zav_f2e&I=Zf1Xmkk~LTF&=c3h98Mn*D@o{64wqreq)8noV?vrb#tpuRUK@7v8m@`E ztPECf=QDkIYdSTxmHwa2d2XnLAgvF$Q8$9?$SiQK$8j7VIgzg`GQ)Bwky{Tt&2FDF zNAiL)Jk2?hSEr|qblq|+5A95!if_=<0sFE2R4%XWql^C6+etUJ@5^+OM2AORQ`=r$ z;JbwK6CcyhySB2U%dGI{&uMfNJnzU0js1ED7seG33qCJ`AET)O1ks_#S!T;rN4fp znzs_6VO#jyem#&Ld!kJnIm92)>e-8-rc}>chUuU~Z5n2uuaX&Li5vB&95k$IWH4Mr zV_Wswbnmm946xkitA+10zJn zB;e{NSN_P!0z2!o(LB14WeupI{%)bTa=C&}u2RRAbw!vrH(R!NiD2V||C_^gF3afm zJt+p5c=EncqL+MdBQ3HEiv8b2IQCzclyDDJ%%&qT5alQx=}bkO|Ig>8X6l5yjxPj+ z1|;p`CWka&urmwhU3Rg=ZH^@Wn``{r!=p^{R@3qoyuvGfRe znS365Vqi<#BU`Edq~LG-P{O#t_kuSyoZJ4^fZnFAQj6s#6gtBaz6+0GV&VkeJH;G} z_obq$=V`WbelPrXe1I!+Q}X(K)PeOp!8oYvOcPqlDN*kbO4rDEFI5xVtm`1n_%KNH z-N@5`zfEo0^%l|HP~P`06?t3Aem9z<%bQd*s6AqzibU7Us3a^D9CF1^2Dn(k5jm(t zGR{yB5lt0X-9<3vGF7lk?ksv)kijQuX(EYv-l2N z#;3}hw%X$NC}nAaVCnT4HlK3VOn}DK)%@ju)>z|z0`X0rY)G*V3Irp|_j;vlrMoU( zif)Mi-z6VDTTHY2>$iDM%ta<5W8fn+cX{9(9O!_^?n#JKXixEfO|Ug15x2x!b*hp+ zx*{F5PwiRKGkf|^t(Gc2NARBQ)UoZxRV0tu!>jMAV9%V}xHbJe>n-#^yX9&~JG7BE zWhy~upuE&4c8lz%;S=m1Hd#8OM>p(aCKz%*0ktMEJZ6+WE_tW7X&pO@=aJl2MI;Xj z<{op^@JHND-rpr|ep@iWJG{oBv8_z0SW0~bLqRcV8Si}AfD%8((v#M$oQr<@TMH7P z-qnq}whFJ8e9xd52?{)vr5Q$!i_1!4wt0zq} zCu}xb%vW;Z=h9b_PMR{AJ=FK6m%1;AJ}l$g*P39^HSsq;dM3*?HHMRzQKS4{v*89e z$v0*r(u;rdmFlulTTX`BKh{;>d7kI`BMR94(Z65uFz|MMs|QvD<8Pw=vWyNe2~!7x7iI ztkL?Yi?nt9I7v-TI5isorVGob7ic{-gWsr=`1(3SNx{AJwWi4OFCWMiD4 z3mZElOR{jw8m8+1MW!S^+kK<&!X@|+e|}o*Z3$+d_DODtF?4L_ZP)YpUOL*GQi=K)7Yst zx*&F;*ySuQ!Q+E5ozS^Sk(;*Q>8P`Oa(^AsXZ}R+Hw3?;Uo&f-S3%Dde)6lEyI^}> zJ89+dM1K6C9eNK=z^uS(hHZLicm613!(Q-7hX&&Nr*dc=;F8dWGK9?7C@p!s6A?oH zS#$F$x;(wX<;JO^eD!VgXx+d@j5VhPng4cXC&ezfFshw&j>m9*RCvO*M?azWCr5BI zMH9T9k^tG++=7V3;xl8Lh2)>wWSgc1?co=(WYZPyEOhVXzlyQs&ozX{1#U|kMT!ZI#}qXB<&Ubi=7hL^CsPW7~AC;S4lEQiMrq&4>%eaK((OGK?-|Zl2@dzsrCp_c15L=h zc@Yhbx<{jS?UX$-w7{($DR5qq&UPGhz|7^f&{&v|XZ%YYb~~@Z!=wXwO!`fxhjL;2 z;uQ}#td1Y|zTk)O8(-+$k>p*QD8izN&xp6gr}0N|Z`@bevmi4h3BQ5gmU}E}kQc=# zwZ|Ooeq8^uF@8+FjP53766&Fkbv7a!yJHAN2)3d6@H>baUCk3mbQAsK@8G^UnrWtq zUJ?Z*L`kCfSVvo|j*r8-m#VC9l^NL$JlW>oPC2XtL(^0|N|*8(=XJ5CDF;{FuCo!! z6DX>*D{?{txm=Mds=D8SpIxdfP3)-ILGR(b)r^)0KAE5SEUa zeH@t0Yde}WvzlC9h4YPqjWNXGDs*4Q^09AKp)lnRmi52D?4I|c;B3(a_|lKRvJ}2R zk9JavvxL{iyK)^ng4CTpP(YH8m$KVBZc_3^t|lY-fqwh ztU|n5H`-WNOt+3EVASNRJpZ*WcJ)w_N{&uuY6pX-aD^(*46 zU+@EGbm8=^t5hyLgI&1R11ar}A;tJIpC!6uRICy)WSk-M(X}S?;v90};XHAq25b*z z;JUGdZxZZ_(4{vpU~mH4CF&YloR!i3{YD-jI_UfM{Di4tM`XsSdZ@XlBz0XdoP3wA z5S+}%6!oK87Pihz?7B$^vD(N&FRY<=#tNW=p*%ufc)3SrAhTR1yOA$$%~x&;zDFHf zQ#YCXP8h&-ljsHeBYt-j6s4n9yGxR$TcI@d2v+1O$QD1gg!jV~Z1+~AMU(W=YgZan zw#)eI1$s~r^L+Ld7Z!J-N;0qzC+cYZibFVa*Gpd(y*YB zi?xw5!jJdbWQR|IahR}Yw#2@=66bbKl6JQ?MagjC%UzO+q-8t#3(;fVMe#hWeWKZI z`Q9{T*Lxb`9>vf1Q$x+9Tj(}c%I6*NBU|&)_%U%Yvs*NXVn5j6k?2{_IAM>IvGMqM zJc0SFT1$hfo5)jb3Xj}rfc+m%VaiOmf-2JrN?5oBvzMIZW+LZe81@)P?N!*Ch(Am{ ztb+bq`;!M&bj26Tc2Wn$M4l=3tBFTXU~zZ_)ArCuPy3^YeEFRB`!g6-sp4)LQz+?E zT!q_L{H0sE#lT+thW576-Ei0FvIm(+A1RHi$7wIjRMi#4npDMjaLNY!z?h2u2Gd8~FQjjELe`a8p~g8Ct;E;&7EPrpS={I4pIqw>Gme!5#EHHH4B z$Xcmv$|ZC7q$OkP;d^YuiRBd2uRU_E_T?UNQSqKpX=39UtMCJz0&$A4xK~C;o(RcPzNHolQUfm>#fF#C~|g zM;6*(=Er0BvU@30@Z3Nxeh$+a zPo2N^7M&U=-O;1$LzY{I`P(zJFBl&DUb!3b!6xs6_?$DqH!=1G_K$%QoV1N3e{72>&W}48& z?$aofDA_YZL#+CmhOhCNY%OZ&MmK-#JW|5TH3gUQKp~Xk&da8msN&up?3F0oI^$jOs8JT$?y@o@;2JdrK8w!(z3SqKjO#DY)PP}xp@(TknJ zXY??DrfnHAr%0XW$A}D6Uw4#Gm+)M{1^-doS^E6X8CE>b4kmw&W8T}Ve7%Mly6#AT zb9+N(HpG^UJ#*>8(g=QDyrF^$i*WT#JR2-?p=CkJ7@WF^%h!v1&`H6i=N)7#)C>`A zs4Ttmc{u60dQ$$!d*uK9rYvZT84lk_fVbUx781LTg5Gp&o6jqQ0_o*69b|PkmtA?F zg{(o>u zB-7s_w{ym(>uKU4s~p{d~)g0J3xv`L9k+%;c9PK}{PL zKR0pJ)JQUnXrV@(bm!8ol^DHhf>fo_1Rs9sA>?ohy8Mjh6gJ>@juP!qo?ywED;f6#Y-JeSvW5O)W0>mOLf_WAjd$rX{&zTBS|zO=*eA^CWh zepX^xTLYf&FI|opw0oh2kYU%L_Pm%gPj&p4S}Xh{>shZ~CN$$hJH$nV^3{U>6aM74 z$e>F3UL^(Gp6`dbu}}ENx!r{>9*0i{a|#xjm}A}XOnjcGMR`2}X!JI1w9_%=+ttMm zV0r`hX1(Ej#&3 z-?%Hsm4C|=}eE*VR94b(t=Q6Z}D^rV@p zg2j5|7QWh7@o8NG=s=Mh9E%$z%S#Pt_9G<}jN8JOUw6dpDe<`CtjgN%^Z=0rdWl;CB?5u%Tn7kX=?6G%pX}B@e`B@ z{Ik#K-LO*VJG|u&lkAW%=QuVdc(S<_f%Ij2E4d5*?Ri&yq&yP7>-iP3!>WOFMEI;4 zJB?!XH&@Z5eg%+T78)599XZRfb)cO6$Ad(^Bb6J$cA=3!vPX-{j-< zT=qxV3=6H!Vat{+Ec~ShsU7Il#^T;5JpUGd3t&|_l(%#fJt;2Yx6J7^`#ap74t+7j zDIa$yIlPmwE|<{w0EXWrBK?(2B^ z_wJY?7l&zmpU7MbY;m3C2;%>Dwti6{t*g|+qzj|Ce1rvh_Y&-pKBJwVRhA%$?UEKf z?1HpQLG)mi=q|bK%uBcHqf1?9X-nU;%q7!WFmsMTEuHfY)n=%viw8Slz?xRr(Zbdo zN}d?OyZqmeDn9d&#L2ddRl@tKEU|CzW%<=3seNrX>=_@xmx*lG^BPwyp3y-z?S#m$ zUFs?wVLyy&RIDLMI*gV{v3$Z6GvQB($5S(3cJS(Yl7HM0F4sbNnP(6+3VmEU$4oX} zyyFZvUc*q^+st#}Oj6Y~#L)sTzA+|PbTzu;*MI}geKM9)#K;E}vwUd5qs^A0zaj~% zofXJSUUYx>oI-_pAvfzDNJ%HfP5t39$+(gdNlQUk8;9z(nHu`}iS7@{UjAM)m>RR) zaHqN_8{}w7Nuqb;MY=ElI5Uc#WHnRTqf^ci>Q#7dHeOn%E4sRc|6fva5+)(he9Oil z8n*V|Y**jYpMLFcpv{8qKl`!hMv1I~wJYPl8-i%?K{tHY_FzkshfvX?9{4G@f{*U) zgvSmEIDRjYo&W7eKB_IW^RQt4KQ@4qQ7X(&k1ViH3nb|;t+v^2(f%fFbqvRWHEH}r zM*}n-u0zr1ZmiTqjs`lHQ>$+i7ncR34Q|F{-xK`Zq@H*;PkeWFRfW#>-gaTEv^&G_Yi64W>u=GS|J9G~$3f zM#hHoADsmAu=W?8TqYhfy%WMR{GdMaDL*$$%wA97=iHZDVE@G&#ZNMD@slPcr3BI} zk&m#x*q!gR(Zjw?MHunwjimR|U+kGnCRNQ=C|o`_h#GphVeGul+(t$4Ki%3(`JgxK zsi`-aZm1*IZ&v)zc5^&9n1G?>;gZ?D!VmI(u2k^S5j8xJE*A(Ub=hZ`V~h$)yXK1C zvT;ns(24q8ZlQ|W2=1I4L@!sn;r7KeS!BAITIl(UM6T zUFgx2MpAs;$Tz>Y#)Z{K+H{qx36>~5mjr$7d(5p_8xJcIu*R&OtBCAUm4h}8Y%rEw zEf9O<@AP0L=vj{X|dD2 ztcXjJ$vr!Y-?sLlwA%J?AG=?sC_Xa|;xjX&+=TreJc-smQiRN56W0_s1=GQm_%b$8 zwsc}J-FoYWb)nnYt?H>XtzfVY8^!YGRZ_|9NT|Q8;w~M9hR+{>eC|8zr-?3)p6*z7yo!}niCox2 zdFkXG4SYv(PpnCg$IZv>C|S)6i;d%PTusJ1f9fIp3l}k@asaDb)00eHkm_}B zk8$r7lJ)QBv}SvmY<#3CrqEeg0XnW5%4Z4osh79N z0uK_ov1E7paL*K}`l|dU!+OB@)_ExVe_*j91LZeVcy@=3 z;x_m7abtfGR&SCx%W_KKzb{&vwz4yJWP}Lbl$dFkocZ&G;-2F58@@YEu*);-q2YcE z0>Hpao>-tdC;@{*4B7rO4zxNamn>BydF_#4IxjR(*AFLTL$~OowPz86pU1P!UL)uP zQ^GN|jofra2(3+ZMbe@UvTn`B82z!U)Jb$GrMX!nf7c=O+#AEc$C~3xKk@%JbsZbv zP(@Ca^UyfvKKIlQp$vI#EU`C}_0bi-r=q83+O9IzvHe^+&|uic8#L=4N=Da2Cae1a z=h4T*$?eED8gh1G!IVi>kbX+U>c)=b^U?qd4xPjZi+ujkAcXuoYNOTvxFm8wkz_~z zptg?qhCPDiQc;e6gZ6L}r%)PD=LQvXCpHQ;8546V7_x(xQpmFzArDDTutJ z;?^5{g6J_^Hn9S=&sH*6z+E{d{G-h z3rGLk;bSIfV9qHysnLwrY|WqU`1LRrsxzMOXZd!Gn?p-5zr2K<}zKVb@dR+j2_FeiuK zn<-`WSL*pKPUaA4i7Ip94Ny;Ik)K2_m0)=3{d$v|e^V8S7jj_wr(LqZ99CEsuInOX>7}2=JvJ5zJNm*TJTBc(rAgsm_(eHyUWb~-<`280lxC} zJV|8t=B^Zd6^+J{DfOCg`YywgB*AG9*M?2WEyzEt;+2}AG+A^S{$FoN&oiW)@13D? zHG&71I->B@aco(n$}V2*K_gctwdpNkE5*Ck@g&wi22a?ijr9g+k=-Sah1t!Zzmxy% z@WY;};_uWlyx9>aD_$5zQ?1-F?!$KG&}R zq~5(vKhLigdE!WU>62Lv{KK{ZD2O_V66=l>nkzb6$BN&S^99`9z(V*x&x+pjUaWmi zU+Q33L+!>#^1c=#V^>~)vjw|&%3e(zA76#uw&&RGv>~LYATlcL{CU!HWtIj~A8}HK$a?S3#nz95 z`03r6f<0S>Z_%&V9@}xWR?if2zr481CEzdD)PT}L<#%Y}4dBkT1^ zeCD@mq3rW0o;t?>BL`l`UN2|o!$GCE8ofjM^pGMFMF!!Mz8mI#b>`#hR53KY1rwZ4 zF!zHi=uGHcdY0LNPdILYEqCG|buwUyLmcVQu^hS*5W&~<4W)RYnLB|OW{SV=|Mc_t9d_6xJ%ZmG_wf5=78u_? z9vP+U*p7(XRJ&;r4i2j05h6Qtec5Te;d!!o#hUo@C?7{Qma|r~x%A!D0Ba4rct~a# z1s02$IqraSc|U7>?tc(oS31aE6{`}>_|%v3V!2YIh-1;#`OoyD;NPAu!P9WlX3{Y0DiJda2^Q1hMS zH>5a!?^2CBp<|@I5{>Zkz0jI0e$ty&wX$A)^q_k-10DKBvqKewDZ=yv{rw9|b#hlEKRO4kv-NzE;2M4FSAnrpJF?fe<>}b=o3z8B ziQCN(cRgywq}d7l)0hF+-|J>T2S0Z&AK%HG%Mk|Pl};nHuV zv}EO0(JiMA?ciKwrEoq-Q4>}_D};~QhYilMCf#T4ao;kWw|l096#gB<2RQS4^J?hQ zF@|TF={(5Q9D$K1;H;5TpxM2LU}a?D`!2!6N)f!G*weVSGnY@^uY=<&3o(27bBRLQ zFE)P58M^aCzHo(i7%iXghR(M-b8|WIc3CA@f<0cd#~(~FBPbTT2R`B6GE4Efj)zBH zxWuOT4kD^Oq(jC`#3+#?+h=+jGmmZK zF8)lDsb&gIX3OR#D2=oEgE4eP3lr_;`%dE|e21Lmva zUPTW6+t|WpXjjuw+Zep~p2dw7Hq&6yEp^>?r=;kTGL`ggZ1WlJ8fpza=YwLm`zXuz zv4Uz`0s^h>FrPoVkoyx4tGpNdx#*z3YLtPmYw{#ftGlCXY8kR422*g1=n*v$pR>*7 z{J}yE(CK>E9^J-bADGZA@fQDomgleK77EX3q-$aGBvYqb)6SSgY8F1d;8b7gs?#1B z`uk>=NAG9j-kO1Y+9xg8-K@mD6|b1p#xYd$+z6MqE#Z8N2C@_X;LYVgiPbn$ z+K|1QLN{&Yaw{#+PI>|#Tt;#0?shntb^*US%Glj`KWP2u?T}o0!T$t{ciEI2%q>4H zTYpCzXZBa&qoxW~yKE*$xT1c)5AQ7UO2OGJnEiyYu(@~1D_V+-v!&cY-j8mif1{jo z8=2<<2jS7Ugb|TnS;+$p+`2D3QL*)We{Vzhi<#E{%24OZp=Gd)+Ah^D?t~h#x75xS z{gO*1eCQi>Jb2U6w!@F#J3?^a&!g9jI(}C!kmL^tUGez}iTpE1(u~Wdm961?dyY0< zS&BPy{$TE9Dmp6#@6n(3vglRnd|MAc`g-z| z4q6zysUE*?+DYbBSwkV@05lhOkU3to#$4}2I4KH!=E-tWR`^9xgO&K=2|`agla7hq z2eO41)#3c26vqQ%xSFr<^Y?#)hw7zl^EC(hEwU?@tv2x*hoM;9nhNJ7UXuTjbl!0_ zzJD06Y|_+Hp)F~UqIK@ib+XFN-g{*45J^QTkrDm$7wDzI5XIFIv#fo}X>86#dNE zunavT`Kqgqu5~%EcaZV=g<5c&Sp(}Xo7m}%{U|?80fRLI_}?MIU%mb#^u%YW9lM@J zym&x6zX(QCg&`K5IRS^E*@cZF^R;W!c|6_PgZ#@hvB=>p_Iu^=uM*0sAlR!#-RC6BN-D1sk{;6mLJo|&;ttev{Z(Ti;LZ6zZ<^P?#gFUG;` zMt~$V?=F^PEs);J951>sg`Sad2CZ8|c;p&&F@5Jkci=cyYd(nfoBX0>9|E`!#Pi6d z0Veq_d~S*%rfu#f4f5$jAq&i*);=1w_G36Un_=JJc&yDyW@dWkxG?l8-fWJ{S8)}- zV)s16Zf#+6$CuNYBm1D~aE@oL)4=vVjYteJV8_-dllr%BZRfU3Jd^83N8ua2lZB7! z2cO@GXgGeKP4ZtyTYmqglPd@EymTwOwyH?4D8cNild|G?Epev4!oolUI?%D0W~(M+ z<>ITngO)vBr+gQTYx9j6}iO5#C-*;)vP)D`26@?FS(8vp)t;W)yM<(uU_FIqBELp{$?mF3B$?JiT4Qr-mD0zWNDxUw9--ay13}eiqm2 zo7f(a`8_u?1*2SF@b*@sf1$$_STs4f+?rp86)S_Kotr!0x7a~M?RyN3%xb|Wb6*E=2eG$&Vs{4p6dZYhm?y0SFCujLQMT~G z80uf42>yF34-oGov&Plq!P-NzcDiP0S>0XgwO|D0ob3nQw^11M_#hutW{TteW8uAY zBU_^Mgmf2p;!4hQo+ZxzSidxwAy2k^zZ&L@x`bH`*ICN>S=8gR;IkVp;%=j~@L1A_ zo=5sis)N_l&kYmDy)1N`6%5yjUW1S>^ipsan;nzTZ%;m7@=#>N zDnu4FXb3x^S|ZVXxTURwKDxi?_WE`M9ruTEr>WiX)BLXB73Z-%D{ZK~heq4Z)HZ7Dscof2$ zm#bpvTcIH@8q9|YzQIw2H|XQho@z}-(8*UYp-@s2ojU7pCkUD-j!_TSok zEcGRxlz;3ixy(FRP;yEKmeuK)F+zvBIw)bwOOcJ8+sKCt{?LP06-c_>o~>){NNi0- z+s?Gtj_xqn^#N+ON4ayl6}tEx$EuKW)=_yGJ(4s~)Da^-HP0CNGtMBbf1KoDL=WWF z=Ag(+#*ge5{leiD*mPwL3-Y$0-*4pce5*eX-J*(XlJ6+KD&dnfjG=Pi1PV517Y-BW zRjg$u{#s~KWP}#}>^Otf-*b8K9WhVN&4c&Lhmvy({xI3cG}58P>W&7$n(etoC`lNb1`fU`xDcdw` z@ebxC!uvXRbQZQ&k7Q1t22qhJ5=zPRsZCU%v+$nH%_E#`PD z&e(#a(Y)%MIb42;97k0OQx^W%`{|eAyeT5Tw%Q0oipp_wXjjtxdy~qg`*ANggD>c( zjhA6f=)n!y2UAr#e&N4!yU5ENi|^V!wwA3(bm$_8^Ud*8) zJAW=*bQRxwX(p`I%8 zDF4%2W-NLvrwlufipy`=@!wVSGGQlvw=d!AI%>ixy&M)P#xZt$s+s6{X{|uz zi{~siV-hKe8U6o$^801lh?J9)R(tqL3ZM2N+n@WX<08Q**kX(yM`AE0ZWw1FMwlC! zf(<`2*`1gwy3@D}ez^sF$$oV_%lhvO|0}p38>6cs+n`L%1dpTgIEMiN;r$w+fB^(wT8%YCgXR{7u?%M z4@)OsM*2<%m-ao&(P7nIX+rM~So}i+2csGgb@LWC7a7=H-CFVPSS;HRX^AA)qr&pR z`Qwv)p%fMiR;0_amRrz_D;cz4i!WChE&9}gQ{lg32v;srN8Z~Eyvfh<=xEleH5 zMZd9#z-qoxT1t#bU6 zKg=&)QbKe79nqVa$ExoSpvssY2v^+7LoSEIu}24K_rW=mfVs6W2y>HGZqUW?pk5fa zH~}8l_wj_4J<(e=9dTbmSmG-Z+?#hapYP=h7O0`K&UJ)7w&%Y^pHA1xmvC}uN4v|1 zQ~zG3!k@E(&&eMsavmoTC@_p9P-XN>_(`pcS=N zym*xnDz~JdH1DLurnmy1Z!VD@9v=u-zaFq`xP%^g1>Ah6CUV8Q{GdOp*@PRG)YU*i z@VWfC-MsEF9sU;I9R~B?$3!>u_Bztq=gQTameOnMdMdjvS9l}C6nPKNv}G{&SZE`9 zPa623Tt3xN%nzm<&mTUO6s-Hh8VpnEUsw6df!bmpJ?1_R_#WYQJGu#O%4@u@s%FzN zjRoWX5L_$jdC@#ydLs9o^0$?`%sN;l>Y1lVUp^QH9-xI|WvQ^39n3FISA~B|CN}Yr z%%gfR$zA?QomF=8&PP>*W>bd^$%DB=S~t|Kc#WKhj^t?D4_Xw7x$&d8*W>|WADV)M zVdvQZU0pQXNyp0kp!~_|S{TzM57u{EnBAN*`t&Xc$+~IWQeOjCCp^L8YJGOVvxy0WPNiDBJm<@PSO_1B&`hRV2lCL^2(+4ZkiO1X z&wgk3r>{aY`Tq{oS#%8LR>VVPFyr~Hy|AZurs!?vta8JA`X#z0I;!p9*A|J{zK7_! zwmcyV5!@-|?TrX|*PBM3x<;Ezz~uD-4CdpwK&$^QEI=bmCQ$)VuZ^H z9G`!HuX$|%t&2(M?(4^#hpnONdmYf}@D9F7qK3t%#rM;}mivC!##HA@T;2471z60X zFCq^=WY0S8=V(l0u7TlW@e6|8`%2j@oO zyA90DLcL>(tc&3L>5Q&In8+SJsI8=7GonzmC!0?&)5apLKbX|YSjg|q^da*;Z82EH zpXr#u|Ne12D|;w=FvJ*+rO7ybrGdTdqJ@{q$*Ar4f)84&2bL#;tNjp{viNc+O$?IG za%_*fV8O=Ud=Is2%6aI%?wA(&8eUVwS;r~;QS>qrz4jLHA%O$%;B+$7nhe>al~#0X zSQZT{-6fvsf>rLDhKL#m?&B=Fb^Nl>_23aU*3O-BW_QAmuWPxyOcm>{-h;uW{j$lO zEd*<=yY%a<5!9Ra$C9B@IDGRU>^eVBhiC@oZ8#j>B+26Eb#U^gFLmL}Lq~gMk zT-j`8k%v_*6#K0z_StA9HTLL*HG9`^sbJ<@OMC zMU!d~k{5)E?lu)n7kQ0Oy7{a?&z2knd*S?BFTUNu9{MLw;lzzO5`Wj*$UW^QZK~46 z38&uhNfx~=^Y`%!`nvG8Ka1(!A*{}JC>hv&Ah}n;{6V}bg8p8`Tc<&M;~G7*i+l+M zX*)XQ?Iw1_rbxWAf*TY$W7>iw*mX-~s}HZB`IS#-bbnXAcUEsqDvQUi39f}N{rlj9 zi^!rT>66X~6_hre!|R+E{NEN0^y^cCAQc5>lhK6^-79Z9+jo5xJ)Y7xh%<`hF4hAD z8!`qqs+BA~(g1@3qVc}8frl6h{(WXL4h}sjStmUEO^J)7*4P6tvFmfba0x**1w7nV z3k7S-aQDF~7Wv7Fa((1+VunALwsc3vxHoWUwBtQ2YN&P25PW)^#ETT`pX&2KlNw z=uZ(l=x8PE_h`m0xm&DAaF#arIfS=Q>-qh=dniRmPB7VPU9KD7#O|g^(wTpTVz}^= zSH4cctH*o!@*Fkvdzy)VuSc>YF^=@_!LK%d%Oa7N9Fc!p@cIVv4L20g!{ZgkYj>n% zPYbNjip0`eqqv3OiaA;&U_opuQ!MKz`W0npogbcmIY9Kue$K^n^;UL7r-EL^24VWQ zRQ}6F6L(kCLwB}5`(CX{E1vx%x0c_0+pT`+dN=}VpPOX~GlWO9EDn#O?y}Jj^)Phs z|L3A-Tj?$`&zGBc59dYSF- zw18M?m$okB-(v3Se(xG;l}^b1*z00tNh6YM`%sbpFih7;$H7y+?9C#<$W8x5>E|}` zRbp3oZhsv9ekzsy&9g-Izbl9d5gE6|^lriPv7QR>Pa3^bgz+)3{nboNp z*j*nYeg5bVt*kM@)4&*{mhI;*Mg~ZWNksVhUCg7)dQvj#guw2;yx@^4rrgOu4jahp zcd28q&o#_wddP}gr%`E-KA3i5xiInH1qe9;)Ni7AiE_{O&`~Pn>89$q5|@FUfv06Zy7s_{Ud5;x(uoGGD5ICX zkDzyACcn2t53^qUg=bG!RylqrEp~iDUluOs&x=e&=TZzFg*=jl78>DIRT2Vx1uON% z3X1nuz^d~$+^xkBeJ&Tne~iQ>G4m##9@;CN8`A+@Lwj&r{FPY zt|Y{!27i@@NjC>;gSq#C(kQX78M}`k%+N>L#&l?3*vG!Ua-ke*B*zK6dFpmm+|Iv@ zd-DeJzQY8wCA|g;Ki;tjK8B2v&CsN=nom?DY<_(jvp%OW-!6VM;@?-&?>>b`t?z@r z!vFArxfVV%G(f6rCI)uVr;$fh;aq$U4h=8(Prok%uTs20LD71F4g;KYK-8d#R zTlaC9cpRL=Q-!`aI#V#m-B&T2G#lzVQXZ}D{`~K`?pXc03I6MCx#qE*G~N3Nm8ZJ% z`D;uut@JpidR{8rwsIh(#TRi}bk8Zi*Fm1U$Zc)N;RF0kP*;8f$(P?sp6j$QYDuDV zKU(>-?JD@R`4)18KW+KTtz;iR3ar$gjaz7nj@u5R*W`M>rN9DLZ^WXeB|xGWQ-!YE zJ*3V(Tp^3ohTWrNxH<0Sb%laavmgh37ms6qG@a>(#V>jsx0`pmq6~TA3EWpVkT(bx z`l<7ykg#wC%MY=@&X#c8DRAcwllvoC>^iNxrLdk~O<|Rl1LLN!{C~5nNRknR??~e- z1UvW9k$U_{(Pw?VgkR^|C(4w5<+GPq;MT)%#JV@j#-{bh<>WYYuf5AAc3(qHfnVrk zm<3l^Wq`c!Oc;8}B<;jAC}Q?iJa)OvkB?Nr+J3i0cj+$H?nYm_8Q2BmEcbBr{?Vc* zu!EFJH!#7Re#c8ksmX8)5%aM#5t`|A<4}t?TGKVR}Eu?~g&N$%Y&6CZ9 zUVZ!uhO|E>YwXeoQ9EDZnWrK3r3qwYY%aQKhVqy7z>0mzkZan?hCN$DYmypBV!ntg zivGk?2V*g6OsP!klqJU9m7!OW;0;cyA?I(~pl^GP*Nd!2^38IrkF0RXds~8##|NdC zMHkkmP!$Z>_Zl|lxA>7PdzfB7fddQvvEj$e@wE5^MimwCyIDr~l$MB~G3Ly~$&uPe zS5Sp~0RM4H9p{?P&Nzv>6k-vi__io%yBTU8KZrLH{EkD%o z?6l}mo8?3c#U4L@?=5t-E8&Ynwv(WS;hTd3OTB6hgEdij{<)CrPjW%)!}F-$Xu%@8 z4W#t4EUG=`$L+r9z~yo>1}`7Xy=%P1d8>)Ex?hrH!E%%z*d0p$yt&eCH5}M{8(A^? zWLNEkpTET&=g%ErdtEGXl0`siV;Em@s6Q$O37s69*^lt;bg*N&!P&axqFTi$I+*+?Ij87RlS z4hqI^tqlLtg1M9MvBuu6g=a_(yS-pAEsIh|Cxb2g{H$o0D0Gni8=NcgYN^JnA+FN8 z#af8*=z~Fx!p}1;gjWh4xa8Xz_+*E$kYZpXYt-huhnYEI4ox(8TQzGULOJ$D&{m5K&kZEn6%;#=35YM7`ROq=DP7r&s z(>WO!SEWaTf7Q^{)@{%|9nXV$iv8)r|IYA$7)9#1wY*Iy4_4StyKcF|*Qgy=FLc6@ z+BiI2dxzP_@1&lU@9BcKHQ!!th>?pDu)E-xL{D_mm5nPv)ZN)EH_wLtiQQ4Af*(J> z+nd_25x%DFF|q{P?bMR@fFiF9=Tq;R!0pXZygGQHu?k?ICEV^P-_ov|F zr)>Uf^LBE4A?8CC-gID$*oBWxk;Ept z(2b)%$;odw?`teHt}VB)?6)nyJYqZ9bsGie#^vnc>Hb2q6x|oq?mRWAKk`PzLX(o2 z)t}y&Gec17OZMjPS>;WKhiRgl{uoyGs*2vm1R~WimH&T!&XGQZ_fB0l{)HwLKl@C* zH-F=S8kTsg7lG&IZ)F=#TEfugzd77}p2&pWX=&SU?p8C$6uaejafcf_C_{Le#t*quSmVB%#?Agg?-xFmZ5e3T~Pv1XepBB%c$x(W^I${Y=7~@0cXWXILy~0J~ zw-J3-3#D->f!ubV8OGQhLqpG@{QhqfM4KexNbq@f+-W8C86gK#`w6_oZ3lS?E&D-v zcUd2GBmCNT3p%7m(?6Eeh^B*hx8OX_&G(`1yG2LFjAN4bGwxCLa0iTAxB~*T| zi8gz*;|XuYoIB?dHo6aGK@RsMgNl8a_jfrybA%eY6&2!(Mlhcy{3J!%HMq*M+1FbR z^rJw%%}?G`c@za!9i;kqb0q;+t8sh*q>jQ*p*VdT1xEj-&8l^>X?+cGR9ASsckE|7 z27z{Ey`ZxTcJumMf?aP}h{K`QT)J8GpB{dQCFQ@^XqBgeJ8sp-=C>%f8z}iG#M`7&E9@)*;Rc!PjC@xc)B7-@Kgq zWWAwXZ%p{ueI{@$%R>IF%aZy7J~S;=%sg{K*uYsDLXx=Bc5ZhyQ$zP&|LG?-6D%m! zwljuX?B*HG!1Fsva8cD^AF{2f<$9dxgb(BeQ$*&}OHOo$M97AF^}{ZMTr{;WVP@%~ z=lYW9Bm1y}+lp&%R{uhbD~OccuQ$NFV=rN+WJvX{K2&5Pc<*CY@J?BTMvwSF_3 z8}@-Rn`gu0<5O<4+yF&~h5l1qDvOUW!NxmT7-;o{d8qB6JtZ0#Shs=?f7law&r9H` zQ0C$jT7ur&4oD|I>VdxEw?6dR4T?4Pd`;G1D0Vx64iEk^-$pZZ3_6CUX}R3YUG)2G zOhnfW=Bz;3i8h&))A}j?+)d<6C*06LkE$k_T^}8MO}LI>hfxMKTVw69Vwe~ zxI6SyvJpA1l2zT9O;1Dywaa`@{-Ml=Ob)tZT5Gw>=FdhX|2Bl0Z|&hDgy(IV#xeLz z7|Kh&nV|Sw0-lUI$1Ypdkh|`DR6ok*nIm@6kys5JDeNx0C%k#r6mv1LryRMMRFK`O zFubct=Orn=B(LudYx`r8Z|#3l@R^C|bNmUPTw;cL!=o5}{JyN{y$LFk6ELyl5qmHE z6RTBEW7&k~yyWOk8dPN4^#2bmZk{6!UJaW|T$t&X(@)kxfYjX!uIm~!jf@vv2% zMduDej>}QZ`E!|X477#ky95~c^bzD7d%E!O0-Y8+uTI<7(~T_(&=|U3_DP5fH z|L5?kJu}E|q+%O8Yuth!81}UWzN129$-=u{9Q@xLUhiWK3!!iHi3sBxtgUhX!zo<7 zwwZae?euNjZ`xP1nd`6A#cw(djak{U&5FJ>MDM>jTz^*$`R~|+iwzZg=vN)l1AHH+ z`JHL_>864S-~#-2u3|ukaerJ#(aO#6Ev#>HCP*A?1xyq4a?!yd4^c3 ze-4JF&a61)twbp&nB^rZ^0+f<@EBi!R8I4(To>ACFaGe;U;s)nR-UcBVj zG0g4NLF&{ePoiaAi)$jH+IgJdLPhQ%B>thK>Gx%`ru9ae;DUDk5zOLxjG*cBU(>ho zL4rA^3d!nxbhfbKQo%$19Cj1`R=j05S5Kf{KE{I8zno`g*uqE5`W|v8*t~7sK!(0p zWB!z93japs(YQ7(<m<5sH|Gh~*(_$`Xh$3DMb~h;AJ-o5OZs7Mur`a484Cu~ z&im`};oxH)AiC=u-yTJV^kQMS@KjE|m4tOlN~CdrEzOFQ$Aqrkx$)1PB;Q37qYe#} zWSnkgCU@efA@L`df2WH3TdVN$ODG@l(U)Xm#`v|wo{c)}M_D+<8J(vu{B;bo@&d1_FcJ(I`8~PQbQGRaPZ%$P>Aa;n!VKxcRnxY zOaBeRx#Q80m@H<~3uugKIuB6MtX26fZJ7 z_A7ahY~ha$FNfuTN|ytB%MfF=U%Ka(Iz9yLqJZmeIMih@-x%$P$T25yPD_psPFhKS zuHK{Rt#aJ%uQ4{HimY5uGqxs2Lat)((_j|B6UFs>>!b$STfCGRiT(aj$whS6JjS{# z7)>3QDC7TLM3bmp#JC$?cDz#VzhnET zr6`b>ZR?A`ozb|OF6GJ}jS(Y_6CFBd+4zks#j~=7-i#c}2YU-*3+9B%FHtjEBtFMXRkvM`Z6q&hv!kY%!t=k3JXi1aCk3F6RGF)(UL< zG#e}!8xFYv`CRwV9`dpKM$T$$B&(DMQ>x|#TJ7)8743wd z@ofy-=AD}FqGjNkx{QW(ceL0{EC!v!;)?=wymG+gDVI9HlOX z{H?=+e4()n^`}mSqws$(;yNp9boDrb2X_@@7aMFa+%y(N<2#VnF=KQTXS?Bx9L_T> z@yS8>joXc6E5v;6_beB`VgvbPrh|SP?jm|=0egALg|;}VW8UN~+<9IMu1Gpa1JC72 zyv@Wr=B`s>{txEO*L&gU_!Q`@-OK9!4y9!|FKBl8Za(#i8p7g5?^~KB|DDwXwp!J2 z82^rKteQw$=NhBahUMHJuA&b!5&hCqnfXmWdN|`f71vJSLkh&Tp&W;XkJ7>)w@k49 zj_4t}p+`jpzT_-+oV6vcT>o%y@o#0gdZs;ldP0SA=9RT&f8yTn67Q)ZdsVBzbK(bM zocFP|U8kwo?>GBILe~6*vmN5Se&J6V7y8!4@yA01hAo$--wDRYdS7}Y?w3*5ba|6_ z?r5#ZLto!n?2GkaTH0R@?<)QHlsDq~NpM4_MKLm$&buhp=K+noI)e8aXpa4+M{y+U zLSdIT=6Gdx8c!pXXyBoBv+PhTnONtui4)tg9NFj^XTSpsd* zcYOau5}u6+;#CFK_}--g{U0r1+d8?@@jE}-^zcLr@eB z)5twN)p25E6+-W*F}GA*x^wIknf>|7^{!Z9>$k%=VEab4tw_+&}}x z?7RMpIp5~CoO<5La-)}7ViCGvo36~ecqkf9X$NL;3RAj*SUMR?6+X&xVY8e-YYe#x#CBQeciCiX$3zi5fRwpI5>{n zz_MP}l6G$fm4ijR{GZTpHl9S+?jT|(5cDLoh7&*bQLWi7@0IEeN78GLkS z(f@hr1-f;#VS^|7(XkE>seH^b?j$D|m}jE#viQDiw3QiD`^2Nr`ytDlwt-aQ<=_xu z&1*$2rkCDT%rkItx$#X4+g&)`{&A$kTg8sAu1xg(UFHwg>Z1L=_wewGW~Xo1;8n;G z{5zV*p9i>#yzF`0jqT6AT^d4no&KBEf6m=RAs6M*{47-FTHO<`^)nH7=?K$RoJjtxU78&n|fw*lkUB6SNk+_ zvInv2n;uD26L+*}FSk~z!F6~Jro`>xUT3t>+^rS|uH>*46%z7UDj1t~Ui?#M38d#v zVu8gx$@O2=$bRW8H9D$}twImkr*#S?mxH-sU?0Jt6a(%-P4ZO?4EXx6T}6 zEuzuuX;vW}?+cUNV*Wp(NJ)h&=$O+l8m!!z-xgh7V=K<1vg<9$vf_X2{Kr#Nw){Ka zQK^EKz!C)82J^lWZ5)e#EjpBIS;Dq;6!*G}{7>m|{X0%*Doa7P=ldk9Pu)bvNO$Sp z#V%+bq=#^mM9g#(EXr~{esKiNqet->jSjfdH5so@o@c!hdtq1ZX&A)^<)+^J@D)qU&dL_~oNE%hM1ShBS#ZE}_pzZ`>L}I|*U5w&zU8PUwhHD* z&I4bT>1IPZ!#bfZBY=HWt*l4?fl&uv@g{$}QUCo9l_;CV{PdIU%PnI~| zm@WE*Z!kln)l}8mx$SIMGEfy<>Pz^nc~~|{LlfF{qR;xfD)sZLpkr^3|OhonQi<-&y&J%^4be7 zAJP+XJFa5(>|&QQn^bT=<1xA|D&;o^J3uvFFq(W?m|96cXwE;1{_S#k)RexkL;~9D zm@_ytGO;Ra(_Yp;m_fJ7|B%k(tFmP;G%zB*0Kd-0vQf=r=xDeSMrmx}cgJfYD7^_y zuQtdkuh!tW)JB@!{|n7JDtM3MqlG_aANTkvIx|1T;-jH2%h=mM{tH*(d(Y?myYOgj z`+gRcFRl3`kwH*AbqOB7E7;%fE2*}JF@l}e^Tw7Qs7rW(P=%$EZ@PWS%w!)W*9Y?P z_subPL=+Z21~+=y7q=G2W7xfPw#TeJ47`G|&HXvwF;;Zcj!J_;OPs8CsD{vZ^5E+$ zPrG%h$gW=~+;^q%nM@NgPoAUy5o`7}td>lJtxvGLb6za?hc`vX zy3Z3Jc8ow zf@eRxL%AadVtsNvmv`+4gQO^2i^(cnDt3#K%igG=zfZ!nj8u896;?;uw73S0eP5j`)FQQ9GO-pkoV z=#42zR}7UX##h7kuA5Z9vkUtC(u47q1O$BD!(;nt;qS0B(A(+CXxa$+HuWdT58uN} z_u~>(UHr9bM(6U*)Uw_dBcj7G_55hQ@})B#&q_hg%uJSjU_Ggr{H0gp zO7nip8{+<{9MKck%1(4pgWQ{ocvRHL$yfuw##A7rM3p5xQKOVA_0(z3Gk)sa0LU2} zL9dm~vXp7oFtm$7`#&}8Sl||FT=kJAnp^PeS;iQ7P~=r_=Sr-!^#uz*3pXQ8srjks zTXD+4<;-k;XNm?~4_6>jX9xRob0C>ScWTqvA9t~Xn^pvFb?(MG6b+;~Gfq;~iru`M z%}#o?_?w`T9F&EL-DOVCR16!C%WjviqgnNxan00+r{5JE_{59Y9Ct|eb*T>i9jM0k z5;e-qEFp!j5$F(qp3jf6gNsiDjGE@NZLe;Mo>2$<^^oz`!-VhRWeh&txh{*1GQ{8^ zDTs}3V&`{PQt5$ZFkYO)^K|rZTK)<;PAhUzQZL8!pL?aBTa}@=UG#DmG>93mg0Crb z!C0#pZ2kU^jn@*|_=IPaquH4k3QeQ3Ay#d2DdfBRu)0rAN%CS)9NELO)tl}nH{RIrPotI5B~ z01=1R@EWn7UGLL~s#(h<8)o*Ui336?MiR(xKQgfw)e06l#W*#b zT+YgL@xFy)hG?6S2+eEokP;X+%ecL<4yLbe#N*b(%w>T;g|Pc{x@#BChcaAimx@2R zrc5EjnId0bpb57FxN~+dm=`8sSnVJ_BvePR8P4L6{z29`eIebSq}bN!_F@dqM7V3^$*~*72>8#dsBJcTpgM~Mh zOjkhCePx-O@J-EDxga#?8_a!7CEZfr0nfWv_Sp}QM@nIt+8WCy00be0{q!qvyS|9g&O{SyMV8e z0eqIVuJ9_+i)!pRj{Q-w4dinkbobUobNQ9i@vWsbP_`$QrCX zfiKm2c{`~QR5qp{!a0~F1&^fLBcD;rFOe(%r-rma7h&RI&JQhC!^e@=q5St58<;ec zx(GH<%k~w#Tk{b3Jd1+WtrM*K_6?M^s*X(J7+1IVqs()^+Hyv&i!4$6GYeHS`;eQQ zE}9#~>}1@;R|*~F``R3s%>FEqq6axvihI@OJ71cqBDlnLXwePj?JOKHUn?51R^{x? z!M;ei8xG&1dY-7@OQXELQA4L@7j3}_Gn_a@`s|kvG~~769FT^!^Ru`~jxzq4XW-Fl z4|XranUd%JqyOtOc_P<2!n#iQzRY=C&(*ZyVKGh9wd1o-nhSqg1SVh4C~R%8!t}J$ z_+Ft*BQN!WML~k#T3+DcllAc;FatBfZ%f)+E0FKD|7Q40oz!r%^cr5J2JvBgl<}>@ zJ)GHnl`VO$vTK*TkyUuDkyGq(}wN zH${y(?p32-K@Vy3>?eEy8-Rbohj427YuU8}190hf3{=@IrgL^3?YQ)koQIk4jX%VW z&qnxlBeNwLM+DPNJWtQ(nvj$50Iz&|2@NTi_|$tEaQRY(9jm;V))`xR5YZ9WrUdZ! zD)w-x3CBd`Zp>i4EotPPARCk2{J=63c$CDTUf+q&SYd)zk=N63%wq~A>#0)gVduH+ z;7qFrer>vl-1I{-P4Qg?Uc8CeS!xtAu!>eJ6gtVdEUvrC9>2OrU~k5Jw&=%pYD|4X zi|v>2PmU%y7ZQUVdDmr!&l@48IT_IhL=Ij5CK-%ahTm&*_|_6#gq6vVGwX^=&)hO( zOb(J}Z&JecWYJj}UI*V<*Z4RS1_7Kwje{KBerkc_*O6G%C7Tze3Esk`Sj--0#+NHTw`H zD^I_LBY!NV#p^%Ow|o8JniYkF!hPJaQ(rt$KLyWYK5YBn^<=yEHx*W`+6zC-K<|not;7kBMm(Ormm+?t0sxXifote((Rj@d)%QzbjjF&;sN7$0J1c zh~56)3yY4$NeAmKDp4D( zC;4`{1hEB2q|<~~^!CC5@H==AOSZ|&O0#xQjoT-Z<#*+)_8Fpd)M>oAXU9&(siSt- z1w;)E;L|_pVB_K{9FSaM^NkoiKHeQezO3P|>g>?y5Dw*P4@uU-8YG_^BHd{wx~%#M zo==w(xRAYxh`JJm zX(r{YVyQW1ulOHH=i!%w_l9Azsc5Q5sZ^R;h5xQq#)OkFSAnuoAlq@ex|^Y7R~-kx*PnsRQT`uKe>${Z)2_?Sp7SexuY(y zfj^vViW03u*taXMOl9#Pl**1HO1l?T2zQubhTsb3iSzuUxI_KU$GAIpBa{G%Z5*1H#M{BPmj!V0!{q8Wl#gy8(i2Yj>VVBu9sMD>gyN!NmF z7_rw`nwn(~M{mJX8jy;A2D`a|@KaBlmVwa&N3fjQvE-cky=`tU7rFi2Ln?75#)!+E z?Sl)I&tbNwGnve?LciSy@%P&(zNxc4Mp&m{+TILyWVjxV{5Xb!f`C$cH&c|J=Fqh7 zNN1A7zf+$p_%BWTz-?8m2)T%@=M-6qr!sX=xJPr;9`W}>tP#fkJI_1Jvlf1~Be?PT z1~cj6OE+D=QS>}ZUV6s>Ox!`tC!dx$tk=QR33)JaGo<#hqK_k&508I&e0RUzm=%8+ zpC|8NT~uso<=Rd-JKdkR?>YoWt)qc}9_+iSEvei-D&|wscSu-A#u|^Qpd~=&8e)K| zc_;AY(iygAum>H}?uNTMySR~H*VskpVZB?J%+R0@uC%+3v&qV|`%ed4jI6|2+h_bh z!4M2Bk4Dmyr7UGe9U)~Xh8xNFyA}fkK8=T0hYPaS4hAAiE4pcc&)FmU>!i`J8o&RZ z;Wu3RVrzSjs1p^AbH*uQ+qgSu#(Dm8oTE4!;;=sM4-1R6fNuL(C>$&1YXonhaY+*H z_Ap{0mz`*B>V z=Lrhlte17PxFJ{+X3|iP5A=PbDXtAYgpY3fxXNKGY<(fR35$Z5lFlZ2G_;kLMQ`9u zYkNa|<_Wa#WX4NL37QLX;qdw*tEhCPv&+QKL%jcX)fBts@AshlXTD_18e>w{*+Ul9 zf&A1BQ*53VjqU!#hqjoDZf`1T{c@Q6$&D1h|2x^(jpwhoXrSlYbQF6g$u{rQL~KMc zy6tOE%SP8y*ZN?*e|(IuQPjY3SpxU&4Et z_kyQQJud7EX6KkIS(;YR;nQDbUri3fsedQwte*bNa*_j0kItn(_x<>}{XXQV-vOCx z!({%V%iMiVCJd7fvga#SQB_k9lnbu@gOlP7G3*?MEBVRdKlOp{hNn<4)2Fm#Yy5UU zh#n>f_&|@5A}gDT&nJUKmuDxP`}={C28e#>uk94v;U7hrE6D8lRjS#$716pf?z2z} zy)RuAdB47rBWaf~wIy6CH)Q}^x>>{FTNu9DwU-S}7y`{>iHNfjJN7_-vQqj%Po64r zE8!h@CimZYeqrVdNrjOQTdUiFH@_0|^U+*v_VeSLdh|hHW(~UDD`dCTooMJ&Ma*Bd zk&pO0L~uT$V4*%;vdZ@cgxpK2*G&m~`xzlL_6PCWda&QMhF_gN5>s|0q3h;!R_GyE z!51FWj4PvfQf&Z5dAHJr4u{Wn={*R($)aNztxMVuM0O}M1HrGGd7^1Qv>(n9`}>#V zsBv$q4ZK8~wzY6eU%_t_^UCQyd-=Rq_K072NOaq)*{-!Fn4=MejsXo^a>g2_`_j?v zTasj!v=(F6OqI?s+<|hjFI_Y26#gXS^Yk3SE1r`JUCA`odXUla{(tG*ER>K!dU$Kxrggf`H(Zso#s%GhM@e-1O98_ zVO*NnNxI}mgQRs>12Q9~NVVrXqv4R~*w!ZF!iXULUEI0memn)%WdysIG@d4|`c6}3 z2Jw9##P9ita@3C=z?U6W#FjV0`PKY|eYs(cDKQ7(={1_WH#$P6-!ZtfX0zMk>zr$q z2J-;_(lHZs(LOF0D;IoYZYCP=|8W}j^Iq`=@g{q(^&(2CCmS_UnT)31rt;AHyz4D1 zL|hKT<)|03-ydyJEV3UL^KP;a*#iU#H6C_(jl4Nj565n$p@Vn6WO_z_eAdaw2M;6S z2C9hblaG;e^SQ@#G2^LR#*|;4?6l@!s$AR&y*K&uB^!t1z}-Xmx=(>2*p8}yAE7jb zK>ppx2!)9>J#ygEF;J9IpUp7X>O1-vqB!v&ZwX`^EP(&KF?#rNbsfN@WJ&TD|NO+ z#M;9cxA+X-3p2cONy5`4Bep_tjpXX8+cGe>;xu6(C;FI`{`^>+;Qdth}u(QA!t#^Rf3xNRym-SvS=s?6YPA!gP*GdA~UJLoQ(j0=k!d90fm8d9Th()hM)-h6Wu_De=ry@xFP!)9vC z_)eX+nebmHEg*N6qte;I(Jgfc{Yq3v!?Z}&V5bV*kaMsdUee~T{P6Y~o<|2U-xqek zSK$^Dd;9KlV{l8YlXT`Nf97<{fvTf(D1E*kpHt~cGYlhCMK7>khucR}GUzuVLase_5~T{g5^38DxL->1vr^@~;d-uZKdqQyqOL*059i$Z`;n$penM}JMD#9{RtXLuL&e!Q;drw4+FXsWGM?YXr z4Hov+mdyApW}&b!jL~l|yP#u_)bvEb&h1P;l#QWcE}WQa3i;Fp{V~f_xR$63rP0^+apH|R^)xW9cwxPIV?w~o&>gYFNq{MTa2Az6!k*a&Na4pe^ z&abb-&7OO>`K@6H_#ix+(bdeu#uSSpBC*)Afjg@O)0Kd~)TPTe$HyW&AKrDL)VwSJ z_QC~uBJ%{kj>_Yn1)!16e`&1Dj~`#AihZwdL;j61*R@_xFC8it~Z(H@PGrOO55?Z+gk@8A)bEMRmc z(XXiLXSwWgkTwRq$$++pGt>5*K%RfT(N4hz_qwWt!lfKuG6UXpsTY*;>X4xRjn%4K zV@P8tegu!?yNzrSJUbq9zojuXk!3q5`c{=%{-u$t#kp#pi`IeP*!FoM?_Ddy*@s(pQfWBGX4)HQO|ar&b7orc&> z`I4y4!khCT7w`5MlI)Zx>BtK%`8IWaq)$(5yk821#5FAI$`I`)O~d#r)1K5ayD%M(6dFl=Wy zspHA7FJ)Ke3#PhT1^V6TN)an+Xx;G$#6)NEx@E%H^feM6y_PWhd3VV8uDxIom-EnA zfAY!yN|{!DWOZ@+&~z1i#i%B>K;4B5WbLrWbpr3U$(v#`)P-wa)A4-lb&P(!TY6Bu zWva;cMsSaNu-JKl@9ScLoBg7p^1YB(OD$0UF$r6C7_<0eqbMl!QrjG!I716pBu?~1ZQ@wZgbPxKf0PjA}pE&Nao9{kp*K6qk%0^3u~`0~!)%i9@^OV18z-U}t5f0B%7n{=#JHrQA%u&O!X4@Xd{jSHq9P`(+stbzC*AMC_r* zZ1(FlbVGa&`#;#gj}CW67p#YCg@Qb3$tngaacAm?R zR>i5gH*uv@{;5+!c?p&9jnn`le0;baPKyX=wZ8TLnt;Pp9Y2J+pNMrhemgugkH zS!aaj3R>UiN;anG zV`ghE`n)lu+AuGwC{%;hTy<`FqbI`aOOTnqnrR=mr@J3Iw(V6aTZiFGQ00S-|A?*3h&4i%{QkogWZR$;(A*$Q$yd ztTI>;$BYE;UA_Z-epD@bTVYU?JIQU0hhtIaXiUN~w)y2wGTiupIxJYmtH&Fma6lYx zy*MxX@~n1Efar-7&Ji_+B~J z!EZC?D;{z3xT=Z9(_YL;bOR?3iNf=51-$r#Ii|}0H-|4gF^bIeF15Xf7Iob~Il*#> z`gldQQ}mk>#ZI|>R(rPOz&tt{tJt<*yjX4*gd9L;l>!c9asGsHg?pNa;pb@mX%|I_^Cf+$$RDm&#_yqL;gMdz1*shTOC6Gj2Qwczcj}wZNzVPN%t~b8 z#)zzr=B@th@dZY)3v;L`$B!%aG=f??!SSmc!WSOU!$r$%#56^)pPyWa_wIpVT3(zD zSApB;GLf6wDYLf}GfDO{)TA5G+H6}KI~|G*%R{)i;CmbB#A4;{4J;z*I-O`>=;2(> z-2g^S!vUk1a+@Wi315wTlyF^f3IEYcbO+y+i*Bikq-0|?2BaO3 zy7lOf_{$!#yD&ghq)E`e5sECLOoKj@`W{f_Su^{ zs|eRx*N3ueJv7i|dnNt^WU_5JBdJHO@Tc!x&-_2hnf5*j;vYxvq+n+?#Ch$Pb^WJ^{kKoU z_I5o}`Ldi=_tQhKHEa0%GA6C@#MSqW{NA2{`0_dq-zQ4ST94Ra z+13IqGSj1+Z-NygxHp#Po4E2G;reN>j&H#uB|kN_XuI|Wn&$(u?rl~g#*d7X)O5dwpCuEdHFvf^WzhyQ4r(uQ zyj^+Z^j(ztM6K;?e;(vap`ZTHpm%{h}g1)x1sbPr} zXI^{L!->DC!Q}rAaT_SEtia`v1?-p46srCHjTR3G;vpZEFeafCE+6}IEx~1a7gh_+ zPM_KQxpp|p!m#x1C_em^HQX;BM!UPh@ha0tV?i<&4E8Hk{wewb4SCQW|AVQo+(mES zs=-~3@lk?vHR*d9W+!%K7C%&|I;2j#@80GamNr-ybO6^jK9k8k6?`^Sr-pgWU&^+1P!fEwV#qD%Kwd)y_w{EO?malk@68_$vKRNb z1xuL!_P?akcQ%$~Kj!B@3>3S8IGnvzCG$CJ2s_bPTXg0LlfGX|so}q9;QTQ>EW?K+ z3c|-aNYin|#r{|!-rD``=FphS%4i;0i!XhId#J-Xdg7vqXUg8psPiC5T%$1WQ6WFH zFNi!pe515=K9W4;F?7}ELK`2zO86_=r5%S%yd8|Wq7JpnY}m~_%zEEkAZ8?mw!HeX zW(}a^Htra#kZm^;v-+%Pocpnlho@O$)Ye4QU-MzZMeoTg^&h>zx0Qd->5FwK$B`3j z%75hBp*Fi7S4MwiI#+MdgJnTTbHBvvMNh%I^8+Z)TO`?$Xhy$SFxhAZaffj$X-=O? za(lKzmLMC1IGZGV;aP0p(p$9NW-3O+XYoZ=9yH^voXE8ODw|iJg-=iNp_llZb-%BS zpob;!*L%jx#pg&>aswCV=`;6r9;8xGL2~V<@PWD(7#$dai)(Jmb_gHDhvIm=?s%KM z@1uubIl@oW`jG3L-9r6%2NeGGb$HRym&`i-ceaO2RY8M?=uepy@SSf|@gd?mCi(4V z2fXZ{EeVCG;%S~1Fc`a%VliQ>CTn4!g~(~!pYMs$Ly=h`wkKL~KT{p3{5k=bGoj2c z%8hahyQAom@DDyx#@eP5DBA6iy>%Af^O3g@sisMqKLn5K)&b1AwV#hkwZq!x7;H`7 zz)Y*_Xrkbobk!>7U#k0K=;8$U<>kt%78}F;dOk+CUSjDMKBOS8hAk6Uir%z3es(KI zxUY(2+~CVlh!2rAE9+u)dpo>&cmO>;+R2={4Z%I7I2??Yqfvqj)RGemm(YBE)YF%I zHU81QyZa=D37;fp9er8YgN}Uk**Uaa+~=BfN@b0kHPLxQC3c5rvaPS2$sndX+B>`O z;ww&=wO=aCYA|#PkyVNJM5$3JLciQ$7aG=3%0+$XYq)Ut+oRDt;3%fl9%H6YZ&8Dt z9j+`%=9Q(U2ul)sSAkcT?`Jib>DHSYgPpU=N_ z-0OM`2WE_yo{#ZB=_GeLf3F=(yLaWTy^RFd>zsI(UCsV}9z~B`{?h*$jIQE-^T?+f z@!$IKfRp!V)>TtzXeM&)O%@2f5`kIsbINk34uWZ2A{w^zpugh{(d|YGw5AvG_|@C+ zDy5_J%}iakCaEjkZ#devOAix1(}H!SSQzZbZMX(>KHkEQ_vcvqJA*JhVjmK09&n4k zKxu3WvOnyRDBNvCzVUeJ%R<1cNe`noC1MZ-^0gvI@h9XoypB#~`--R2gE`+xU28XQ zKVLBY97;s~RhR$WrUJQ;T1=ntnT<0VjK=e!5T$S4!UkjFs#qL&p2}1OS7F-FWGqtf zE4{333YD@VF$ex-IahorO`Ma5)fk@@sRor9G9;^XW6NArXx@%m$~aulXH?i><>pX~ z-~2*$^oE;EL-+ z7c3_R%F~DPh%(VV7k!y&PxIKQvu?C)(;tfY;K~iO)L=6%1Al$?%cdnOqvM=n_@{TE z=IHCB&`tDZ3{LU91__pmeAMl!%h}L-x2VX(7T@wqc}=A;{&kJPMf*xwcfEm-#HFEn z)l-otzeN%4mZADjA)gm%1hG~CUv@IVi?R&9lV7(DeALd>1$a=sRqUghU)N@-&sX3!S&tE5pMB@cTN!9lja(nG1FzW-|kUJ zp$R6&p5Y%iS|V1sOa@iml$G`$3@@IF&#Ri)+H*$Oaytbbbej1)u~!+Xk%8}OCXTV| z{HV@G_#H1tvR5Zm(Cc?GG~4A1E}y#KMGKCQ^={^wFc@>YhQh<@G0KAf474}U;t|~;H-87;rJ@Q2-x4Uv z?~qlAdC)KA8t&Mu(c(w8s6Q_9`M>sYefME_l^>5j2R+!VkUO-qRf<`9=lQ)i`go+C zh&|WxWE(e`AbV*6LOxfsN~VXGbFbp6g|?(6?J^E8*e|{Ps2@5#w}a-^16aPao$RK? zP}~y?msQDf)cM9h91=Zf*JF7+bd53cwx^=#xGnp!?u+D4jZfP-Ut1=+NEKOlJxQP8PlCUT{CWg*O-x@^%Ss>grjNhdm!-<5UOfwHs>K^I{+r#Aixj z({Ap1W&kqpCgFTiAWQ5vi*&-9>5~0!{`7+yK8g3u4ej;0x~}j(FR6sWxh57~b(y?3 z?T6Bt%Y2sAG@MwS2HTBU?8}-kx>50&zW$oS{l}Oft7|NpN*u}@)oc(TGL4UlwdtSD zMtWu34hS;gDW7#Qe10*KdbLR2RP`k%k1Eoi^ObwN?Su^kZ+EF_ERXf&Q?iy@O$4Z^tHlc69TI#k`u*YY1;8x;2CA6Rr zbGprC%jb+Ci`YM;-q)Z1GZ38)o#;!Sy+Ce^i=po@{ zTUw9p_sW?u3wC6FJWrzoxNR z`{^`x?N>6-7kn6znH=%%H1=BR@Jf*zoER>$h?_sL{lXil;95j)zk17bmkh?`F)>&p zpUN}?1|U2w3AHzTOP?2sU3&jAtjX^{Tg3ZamzO!H>iLBGFyVOGQjEOvPVC4oWwQT# znVN=Q=htVfrix z_24i%QyWhu4uSls;It1~8H;Tb?D-2aM9YF?xOU8E4pZ;Y_l9NI-Qza@uC4~{f>XGl zv0oOwL=~%=OVGEjBki=jLJ!XF$6JGAT>97%aYd2nRk@T^y8FYI=!ZGX#lW2B^+UpR+ooMFgECxdR?l~k+yy)nDS7ZhK%AwFOmX?cM z*`rz2`10foH@n1%+o~gC(>CVzz!I*t5jZrjKxF1^(06k(4)-!)slj6??8bS@xaZ5? z_3n$0gVIo#;mcdrXyKm79>lxEvSIQ|sH9i{C40B?&_FFj_Ph;TUM?%!`wqOvFsb}K zIlS{3B;HFS5#q6zuMpIT_!ZTwtO zh=!51Z20x76!psooAS!}cOO+OF0R4+K2s%sZ7k`cX)uK!4dV8jEKxW<91f=(`HLRI zakln2oQ{Yb-KkyFCGT1 z_Z0Cj;X|?DWeg@P)ntY4BS_sbr>&#(Ws#rQHT|aao%>}eyY-OmaT0%H!q_#FO;nKA zy)C<5-ccC`6^qbym4~d)i{4^SBJK;-YINRuFk<3D;KufISvxm!jpBoD*R(H zzzE$+zBEQ36|0Y8C*{gYZ|Y(1g_H31?`D3#XMG%orZRk2Qyyt zS2FNuAZxGCov#`uakQE=gh~hLh>q5k5s2!+uNKGY>GAK zF5<&Df8K7|Na!2H;_ra#!r8QvF6ft2?Eodd!_)z#*VD08B~=pf;ToD|j*+T2Y((dM zTgl^EdwBVF<9RD}P36JWcqJH;F{faaV8c*^B+{bvR!{+NMIyiO7|yazSjJW9vT zweSvB$~fm-go!ab`MPUb*rR__xa%s|)--E0-rd`F&X@nS!~Kdw_~z*&$r9O?J#NFL zZ-cB+G+a2K|0KX|b|B|_bn$v&IjgTvHy+y=6mSBl_dolT+FJq8(&d@`X-loG)p5VvH%exrpoioz$9I#jB&{+9}~c&EzgYiU`OT9#8*; zOgu4C^2q=8^F3||pZx5|w!O{xYs1LyXDpFk05|Gsf;{p4aXvkm-?JMC>krA8VP3$x zDAtnV{h8t&>oV{7N*z8LBK!1ZpDb{Vy6};eU_env${epKGHw;v(CZlwtMsS##aBq- zb)3XZ_cpB#vqEcSG5;eRNQIB_BS5ha^|5f!=;+F+}GjA0MZV z@PSwH&q0UHFZ3j*g%zYOKb0FgTH!`wI6iE;DT^o&yC8=nxcdDLi}4g$LB9_)E#8p3 zdakE0Z+=k6+glur<_A#bK{eDLiDcVOieA!)B0PVU&Aa^(j1+zy(R#sb@1G&4dl`b1 z@FM=e-45Y>qOt6i8jGoyQsDedQtOrS2 zbjKA%Z@z7a3Y?1yF?O_vY<^GS@3?SPxYATeDQg1Oq#VV7ZAbXQY@nw@B90q*v8?&m zs7Jt1NN1Grz1GXgO!Wb&M|~@c8E*h9(XC)NIa~j%h7O)wjo`=vZrNS1i(|{tazItG z^5tc`*}X?G*qd!C;6*rpQsRX*9-bon$OL zZOu;P_C~?lQ@FK%Cm&I!3^$!Z@Qfsu`fmc+C-xAmW;fpd{W!r_KZ51@OC?bwM1Jt1 zg|tty$ODOdsZD`kJN((ryIe5FzAniy8WF_CT%JW);~&$T;y|t;n5F;RvJhx8fOk6C z8?iQ}nDy!|v)xul-mM`Ry0L~Y7p&ZS>*LX>B#o^XS<@HJ=PC2oAl`GU8FIG7;6$ZE znOEd6kwMPK7#%$#+y00RJ&v8Zjoj;-4iYK~#2NZglGVEpy>jEU|G+ygdhW<-ynriB zetggoCp>G6#y0D#tY?)avez8MC*y}a!zBs>TRKWd>}b!Nd>>)n@#)f?-aZ%_t^>74 zX$bt2&1V&uiH=Vt8U({udCElko&J}iI|uON6~YTCIzFXa`ts5<8c2v*hqE0Y@x7A< zfjvBk2L{7GUEqFK!jk2W#tYVDpV~7QN2~{dep|^5^?}T9O^^NTac)Wv67jP903uhDr0H zt*|zJ07m~kiudKBk0A0bx_jI82-W7H`mZ=2XFK z`Ahb$ho9KxU7{B0ewkb52pkt~)5wQe%-`FO#)q_0^Ox$9fFK*x#g?GQVmZ?5D|mWh zZux)K@%dT7LAr4UXHRxwigQ#bLw1p_Y^&k-lm;WpbwAE)Je5^{7QL`rF*u)9$G&-6 zVu*3P=<+<_CN0J|XP1n@JXdnD#1fV1MF=}%MmtJ-qsHSDZtu$EW7`Y9I?u&|Ckxrf zzEWyB*a5m%{rC-|0E)dQI`}=B+&hF*mP2^)pMh{0pNwub z`D}>PU35l%QmJ6VjExc=Pj(WEx9^ip_#-kG1BNHnj~=Cig+pLK!YB8bgj+%5aT1kDhvkd}UQ7X^A)4jK=NkkYGEEEjcJ$$a#Fp zp=g}=KR4BEKYQPPGAX-WXv@-^TF?)>{8MoAvk!Or*#~PnWaHV9!>rS^6;!xQ9;suu z@jLgm5aoCs+vYBk#o64%lT&)q9H-}0=emxP_f^ohf_p|C}f~{2i zoxESVbERjS$w>B_Z0-GIk4tsYPjp-MJ+5JCSE_~IdMn;eDCUO7f-_@$1=EI4mLwmt zq*p70+TL434h(|Bn=s7FaNyq-+ThJ3v1|R7!Rq_0CHeaeP=ezFsIgTVW`Y^YTytbaBRr+z=;Wy7p+aN9xQ zx~-R`?z00Mo{0PY583m5W_ZU^k@)^8U!yNPk4ot{{n1b;L4s(tp*r5WM6rL@RiX8; z5RH8xNcy7bgAAv4s7Rh~x&j}!V5zZOALu#_!8Paom>&GM%)1MN^VN9F zHtIxEI+hqiY@yV=kxKvw6{h?8=VreB?$A96f##Pp*0M&Voyy zpO%Myxd}{B?CMEQ%zS2^JZ1>NUpJzSIq;!-JreBAr54%UA$x0vjR}WgIbk;+Vqk*1 z-$ce^a}et~cP>5t{J3o=-_ojuYVSo8@SmqUDiT8rL)e_d5?sn6I-iKqtkI=~f zOzn^ALj|z7`%w~~qD@0n%W2Ju54__-!Ix_}2czvi{K+#Xock1oi7T%#)9gWL-}xYH zyFKLpWYHKS-$`nHqdgma{u(MTI7=sPSdVeSFJ@JqiYl#aKJcsP9QDjc%KcePZ_H#$ z4E{^^1_bbdYt@jy>=NcT_Y?dOO;pSOcjou`Yc0<9a9pa+DOIQew4m+pBh7)Xeh_>^-T z$MV6x_|Bsn#oy?H;5+4SP{Om)T>ROt#m|0F#;sme7%=Z8b2k`*sTTW@vTX$4Wjq1> zSES?j+(Kr0!w3t?6VUq4r?h0%K>Q07{nk-mncmg4bZ%V-louKEMXS`%5K)9z!#c99 zPAb&jw~9>Nu5kB$Lr^+UIH@h4$`-iVqrc5zjC^*D=|xy#P)jTnott>t9dn%7kp`!e zg_2N_yE7Y}k1v%2Y2sDk{*XU~e{(W=g$L=0*!mkt-Ne_ihz1n>2SC{P_nh>9~$Nf7HMU z+fz`TxnDL%q9s^FXYnSmGxa(zE(zDmA=&kmw|pWD%#OgmGfSE4@q2Xhm^C`BE9F<4 zL>}Nn6c+iF%RF06aIGR4N9x4x(Psd3oQrX8nar_1TjW&p%W?DVING{VaI03I$0PYd z-v7jTvfZtY9T}c%T>V=5Ei0$+thcfoqlRK=S~9Fgm@?0vQ>d%l#Wp@zlkf}YWu#z2 ze_x*Uu@CNtWx;IBVK(^H3i{zGkI5^xak5fD{^}}xt(hh>6K|(Iy68!DJ)Tkf?N-P* zbr5^&f(6@Cg0Hs)v+mYzwjggO8E^Vb?sr|dYxp8MHtjj>b9I%C5dEowFJ%a5caMb% zmhe)iZFnhikd5JMFJ+AdZs&z z*cNAZ8h*B!mOqp5zc;-|MZG=pwzZaJ4bVkcTrNWA{9=`DRiH8=54ls^Wyg9bL#w6&z1zuC$Q@x-3lBt|RUjWH`h@XA4k4`7jVTWGAw{3Z zq!z!7mlzvj%mKPq`KlFt@zAKS}CZY@Mb(%tzo z{A`1yCo(l~S!xgclKmL=>0g=FTZwQ%#9^jzJ-b~I=lsY+U{iAW?T@CIKQ0*op*Czz z_dk*;R=#b_0S8x2>@_-xA6vZn5@ii!wmSpu)2XakWe%P0(hC#%Y~`X>ipC)k*poP2 zGJbJAat+L+jeWagX}a)w7#)I^=+0afZ=;{KB*AoS5UY4IkG_Wecg}wt*9RMhWngx+ zK0hWn_5+a%^Pe>=)1`(MjSt3&vML^&IRz6&CZMP92^Mfe9b?lyFx;boFA`tBzWDk- z)eb9@>@vdluBR}l&oiESdk|I#m)5IRITpG=m68JT$#Zoh_a35zF!A~7IAJH>Bz1<% zohaNazQV?7+TzZsaQu>Mh2jM@u%C98h0XS&xNJ`9!!)@5*TLxaFA~?EdP}T}>hSi^5b3y=VkdNX1yvT^ zr4R9ivM-8ya1v)`zCMI~F#1zF$etL{D`nJynMK5IYt~t@TH|=4) z)0ev}8wdZhF^~>XW-jIuQr3uV%hh~6ZHA6(qmf}gnD3t4t7OtsOg-zdU0K zcdsa9M3&2j9yG`0N6DC#^@Q07e_T-FH`0wB$*Gs%604lSm{VnrQRzFV(xx{$tx6PW zC6PP&Q2{TTd~RuTk?J-JUrE>w*5J35jx4`KFaNg4v_w|Z@If-1)XkWFj+FA^is)qb zO+0p}F75{nJ>Q=T5_9~@3?7Jq;9=?ptHj^b@)2zrXE0DYv3TD2l4gM5_;km6NSDZ`u zCpgljLr=5rf|+09_>r!akKx=#2kZ5dP!tm{8z8(Gvs`oVTe+3FofV$D>QYz_f61>l zYT?%WD{Z@)l{;?H5YgG5(m99c$yp=nPAJAz)X5?p9ALCH1=Alju_e-@jc+}dt3)guNtdgK`P^gYXFT^3%fj!TfVHJgveRj6wPNk>*{22Esaojq<^=wv_2;7(UnN(IAk2Puj-L;khM7AP z(6RqXcEfoCIT@X!N!Ek-oqEx!SBn5t;Mb2S;S_PS z>!HER^zV^Io<3TWV)?*2YpmNDhJi=3$|P=f&^mAg)zqEt-djhf%O8?|=kKyvBlS@v zO@r5!YRQVtJ*g?-NE_pE&79tNTY3Rqyo%UT*A29e3hAD6FPZZj~>EzWYqazFm>2JutwchsU723hY7CJo*sxsm-tPW0o4qG|!``{sp_0 z;Y|jPoRpJ;Wb1y7#_mD36YXoKK(hWnOAU(v&s3xWyb@`5c{V}L8i3NRw= zB`=ltqDrx|Xg_P7Wa)era@bWt&Gi?#W)CYo+!_d-G52LRUJu7B(F5%_@j5%@Wr0mW zhu~rKh=1G~Os!k~Q3sj4#P-M_^r_54`tyOb&rl2Ai%;O5bq3$IZwF1!QAf-9G6@S7 z8Lgc5=(ygOFHv>IuR9Uw@ll?IEM?@-5JS_a1n~W@0G27e$pJk?nXaJbD%7SUx3>PmjGMIMwR7(cX*s>Dl5q9Hr zcwhad>tUTy3S9ph^H0#h@cc}aPrk_Bx_gmCULAM3Eai5`RIp82E*Q$rlGE3%DW^KH zjUk{AWrO{{L)-Q(Ci&JF`7s7-txm9ePyK1eov*aI-9)Zhp^MIAlTg+1hz#*2*j!eO z*1H`@%hQVnT~NcEo%THZpy=s~ox-aC9acZqpTf7Cr-4gm@!D1~^Z0~9|8$+qWsm4S zk4%9?@d*nF9E6K^QqVp18CMhxl92{!NNX~1+%j@69oi$ZgMra3u#-1E(-8dR0wq49 zo#cP+W1W@*mZ{*nAU6#>acpna=p|@ixJJ3`^ z+w>P>Y0qrFP;MtRX9@4gl{JoKJFXzxHbB}~qYi}qNU4rz-jWm_7(MczXlQFdKe)9VFPWzh={ zJ8$DIkyhyTC;;Cskz`58BiN)^Nk{4T#I#%H=*6R;91_U8>)YeO?Nhk8DU@j!Eu=e} z8YxaMi1(eZh2`?;_^YGK7ku<4yHwFl3$4 z(roW@LjwvmRdApk#yEkRd!tv7ZDQ`X$vVuk!}?3*>ml}?!*E`F|bf+ z5K%%UB?P3T%L3#c1F^7>5W(*5M*Ysm`=86TMAqVA-~G&<`HdsYbkp!*T~C@5Yk-Sk z3CLJpz_(4&LtJwjs@7hVOrNJjYYhI|z3mgcsC0umLbGnkHqFt5&A0O?>2REdj4(%F zN+9l~+~Uz`_K-D3;eENc+(15tmk6kFQA5Ou`fWOx3***>9Mg;c+BI_X!< zXB{%frYGXrYig2-5rC`(@pxcU$C_1);i4H0O~pIhJWgbFEmAQ5c9EpVXe*@NKZ<-S zBTCxa7uN)vI&l>9&XDnt?9U(+?s#UsBZ4uSFaDw3eUzyt39%*p9+T=93@CLv5{s)OJo7!_(>1J-@1r@fE&H8%{k_F>Rv{ zPsq~7m1lxIHR&MRbAAo=->eA5^`5+9o-#y{75X(#ly!7^gq*2E+8AGwW(&bkiNLpr zU_N)F6}&ejpvM3&HrM<*B~2zsU!CGk8a{OB!#_F^7bsJ)HN>RJWe7W3$G-pAK~bKf zw{EyIAK9dW=~}1J%tuK|t1M^&52UR8y9S8#ev$}nYeN6I`USR7@6&>tPdmn%46d`vXtKdohvJ$&hM%N;uHxR{%`8HoNU z;YFWcAhXLdfX3-exW7KdT*6mT>&M@;QgamlbUBDunr|A7%?sy#}$isA6KzICnduu)|?#{_lttHa+p|lMrK&;L;Zyx!oN=^ z7Cd$_#UJR|){!)Modq8I1j6hXNt8a;BBa(pI%iiWJRBkVbk0ZP`t2YdByS1@%~WhS zwTtB^E}@Pt_uDjcg*kmOFft4C-woiB**^4HWQ!bCP1&1w*Qv2I2p!Ix<$d2zMy&8o zM{mnu$1OI|!!c*6N!6SW@im3pPr;y=KCF_vSPR~5CgMXh>C*@o8ldouVq5y~uFggX z{#*vhfuE952Q^7&Vkt%Sf54Ab^};2QStwevjh|jwkJnqYq+P$xp&y$qajQBU6@GVk z{Z-NBrLQ0z{jELQaQ!-ljAhd4lUE^Wo1S=2I*f601w3ls5X^aX9EV;kWNIq2$^K|7 zef}1}mwWYsa-Rwm>Z|c9+r+zS_oH<4fg!h@Xo-Z3aLmxlubfwFgAT)mXFH<{Y3v$| z3atc8bSU7ar-c`^IUVEWE=#_K_M)QpNz@|w#(O&XP*|(*eoeb2Tk%H&a$C;9?prCV zUmQfrs@3G?qQ!szwa1;Gk?45UOS0sh0n{Vokv!6$2VEG1xQ7||@}AgdC1-NI^r`JO zx$MI#7WZv+l9LaTcguCVr-4hV!=;WAJ4AA%qOhV>2EHl2+Om z8q@JYxzShlc6-PC^bFKYDdDyjWujc>n?;!2_s zIf(pkQcRY};N|cQpM?G|x;s0(u9T=7PoQ(@?b|X+C7;H?@>*mY2j++;DAMM?T|H&6 zDGa}hdG2S;ol3+G@Jg_k-J@bHYUJ!*al{=xtacnOp#yQBtGzwF_zUvVp|lK-Pmk}1vVKl z81|fHX!((~%RhP&HktR@WrCPN6-YaM#<8YQ+#lBnt$AiD>nv^)i%Kf6OtXML9(RQ{ z4N*txwVlkTpEZt6j)4D#V$NUK;F5a+N`?(&8e683bDOFz=@UDh}k9RUOE z=HDh+&=P2>H-z}EC z%k-t&!c(;4W-q?2LK!V04>c=$Gs{~)4A>lkb-#|Ka>X5t)XmPbuERvI%EIV>s&w1my$)6S-0s*Wz?=-@S0u* z#n_JImpBXuqC@a_%O3u9x&wYxL}9PmTIRM(4jW76BQW>@ck&&KH4hKsxLbkjG#k>! ze(%4nlG!e;qqo}2aP&(t_wVB;?)+jOf4s_ZM(-MtkMWbPKdcIkHx`)mDgYmKKUKc) zI76BjHE}>cfE^7oMNxAU`aUk?KR*C}`xPT|^(aQ7(XeY zEtk|d{toG_Gy>b2#Lo)-x5QLrLxje%S0+W-?PA zqtk%}a1HXvEuv5QcX_IX3KBPo3{>$pUOloNpB(y2ub!PvJ9^pTK-50`Ex*fSCkidj zCKk6kMoWsj-+*H~iL~6%6~E8uVs%&we1*1R%vYOVg0I`=Z3qOPR`!B(~|~r*hO_#0oI%&StJ*+Z)bW=P=}9DRaHKiymI7rqY=M z__E3o*clTKou)uZlb+~2v9*w%&=$Oe7s4-Xn1G$_0=VuBKT7xF>P}Zjn&%FGS7>8I@ZiGZN8UuKMkZU;xKyUBy(X;plxFy%~SY5Tbr%nQ5cR{CxZEy zC-z8*NyHy}U-mWs7TJFl`L4)Hen#waa-wtY{7QdW(;#b1cRY^D$E4HrG6+41TqBZ+hJ2t|^0I*_e(Vn+7`8 zt_UaXM)7{MFP04zteSqq@-hA85x&f@JId}93*Xgh_9{G>j!&&7mmE2sQa4&VPJuULQiX19n3awT1xj8{Wseauei{~kgsAlaFcCq)xqnMaukH$VY8KfQq9vu zbQ}7V>l~XdzE(V{c_zcQK5$pqh>`<$`OI`Pctk|OdZvBlxL6A;DHNQIk*c(>#Q>)@ z#NK=AF0akj!;^)A!?xk2MB$w(?aj=kJj+IIu(UUpvomCzN5&FBLvutYE?QUWvb}n)%WyYoV)!w`nqO&e~#pXgpNQ zJ5ykZ=$aQiFU4W`e9W;y(ENTFSC?OuSh}mwlc9-ioB=Q4?cemF0ITh`^48j(u(3LZ z0TZ&A;1A(iR;h|JP(b#;RfY>O54LXzV)J33u0r?7;|2Y}W}u#*$%tU+q{N zo0f#^Be|@$Xee~nC*b-+uZpdc2Sa&xI^>SOU~8XhL4WEI^d2ha{Bm9R7*@3LWVSp~ zq1#i-Y1fuB{B5QO+twS$m;q){*%hmeBs$(bQ{+ z@N$nbMXc+8v;FpZp+AJCLRsq=`>wQ#);{`1%cs{=u8Pn^S$!b_tp2dBW5v8`=50LQ zmEw1N+=>v`Je$d0X*QCt-(cAEF6Cw2Oi?55{%$k4?ARP*Jbs^umo_bIn8brr>)WAc zo`PdT&j1SQA$rk9r?N#+%6Of35`KxfydwH487x)D=5Joi^OiOKtq;cq>tgF_og27kTz;1q2P7?cCWd(mw2YjIa<=!*E9tvqtH z=%~70j+7qbWjW?HxL6*J*qgyTK6NCl7H1&OGng%@3Z%y?KG06Twfy8xJ<*k&j8EGJ z@zG2NdDn8Vvcq|nl2l96`9^#`c7kt7Qo*ZVWmsfOlG>d%bZ1Xsn|?lD`28%a!jQRq zI6wH!4tW6@){;Z$C)Hv3gC@~e$6Rv$?8lq$d6Bc?6N>2OCu{Z_B)rwB zu+ZGgEc@Q3+25CnJ^UvBK2GR!S-JS?zFM~bl`3A{EJOCRPIPsJBl06cu(r=$E*}a| zPz%#p@G!eIpf&9B0guE z36_k$fN=qRC9ZBYc&*|ioiIun%|h2oz3Y$K`5!Cg1hYgEDsH=1{g`{c8TNQa3eBQ` z578M3Gm|33>yBbN4ISCLQ~u1|vY{qV1Qz=xc&LUfDpDNT%)C@I~<^qS$)fCVe@ zEL|UG(~^-Z%jHea2cY#s7XFn_WRG7hBAdj&#nIIDLj`3r_Hc0CBQ@%jAH@Ie@Dl8U_{)e_r0Rl2SJ z-+n$-^x>X05ZsSPTe<2xC4}5Qif*P^ETdL*@_gIXHn&S965RP5iG^!@Bq`~&*mcWP zI&+sH&fM8S=N%qVri{zNE)2%-%ru0~W~|4$W%Q=y9c`5b@|k|>(0!f@&(G?-?tv=K zoiD?aK6hEeXG?gM`s0wn z26ju_={{VFLHp_V_}96P*r6fbv&T-28pHrZPEs4SpxjsY|;@1c2PK6k(`iC7BT|!ev$WT}Nn15V44HrJgVp;H7 z_F{4;oD^zriRjNN&=mWL)&Y!+lF63WiH_i3;+^YX3;U+-L%q*@C4*~Yxzx^`1_k_} z#&L3ve`f{KPQm)F$V_3^)~evA@NnK%%HcZWZ_rU^b%b>CVfnvo;cFF+OyM6c>|zV~ z+E{E^t;;suolH}F%gErAC*PK%5BCFykdo@fZ+#W}gYX%8j)-Dm(k;XfbZcV;yql$t z%j)IuuNo(F+WZ(F2J1@?RlgyB8ynbM3dLjpU3_*H@Hrv{?>hyuJ!3af;L9d*?ly-n zdFM}alv?T8(Eyo+iYaP6k7GpNTcWpDFnFq>v17_(-nykPG-sX0jB#Tm5uNO4 zM*Pl-!RTC@ipYY!OsjQ0DV6;qqxUYn?{W?33Xkhn^VPDy?fan1U>Up$yONow6V{Fs z?@;MJ%wc&wwPpyve&I3xQr`$8Cm+PRs|B*qOG8jE?$LjTma{!mH`A2i|0uk5ESDGe zu$sgwTqx)*Ij49Prbb@U;N`vGB4$*B#9w4TK2%ybo}QFNBXM==ZIzJ{7%%_kK z`#lmb))rz{$w(&E)DphmbST$uOqlF&9tpFIcbHtpHgtr zP?Z+$+e%-ayrq=MI{dBoAWX2&M{UPf5|wvqG&n4qV(jYqIu~WQo;!-C_3Qb}8TGhY z(OY`ZX9oRSH4N9UN8oVJdwk^*Yb+cX1NqlclE5!FP^&Ra`svhisEA(Rx1#$}VQwz> z;M!Oq$wIxuL>3#mn6$68ws~4+&rn8P?omv*sl-R@x50qhp(4MTSLtc(*p`L-zqdSa zmgo_Pjl-LhdHnSu1Kd?k#gvQH64`4t%KVkkrju{Dr-2=^T=0z^+&oqpi~koYrZKc z?%=@2Y;dOaVXx>yq(2|lxi=hp=3}&tCg0IhFgJJwG%wv}`VCfCI@KR8{fBX<&Ev7j zED=s-xvXHm2|A7y`(cuI#loG2$hnn<`=KwGZJ_}kiZ0j9j~?+Wt$i?MR3QpBwPRjR zDpdI37>#nS<{($^a z-ffkRqVsnnnpUiZ?|lS6!9SY^#cJW|oKoC+wv6%gX{6P)J)D|Fo=D`L?kk4DeudzP z6^*3rtufRgI)H~wG((`pet537;P1;UA#a-uzNVD*^889`qgUhiod>*DZvfsWrsHqJ zZrL1(7Us4T!zj8Pr9B;hApI)Lvv|#qhD-1#VK>Gr&0_6un&HE~{df(Ttn#HbwA2NA zcGzP!d4?-pdV7~X=UDS!qHE@>(h-y!7CK&F>(|JC>+KPr=u*` zYd1~M`$#?5B)+&tA5cgVe1~{h&pV=9@aqw{;1k<3V-+1LX^&ZR^my_q;j zlzVZf!`kTw$o8>1W-N|lLdl@FPg^PB)OVR_juLJ)6rty}Rc!8AM?9(sM%Rla{OP>e z_6`4dR%s@y%WMuCSj-W5nWi*KxzHV zU>|slmx;cTcN@iSpdfbg6hlmpJdEK@WvrlUH_TcRf#qh8__fr5_!w4(tP#B=o$p=6 z#H=0CD`iSh7-Nmf96#)w^`Y`tbrs#uRL3)Kf0lLJ5~Je9PA)X_`U^3zHCK?1JRHp& zTDmfSr$Dx7ZZ{s;+8=9Q9>%M?n|X((-WV@FHw^|QvP~|obiG>-XfEHvU5^VE*)Kn= znaU(*-RkfvMORvUtphy8jsB}aB(fg`^61$%qL(@q4xM(hcm-D)r+l}~-?Bwp3+_GA zu=!;_es72gj`lkT-9R$v$14-*pol-M}N*tmnjD6)h3nDZi=1ra(Slu=qNz7a8ZyN<8OuAQ`@@ zB-K?me0!NK4j&0c_l&&CsqGyF=O6(~t-4bAXd_se#33UtkDvSCM+r&ai7EG%?AxJE z!A1#Wv+OJH|3_2gtaI^dng^eCyBCbdmY{Ha2Fsc}9Erb!@aq0;-Vzo_lJA$PLx&hWz}7yU#7^e9cn9=GAl_U#3_FxUwRZ=dpio5Y-dm5cQC z8a!9{I%Fft@LKOK`z$`=##Q=ZPNndYjhF)CjmfxbP{_szpO0*Q9PFlSuZX=n6dGsJ zpnv}b+oHUc##a9&)lUPtbhkDBF1!MlF=}j>@VYogAElUyr}%R5_r6VjnE9?z#a-+u?A-VJO@=Ch4m0h?_P?(RHmc-B>gL$7ZD?NG_Y} zlIZEkIEsW9E7(=DS=9QnJ%Zi@@SP?TaBAj$#2is%5no17wL%P)-uCBrL`Ljo|NT($ zu;9}ki>$iBp*DVF#UD4?eCGjW=FH~(+`Q?6kvwc|?^G(}^vCs-A{-0)$36|{jS(gl z_!{wmqu*o<9vFqmlU>=PYn^cR(`57z{Z@Yr%rL!RANJW*%5H1eVCbC`9Pa#>6)$k7 z^Zg#v40-Wcxy7AUJr(|Q>voP$qqOiLs~FNy2^kDlhAg{8un04`dPyx698<@76JPf5 zr435Dgra4o*tP!IAZua_T5NP!hpqF->i227XXnpHt`pgxwV$YH>RDOBr~x?PkdAK4 z_A`@$8`N@P6>e<5$p>6jhKolj7QK?n7Un$?9&cUg*FCQ&zMUxy#Pd@--}Ki7FH!SC>3{BAAbTIZ#B`#TbIS8K3~jZXXM>=?>Imu;n)O|4W~yjtWUdy8H*!GzhiO14h) z-v!+iUZy@>=|*P>?!VcE&mJMX+;}8jb&tl_DeKuz)7un3)C_OF9pfMF7-HbjXuMvS zE4y56h(&V*kNx6FcE(x}-zG)i$>v8qZnHfc>IH9SxsK$3PYo*lw@NKSdmy#14F*p1 z!$HRnl`A$^lk+8YxV-dd)9+g#;M{)n?Nz`ZiX4rToq}}Qw`g`IQ;|773S=K_6#0@u zk+ru@gVm`mJpWODvKBAKgHhoS*G(s2*v zv7+1(UA7#+q&Nm{rETDyXmFM(LN^Bq2Gn&vN_eG$9ip)4#DvDyypmWy}c zV|kV5n;o(2gkWHH?n(;;bKvW=SkY;c%ZEG>Vq8B3>5vEdY+!{Z_3o2M>qmd*^(uX# z*gp@)D>m`(E-L7-sstZ1GFZ7!AWa=~idJN5@@)}7wo)V-kN8NWV{YNuP$Ow&&%xL) zX7ZVs7(7_v%Xh949rQg?;9%;&PTXEazvbT3aQ`5_O=JzOy5->Oe09F-lO{g)7ae3{ z@3PB=d#K)`iZ)ydmFd(>#qE`%$Hc#oHSVy3j^KTTDF#*KYY)Zv{8WsX{fsqH%u(x03{JHKlF5uWqT@NH$8xSDN?}#eU%EcZo#q?8!g;OD!@echiSI&jV8^La9k`p`^*SEuLcVi=S*h5 zt&Vik#P_r}kKa3D0o^s#*Yz*R7^7y`Qo>$L!FhG#Ymdbl6MxWpr#% zHN6?Ki^mxZ!P@(W@WIQ6ADEaa(9I1-BfP4Bl3Vl`N34dd}v9*#RLIzytS1!nf#`UyH@dqBYWd{!V&a5 z?jkdJ%V0Sr81IMf;lBSS;n%VRsHpB>+NlcQ#&d8$atP(ocmy^lRcKS^La**7GsUushL@A$T^(%u!l5iGjKY#P?{swF!}QS5SwT8gae zuWi&Jq>$e69z06V9Nm(GFuKN7vh@A~oO@y|?f1$Y%S6uiflo9>uJPdtt%m4=6g=b( zZ2a-{RQKaEwe#D}6GhhYPycMxxU2EjRKeqFQAc=`6`OqC2FIFxF>awfzcptHB8Md5 zuUkG-4m82m%2@b~++LyH!vg*fg?H5G9owJkNuA{XP}7`&eDEkc3_Wofub{^IO;(}J zsYT>ea+06VvB5v_oa{GilwM)3nKQPplWp1-lFkg?P!e=`g*Id(+VqCDdQlMDpavC~}LBBDrP$ zeBu;KXipaDOR=9zTFs!Pb`S%0=d+b(d?~8S2lANhA~K}fh(G+_tgg<~#)`Z`tTp|| zTr+!Pl+p=I^l0ICi-E6qg7MRR7W;ImfhHR2AW3A#_e~W(Pmc&pDLf_fJ7AAb8&Y5> zIvsuv+)hVSUedA##$&pA)7t0%XkzD%j$21IQ1LL)4WHu663&|8P*fluXlC&lbL~+t z@=A4AwOL0!XZmsAY+J7X+b=(|(fULOx}B4y=IfyG@?jjV-p3BFdQMAj?u3)yV}8!P z9w%eeqzhY`DCmjklt~SQROZ9`?QuX@cr5lT+`-2Dy-m+I4@cS53O?V#09M5b82v<# zKd943x2GAHWp{@CX<1Eb4(*`SID*fZ>P1F{>UiEE$#L%R;iTI+ppDISP-F`1MV{sM zWpnQEavTnIKa32oW9(b+JLJ;e0bP|+dDy!_upg9w?S2PkQ)~5M7$^FG4!>hPvJF7| zI5uo~$`cEB(i3^nL1XVO=~<FZR; znAXe>)zF~IBIQe@zgw_}#s;t}A1txiZ6DT} zyetYk;&sP97a~tT6PzKIAwD@L5@w==>!fdk+V&Lusq& zzRDe1*GG8zQWf%Cp{CD8IQT4n=W)r($MAeU5V3hO;UT8LH^%w z@@v^UX=6KaFZg>=wxFvy*q%Ua3A)DfSKC2fJ__3vqa^n#ZzA-$m9(k<5{$dyO1qrJ z4g13@8I#jT|7zili5|~3mAR5f&L8UAXBT(8yn{~cP(zs92HA}_zVyrEDCNhP@Cz>H zFuf6oZ0+>Q>qVRjg;q7cF@&{qC97m(Y*5zA{(KDX_YifaA;a*qM(OSUo!)vz2`+I)64t%CZc>9eBgKIe3zt zi^$%-(c>L{>%t|Y7{BG@*{dF^6jf75v6?6OLcwOSHSk4JPJ?VzXdPw^7$BWsyO?&X zIH1Sp7_9m9fSb#*BvTJZ;;ZcyZb3X-IpuXT3|*{1XL2uxuv-UW)&aA zxj6+aS!9K^-nk+*?ExQg#FIYV61_7;H!GEm2com^##l78r+`m8C?!%&cs;Fn?(bP> zw>{$~ihl?<9vWYIw3+kxw7hNTFHkXs7JQwv0B1L~qKA2KBk^wL zX^{wno%+0k&{FUw1Fxr^VUv!#(C>&=>i?R!-tC?Axvx5CYoeq2LVMbEUi3G-4B#;z z#B**Fh~8%AT+ww5)UO@F6UP#!{mhSMj=M+Qk4bo0U;s^8|B22_`%pQhNMEod(=qYl z8>VuoKbnT+Ku)89hlv^WJ4p@aKCYEa_@RhW`8sqn`O`TH{yv_s6JIm%dNecw@?@h%*oo|AHik!?V}fQ&wX2-)>TMbi z(iZ$`=hM&+*N~i--9cW0uhjU0Di({Zan8d+%0H-Id8qy}xr<$Hl`MdHOtQkL*a%EJ zkjKw_Nr3)(1!+*9ST^rZdpfse1HI5}clzB=9ZZ;(iXYmWd3n7Ko?a|~&fH}7NbGXs zcXh|NXIprAH#u~pcf2n83_DD>z5*ld){VL&eN@NynH3L|u zA#12ebVdAso*%N*!Nt%Nv=8sg4gL(p^wVY7D*6XKJA2cMd1_cNYXO)2o`!4t4`6+8 z3hNN=LC?M&rL-A?`DuwYHq729^0_vZdf~QMA~K|!3d*$Mr6o?*W}xxQBmUrr4}E?A zm+s~pOUyrN(6Qd>R*V+^X9#Wz_W1qZfzF(q zUGbTO;xo^--Y}(!1MxQ{9X@XwxpuY@dTuXAZDkjhYokgfV+v?Z z^>IG_mMvbm_@HKEgKXT6I;?%rUwXcEA?5UR#HW4YW_tGlZ+e;_Iv*9JT7%Ttq**4I zRhR;+>b^8Vc{yRwWBP6WT6Umn09J(M{lCASofiK-GoU@<#su;b-zVYya14zXET+?^ z)iAbHk%ynYL#{d+n5yW{tXmw=D7yE5Lg?CwpHW{5^wP>V}0rQ^8e=i?lIkQ{f-ph zmk6I&e@m=V4}|}d^D>QX3_qM=QL(at?bx`A#tN;e{p0SUn`swO=dW}z%F`jJERO0f ztK*003K>3kBe@mGVRzSd{Oj$d6P01Ge`kuT9*NSDU_4FOEBbS%qOX_8pE~bgW`8!*f#qkZE^s_=XJ&$grbu|k z=g21Hnj-5!3Pz1AV=;^UNZIor9cL4`!!&mk~Y>{q| zh@u_6=#;4ujxS3>eQhJJyQ_~I7Y^gT$vuhwtUmN*Xa*@4-sI!fh@4lrTH6jk{QMX= zp9_IVKQc*P5d9qV-<)^5Gz?`4kx-ftC7Cf$u(cE8(d2i8UoY2#=aE#5^ccfl`?*n6 z*H+5U3*wgInT!+98pHvqimlunlX%pXZLUfB?3Ba<$X_Xxo$Y_VV@RltKW+Nw? zp*%Ah-Q06||4=g+EJ?+~#g`=8UiKrqxAElH=R4m}>Ow`|#m#heu`Dr417W+0u;@-Y zyL3x}eQ^P}kfxDCTF_*=N{R3EAtaS1|mJV7~@yVvqNW9 zC`l!cYATNM2C<*?*Y`%_n|j&nxH^ox&`+BCZ2`&uwMNy=2rL}Y$P02Ua3(7jc|CI_ z={Bb5I9PPZhWDi&uXQo6IR#2hnOt&48>_nJLB4na>*BYFHb=-|lz#yC+%#Lj;6&%h zfL=^JeH`uj8A(IV_;am`g0VI*94a3KlbP&b8Jz$Nk79O2wU+w+li;9s84sMTi`-?& zxOgu}_9sLirQHkLZlg*Xe$>3;zu7Lob{w3|_aL!)J`26Kks5}Skh2kZ=`-PrHWfJ_ zoRU3xZiA+!@om{6gFhQ+!mDOF)WwD;3=lhv@Vgo{6*;aFT%)QhCoxZMEXlu9!xi^@ z>@!c}53-u6TZTIJef47vbAm}nbl9bR{w*6ojxZ^X!qV+J?BH={TDd_+r~mo!`GWm^ zV@Et9rf%mi|LEg;Q!3O-_pyIn8YtI)84i?R%QA8=C6ToS-bdrq@W< z7Vf5k*B59`|Fg2qGb9Mx5iM8*p6pVdJcjmLgf~w2d3%w0iAg<(nHjpgYeLhWOUM{T-!1kYJd`ci8|9cER zn&+@{s{WL!+)Vyu4*YjzFm>+tjqvnKrTk67!ylQBYd_zzmdXvJWY!LHG9512s)Jg` zav1DUWd#>|V3XGftjucRBL!bn9N(~g$$8nLY(j-UjWimt$JspwT7%03EC$O5geWaPbq zZ#&x$=UFCnKCh5fi)Yn;O&NGnXWHi)OpBJ6(JDJG%Uw1NTmBq`mf;RovAUk-%{Rc} z$^vdE^7~DFB4MPNBg+vx+t8D#Nc>dJbU!Fz_x&(j*MG!&rVGu}rVNQol_mLKuHr%X zTIs8sUGT1pJxXSK;l_k_l}7T{XqLE*zF8N@{tdUmw&&p}@XO=xD}hk`G(`B?vteQK z)FZ&19(MZ6M@`Vfq{d`Ss`TK+i?z{CO)%T{C$QSuT5>S*z=Sh(e6p!M?(gx!#AS|> z7_~a|9Nt$N6w(eK6|HgWXBcuG`0*EOCD=SK1$TRfu<7g9(U6`^G{Yo_Te}FRM7v+~ zOVvZBD|Dw2#glj*bce~Exk;`cHbC;Pgx~Em6{`nE0Fg;ddw@19SF9HAU(H-D%?8Xa z0!-hgvLx3Is(uL=YTS!%3MSsKE{&9RQiWG58o)C!4X>l`OJ*i$(8Y@>^n7CtZ!K5H zz2ht zU^6Jri-M$wkHmfZEi@==N%h~Tqi&5cq$$bR^&yOhsF)#pK^_(#AQtWtOuajNrTM!z za~(Th(w+E~HurLuQK{y;hP%{;(+wOV79 zdMFNLHOk)CHsI+#CFzVW?v$@>i^D&5qWniQSFABZo=YkYbuX7V8ye%r!EAh6rbO|k z8j$1JNNX$P!@^bZU}Px{&Yr^zUN0cE+K%meo3|EQMLyL@I{nH{65QFDTo)(Op7jy@ z;av;FW^6-6f!HUAIrQp}44imU%~EDH(H~2DyqHzT|5}Amk?ul?awpZKHZNfB4?#i(7MnbzU z>Cs&~#6C*KuhKwfKJ^wADwse;t%k?n)q&?g;h!C@&d(a^z$05^+z5uh%GO4T-mnN) zZ|~)&ZfWDbRI8L&@;~4rkOYmpK4(E@OIjWvUVr#K6UwwNVzN=|gP3*ynpH`a0fWhik-sQmut5>;*UD{U{W=30B^t z5q59lc2n1m;`=i*gN=?;L0okaEQc5J)s1o@d#D1T&fcuF!X87r#h}{0hD$q+gYA$+ z%-$-`o}100z_{Xe4djtq#u$1&3BShaaT_~xB&g&;uE#cZmNpWazfw@74>!zI#DXJ_ZFWY zeJ%-R7Ui-jPG)dJu3(KFWeP(FA-zH590@(lkgucg>07Os9R^C)O;CbLolM1H zHW+6a0*~u&>h2x8PRifqAblRqsyd0>v2HtX$hMOEd?F-?&t!+KSi#E9bbR%4IyUh) zA1zp&`kQiKYPFU}S&TxUVJ$jeFJ|s>0raG2FN8l0;B}2Qm{A^rCnk0hY;VL*GbL&K zwGKGeW`T1R|JD4|FbBl-D@2&bR<^V4Drq{~;MRp!{@7I$YXlc!ou?9C5U-9^&&%-6 z_A>K%T~A4)S3xsqKmVOE4Oz{i_p8fdp7kRz=+qLFerx7SPFh0AVVlriTGYkt5L)Py zd)gUalZ8&$e{vxZ-^vRy3KmACf+zVxl9?$_*Op~dO^?gGaErXyhwl~lpe5Yg+!^x} z<3(S{nZ`jWa>KVGecJ;*b&v$Zza_PMluoPO!nxf>(%IA9v2~>$22W1M){QIqDczP@n4ukXS2I-!p z>Unaoc@f8E4lqH|&m>GTE8`ySVrH?)gTCoy$=0>1;&zrnwwJzf?F?nu)fVF1Q$OCL zgDU3B4#L*9jO|RUn|SZ=;n=gS06UTf@$6fwkgF2;7lI*hCBp_L?jg8+ z(TZP8w15{+#j=KwW7$Wn5jwI6$_wAIZL3G3Ug&b2+-~!KRn!G1qYMUp+awp#htj*h zWi(X%0B1!uIK4Ck3*#GQ>)RU8{gR^8(9oTX4oIM~Ho4tTs?y0En^&eFenFWeLhQ$m ze9T2|t1<=6*F79I(O2rq z4+%c@xN4-!b)=3e!yr3SfdxBna$m2>=#h{By8-jrqM|7Bb(WFFOv|CvwV>ho)Qw zjxWpO^Xndv_hvb4*c8dSikeXW;52o({zEq6zLP*nW#DI(4x4}1o9qs83SA<&LsM=46>*+Wt^wI-@r;&|j z0)6;$fs_ZFkrfAt9f({qCd~geUuU7FPo}95wZE1 zBG00Rok-e2`6ch@tm_nR(RDMa=zb;B=U?g;HtFHeq5|l3e8-AS*3+T74jA%Foxc&g zo#eU45wlN@J+Zw_!Lb8G?tDJC|0}owk&!s@{*0`~&Iy(+A`>n69(ymm5>xsl;>!A4 zeD5qHT=Uq2VJ0K&hTPagDy?!Th|FLI%T+Mmu@LwFQRg+-BR@=N3PD_wXr2 z^qa+f+*MHUu>ch>y=1Q%G?2LD2-3Rsq}z4Tq^!7~hEyGq4cP07z*nhw_brgE4(y45 zsnapP@&W%YyrNh96Y->bne6kB(Ky#ogeALAvS$m!$otqA^4==;gfopWF#ix1H4KnU zPaBTU*8kP{FUqzERtd(nWpC=*X5S=ymcuZc7`E=074{9@Ch{gK_{9-c=y^eWev2%{#o75}g2VmIQ2E--O9o32cOem%)+9^jcD)6iL8GM0 zTj$`%e0}t(PeXoOF<%in5~Fl;vFxQ2i;Z7Jc{#u7T2UjvIX-DbirzG@t~WnL1)g%~BZ+4{Vx!2mYcmaU`6ZiYW&ypFT#;RSNiyNU z2&&G_Xz%SWUsOTP;zH;(`|%&gl#s-#ab$KO>y&PTVaqmP!s%=Lo8V?NuZo0sjJG7` zVm)?l5&ss7>Nuailr{vMqU(AkvR}*W@b#Y(p=cS$ENmOd$YLULKR)Nd!&cE-{omBu zX`xK@*Km89xGOB`)8JJq3Vy@7)-+9eKn?)v3 z*S5>whO;ZPHQMUZD-2KPC-1Rn2Vm(`fQJ^;&3F$MW~- zdPrgUFsiSxGwn4DW4e^%MPV)cimxd9rRxh zf8K8zQtoZV@RL(1W@;cE?N>t!R4Qcynh5WOhD82OAX{>`fs_{ry~vV%yjevbZe^*^ z4^`tmn#B&sD-RVTIZL>BizW?ogPlPMe}7C9T~!6!s!%F9+S8V}QxI89j^J~rSm64N z2wd%B%q^Br!k&;!j6GVzDr%IFF*F=XeIM{*zgW8T{0*Ixe_Qt{*#L@13h?&jJLVBC za<#4&;YoNs?=@cNdq-8``j*}-Qt$=eEg+;`Y37=Cf>(Ar0`g>+BSLl7>s7IUAMQW$Sdz{cQ#O!1HhnOKz4il`|5ImH-r9Cl*7k`6C>Yk@Jp zbJ}$^7d@8I(85QQx@sD))?P_1J-$=(!iu`#-BjSr_QBYwGmU*GGDbCna8%5dSLSUb z+YyH-C}o#q==xx4yKsUcbI0@OWyZ)<+ligcC9*EROp!7_3t8%inQCw>`MGxxI;Tl| znz+#`468-q@_`bC;%g|s25B{!S807|hqKJ&6vZ=bNcqrakPlZ&Lz3&ewR(wxK zuKcf_Tl+bQeR~XwX4J7AV;CI&jfaN!9ez_Ynzm$KqK9*@+Idyp#O#d*(*ELY8I~t} zY7bNK>v9oi7e`{URt{ADIEsPyI{ln96R&SP6IP%REqh@(w?2 zYJo||Bd{bhuda0B85*=v4vx9;tf>1kIyCzvRZe{ z6GDq!}4?KII_s(o1&# z({jqz6&!=Sp?t_au~!*Wiu?h;C7G**jy<=SqSW^BJu#zkc5E>2mp00V#WbSu(J*PB zm^n1e+!S$H@vxhGji;^`8A)$a@NZGM#me|sF3*0Xqm0f%xJoUrVkXG2tCRxVQ+kPL~*#d#4k+gi%cUqL& z+3xyqL+rj>gWT;>+CFv|He4!0Qe-YSjGBnRE}OtT-m)1+cCcC#2W#nG9u+J_pn~AI z%4@JR!BC2>lF@`-QM^|leXMp%h4=Y&yze$WG+q?>fD04ZS;;EeZ2FVFulD3U-piv* zcoX&|kCqk9o{k}7x1nUcE9LDP1O0AsXj6#h^DPMa?nzj8dOh1Y=QeGdVT{7HHQcmC z4=To~u3KCH&np4fMV(a);d@8B!sknfamZ`xc>Nk1Qq2bWdti;LVz1haj1K^a%uyb`Y-`o^TV}I4q$g1u#^Hna`m70YR zyH=)p))+BDhuM3Fs-3@6HqDpG!Q`I|mgX=5JqHyad1k)QI-29DzeyoNaCGBha4vKm?|04-uk7-$qcMSHUR+PX!FTCyP%N*{ z*T(sSnOLw&kvAR{JI}ll+}v`J#eHg^bGgfLN28kecA5yugE(vu??{){wRDXOzfY?s zKd32o?}}TXa?Y$Sw$ns(jV^-C$>B6`o-qbp$-uU0x4HeBSlZ(Cmlm}cN$U0vqu~?x zQ2zlJxHc(bs*lLTRPyCUn>?_kG7+D=Z!pO+fh&B_2r zg+^=N%p!h&r7jkG(mP7H8pmxcRAKQe56&+Ka>H(7 z&lz$U_ro8u#&fnfyCx9VJuLb9wKMQ@zqn_mm$4@%;@shmyyfB5Dx)XCJw-V)qaU|3wdEeOemu!BJi+ ze|8o%T@smJJO-I7E^)74mKg1}OJwDgN$mAU;)_KV3X=-?jW22lzalc5R?TEhZVbQD;ub$?Ae+;}h3eIl+V?Oo{6@q4`Bn_hGUY4m9HAxpt4*7Zux?%J z>BSgp44ry_pHvSg1IrKe&$26Z9oA{0&8rv=3%|0_hlgX|u)Xm3eT#QfnT@2*+Xai( zn{9UvqM@vsj(UTuc-kVi-&PE`e_R%+CHyi+g*$3S3+u5*L9ozc;jQ?HSH|n%vCzF2 z2AA1+30>R`^%`9Bky51aCoZAxo<$=)%y!M>sUy37;Oc@f{?FT68T zN)h$YRu-n%1RuM8(xT<{^m&d1`oXanJ~EoqtVviZ*bz^MMzP|qF{FRFiB^ws=c>5| zh}o2aC;yJ%H)rTWbAaeE#>v=YPrW7f~#wc#x zV>7K1^QZHHXqiT|BfdP{C0O%i?5W6_uQ@HFwgK9F#-<0P*g7-e6f~|FxNLbm21y&A##|Tw5dXQw#caRTO@1jrGis!d(m-JM;gILBj){jxWz7PP;EkDVs?C+B9vk3_MkB4n!1%@o{DY>E^Lw{~ok$d#Wx_8-)m%qlab8g1a))l&-?Rh-)n>Cs*?}DX@ z0h>Lk3wh7;rl6DGxPh|{?B8U<@~k;;Z1dqveH;ZV8%gy*TbBWT|a zNWZvA0$D3IO&K9wHK!ZwjD=69XNSE%>TzUT3|H z;jG$jjC31B$%jTm!7m?=jy&NDeu`O4t_bQn&m?}`hf%qG2E|`F%N?{7urIv?^D4Y} zjglwsec1)4>_&Fkb|a0Qy`LhN_2Wy$f4eVNWVa2Bm)za=5Fd3cq@7K?u++j3?pIRK z#J&e6l&``M5zbYk!ST}!(+|7gFZHmy;>gbyW%YVOHP252L0vO8vNyTkW}Sfa!6 zaBLfySGQK-JRO`NhbhXNm{Xc5j^^#a)3e3=U(Ix^n%-5qY?=|)91<@K0VpeoIq zqzX@wBQxsb4$Pbw!vAR7Ls{tDjCW69rdk0MJoyQ^m4)+FPgUV8$;0D~19{1mk?3jq zUp;TK9s?2ji|7AZ@|i7CWUSkSzTY!gr`P6~ADxInrt6M5th9mJs$5vC{D)l?Sv+bZ z_8`FhI{&#t9gjX2U`+g1$*-eB$)Kr#N{&|YKQrv1`70bNB3oq1ybk7z_t4&p8eMv?zeU!RaNL`%xqyZJP*4js*=aDWpw9l3*9b!(as*ZDlNj7C9~KX zC4X|w>MXe8v3v;45$v&TXqw!Q{Y;xeL-|h1E{)`UBScR9ycjq;=!hKH2?#VPz^Q^d zmMIITNgWa6Jd$% z4rLf(f6y*a^ukjb_O;jc=UYT}UY}BoPsric#p5wYPJE8}E4E*YaQsRvKBVsDm$e-c zeKr}1r#09$TQ9OYSxer1Hgac?1s1w(7cLvG<;vEEFy5StHGg+9uLrBizTu0Aa9hCl zSt(+c@J0Uew3SsaevC!m2TLPkTgX4x9_}Wa@I^b0f7;>#`ItQ@7g~#tX@2z8np40& zDWAIB5UV<;K)redKl9xH*X?rgwpqpw1%}XJ&p*^t-+^b*Dm&u4n{*Xrcz^hAP->?#oiw4Mf}_2?pmh^ABcL*gq~DUjt9e z@`UE; zByaF$3ywLUB`X5cMb`X$;p6BLS4q1jSV<1O5f8`j2eI7g z>`at+rQqq~K=xsB6MdPj2A|Vqyj9#xXARha=6xkHs~2J}C`iYh1N+&lsA#%aAo!w3 z9Jy@PMoOsvOR$@0r{CocYIBxJZ+`EIU#=pH(=7sZn&0Yj#x_x-$Y)WS5zFrXH3rX* z#;J*U+~<)E4Cd~F@gIG*+_wuY+3!We*M8;JOLd@pY!9kLMp#*t8t$&igYmEwHZ<)j zc}o{yMUQj5aQ{5mw259lVy@)0b1R;YRFx(j>WVGBO%PrY4gEgr_#xp%ou-h6?Ilqx zJ-wa=$t=2I<1tG}=g1%OvykvEDIUk#*vQklpmE(Cr zS4G%$EWysnJ^8f?ZM=_h!(X>Myz03n(g%k_`DkvPn#TpQ)sjQBbQ6;wYliWCcfe$A zvFP9I5PcyZ%Z;x~#>A%(Ws$n|n$I--E8 zStVaLAc6udODVDYK-r4SRv3G#N)6U~k@F?Nf9-mn?5D`{*E?;Xq#`o4tIH&t`q|=g zWe(n0s?euzzBK#V9eONlmHm99fivP~@$E2^on7lssp*|??r#jAJ}8Qe@03&2N`1*y z)v2_8Wg@*>9L0xLn+X0*3?8fNa8~1h{FW^A%Bf}jtGCdW4kD*JXa%pl5k)4mzR;t9 z8+G4Si#>yH0j?x`WTtnOFz0V6W*1-Qv&Oh%XYKZOhRmVk{V?H$6D|&H;YP+HL+!lq zBTTK4rQaF@>tm^y8hMY^pAHw^rU&$Qp)Fr2HNqK%d|WuP*RFoobzHsdBF$Uylpftx z#NC%A&42Es`v3T8D!E^PO(rx|Y)Swl~wWb^4)6!IQnit4D zT8z-CG#?j#C9$2)gg<4{M|$Nums?L$#P=B`g5_Z=dmj53vzrD>$FFW7$07Ep$%x1P z{8--Vwv<}4s^~&lvczbq33RN}VP&kzhlhw&ZuF>^w-d&>Ql7LT8~e^ zFEk$4cHx$Ks_ffu;X4yt&`t|KGW$W^l;-`6tOEvd*K##99}^7fCwdi5civq-v*@oKFXZ z_EFM#54&_Yn7;k~Nf~;-WD%zgL=Ny#^g9#GZf$eKOq&Q)zOLf8(l?V+)d?E@aJC?MOaRbSau@LRJ@zfuxZZY#tX;5z+CtTXBx6HxvsRlrx(@QedSlW z#?qPj-^jQJmtAgChhcOcmMlqOo_nuR*M;+i{{AeVH)}3Ni@H>%?JoJ1&?=aYD$-P| zuGqNQ6b%;zkK*<^?l4Ot7^11|wS9GCBc+>Iq4sqvx2)2^pNicmo}$42d=dT9h61?n zKFhS`FQKlZe^YSL82;wl6yYg|L%@+#*72~W;O2Q@W%XTN;B1QKv}mZ#(63u(dxFk8 zC;+xQ*;*@8s8kBRaYY0FeBThu*5=@@^#e&x-Y`0DoJK2ep5_CUh4=Po2_7ad=F1f( z;D_OVwY_4HROH0QqVKdO-d)}lUsgvWH!Mza?Zz$C%j-z}il?K$p(!lH4D$I;3EwB? z;+(Pn_3(#WHqiTBKd4S{JY0JyVcYg%^w;aj6$MZD&G9)X5&om>N-L~#4?{~%ZrxAs zOY|*XuHD}hpK69>q9?pqU&Lz)cZ1FDDm~Rrm$~-Tpxx_I=y%vB?yC|;eHQ#7$-2X` zrVqoBnS8L%^%nmvu`d! z{H%w3P7fWCQJaC})lstZ_qAaXPzb;CpP6=qig^FaFfQo^zb$gj-j8&`mr*Ue@Q5jX z+C(GYxkff`a0deaucDpg{OidWL}voh)- z7<3zoMxo?rGVax{;f_^C*gHb}9t;!NN8gonT>C8@a(3ejUn{|WUNL55*~ogAJwbZe zAnBHq_o()pJ)D=tVd~&m9x`Jp=AF#It8Gy%s$ne+xq6B+&7HV?<0y=+Pe$2*5&Yaq z6FmEphmx$5?CTIOa&3A{{>4W8w!WzU507GNKS#-f$M#gA7TTVFcYe9p14M2_+p$sn z&Ky^Cb=-|IhZ-g?vOj)0g) zCLg}ZS7w<)`C2NfJ(cYay(^%4p%pQow1)-X)fFO$TW)2cWXI8@=^&gpOr69(Ir8_4c!I(qzNy{c&3NGaj?Z?3Xb29844cPC(u5?P@ zliptY!rRJppf+DH?H{e+`&Vn>pUwF=nUl)GrZ>5UI)Q5Nr+%-HzMeEQ494**u=fZ>WKa}17@G) z`J%JhIB-YwlZ(%>^k@Ary;nLWOnk;Kf14`Um2o&3n#ODbw2Y0exu^C!F&j}rl6beqUsCaOjYo0b0IaE>jG&xQ({=zNToYj^-448)g z!;D~dJsHF03b~$w5zZqAXa71gsveGv>w-0r+LH%-9f_%Z=ipc0JN(j}1mW8`K~Mhu zeEgp=SLn_uIiv?}X19DT&=j{FLA#2%|F=D`^yw;{yGoZuwW`rcy=0nZ_nuFgA$02E zZCXBJ314+W3t`dwP^(ewk@cxRUo~F%${*EXRpblS zKgR)%i^4>Hu^m7D+yz~<#M^x&pOuK+LND(fSYf;7*nHt%KvOOjuM&P$BYk96>_M~r zP40G2+)4zKw%5(ik}v*pRI8jzb9R?={XP!R$=?X~W%pzU{&B=KY{KMY;vF}PrQLGp z+I#ij7F!IxBeJJ|lu8_9Y;d?d6W<;y(cKVTn5*takDd8^a*GD6zvsg0vnwkJ@TcY0 z9kBnG$ZwT*hspCTSe@9HHSnplq}L8wG(3`*iJ3QIUlf9;kK|cd3<-Brkhrjlxe1;2 zm~DbJJhFz*Z;7J7LGP*W-z#-FeRNP{SP08opPB8i0BXF^LF8wtaE)J{*svoJ{`o7| z;PnIWbCx6go9^+$u4edI5ruJI_sR5R3?Z#4?K_#fvBU9foX9Eu_<$=f7Cxr)f-&;C z#O~zao5))_Nm|Mu(_^7Kt1|pSj+fua*3?YJ+f%Vn?E98Inh-&cR_~)CdM+zGC&BU_ zTQF~o5-UgwptkNZ`o}h!x0xEDu9LVCYpvny1k;io%t6P&iEKXk)5eW|$j5DK-KtA- zkoqbCKIX3E5dz#k5{==qD8A0r6`e+BV8-$&maKAz_P^J~Exk(KubUALUQH5uS5wd;~*m9VC|V_T+JY0}Zl?7Cvqp42TGYL&zv@ z`pp$Tw`X9_qkU|X;|RwLg!4f%uaYJ-*+#>upyt=Q1!!b9+q4Q6+C4uH)6NJWSHpN#m_jo>mCexzL{0d zt*74i7@Bhqal0UOcnDtfqwM*zxrP>~aXx|Ss{WJ^=7^o;8*wf$md~&s550uVaO&*C zUQu84{W%$rcen6A?=9hwyB*0BOJ%xaCD^n~-0vXvWt!`Iz3mNwjxjQ*=Y|ErLYQ;G!netf{r9TF` z$CJ=cqR%QXccamhJll6NCH{f~e>ojf16J??BW)aP&ck1%vh`8#se?2O(GgGh@SO`# z-){%H&GC@rPPmPM7Y9j4iHrev*kM4)W>f`7aGQg6aQKjnCFdj9jdPJSPR#5J`6hnZ zN*5#2)6vu<&&U4KMRTHH?loLs7kUqXr(pGO@_WWroaW%#!UPn_XR=;J!PIGf1x?wf z$4B@l+Giq^k`d^`e;2-}7ICd869kKXNxES?Ggl9!DxFVsSU-w4B@KtNVG(u*_26H9 z#B9=kHYOA|aTl32G~`0@vO{j2;r*+mRxgM8dz)F$Yzw?g-G+Pjin!Z1Q$##XL0-QT zk_07ndZw8~H+#P0FFhluFtv@=Cmfdb_E$sv^m5e1?;@!X58a_TEpnr z$)9v(^&;8)=>}+idPwLr9q@k>2)SKke% zr}^APNeizp=fY8O8vEF14TVJrA5&}$zvj6>FiS)h`I!Oi`?zWJ=*W(CF2N9yW4m}m z6o#6PyW2nSBOz{%RL}UG_`N8@rJ@L*)w8*J$9d?sbep&% z{$j0>W08^(D|UaC{B3Uug2yD_YJeguOIbyS*2+jJBbwJc7(-KJb9ZxI%hzl(L$J7s z2UsRE;};=h-1v>AmU?oJn&AkaRD@MGtYtNa=3r520<=F&rM~-O>1y<0IwGl+U0&Zr zXY_>DbM;={ed#FCn;nL3nyjt~%y_f3XPC`DmKEKHg#*RYOyjp1O7{Vs$3_<@(V{o#rnfFhz!Iljn zaBw~)>u{(6NyinXR*ehj&`L|Bn20>}(e_5T$4|90?$#5v9 zAB}n72&r$V;JU|h$wy~&tB%L3KriO|zAx@Y{8#5S=S9%^l8bc8>}}oO9piC5q7*M4 zooBI|6$EefzdElZ(Z%<$0{E~llEQnVFz8P$mfoLDe_b3fbVV?ZocUO{_xpXaZxfkZ z!Y|VxKL-69;_+SV8GQYG=+gWHbS`?T!KC3LFE^{7&V{&I6noC7e?b+=LwQdXIepT6{U*;JL8--LuTIu$ZJP(d#h;b zs&I{zzwVd#g+|cfLw6`BFOK&drHhieX*l^@j_b_O#ex*!O+I^$$#-8v4xSxQ`jdD- znj7jI65z2QlWjOE*u1wEiG9;u{>8-{SM{S{U8z?$f8j}5c35N(%eFIZ6K^`3Eqdl3 z-MCzVIh3l!-Eh|vNp++GEw$K1-P=y^Kb=)D%ApA5(>?j2)=8LSD88HX>R2Hh5Na5U zmFI=mQg~;|g%2*}O{^rq?-tH<)Rd~+alz$mV+3AFLVZpFS9)&)kF~{UyXnfT--gnr z8(%4MUJUmS6rO^D0<`*d=L3i8;^pdDSewzrjS_5da#;vMzvt9lpKzT_uE>FDC$RMp z8F>xcU>{n{4^A^jrKk@M0VgC^eTUPm`&;NXp79+~ns9rO-QLd^JTS!FPls^*=3X{& zpCdXLgOcb9T*+KWEw z5qEUhNF%kr(a)XpWd=9Y#NT)srjNbBUbs8KtH;Ln9)3cfX;9j}9ZnDPSxsk4WVdWZ z{m+%hd_?ad5q!nP+a9s}@X;9hpakC*KjGB}L&XmKD;;`bBMB*!r&B4}R2Eyt(~mpC z+b$HQ3+~D43tizeZaZGAy3XESbjF+kiO?POh;JS)c%fcN?V5I_$F`WZQ0S9KD^d9m zJ;A6?7x~wD+-90Kx|HSO?zm}eyZlO8koTMV1w`_OzFsiR-huOSgV=~jS6UdgtvwfS z(G7Dfcoqp~(S!Y5C&lUODbP@?W`#|SWZq5WLC&idzgs=L;b}PVZ=~$FmL58-D-e2) z&uodvq1(`-1Y56Oj@TPrxw8_@H$}E-SZ&~8)iu(yS}CORw~%FQm~-CviK9< znb3L|hXWHnu(c=bq3suqkm?HVExt$V9XG?iqav&5B{XI$IUT(e!-t9-1eJ~_DX<}1 zX3=Plc`dm}-kZcCSNYRu_JVp3p25?93H|cc&t%~cU$-RpHiEu(mv)(Zm1eX?P;EsO zX|gKW9`EVUO-)C3XcRj=tT)Dn&BBgb_qp_r5o)axMb@SYA0hrG|IExq$i)+Ez=kkl z*QSQE^{Xk~EP@vZU2cX_FghMEkx=W~(S@dp1eOas$|M_$^!7rVP` z2#U{+#sa}sHRxlD5c^Nu*} zEq5xV4Hoj~yEc=hd1}FBQ8vP}bNERv`2TxL@Z^;j3#fI*zPF)hK2*tyP9%v)j8rxC4MThr)Xp4cGyHUA!Gg~!cEnWE1EdD*G^4Ut7_@$Kv zpBM9Fi*$5A9#!~vU1ypw))}4Wh9WgAmXGf_1wF1Mpx3yi?6Ge&6bKy-;UZb`squI-y##qL&oR3ris)yt8P7%TTeW96<*xZg<0m@VIhq<{ysQ=n-p;19 zKMs%!-GH#zk9B^t9?&ffIeZR@V?jU0z-?7LroAoU6MIFIryxt#UG$SoweCU6qyDS& z`$y@c?qyngozD|`SHETd)%m<%pXl9+jqUwBzD&k|ex}vL z?eIcw6E0+h^NBSKqsJy=@kz0(39P4=+eO}(bqf!=7Ekp)pGhxnm2Bi@U5sCpk5?6E z+46XQdVA>y&FnpfAGdIaeA#BaR>@?;=Z%C`&qacfdRO?%%yBFv5~I!Z>h!`-(RzP5 zG+o}#PXCOg)D3rqmv0zP6#495wDKVD_(Y;?sYplnB#Vru6a3^U6{Ku0M31^fTusXZ zu}Hw=l#6V(yaR3v4MS$~ZT?TLc#D@uqC-`zWVKN}2F%isrmS;8YLXwtjyX#&N4Cg( zdRxI+_-jHXlUe^sVo%=VEA26g;r(4#k=p*>)MV}=V?sZ<&0{7M6-DOb5L@(~BHrAJ zoVw2UZji}U!CnqcV6Oxxt@-=b_J01xKjz3YO~J8GT=HW2a5`6zK!Jx^xgyhorpSN` zO!4LK{6`92bS0+h7qQbzop5bj2$WnK`S_W(NG=XWxQD0Y^uww!s6?*~^r8JC4QI9T_~Ke^oGZ=2Z+BOw(B&G*HO)k}%>$l3ZYrwJ zMq%WJuI%-m+2o(Rla_>weKlF2vt1-YO0>C#zC8wsd(;0ts^?uAsLey;`EX0DZIKLKeL-ks#yND04{Sc^MSq|&^xjjJr8=aXa5X>wyy)8uW#Y$ z))x4v7m42n`(zp~C&SQCSFeR0m9$K8|;^Hil&Fp>`ir&uI=qf4IKgqgo@h5FKCbr3Bjm z+2y{|vH3?TVzsK7%6xSUk_KUrTMNG|7{!whh#ae^WSL2o_hiFz&ScMGw9rL23wx@U+n@}t=t>RYd z5%f-NFKyXvE!o)OMW$W<>)}%rtk7%o7A$EI^XWsO+ZVIa|99`b;?`17{9T%F@51$8 zN6~8qq38U)uWpT-4!(7$#EG&_lpi($ul9r?dtf}jrS6W%=ZUy*V;yU|5KTtYWt2B% zB3}|N_%K7ZpwO~NHq2=(%F1)`ekEterzpWcLvXRiJ>tLDL<`13Tf2TnuG|sT2|;jl z{#Z9=&jcuJjEDB`ugv0%1aE8Oad>YjxBl!1`-5q4GBRa}XL?Zh5iRKjn!>=ORMX+Ys9s>>u>*H_<9y*w`yBz<7u~w?JPRp zDHzv3L|=VY+$OZI@`x#x(2UK+qC1ZzrI!@x_lqP7{>%As2NmS)%Eunx1>84t0pbR3 z#iw&uSkw(0j2;n$cWxKCyQKwsJ&eH8m9dh=VfE-TQ(bzsXbL=p&t~GiWr6%f zL2;KXwTn)oE4yB@Ve1rO_qz}hC7ak#*I77m??At1Cg!I(hHD1G=T|EmbTXXQJ+Gui z(FG<0HtXZx)dVDW__2~ddOXi36Mn|} z=&cOL`O<39jITDRykCetJZDPx>_&QLl!$JaH{`wm46jbauaMtF>L~XSfAoV&=RWq^ONcp6@jSCrnzSahQfI|k zP^*5*E`HU-myErr-LjKi?=!(^ivuwIFNZ|yY@rIG9_pNE%d%>GsNL_s^!=Koy1&;Q z@Ot)c+*x5mx9&HD!Ye<#pXAS~jJ>Jfh$?z|VWyznbQA_QEyvkIUCef@4kT>TvFMpB zlXK$S`xk`>TOuMmLfWX!zePB6uZSsl&caIWU!Eh>5ol{Hpe-u@tJ@dvM^hcnRSUl2 zD+*q|oY%=Ls4S}{#-oDi>dsc^Z{iHFOMlaC0)sT8%Kq{65>=Ekt%zIP4V~MU407Cf}zBKY6&)&76TB zUdDX{=dZHAZ9I!=O9sSuPctcba+vz_dHcH81!R)kY&1C*!c(P~g}<7KuMf)+)3t`^ zE?kIP!vdjjw32lyxncn4G-`~KA*Ng>qvu#icMc3<2f2TL_!Zv&AD_)$@g87nSP|0I zlF78IcW9I&_jPnsv$(YixN8pNC2Nym;kVJ6y<9kX_#bLE%N$=F{m|OHFW9FudJMBu;!cdnWVD^t5j2kpIj-|NN1Dyojd8H4gag> zU0dvso*4nj_X`DyWo;O&HdYv@{)wIoF@fWa7<^ODg4~rB`WSl*ev6RN8=mW&AYk~@~o(91~Gy_ zn-*Ankrj?yX@m4#J~YI=krrO<6=ld1jQ+VF`KOl=kCJWl#fT?#-ANzz^p^}qaG#N6 z`B3J!m*4TvEJIpFJ3AyN#9pm%I8CUi8(rT*-OD5pE|x$HBqQmlGYvHS#%qx{;~MW@ znHX~QqTt5}85;k156yRd!W=3#(tWY_Y5kmHk=kH+Tp4lz+Fr%P=7$B8%L4F8x{XO} zamFvPz1Uw6C7|=vVH+3??H~`wxR@%>oc|svVb;mP1 zML7tkRp75~GZEffgujL%Jll`3nx;iqTO5n~L-WZAo>BkibtAoa_{dqIs}c6wWMfTx z52^V7JNxec)pmIm6^I*hGt0Wqg68lkoL!JdpB=4WyT@`?PpCiczP~4uJ8jPIzEPO< z{vyfy2{>L#L;cmm0;zFl>9;Xck@+l(q~*-v8SI&mPAq0e9x6fnZxOu65)%1(C%w}1 zgPuFg_gsUPBU3jD0f&c@4c7MbLtYZy6A;1j67-NgFC5|;itPM3Q#f)h<^R|A$5pC0 z`Xv+5N)e&}X?1MY9E_X3{WV;CqbU~j?ZK8_X(B(kjb20Y(6%-e z&z9|Ack+R_>DVO0Xo0OuqhJ$hz$War#%At|PaJuW zr1Kslb$~CdRz6@d-dZ?$A_f0uq>ElX=9(52zLTnXPdo=J;dN&Lc1&z$<4Wc5SDxQo zYKD?ZD+%0`Ho}QfT)XbW?@;pLkZ8Ros+Zxtcd&#||HewX;zc0+xm85Jb&Y02g}P|} zu@{rArA!*K^!OdLi0e%i>B@hzA=$>6knf9Fk1l7Va%NZl*tKLw&O!v1_@h9plGXpW z6!n7=uy&FJxfHX7M%q?TokLNqbpq#^E5_s44|z5(ehDU=IfN+A4W6W{hjAm=qU9qcaFV?>ICF8yXQ@y1p=&T)Jua@)Ot8@ZP z2JIJ}f42ZvY&fT@m64VU(@kNvHrlr#zImzeR`*Zp!r4~K zUif14$d7eF5(}a9APPAAfv7wez@a$?i)0S4#;5aS(H8cUvti$Om!o2Q9#J~vNmU&_Qmsx0HtgO)==b^Kc_Rc(-?$&#WsK0o^CO+Z zxyswMW3e_Rl%-@_;rO9ktY5gB+=_WfdyBO(rT#J7wOZFF=s&#B*(K$@+BscsOXf3hEo8VdBW@ku(ALz&=b=QMiw%x>Ci-oriJib$-_ zN1owE_WZRh#=Dim$SR-A+O!a!>-}-7td-SQJ79(ifA6o15DdD>{eROK-GB6;NV?hp z9Tzj;(xyj-itf_GHTr0aZDslS;j}mI6LopxB6@p!79#B{5ZT$>KTF&f=ZAu=#?0cG z6*O1HqE9}btiGp#&(+cRq`Kjp&LLyIzsQEGOfOl|#TmtOafe$>{Q}EbpUOg1O!e>Y$;Wyw;aRxx5L@3wZb?T{N2N2=IdB~J7-}FgI~sC_ z^90tJ=jcJ{si2ol(G=0UJRfQlg?A?A5rYKwKn{7_+B7#J1dOP#h+ybNI890=y`RabyJ3D~ok6Fr@G3l5) zJ&Y`KYp2=DGcj)Ce)h;)59O27us1@MIqufQsf7ht;88~s6TRu6#ZT$6+uH1VvOGKo zRG|HrreMYa3;O1oPrvTPBf%7Q-@-7~LWhOw&&Si=-SE1_^Bu(H(QM^|Q3elKK`WoV z$Mbvfq70GQTz&lVE`(^t8=`VGh#usb+kMGX*$oZe=PxURt8ge$>*0CS$%g3qeUE)F zvcTxFNbEAcA-WyZj*%NAgd@~l=x)x)+Ls#z<^0R6rdA)1y3?SRENyb7TOYf}7UAzZ zMY>IAGxc`jIT2-DqC6F@owog7A0F9l$>+iTs7$M5!XhWk+L?@nic;iy&3d}jrI;ER zhOs{@L+GEE+}qo+R`mUp3DS@AjQEN;vSL{{J#yg@)eW>~p4PLW`z{Y(*0_lNdn%8p zQ5A?T`$hY@nxr)rIx%lFh**{nD z_@D+lrW9h6bI1afAlmfi4_%tRj(s#=1dYJ~nB^)Iw9B;Pd&p>EPy7cuddGZx92tjE zt>J9NG8=S0$VKJF-6X^IA^jk$h00~UY*(==Dwbv7kmF?5Dxrob?1Qi93NgMAM4Kc3 z(y*tLy=_>IM4w1JD##>?$CbIK)fF-mI@!CBP%5igk%5bin^$k9rQV8hyEOqNM63zz|Ll# z%@I<-bS@a;c6bIxR$mbGT$oN@`24SiyQGfYtNEV*%BcT#CBq3%M_uNf;5Id(m*5cCv%7g3k)`bk`%9pCHiD$@IC51 zYaUc4-DinyiU97>)}DoU-tF68&ktR)!9lJm{nwLER2?*N zQYsqKN7kQvXgUwoyR-0ZUk@p$*T5sbPoZMBm>!#p`|nF&xALnXXzo<%YLY_*Gs>Bt zw-uVb199#_muShvMHt4tnQJ`iiQz&a?i%s=UP%kvF-;RaZ=+CUoF~}+?>z02nTm0_ z*+eaPE;1%%!qlyp^?J_1wT2?hJhy}#w+y1&$NZ()JcA>A(sJYui$um3G1B?Vo_?)O z?AJ8vztF>8?$>y{LxGK4W{di~JoJUul1Jlr(6BbXU%4S(MdVJoW76dWT<-f#cBm~t-iQd;>^#h@`RvYNZajYFPa_|>hAruIJ^d-QhwYEh z!rRJZluLUtqnX;c_?c%nCnu4TKAvIW*hgKsR$=O3S^VI-tl$SaqD;P*jIA9kY&2`6 zrCUsKvo{P2euT5>-blQ!)5La!D_njCjtNHaLsW1~zI?{heZWP2Ev57%LN9j5p< zFb>Yn#l+BHCskBENynDVk{SIJMrUP&jbiT9_KPO0lB4ipz!etE z`~Rf}(%^eU+QcZu0LNDsq9aL>+MHJ59G(LF7f{UhK9=M8efuyf&XrU?u>`r~%Nc`5 z*ztgsm{pt%vkOwZUU|@pfHJzjBa&GNwXpA66fVfiu!MCc&_foA%em)t+I_02VvL0R z8n$?N6rD8TGquU6tZRu=fUck%j~@OYqUQ^_hKRr8YWeQw>|-oAK1sOo;!pB-@KXw3%E({!t9d1y5HSan71n$*M@#3!JZUT`=W9B!G88_y9Zq?TTR{8 z+X}+EMp4s^|Eu$trtoKWH|IO;+{`T7)q&`J=geH~R=<^3iG=xP8r}7hPPneYhIFmKER9HfKATBku7c)H7ijUUjqkSu z=`OP>+T!kZ{$F1st?}TRaL-gSdb%#m%TqAH<_7C9$%C!F7@uMrlV@qtw6rOi+Kf2Q z&aa<|!O|sI7wO8TIBevzxCFFrze#-6t?+D6G}nIIW6#p{u`($Xy{XZHDV(qP_*4qM z(^588+7woNhN-xE1+m!JLq%@3m|6Ikz1t*<12c-Tb&MD*Gg8G`yCpdJuZ=xiW`>vX zVbF`Ms1r1H(nC)q@W(unWUkcW*|<^o@xFjPQZ~ej-ZT^rWC9;cc}jmJ&{EZxta?!t zE#kU`PU9L;dz~CYcJ9NcS9#A4t!(F2w7`F#R5RJWuDjW-d)cx_u$W`TJnz z3nMml(_(a9ip7Ra1>}jC7RvLYAmgeEB zry_iO{85lACrK;1vT5jmau)J!AzDj(U|@1j)YxK;8u1v|t6m|FP23k_z8eSUwKBmo zP0sD+*_zUM0v*01+B9$~XNG5!N}f4*yfy=J4#n*3B~`4bEW+78OGuFL7QOYv221%F zcyo9ePSbD*FApKNI-IEe)5LxqdwJ}*0R z_yL=3YyfxpP|UnmC7K)7hDI$JVfz+$D&NcZeQUzeD|*PDH0z+-JQoie_M7bF%z@uS zO0oK?F8zCkXVB~{!L!-)jqOq#d{v+RG6 z`8!94JsfC(6B^uWrm&B=4-KQ+tm^1Fo?$U^uMX@blaabLO|;Tz9-bK&Bb#t*lhWGVW!&5Kzeeh0a0|*TkM} zbs@VA7ol*I501DUVVBlBVD6`QIB88Gz7IXQoH7Kl}+k zxAJZ9mmj3<=tP`2W{LY|U2ObYo(X6kg<)3;MPBn};CdqWizz)~=2g-3$iy!+d9S(2 zvh3T)*gqv z`5n{IblwtI%9Osa#4T!Q4oHV;$7VKhx&|D!mcV&tHmPrJrMJ?TpksX<`xR`3!5@8b z=ph8oKiZJFcBF8!)_W>5lj}LPcSH4PIBUtaLmBTYWP{>})t(mWST>vcMO)dZn`$V# znT|f5r`#2*4fW(Qtg>w+((;?=?$ghx!YMVjQPKfh21R1VmrUMQ&w&;FUp*hpbE6{P zhal{XQk`;56Sc^ZfX|0ilHjh7!%nG);;h;r9=WrGYa?H5eJNP=PKrJlltlH$o@G_s zQ+$8w4?1G$5z+Cv9f;XENH}-|rAs3hA-6CRaeF&h!V&|t)`VcZPqbi!VGA6UrU|3Q zSi<{@HfTW-Ud}6FRxd3eG3+qB?3{=!&s+cT^F1weiexG$W+G>BF`tWxv8}uo3H|I4 z%i7qi&t{lAGz=D26?IA5?o;zO5DFtdM*|oU&kI?RlugvWuRvY$epi?AZz2>KZp7H+Y0S_qY&?~Q_#ut zYZmk8c+<8MqJ|0caAITz`ey2r7vWroau~33hw7sZ( z!hTXK`(5BkM{cgB=Sh^xMKQ%110)Rz!Q&6|jGnW@5$-WBoKj0J zP3okYYg8cVaF`7m!LyRrromh?OtfU5E~>K1u_5#axjl;K=y{aDXIvwD?XnVL@1t<| zl?(ColHfA{^w;(y?+l>K_55pct3(IBx8iouG@*UzCVIka7Ia#|u*c#d`+8arCP#B| zD*1rPOkodXU9E&C_>7|?OaYyo!B}**fE_!w4kK*hc%S*5%;9_WVGF|WYxN;!^eBq9 z=A5DmFKh(c7e1slm2&Wy@Pd74;4DqABnk*5e$l322Wl;F8A$WFj5zQn2 ztL?p;7oe#*gy+C&v-%Tu&}>bHyXHZ1a-<>_9NCF{_xo)A3|*voCZTbBn&=1Ty(HD< zLiFtgNqMz}`gyn0@!d+bt?B|@aQW+|Xqq!ea> zgs3>!H#CvcPh#ky&sS*U^+`tZEH`ewxhH^UrD}F8;d(4kySsP zNxe3~ddCdT!Hy*_eho)}s~h~(d)S*qB^Vm!;8uf^=zg3ceyk~l;O#eJ<79<+F`xc< z`|C67IV)~2x~l_7ZQ3MAdRZbqv5RTPXru0IB+dsGifpSbP;{pNbvAY6%j+2sj*Z3s zrfycvwSgU3MbOk6B$(xY2fxFtg(it#sLyIkB$e&Nsr0_Ojm#F+>!aag^o6*c3#aj4 zj?r~WJ)(4D0W31(@mpSjxc)bWZq!~yBaVD!Be_rctxGz7$h)&{e?1KDEywSod=hTy zOP}X{q;lNHQT)&fWu-otA6&rcW4d@cdo?! zq7K$_+yL*LgRw?hsZLe>2ECsofnQ`Vc^9w8^G}j7V1F}n579<>Mi!<-v||$~4ESC?7^%w9f>X0w zvFM1j(D4PIpWWU>mrSmusylCqmQAq4fQm!#v~VKl*50KX^8JUKA zmqdciHBxj{MFgEcs*{!OR>rL9xlkXro*D6c8C#7~JWwqlzuqo_T;wj!MQUM9!))MT z83m)Doq|}m`Y%alJf+CyzuuK_3f;C)e%AutG8T*z~26(tS7!sB8?DbbW+!&vW zm~W>@w@o|U7^?)Ef`hDKusW=6q~TIxm}t*H1B^4zEs7&>eZ zvBXVQIHr{V)h{yS%)~CbKX4}U!=Evmi#n*5Pr|rq+t?l#J@^j#-%Q55;4U@UMG)R} zoQ1Un(NWysGL@&?*H4qswsaaRI<^q1%MW2#z)h0nEsbZqw(EX+#FF1DAon_FfySr{;@zz1 zFMDsg#WRZiZdriPuwWdJ)@J#^4miIt4Hw!g$*22@m^^YPVqNdE=wD%UluaX@XLq|U z>VRc{eTp@rAw*lVv~r6(Rek1eHc&Gt}4cN#z!|tYY=uON)+eV&0 z#qY=;y%k~dq6CUpT*-x1HaL0Q2ch|u%;vrg9z2Xhg2^~CU9^qn7?<|XWW2`cAZ=zO zLcSATtw7u|AE?$m8)4~00 zN0kYZ6!zd^>n!4JHhI~I5#ODRkf-i#}V|lK;@YUbt zxUa6q0h386+gZZ$4^x!!Uhd>88)CV+g=XgpKz7|>8-wH#`nw46R=6C;RtX8GpcY#I)A28EQ&!NH4{*wgOUkkUx(V-WZYD!v3DHMaiZp2wc4dFIGK( zyUS#uo0=2`JR$hQxK?UHAoJ^~`&Um3q^p4)8F`W53YT->b(OVgNu4cnKb~JO> zQbKfgDdrkBk*#^Q7_aJwb*(1s*x@yJ)|HGXhv6L6ukTV--)WkvPK#S(W!iJN7$cz_0`i z%eh4mvj7@%VsT`8E4weQgP)3#@XyZ`TwZjM4(^b^hyB^4<%>FUJkn72u#hD$i9<5S1ymptWd7? z>0%=$=;L54_dLF=FqtNG7Zxk#3Ed4^sBD8gZrT>%^Q&AoDRVQ@9_@kr@82ZzfH^j6 z@{GcX2iZ|QN1WsP&ECk_WX;G{nw}yFgEiE9}eQm)tjVZj2Cqr)Irt1s<0u&voY!|_kYb+7rc9JO-(j< z_p`s|@3BVKln7j3ZonGDmf>efG7h#LBtx=i!`W&F%#7|cYo5t6y)^-yX-kZvSh(kOO1RtGb}xbNoW zG`2MuaBj~)>)zcYA+C)|gla;f<_JrpDo8f@Up>Fpp^S#cQbcU~K~nGAVW5ORvddyw zWWFOp&&5G?g9n*XB@UOr7U-1X`uwXpsIBDu>K_H7!s8d92)-I}F-$d=M zD6teJU8w#o!I7gw1Zqas(8}HkA0w zz4TpGzNlO1h|PUrQ1xe|H^c^8jz{#@^X-3lR;&l-S6qw|9R1e|d)HaQ5igb@e3l-D zjZWmb^2JPTjxH8uWx~o6BxiXLz04VR`DKelA-o~*6567}p^fbv$a{(M034JptE<St+~vLxBIDa4p%H3xaow)9B}>aOxl1!RiZDa4j_(YYW%1 zPG4mRIe&QT_X3i5!x}Q?-nie}!nP_dMu;d9p|^GlJhFZ1o1e$&P~{TQWUVNwB5J1p z34;Z1Q(EcPY7MBrxykNx4fX)nY)EY#%?!DQ+&!rj+xPIgU2g@GQ9IGK(}+1Lt-zD` zScLZ!l2AV#o=+EnCrxY58GnqRRn_-+mY6t8i;baD*?n~06$63B2uYfno<ig zb{KZf4~NPgic+{9V{S-1I#%5x60+vd%!)zHg%&1pnD>@ByxuO$6`U)&L{(~e?%N|i z({t2Br+XTHYZS2$u>zc2bqMZVYstr{;WYivcPiT)!Mx@=;LheynAQ#8|vWf@`c=Kus8IV$>H&<3jlN#T#%8>rVd z1-!Z+f-dJSW;x%WKdY!_*nX1;{ktG9jD*c%cd6QI1*nZF!jKQSY*o+({PT;&zNl~H z{b)-}+7N=x4u{yA{fl8bKLJ;iWXaVJJcCdAB#llCXRQyo7n0A4@8@k}kspMd$4~;9 z?-}IH3~y@jwUc@sU&Q{LmB%Ws18o1JB}%&b3=!GGgwm(((nnDX5wb5Bif_W%0|N(K zUX+R>V?&8>VHAy=E}||r7Hm#1&nPiW#KXCqm85Hi)lc`Ky5K6gST`MmV~5vQ=gr#SdFNQgZj% z+F(8WFiC*_wN%jb0l$aCSkVk$rFP^>e zxRcEhw}6aKAX-ftM5fQpadl=4)U2-&iCTj6q&Vzn1HSrA`hNZpb)+V)1B=YSq&b-U+4XI3^QhB=997OO&` zo-@8y{~~mX4K6(00r!JZZ2rKND5QJ%JbEihGMlPWX8H%bcodgIF<1I3tNIUYyEII*i>L_*pB4Fp~AD|HQnE6h#gD) zQQfwUeeGC=pxSKC3EE9co<5;Ya_X?;jG9t&E%*;jgKV!j8=Yu~3#nyLdUBmSv6sT1 zv^30{`j~y1rdrBM5n zh`7R`^y?G>&aB^!%E@Ky))&45b#A7Iy~PBP?-i(X=k9)gXb{gG`^s6Ds~)Xk*%wt1 zYgUR_=|bXT!OxG(PORd&V5-*_W0Ou~|BR)eu@%J)V}*qZ;y7gzON%F7qS>ldqQ%R= zS##;o(=s3)?yZ!}RYyj~4Hmak1@?2ZV3j+HRXkRPvlstfQP;`K3eHJby#v0%Mr`)h z6;Nj}C|O-dY6t6LTyHootyp{R&PfeSJ(r3#^$pCHWa1}x|LBNYlc-ly=~3Oi^xnK8 zHlxxGyJdX)buXg_IPiH-EM_}iC%@HsHb<8~ZjQggjx6CiI>`t~P0tm4H@ZyqxPLaz zCWq{cai>a~FVa}6JEC%)hZ~|&1@RM`NqU|atr_>6Rw(RXr&U}~yDS3s8N-OKhZ7YS z#?eR#uCbRjhVzU-1o_Lefv1;peNGnkoH|L&JpyT<{zV#hbw0Z+sl~IC_V&+MqK|8# zIJgj>o%%?5IF?EOaz=AWID*2Q$o(}_F(!)i&sZwv8DoiAAbt+35~-=S z;nk<9LW{rasUTK?pPvvMlkH-ctGVapU?$S+%1y)_^iXi71lH}kblCO~`exxLS~K&l z=$p?*xbTd{?RMYEEEfy3+zI4-&jZXsd?^g}C1P{yOmcZZD;1wU6~Pzpu^BVINC&?3yf8^gbn{!qngrnS=7^MmB$f3Or0oP`qA@^emIY_cAqUor7lOEX<0_V*>(}@s;zO`>b4vo77T}(Z2m`#$%&gA-iV}>_t<^xI5l7 zMErlXebo@2N5g-2$>M3O@w^>o^7n$e&t8%+YZT;;uS0cEHyh9W%l9%e@#MIJD79M^ zq0dU;9{H0zH?x8EhV6VW6~$^7u0q1%csOqNB4JM_1INuVyX67e(3A?A9skRKn7VC8OhNSxx>&jYaeG*S@0?h$4+Efw~>_)BAj);Of=g;oFF z*A)#~1_QoVmFxLJGV=M|v%nAYbqd+8!uiOui-+!3MN%R=p7ypo_wPoBa^CEi>#1-V zvWbgOvkcy=-#f5{Tq%xuNGNmGQLoqX=NJ%T>_dX)wTJrM>;LfYTd06jVg*?EWH9Txrw)lG&I_B`#s*9@N7E)hB&L?u^$m99oZb}7 z^d3QL#|ZG;DHaXJrR=?=KaKra$9u5vCY!kL-K{>DPR(dx&I+nr@0x}B)-^2Co@dr< zD8=2VLeiUH1GCfHasK69_RGo=BCjCqec~>7wyX^<(qo13ZId{A+k|soxnID`o1K^} zgp?T9FTK+zzfQcOnuY|8PkWfWhbla)vS9BxnvMLxchFp$5tiRXlnz@VI%*rwoi||0 zuU*i(YY$AdN=f-aU5s55&OJ_R&z(v2ped;r>8?*h*rHfNjML};TP4@1%WyX4oK#xA zp^$BVV~xn)UN|_UQ>43Z6U-G-(fPBJIPrbKQ)z$hU%t#HC~^PJxp1hD$rU)BxI)M9 zJ6Bst4q17_hYtVHNU#6BFIpa+g)$2<;da&IEHsdH(_|Q+KI$jNJ4%c=fVEI&xD1hFm{f> zv-PJ$-BT=ad0sM_7k7}l$BLL?6%5Tk57>6T$6u(CiBGG`P4ZvsDVfO~b7Y*$q{wc7QWzLkuxTeO3p!M`Dp zS{}*nggN2rr4;nKhmx}g{Aj?mYP!_Rh!wxp$8-O9ynZLejyPK&^XEQzB{UGv@9p&0 zH)9wt&tz|eJO^)V1@}wNZS?TiJB{UGkg=KJdA%|qnmWa1Sv8h*O#LAO6*m9}#*CNTqQh4!L9mo?yq z3fxKgOUw#vIS*$$ex^sUuIlC3?-2zHkY>$Uh}jbbQC}Ae^vgzsl$dbuVrM~Y{2e?NHxnK&cuP-4+ThqYFPQG`t8=Sb zf;-6(Fkk+O+_5vp*$!V=OBb?XOH4u9_dv}=k(ioH;ByY={uxWPpBC=&Je`S(ZtNSM zmpV=;fcAw9^1EXPU9#~hJy>STHa}Vo_Y)B)`)eyOcQeL}&%W4xejCdhZHE)>X?!mq zO$KVT(C8O4@ZiM_rnprTyCqZL7Bi8xp3z3evwS4Yy+oFZPeTK*?O`>&EL&$Ah7RZN z^kJpM;+7g(4mcpFy`9~fy#W6tA`zpbQD?<1n~~7h@B%Lyf>Zi>uzz@u1qxicV{yjNkd#*mWfPTA(`16LPeh4G~3>X zt$G(lGe-ZUMeCP{<}B5~$!}H&>TG4c=ghG!!52N-O6%TST8JwDXiW0?OCoEdX`O5x z4Jvpl+Egxt{+cwnJ6#k6?wLld7VyvYYGt7#RAHu`3CA_7*?G>m&f8W7cC(0FQCp0e z19rgqVha;;{mmMW0Ic7)S+JAO8OrDw;pD}WKt5Bh3EvH^C|?$%X$l3t``Gf=fLOoy zkM=Zh_BZGMIDg{v$zPd>`8tYOxXpo^ZVBGkG?GOFZBbd`1w$hvmZIna$ZRo9rWx)UrG!b>CK>#teNxvW0#5v8-7}o3b1z_B$0(lbAHXfEHKa*v8!h?XLnoDOW$N;qcn(qwQf`eV{;ICj zcvKv1y&J|t_}QMr_anVQD(ur0YxLYrLA}FKQZ5|F`*VBvjOt=PrM1y}HU%dyg^0Gk z=b0v5g*c<~ksP|fb3+;nG4X8!d+oCZ3L7KvXO9cncSsTr;U);ryw8$%FF^f~2sAIL z6-DM-;zWEBTyM6M!%4F-d_xd4PCa0!f{ju9|LIIF=X z6)D-3#BpOdbv<&D`spjMgz{**_rW!qs&}`}&{KebT|6KB-%B!0Srd($a}Y82I+N?v zf$pILI5cuJxu7P^ccz@jI;4|r{mMCS*1ka66_ISd9efVOp>OUjGO#s_zT`Sgvwzh;eR`*NXglti9aj7DJf zT1al=eYN^rocW%CvI7pHFB7$qICwvwrwpK;O?J4Wv;#x8MKhoC&+y4v!iWP`zJGN0t^NX~@YbJZ%mBaa{VnVl{&Vomy?_$%7`NF^Z z-q7ccwz#%pTYqhT8odFl_zW%m$6%UJKMzws`9g;4c>?cRLF-yFEHhQfk)8>3g^4rW zll6r^?^>|FoD8>18<;_i79_KCVOpI=l1+zT!D+r1uI*vb?#tk*z6-OC&KLNWn&Ie; zaLhd%$XK;0?s3hnuc|+Z=?kY83+rjX=pZ)mE5BE@@cDVJIPc~o`Y{BTGvG~~C zM4oev<>jwo{TUghHBP86O-9xH96@$2pJNCn3(eN??~$zm-I^$9ZO&#>&KaPDzgwl+ zD3PX})NQ^oly2Q(g=V2NSo|H8Ic^~uJ(A}%IsUJXg=3YH;5- zE_)Ly4SSSm?{%K%I_;9SO4*~mX=`sp+J#8=Om;et%1BmdM-tidBYXXxU*A9c+bb`} zeeUPFuj_pwZNN(QTVEMcab+mc*+nAv+u?9a5S}c5zz$&{2D?Y&lcKM{pu3s(-;Ngk zdNKiOwL%={+@7z+5$s-$5B+L-lCB-HD$ ze*S16n`>>6dpD53RrFbg`V#mc6({6M$(rXpU%w_EH&?8zdONBK$6TffOT>by4DX;x znw5=(+V#Ajv>2@cLxcmjE+YEcQdDi&7CI}in1wkxa=khfcAq*$?hWp6GfacO`Au?Y z7x%;aCUbAZeKu&A4)1v9pY26Of^~Q5sYkCQCWaIfy&vj$rMC^z<9D*?2^RQBkD)Zt zi^R`-PHW2+BXrJFHdt#N%(&10O3)}WZ_^qoUAmb%*(WpoV|&4_0v4xWZ|WpgDCAki_dE}-Dk2f?@${5U7d@w|&J^$Q-fFv2ko`)6L2n#r zuPB(ta2{z;oF%4cgkeFKDs#_u1=HDr@_C1dShgbeobm79+lyt@(bklV>n@u_O<%c3 zeR2T?zv?AM2i@pDZEcC=n$G~OAF0f|T*H=az~*haGz#-O_71-o%i2frob z@wiu(Df0d2>B?f5Ic5=^3nA1?qL#LF2-x|V%IM0=!}APRQF6UHik9rdhM9lKjXDQ> z%nn9)QVM&e=Zse4M0`EHik#)Qb;*;anBvgMhE>JVqWB8>QM0{zak(85ic1i?r<$;& zAPW1-bl{)qY~?&njHoNd??D3uH2xmS>mVEz`G2`2@P>;*$P3|IS7Oo0f0I*gb36Htx$h`??q( zt#e8C>%p*ov;oiDyP1x?FNSn-qTx#y!J&UG80|JlxL^7u|2vyu>Y)TEj*nr@%8oEq z$U*3o6k_j|Ko@owZY$#k@R{eNYW!;*z<3&e)$A zT^vo$L2u^+!I5*)Ja>{zWiFmzVaxsK)Lk7^EVM{8q9hRW>@slq^Bppqdp-}FhV$?5 zyDW3JCg zoE+20re(-u<7e(Mdo+-h`KaNat2J&0H?gVTEpTni26T+vTiu(#5U%S|pm6jbaX*ww z&mO6wlYT!HZF-}I0Tn#U_UyPouSS;kNJLWkf%o|SsSL@P`N-2+$>w?RS(J1bfzJC$ zyu3ZuUI>K2hzD#^r5)=2#X^KY!58UfEciT9IP`=#w6s#F_`VA?RO^r^IMEz$8gikd zpik~wy`yE-yyrfrn<3of)J z;bG+tV!mAm;mw?}FSD|0Sa=h>)=w2q)C;0}BQ>FByA3Y!*BQQXS#j5XIOvO!uJcmV z!ErO4-&e#c?yZ8^?*#mu@ZocDce{u6IM(pa|4{b0k^5GKj7=fO$hZ^OTuY_vo>y%n8|HpR2G&%p@xwuaWml4ngR0Q5&QOS z0bae@g~HoPf>lyZbp0ycFOrkOrnp<-MC^wC+1|rjx9fF>+`wRzpi{ zD>IyB3H!n8VJCh?RQbsYean;ZoHM%Xl1z~EJ`Igu`7QOLI>uWks7*kai#rwyH1ZCx~lwfli{H7zj?mUQx{KU<8UHshiH78S-!r zw2PAPhwFrnwOVj{T8xt`2M9(lzK`^`R4DQ06}3KWi$|`081eIc^^>d1&^aRw&j$V_ zi9$0Rc8SNN@%z|A8FP>e8JIU`E@?`iNF%+L^lLJ{F&Y@^&HaJ-YuJ_HTF^5s#<`z4 zq?g~vCro@#^A5SO4_wE{-n9XNdZvO9w-(e7;aMKv=XBO-o{!rT50|Pa_B+rVGx{EgoUtjZvn-rW8lCHaR%yHEH*{$whC@4QK_8CoNBTUh@LpVqn*fhAkv!8Klw zuT7A#ohbBe6e8bOAIE=Z@V>lKW^7@AqQYDl^V5q%WCy*wKp!5#cbQI(JYH57;o8`N zY|M0Z$X~STpW%ajEwRphJ&v3$tG<4E6>isT$JIe&s31F)4p+QLO)vC_Dr3|UI3*dA zHXRp)UzVd;q6jLfe2;b2E2D$=jEMCtXJ0O=;J)%6OiABKjPKiH!tDUOd~~1HCD@~A zek}Ut1qz;>Xok7dNZ~?1afmc{AN0^PnAL`{Vc^$hs zT^XgTa&c_UNLF=H14kRnQM~FdG238=9^#LQR(fpFGFRA;Bq#>$AllP)k#T|Rv=u9= zf_YEDy^twFV__g||HS*3<+Cwc?gmR8pn+%HqkClXJ3(Hn1f3X^L0u*ku*Uy9@%K*> z?-uzWvbx*?MU#QT)$dKHiB6fo7RR~@1rJ}`q<`K?B2cr0?3$qo z>9<*U;jn{g`B-57jl-yzv5p*{cAp-;$al)BTWn&IC!%L3VR_9+B0YL7)moTI9i}C* zxy#MrzagH_TSYeLI%kA$%7wGiX;SJEOrKn-pxdLgSx|~5&jn_|FEK{s>|g-H+qoa-AvoP_xt@O8WINLGE1GnZ!V*3tfQfep*kF{K98Qj5YCoICS#x4E2dW0{}k^Og- zs--Kj84rvholy+m14oQ2yh5J>6@3RCLGG2qzZh;rs2)#C?4N-D%fJt5?~v zpT-K9ys`*lk5xoJ6`sSuXrQoe>>XOb{jR%v!VtPMo(0`o3YRNc@GglZJ|iWt>*qo& zRqkZ3(={MAIT;RelUO77{)rFY1wWNKG9@*UJ{a++e?K2onnEk%K2r_v6r+d1yl1M? zufG>V$-oLyC84Msq{;@Ix5b;d6e!p4CLgQj<6)~WB4yfGf}#d`N|R7~F;n#FM-BaV zelj+Ad6TqK;Pi>TST(Yp#Ve)J&F{X@Rqi$dxqLaC`KpR}D|ud+XF%3^hoW@O6;Zk5 zV!SQLzyQ`r9Ax%*`sW`AC@N`W;0j1Vz^@>60eRYSk_K6Do5e#`sb{oT^Ex&H{ye_ zEZ?Q=q0IIFv~yXcJ-3}+Su`K68i&}*U&>hfE(aS1yNKk!YC|z#Kblt#pieG1BG5dL z`{q-aq}&>uTAhLAF+pU~v&qm+H9@deC)4iJMf|^wSfjQ>6d2t~?Tzvpmsr*-cxqCUZT2rB?{+D=u zG{^h6cqE+N$NU?(gB@@_F&JMl1eK!i+>Pb_~G~Aw;&HZoPEcy2aod1`J zpTElqd!mY8;?5X+rkTa*n!&pv7BeN3s!tv2q`#Xa@$p(7vB^uN4x+2{*^_asuZMFo zXXl`dtCmaOO{Pv32{fYSD7&LQ54YbI;oS>YR$bwT%`62?_Zo<1wl$=5HlQc!4l^6N z3U$WW*iUx|d|vi&hMuf&e$FC9CZ$nhx$Csm`nl)?*Rs-f@m{BT5YIX9sjZ_WX5Hv! zf~yLMPbtC_`GM?n6VKPn{BO43|7FRUY@w)*E~{SAunIS8vhg8cG&PD(pmJ>$^!2QE zk=t?&oW7QXDT&7giH>r#Lm`YdgxzH^5~}Fw%;kQ~6|65t8?XQE!@136#PBEgnb`Pa zr|NxXVQGuLib(YC@f8IAY{t!$5yF&j<1u72fal5hwK0?hv>QQ&-^GF)REQYQizS|_ zrE@oUvR{eH*pZflx7{OH=i>!X#ZE}kYvf6{J-Su>k=3Zj1Qqu9SP+BZKk`ZC4P8vV zx)Be2R#bf&(Trt@a>99Q1L#$AZImVP{nqR{yOX1V_je2MJ@lGbwTs?Gufk~WbaXe~A-mfg5S5sQb_Jd*k>y=Znz6Wir%=xypKEd^s% zLeBru#I?9Alxgl@qb~x}uI+`&tfj;wv5CG}1oTzkW>z1(P|0VAna?QFaBVepP|cuk zH4@q2H>SA1E*9qI^H@-UD`YO@V$YV-)32KR;?T^}t9e4))} zQ87Fn-jSvm+%K2A0}t2n9`XY4O$U3*`5O*Lk~km#qR7pZ ze~&b!Bj@E^a@`YDROH%Q38p+QWbf!&XlzR08MjX) z&))_g)`vrT??LvaY6XG=w_)ued2)N%Q~F?<9CVs`*ilYRMR?(tLz2?3ls^UJ0Rs!4>?5T~!U8 zS~{#+3cG#1h|U02UFO$CYEv=HY_7#@%ppv=ZJBex-j(9C0PWAES#uRsYELsnY9_uWEF3QuR=UIzv?yp z{z4HdN4r=z_sG@yZNc%?;%xo`-o>+E4@M^6Aiq-rXpm|v%@dPn^Iq}0_u)+lw%$*a z7OEkBoD&w?HM6OC<~UFpi_Ni0)z6I{(cO0>kvTJ;w3-QEE6T)z)eY>QKfenHZs&a~ z4+L}WPo`e;<7s8-5w_~}JdCm~!tMZ9_FF1|zbjMlO6Mkt3|olBTh=2i|b?U_mts zm_rI7?;ysIp@EDj%l=(GxX%i^SP1^+mQ`c_YGezuF@5o9YCcbhNp8s)DOSebywkuP z^&|u<92Z3CO{Fb{;Z(1sku`o)!)3!fsMD3~aIyhn794`o&wT`g9T9WK4|VJAvn}f# zpm{zTqYMKC7lbWHI5%7wPwxTNJ zbQ9M_Wrclr{OGAiI{31GD^9+;&PpmZk+!7(?=#*C<|a$gqKb6d*_6*dr#NHBu0YhB z?+^`Mum+L*wi^_4mo&X~z`p!c6q)jj75~h?<)8VvafN~?$-8vL04W?Dyn_sE)Z(5r z-dQ%5^HLTPv<2;ktfU*6zy1N;az%hY{x{kBUQha;R3^_4>tOGa=`(b%gj z*>N%dtOjCB{323(Rt}SLdDfTD@KO0@xJzR2$G%derC|ZZdubRfxJ!EOC}P3Wa4c}_ zU_T6upe~n#sZ-01`da`0?W`hn?XIUA2Q5I4JI}P17Bc&TKDaz22|qNy5amBMSgWuB zyPh9l=ju7@Z^344j+jNP3w!C|N?CYmJY`RQd*H0~ZhTkHWE>Zc!GZah9Fs+&>PJC& zfj9PrcCpzRnN%bFJKZ;QYxN|97kuv$6B-8Hrrr-+vHVv&zRcyF$kt0Bz9|zA)ECw4=VAQkPd`A`%u&KFZy${9YGndrO?*mB zguF(k=uk@yedHnuqigHPu)0LLzM`FOdNrP&mi4aPSHCn_oYuDdMAaGI{ znMu_^Hs#>_*CJ-R#2C{bAIIb=8;HaxFZ4PmVBGd979_V4Th6Co-5Lp!eXfIs?HGxi zC%x?MB7ImG#Be5$ESoyT30~WaaNt!I`Fvv>R*YT_6_ZCSd#Nh+-`S2!SS<*cdK76Z5scIepoM0}(qbrHJtd)F74YC~)}_X~NiVcoU55Zx?7y?-ugYYL@V zCLQ$6Nei}U_F7yIjN|$7MS^_eUP!7A7i#%^rkj}sfL=KVzSt9iaVH;sfI zdPBeQT+O7rU96=%f$GWLpq47OA}x8IotG=euEN`7!q@5eF0qY!VY}I8y8tkLTQT3g ziv(~T+tkq!d5X=5iCY+z?!7HEJM~7pJ@`V zf7l|JJcV<3E=da&Iu>H{-!%H;%@vx~^h~6~J1+IhZ_+ZC6oD1@fgfp9#Wme)Y|_sZ z8vO7BT{v~2Xv}>L>{@RDv%e3R?^|okFb(O~VFG<^ksq3b69@j18B>h0cVaS>#LJjq zlO`sdOT^Jv#{{iOvh;^xFrBV>i?vp&@PA)!q*PtX2J>EqgWvbSPP3G(8|#G6tNn2K zzVaoP#*qEBY-?b;GD0q+Pw+lgCdM4WXl!pHt`NzH!osat^+|}7ABQnW7S?-@E0q9to&QSr-hTLrE@x+dN!Z! zmv_YZRlYbA+bY_7+YdR1H^U^Rh3s*0#Gel-*mt9q4f?{rJ8GhFP^wUH>~JGZnka?p z&>f`BgfnB8Z9!{!3A^xI6B^tzJYIewsf+QZG6V0?R;%UgT&fGEDsoTNs(*sLnJejf zj})3UA&&c6t#NJz*BiwbunD4P$d;86R=XI|3-w9#8)u=vvNK`MTo)bgw;4*IQ6kj} z9RyD+M9k&a#MPFw^8AaCw7QO|xVrJ|OE9F0>`02j6y)8|>(^mQ`I|JzGa8xNl_FnT z3+TS!jO&$mh~4`6IQt_E^GA0uDZZ<_=x@VI<2^>TA@y=@_8IrE`g1$WtG=cJ-zFT?l*32Ru!<*?A3*Hr%evln0QpBd~1?U;BB5L<~fmGoD;fq_hXvhr* zEFKsM@3urXRca}8xW9Txcob3QTIMz-YyO_?V3vAXF!fJFh51CLQ(%le*Ycsdp^DtL zSxeiGRMY0i(kym$9@0Ao3%_`87l`XP)4zlL`Z>Ke?h9c#AsE*xRG4C&6AnL4!N^Tz zq~xm-lJ0o-&-qaP{@Ol15#i%9MKP?Fmi9_OX2&{muz~jlN9SU=^fhKK%0t=b!QAV$ zocxnM1S|hWhes z(T_1kuXfhb>o+A(Y+FX8i8_A|=D_nq5xe)w7}q`>!$qt0q;`TgGzTOg?PwKiT>2d8 z-NS@Uq>!XmchJJJ5qSOV8I%5Nq)W7yi*N#3;iVpO^df=aqcAT+!7OhxoRYWab_jm=*9n?_LLc zR-=!&0nu2IS|Uok(G0yZY2nXMBifv;fE6qOO}jhUP@b=S!*fih*Z(q_{!1IqVPz$x8WA9j=7`k~aekL!@1&Dg!cFQ9YrAO3dV6}YoDb^xq78ZA%*rN-=>M$5`xe%GBhSMmfjzGguPs=2q&uo zO!QsM^!Iz9lB~zm7Z*tZf5Xmq-GH2xjqIu}&jSwTT!;x-f<9d%Nc>8}CGO1@KBPDv zoQv8PA>RR7=nw8^-JXAqIp}i_z^npn?i#>^i!>p}^BYp42kbMyUwhpS#T&iyYKh@I zFT**XSw9BQ%e-sJ^HL<-b`^2%oEAJ)6Y*isF~MZ6w|`z3Okbb7#qRv(yMf|%%t~3x ziuvzwY`{U>S-+2HsPk;XGasz~d5;b0;yxw0Xc!L-6j*L*M&8n)LZ^nYh-=HB)y5a- zkby@;-)RC}d-Vb}SN0WD{`!xK4K+aU-N$UaChs+vpVP0mU*OCHQB65Io;Q*Zo_+8* z;RCxZdQ5An8}zi|VVqw~YV-AxdMyeM*DtTy6?vb&pi-Ps<3+A;-nD+}7Oc5k8 z;pNdhbZ&bs&|D}*KRBgQgN9tDbIk#Z?7cC^tVP6@tiy$_G@PivOTH92;^6EQjOKlR z<}ko%-czq1SSXN8xliXPS_fAy%;lU6aqN+Lt zm;LqnZ>9-chcw(2g#va;H2$Fp6 z2s^4LY|U??9|GqiRl5-0J^4(Qt%0TXM&v(!M<%B%!uHZoEC@fq9y%=Jyw**~K0S+c zu4tv-tH#5hXN}Kr|JT9~A}Tp~pXj+PMd>5H+k|W;T8{!~uE|vzSz*X(7xH|uW&!rC zR~G%6)s0b8zN1e28vVZ824UMnuzO-0YntqiQ4cdP`A;~h9V>L;_Yw!W5Cj4r?*p22+ccsa4#Jrzrq^7~L{3kzv?fX&Y^Omn>TIxs}vK^*Fir9*BGaUVJ z9NXrHk&ivzsOOy3p5iKYbDlenxO0tyjwe??bkfvyBQSAxFOz>|0Q>V%c=Vck{wD#K z`Hj+{A)b^siKC}}89WDeF<&`#Xnx8@e6O=8QB?yncXnce%NMdH$^{{ve#l#r!Wtcy zVWM^-M&+#|Q&!7Df36Uh-|>9J>2!K^?O7UL+EXnY(*m^w3yv(+f zbw+C=EHw|qLVp@*%+bZ_`DGw!W^~yEMm4)E^kNWQJjM)Ih2wcQ93e;EjIUnMBjGge@`VJyW{AH zl(Y0pLLgfk$2$QPH=|&zIP$GgVYFN3dZx>s8@Bm^JyZ zx;22UPq=$c>r*Y~>L>nKN!cuMvUQE;=S(bfNo@Z|Vf6ljYUvaQvHjHi! z=WIZABzf&b;?L_u+1wFXMqWtJ&}FNCtVEk@GS-aQP4YjPplwwWdTV^DT#FyjfggD% zxU3f$yio-YN2Q{@p^E*M)4|4(`B<{|ji7V66xFv)p~FAtuuq4akX+{tou#d!aVx!` zAf1klmmA5?CL7e|$K#9x@5_sGfm7X9sFWNRjFfDm0t>Fw`tKxv4kgl6JFnA+S00L< z?a{%SaNhaSxsZ&OiKPRsKc;$vg4p-0`^ULt z_fFBueN)-@u_<)1S_8F^dupim^$Emh=?Z@r@cf4s-*1odyjW*G%aK?MS>6daV9#4p z7wd<%YZ-9!6tQVTZDCp-j|_7u@^5@QeLG}4R^55P<_8hf-{cx{t1oNQT8L57B`|!M zL*~-47=PK5^ZvS6;@t(bu467fKTN|r-fe2az1h*u zyJ5dhO%UJeO!Ixb>9C?CCiZtBX88v|bFloj1)FDFOVY6t~78Oj*@WQuyt?a#p zHkOR%zLX;wqPBZiY4R5dOsw-HOXULS_`DkGeL{@gbScEpNkfFS-YZD2!8ADBRqCJf zRv9*!JuVPmBkDxO;$B$&-&VA&c|<%l4AAy99IhuByIH7>UW)|u1dK5nS#y6WOQ=@poeeRy~a;4oBK(BAE@(G387xUk$!1cs^*XlV}qE zzp$vU6jn+ZV>vPAySC=3kR%kC3f6bdttG)IB-jF?P^E_CVl&)D)DT$Du$ zg!f$;mzpp_d?yZUDI{u(V`=e%E;>BUhUJt7VY*`y&si-Nm?ZT=E^>%)%ju7_-qZrU zArbJI6UHJIF2UcNZ3v&0LZqxa=(MdeXtcY@JO^{W1kWRTpBm4?OnLW*8qd_|-z0se zv*5Bj3x%?e*@&;J@%uqU|C}Gi-*k`V>=AXpiOsAx#}J;$(mk$NyhAO5(^7Ak{ z!Y-CR8h4s*FC5I4tTo1*X}SFOZWA~>lcx9dqG-a0gG~0te9TbHhu9HkmUTS5m{GfY_6%`8Kd;F45;gi0}Xm+vi`Rm_lI@PNJHUJKn5fq3pyR$a5s z0e2F3*8ac0WO*7Nvw)}3D83t|BlNuc_;7| zm!faJCedQHo%xEKa81Vxp`|UN!PC4D^d}XPNAHr*U`y2{X12#b$SZt%H^jmuh?=j!Uf%P7`_^piTUbfvO_fAimLvAtJ!Io<=22gT{6k*%yR)|Ms&zBYCc2Njyd`lOoTwA5t<_91%~O+3#bHehFqasEjTnH}XvH_za9?dLj7oOf294a-CK8YNLhQ!DIDU!$Yx5?$2n3(pnl zDBZD*J??YFgbRtN8Q@Re)=h>`*%JEU9qiR$9qi@I_O^@(OnH_Wwp!)E;MqlT&?b-$ za;c$pol{thMiHid8!SBMog+AG?M%DWJZX7dB6D+GgxOXB2sBV(PNSA%!_o{qQ$0vR zKB{2sQcsMu;at{sZImZ+#WRJjDIWBoB~@^LnMsRt_J zW0Br9j#zx`r1wIHfhj&^|E`j33wplxgbQc@KPJJ)FUHVHN?^ui#rCyvXk;H6eR^mDL0OxM^Bo#Vx+(${VRHK6> zYsXWg;)8T-!Tst5K`m%MBPsl>YruKIijeS%$Lr1xwnj`3-}!CMdekqY!8-aVb>D*( zj%HL4=8A~jJ{S}AUv*ZIC%@~apkd(vYVy$vGrmPa_2FK2OVbVwz3Kh4-Cj+a4s&*) zavQ#~&J0!DYfQ%Wt*%VwyfrpDm*aL{DJfCsJpB1x^x_K}CYc=xiZpx|TP6rP-;4AE zgN62=KhOy7P2Ix6`)B*(Mh}>)W@FgcRI>d`C)FyDf#<`UOn;FYveu+RNtTtoIuoQ=y1vLMsm#l)7Z!GWZ3yg!yl-neNZ&&m$7cQ-L}K6|Im{@-lh@W~Rn z*Lfq;iy?HWemuV|oTl+(hcHpEG1o_P5D?ue_$ZK}H`*h3p64J7zt20@F6SXT(V6*Z za<9?bP;`#G$BxE0;m^ZF+?ClXFzwlS}V=}=ao`no5-pTyG7-OJbjzwAs5#-;@kDGC z8^9TSrg$|d5f(aon8Ouqq=&}iP3}=ag}NLq8p>(MSL@lI5t>+LklnA1yvKfO@=lMdAqbrBE!YuZf<)y6j9C`MVmTA0I(-|6lP-~;mPqF` z)X~{*d|9uHIy4?_?VsmjW~y)&6~e5kmh6uR!96eT%WAM^1HXD9H#HTdhxd{Z-X<`a z&9m6wJgW*CTj-7-lDxyoo2-7I%JtC{s2fzVf&c08p6EQh%zZ1EF;$96@@$FM%WNjU z(isYtp12j#A{r#;3zaKrkc+!Vmh(=ixb_IVIorSt@;G1O{8mUroe&I?Z>3ALr8r}1 z7nv5MiVfAtkc-J-0YmhlPxCNh(n1pE+Dc3K8zlN;J?nN2!W1Fz)y*4C7CiN%LvE(` z^VnlnSz`W}2=v^NXUn=4VejB{Y_2>&`rb=G|FQ#$4|g)viE5ao%eCUbKvDf85w-dz z4SSnF5;;Q+2{A?RyLyGWFLr^Smp3{lE+pYiQ&AkK1I0D%EI-x)VSQncI94H&dT5EX z3(5F-_ZCSWnm~_voS{{|Gnk{X8kTsZ;FloZ$o9F2&i^ZorJ)t%MJM-)*XN;eX&$rY zeyz`c*5kCtOAQ#fX6}H_mO7HgGd1ml zYN=1uRQBt95#DMH5xQQ=;npfw`nTDupDh#8$35850a*P~g{5rsK-A+@DD2or2666C z(y4X$LOG*#-$rWQcar8-R9ElHyg^?^OXA1@ZxX4Z0fFCE1pT|r2HY*iHt`|CIGdHE zB5gVnZY=1Z?SIxgp=2Nb{R8SntB&xSV9;h1>$j7&qa5K}mjRg>E$r6?9ZXP)$Fw)2 zjYd|~(~x!v40ybk*lpvTQx~=(xS)WI$s*W(pd2D;Z}LOr4q>Vv=9nC3|FtZI3g2P= zU!U2?dj_`u7><|ApR;?nOfhk40{%8lXFA_ZAupGSqjHH{V^5}A-(01c#b!)uq&7yK z$;Q_Yi$yT!--DJu5=AW5ChIHj@<<2n-A<(id{3J5O@+jvVe?B{(VB!A?r^ z*=5Rm0N0g^4EcL)V8Ax$c2yGh*dV$-yOIuHEzQ(63NiX<3Fnv(5=1oVqoZIq#@#UG zZ`Z{L;<{&L)BEb>&OV$ElL}pHG1^>cg|e&R*wjzN=2oJ)BIpSvu3N z7y6iIi5lMRNXF1hu59}g{#k0^IxX8xTr5UmZb%?fmv*u2Q$CQ{71PfmSaG%&jCXQ% z{d`Z)^E|b`OE}M@gt5QkPGFon{r|q2<^!Mjca#Fsy1STJWh#9$_Xag9wHJM8FhcdK z0yuhHCZ23I4(!+h3!g6LG=C*_d4!;9L=K61pozuHZF%Qk6LWLrxqhQC?iE+8J|Vjh zT81eYd|@b^5W|_zW|dU`=wP;m-)gh?chio&wF1r{qNB!zQ=60ntmBaq%tHS++flF{ zl4VJ78*_`;D7e5&6oy;UO-yow9cMyves#kpf!%>7=r)cNzVR}E48N;B`f!oDzv>iy zt}sKhdoFC#Ovr&{L3H8T%k;6>61Hx(GG3p^L;V4+&s^lZl;bAwa(Tc~2QR`bV?T(* z_f&gjctRqN=lCX$qRYBC_lfW7-Fds&orFrudLwH`H*NCF80|6&qEf3#%tNFuMFo@bZNe z=lLYk!#A>7?Hfl($*h5sa+4^LvyQSZW#EKzGYNfeg{`yyH|Jy9mf%MR=YjVe7xenK z(bIpp{$st1_&(sCqHD>B?aE=Doq9M_my6FG)}$u0oeuk}k6%}AuyTo2m?#LrSKmQI z!a9I%8I<17mI>3a!iqUzcw#NjJnDIFWnUVu{yIQ5%SvHnGtVmT=wv4D>R6wW3~lK^ zk#y^2>XjpnVOfDB-P(fZ+K%AgqK7PSoD0(2)E&&puXVdahhE~H zT0A?3%PbEqBaudS(avqpgdgK^WX?utyCe8IB*5iZe%MFZb$cV9;bz0cR z`$|l829aH-rsH)j??_(5XZUJohz$ruOJcpK>gZY&hipQ#Z5#P7pJ#ioX29Zn3%eDd zi#ee@XLoJ1QE5m6jUOu6&mveKr-=>jTX847fW_+q=WEL`?@G9$NYMjOGXcZ56gXzpsUcRgDN%h3`2b>ug`ImfvHDvCE;p6!-cKx~sE=<~rfhSan#~>LhYwz5DV;!NI zPUG8d&?Qd$M45x_@LYQzW+m?-*~+64EFOqc;azNyaWHoC9m9Q)vmozDFDjl66v}D7 zr$<_>aW*BK=dQ!qC{t$~(#}M}!gzA-_Nu~>`S3C$*)vUJNR2GP z3wDKQUz&pl4*#3&MP{pTrXv{cS~(o(00RxhYGqp+{2G&j zd(Vebt!F7TGUNiCmp_6jMyunRaWdL1YXw%9rD?GKdfNSUA3J$m8Sg*m;*NncQ~Vf; z8%q;m${NTpR~Mem+JK}Wu9LsD#nk8+{A35p-6VB}zE|=R$26qq4g2=Q&gRc}E4^ZgTYFMNewmbB(>_+00F~ zS;(kd!j@gq#F8nz=gzi>3>oDDh4!^jz1hevK3<7}l6bUiju0HkX~8S=fkG+Y(Oh3P z!zu2Esn82zYxgXK``IlRyH|@$)eEIV1gGgOjU}8tt^vnWob|nT7`tI%h*?{9L%#Gj zvE9b|?ss^j^P~ZjxnP36pRri1zphH!xPwlVmqJvn57B3PFjs6ZytzL6#TFuEVW;6H@stw$mnp8ng;fQzb~52c)x1VUV-Tf-ZNz& z1=s&}kqJBXk#Cg=zvad3zeWRu&d=-D+n;Cm(Wjg25E}D@+47w$^iVX)ehw#wUfh55 zAe~+`Okp<97Qt>p6wKEvGVh&I$o^{wk!2?fAI5K9Lz6kXGC(vUu!j0SoQx6Q0tg;mXBMK#UW}YbngPpz`8?a(!m@@gM)sf( zjJ2y5%^S8HZ$nd2tay(UP377(_bU5Zwy<3@^>A!cEMD&!ZB)1ICN;SrfwKwaB=M>i zIF%MIbp^bqTL_P><&b;pP2SYFA$htdZg?JH7fsiom9vaOg%gR(u5P-t&A` zOre#^HJKID*v4CCh(4T-Z|f4sC~pZosCUPiyhp4)LlXlnIY+3`K~y8gbyT%o+;8!n z9ObN8?|*ogj2@D-O;4jB{@uQODRd@MamP8Ij56?_P{6QkmGF9#7Iv zf2Qd?dw;38izRb5$b`K~c=})jyZn+sjr?yX|5lkujb=Qe8<#4xX8BkMpQIwAs+_zk z)56ZxHfZCzbg+dLDxPuwz_WSPqs^8>bz?NO=>CYfnX9U@7}93LYQAAAaK;|IWtw>{w*xmV^ zkN2m4<`Q^jKRec1_j?&?=(UP|v^~#GmZ`znHV2c^9oeHcb$BJoK|y$TbU2W zOlW4-&HjADQyV_u3q$k?4G}zt+Ymu&)35lLP#M__G zp2OGU;=fgOm$!D&IX@-ACIpb>mr|*b!3FwJD9%*ZEy7+=VV^d}@%SYAbfJ)*YR+TF z1UB%n_3W$RJ^VRL=Fi~*k6Yv`_ZLW~uEpl;E399=IkpVsUhI=Q1UiqpXp;Oy>{wDx z)-~uL&?y}*hf3L=NxC>Nq_|HTGxXdSDtNXWXUHSAm_CE5*Jr5CPa)a$d{&iBqj3k5 z*|a?-h;m$m1E*%Qi;>H@|2qYk84KwllVr-(-D6t3cXK$mkDK5!q1noDPj(7 z+<)&8gSk!b$?m1WP%_zo`QG)c>!UmDw`_n%fE)=J)J9*}4+pt)o#`i0sPS9&nq|KH zox<~c0%Y|j?3SeK_H|It?0Im}-Nlwr&Ykxu#Gx7UMX!U~aqd(PdZp{A?JR2qJPGF9 zhXm$Ct&#a69uueflN+a{F<;h*Gk`jo+f^-`9KRmr`^U0H-z^{$Tn4GjjpT@f0xqok zueR^l>_qd|`Sj&I&dRcYzDWRd6cpL`P-}!)ugC6$t>l}J3Rb-JLa+eEU9Q^H+Ts3 z&s9O#^Y*-`f(798Duv*uKqIVx~EAbwEvd12m4+&9hpU7IH9q{9I25f7D#AEemdiDBjj8M7H)Q+oS zs&W#7Ylkt7U3#e2DM8rqM)EIx4VBWqPFKrMXSaT?0h1O&Q*|4e@5jHW3)p3=o8%BFW7)P_lD88ijmaWt%lZ?{uZ6&{i>~I5|->aD|l=nLq~CzZS|ch z=5s{}?_7%Ta)}Mw`X&NL%Y=QJ_WSboczZky)&+N1CZ7j?kBr4Izf8f`NIqA(4AnbU zrj6-*w;=yC75AT(GrhTs@xnPB-=Rq&E8FO_o$~1C+`x8cEktl^0n%Llh~{#>?(sQ# z$f&);D$iJB{5fb3@FYwjQtb%9$PKFow;D!+{HX1vATJ z>5iQ%>A-pC*-cG#6rak5%LGTp2Ns;QE5+}5rDW+)7d-#w3zNYuY(%m*uK5emQWGOM zn9zz5-eP*|lta(5)_GcPpr1A+vkha-P`NO?ub!9h zdWs~Ev3eef>eTMlB-}W)94oorq*x)g3@BprrJV5b%YMyi!O{KFdWP@xY3Jj)h-glR*|IKnNrQ7zjJY1k zT3!&J@BC+Es~V?zP4b&IdFexRogIyv8?bUNBhR%Et6+W9#D> zEcQwhO-R2<`?*VE)$suGuAe&k9ovW@JH^PbW7AQ<^_u_h&p*prVw9mjawa#4LU*jh zo~IkowDT?r60=1G_mjHox3D?xI-I2zi@-(Vy6Yz0q<;MOoLf^x9{Ov*wICaRt2VO3 zmw8_GfpUbs^CFT}&N%SiyN^{pPr(k|&w_c5-Z1hg;~xF7Zvb`;f5^Ou5%kZ*qH*d} zHhDPThg;>r#wne+-{;TBc1P|@yvK9|8aNT0&F>VJqBBZ5I5KE69HKvy$gwV%=IMi( zhAC`hrwzZe1!3qxI}$y5Dn5+Y#fl9bY~W)<++7k2l|$vC{az;6E}IUg_^DLMxcVm@z5BdamA4+W9&Cg~Oc5FNbR-@cu12};J$8S> z8u&-XqraSupf|P+ItK3%x3`;aQ+LDGJ;|J>oWc};I3QY(fw>++^40hY9XEeA$m@Gd z-;H~L5Ap2N^}|@BjscQQN-#O6ktoToq$gh2)A^o~?9aM&_$TDrDy?!NZ>fnQZ!tZzEwhIc=c@nhCN>V4LT_o{K|)ZzXAH*KW+h~ZwWy@IM` zvhHvU3TE3EC(!hU{WQhTT_Dzao1Pv%3BNr~u_+}y|7Xr+Iy9Dw zx=plUZdiuwTNg;~P&-T;>w%FK8Z1mT5)WK6Fzxdm(r<+!wq?a&(%+SJF8z(s7QX>A z#@r>o6LoRDe>xsaZDPYbl4(`cbvm|fhQOBB_Nb5RX|^zzmF={JaJM^-ikd}{8iA-5 z@H{B(o22;kGVJ4C;9oLV*yo2<_~6d7C710I?62BDPZpe`KK<^A4z6E{a`!E0RJJFd zMa}fAnG(L=U@U%5IOHG2f##1O=FdW@tsu3Jd6!vX2AgSNh>4rc&fD1H%CZey2U5d1 zeNt#v`mdg!zs9p-ToYj#87O+UxQX6BCy8xFfuz?Xi8}7?piAeBWW^m$Q2o6UxBi-v zU&G~~aX()DAd&n$v!JFu&J9!m-u4Fp9H*|a_zx{F1AyLdwAa$Q~|#Sz`+4E}h?qx8KBwzWogDlTyIP`c}5c-x9;V`(po&Mp5+g)zDv? z37rR>MAqC6PK6sVVOtA(aX<$N(lIE%K0>$R>Mi;~K@x`+?jp)6nuwg3jY-iPne{Ps zT$kF2ykoY+U)-M8Lw6{v?q=&_?BG}wgj%m*#K+??9aJ_5%laNHPErx1I4*8g!O#jw!7S&cTt2FMXE6Rf3Aq$aktQH=NbKR8bdlK=~4r^Arb7r}a z)fw=N$7!pvMBkR|+dmcKq88&vWCv@HF~Sq=7$`-SiwyFNG3ZGubY|=!$2u3HM;HV6 zb+8TG7cBK^BV;PY1SI7V8ccNbq?&u_m+AHhsB*{PE3fPAeVm~?WDQP5za^u7n4{5j z4HQ3Bvc?O}uo;wzwK)sOpC7W+WR_Lm{`}()im=OE>z=WS4OpX(DQW-J`FS~a>40KI zEIPZB6`pn+c<>88Q)%P>4A3`Ob@ETho{k9K78yHOI+Rc)oM zqsBnxNdsHeu7+sb5NjS8N*F~Kua zFzP@H+_DGjWpYoz-y_=idnpQ;H;UMZMuO=t(vk2`iySWgP5-~MOL}^rg&tLfTv!oK zycAo5=RH^#WS*uEZKI#5VAOCF%# zV&CZ6-Ik?Jc^>pscoX~jLIZ7_I~mCw*dXsExIUWm?DBSyRWF?QeQaf4=D>oN5g0im z4GtRE62t9uSntUwUXwHM(q=E2Z)k|8N1|}-y;t2g zRn9N_o&pKYJEWMiUnk~g^!b%!xYk#u_!`xTpCJ%GI*IBU$I@x$In1KS9=b9fc>nOO z=tEf$W=%{+Zskp~MrH+4D?)I)?}9l?G7;FaPw;f8E<~SrzL{1jQ@dvZL)|TS z7-vsQCm#8Q8_N6X=$r3(Cw+t^=ubIi95$FP})MQ?iSAzze+2b$btYo&~uCI&^!KA#B;KG+nPkn0twzW97A0a`PL_wj%nay8ggRPuN^#3})y?Hzy9`WLS zx%La)$_X7RrIeu_WpV&hooU1tRFT&(4}A!I|lEbKNc z>AQ^{*{Oqb;xU-ReI;Ku-^JwTll1mdJvuC!^Ml4D!+b|4dp%SGovs^E-YG9Qd(@E* zKjT5a?M`H>W!AVM^26TUip=pL=Vx(7_KO?a$feb4P$~1kzMn13+G`QSw4-6DoF*DE zshQ3=B#BE-futdk>*4h{7ilSD&b}Imk1xi8*P8kfx>>l=y-;H0l zMxk^56c%yHi9aI+T+^RLd|fBvsjNNkdAeBmGTwtpW%0egh3H2FuSH@dP(J;hL}u_E zY`hz;l?vIr7}&wzD!HU7T#<`bpbwy4h8au=$;qo?68-`o+QlZOeF_=l%SaIj->KzRSho z??{U(*CVxs!F6pVdsOan3HtAAhnCh`2@I))zli>Gt)$R2+$9o}hYzh_)8bl{3 zEai;j7-)ao#^x2+A?MBivue)?^y6je(qK2bbV6evi}{a54%%a!`Ob&)5k^)pLa3`q5*{{A&&o9EgCxf0)4hs5>``# zh|<^9^akJ8j63j4^o=;caE2S6%NY~*$ zH+f_efoAzsIPDOz%l@tq+a<*J^|EAcRws??9RksPknqc~NGS%v5u&p!>rc0=b2(H;~`3hQ{Gk-Zs*|Qw=oL9WS$6*ptNu z+~de|Hoj(yyh85MFB>E=rZ$jlD&_1O74Cx=dz|e(tqu91n{c$gA9)u%6E+$0eY^LI zwS3l|?1MndMv?IVU$lsE&lJy=Ii9f;gEgYzp?!fx=NqDGE6@A29Iq?Y)=X_>B=Ps{ zE|NP^33D@ePclB2Jyz3(>t^mHbhIZos~sRO>4t%eceAYlwzxlu|GxGNA-TufX}0Qb znitj1#Eq9i|49_gcTHi@0tamVn~VI(86?`D@B04P@jYob8#F}|uX-|YN^XVd)HjNu zueR|1_6K=($R3lWUE!@GWQ~ukanIkE^N*~F>GNs0#XZ=|oIBXEA;uWP{U(o+wuwf@ znBh^{2JQ>qOA-f#^Z&y>I%1;)Q@%hkS-SwseSYe?&TGcPlk@a6%3A3_F9+

    C&11mH6rt z5C$Ww@K zGu1sB6uSfn=dU2>)U9Mg?-%iB(Iu!o`!Vca?8fjd~}J5tC{aklyN3vtQ_eVn+R`bHN=!qpU2KC8eCx4K2ZxScJ+bK;iUtX~Kn zx0?CyB_25HYc*_N-6$6KDMZ5%;=#_|&Tb6yz~f2-A-v&-IP3z$tOQk1HZZ0bGxdjG zoB|8=m703eXYo>c_ZBeR6EE03V|h^5qHxmus} z=Z6E~de1^J^j&V}7-6q4$0fJY6Aq#nyxMn3qi`ye=`2;=8!U}ufCM_u_Y6`OS4py_DfLa{4l6q-oP7o`Jj9^7kDvpp2$0G&^gH$ z;;a|3UoU+zx*-jsmapdpJpi48mc!hcf+T!sH7dlkf_IWSn9+Sr_G>G2O47M)x;wsE z+z&1fEoQbWd~j3lSeOzwm3!Pa!lEU5AQ!nsSQ$yZKj)mJGe6OEG9Jjxf~xtN{KaN- zbX&RvT;hkZJ>?eEtwtTDezkmiM*)T|{s0TN4i`I_57w0pgm0RESjiVx{O84P{jJGu zdlKhL!wBSt$ugx6=D17ZEX~hOrQPz0kPVT|cg34qO|T3XK`L`%CoW5Hzf%Dy+|T9t z&r9$b%`|>oS=b>jixo!?vzY7`+=PwQtU%0*feH<(!8kts}z`ln2`=SpXOJNd*yx2y;I50!#{3qzH4-Jvvi zH?N&(hY#kCf+gjP#N;$%oHbt$lC;CvOS*}Sb_j-gy;MF!-wmzyCQ4`ivqopsPRRnf z^~cy&g%S)dc>r0fbNL#|Be+#og2R7pLd_5#9QtU0w2Sa%Uu(>+Qii^L>jeADI+*XO zCS~LF9?bAeum`A~J|Ws9TI1yu$_>3$Wb?wzu`qlwm_(D0#mEkQ$Rqk$qr2Egu?XKB z{0O#I*I9n7KW37j%G1<@>lB(|f3+dd=cX3Xx z8D3AC3`Wj2>}|M!FIrNiyZt{F}>20jag>G#j^wxrcKUhe`-+9JmT=p7pIyAVpBg|KDRL1Q$( z5*B%6ab5D+>ZWx8r6<~KV2C~1nyG;>Zw)V?x01&XE10cv_ei-R!_P}Rps?3ErqDvU zIhA=ZU|gsI_l zl)SQr=WomT5Fc+G{huT3Og9s{+)}n#{zVgGZ|hRu40%oW%!hCNocK_0Gi>;r2*=0X z5Y(E+D0CqqE)S23TFOnXcJkuZH)f5BRp^qfHqd-f!+N~S-0T#knG)#`jEWgcT6 zgu$^M{|VlIiCNTlzEsb7yV3)ndsRW(lt!_fSoHI!eSjwk+nLN>5A2rL4+c86iMuxY z;L;cRps?G4y+7iEt}W9*=hpBh%P30>Zi|4n_yz1l8{phr+N0WLb6I`F#c4&*D>PfM z>h&082U|$@{Ff1K*y_+%>dBdG9F9+YOaUIRU{=%*+wsX+y64}d?D+!fdcIm_CTO}@ zV;%7gtj=s=-S64p(;F)wBw66oM_HiUyc}5b`i0Oj#{jPlFO+&L>#c3^wucPVD^v@z z?aC$|&c<-tL}~obA<^`1&2(d!i13J&Uk) z@CRs$%HS`zO7Mwo7dSjLosF2`ivfXppel*rvxk|Ws}|*Yh?BGIf;l=@Ie;2}%%5Ki z$G6)vr1@DhZjOH+C4xo3Ft(cZ{M;#7;G0&%Q#A_lz{>YvSxb5j(0hM#Z@7Ez2P-(` ziZNE|;C4ilr_=5<`0oT5O}%(IN*1{IjDvLMZ@wCV_1&`Jzhn1BBWqLa?!OSO)jKgo zx}~l%&jZB)xm^EG5nh`85oA^k6_yT^#g2Xlm>Bnh-#=iBO8Vr#`u0GqBCc1snh|6_ zuw)z5=zITF7|g0z$I~gN;8Zyuc3PT?R$Cp>azi@2dY8e@#ap7fY!28fMexvaTbwnh z27)$L3b7G@J!86p^VQwlrO1iC$JJoP_N8L5wl4w`vt=DZT(s45KBDtJqeyP zZQw!GJ~;eBHC%9z7k_)$qe;?w=sU8Ie&#{wr$br17IVI!z!ZnB83b?s>ktl7-o0rC zu?K19&$!};j(;NI;lL1aL5&N#KAsO%w*E|=?pB9r=J(ew8Wo`~cY4 zFAA$&13*VG<%*vfE-su1!E%FGOO*+}P70RJ`SRQ_tQkn13nAykcr#+ctjU4+RsPJ? z#{zF|rF``J3?83IOlGrAX7ERwbu`$c4<89#D%SAf@jiI}kv;r(@AZ)na-MkZLKu91 zvYp*+u*I86v!s5@-(#)tS=Oa)QXVjw8E8oxd&;+q?YFA=&B z=1jOQXgwc~v9Fg?XX`$$*6fH`3pcL5 zK0^H73|46!faRwLNO${LGu`m3wmQs=7%GH~bGBLIV2yuY>7na_P;A$ag%|(n@F|g& zScg;KLBLtzp`j5bY>$`D`Qy6-@cpeCP#t?njC4V)7`GNKHAN9uoZdUB1E6%xUs3s) z4O*uThoRR@Sss06PkT>?i)R-zbsYioEK@+~1_hLO|Fqj}tJ`#&NlXvqGu()Rz zNXtrRN8-IP?XNZ@DNW&9soO4guQv3n*&-C*Hpf0~_R`sYylxF1QaS>IFGg|yWJ{d1 zVzHEC-)Lin?>6MXy^Ia~^z=g98T=j|-5V}CP&O($US6uzTZ8VJd07IpDlSu|M76r#@k>=Lkuh(bwu>>Fu_R_VrX0C$m-8I;gP0N;$;y7{E!DO z`MU*vt+^!`yH^%h{oW(>TgK0E#$&feLVxGyV&ZJd8!8#W?#&W*W{fBPI3Eo93)XSX zJQo!A#KR1Ib5SRj`rpe)mzz__Dpak}vhoe>KcLUVi-36H~Tl+ zxA{3^-SLr7pRi1vookGRbYC>T8_N7$T=7Q(b!wA_b0dSeh zsDa6;h3so@e{6Z(7i4!B^Y3$AuyTVc9Q)dvnYK{guuUK8>$dR91HKqrI~i^^1&QT) z#IOwvhuQn>S=1OCgz2f!PblK*ClC$4=EMHF5=r()>dC#{23xj{qy8{A%$(j6>U64` zrxJ&AZ=fPf`kc%1!hCTgWun=YP=2e@7*!4l^t-fQNZ6o79swsQ>(cK`1U|i929CYP z@U!%m@jH?Y5!W=>&pb1neP|UVb*$whzuV!|EnVTz#ZQumJMMUM*cdpaIe@syVfYay zN_jZLshjeKAp_GIIp#ae6rJ4zq0Z<$m(y@Xh3E`;HRF(&P+*B&H)Mfwo*z3j!UBDN zmxAG{3_kQDBldVFD}JNTMt60wuVC;nkwsR8&FUOv)(h4wltJIHdVWTnd; zFzV?n>3#N=EWHK%6Jg(gIl`#&P&l}F19|!~_=&HDc=h>Psct`?_#0;mf3iZSK(=>e z7%rvEqeDY6uPigi!LqvW{qiUw?uD|=h83gnYPl|6y6=QHcgDf#Sx)?}8*!G>QsHFm z6Je0S1PnTmCf(=9oG8M_#_u6@=NmD)Coz8ZcBPwXHD9e2hReo|BYhycdCCvOx-EwA zD7cKx@OH%|`~4v=--AyQOmWbnKu9q56b7^ez@cjeEbGd8o~FDCho|2KosDk%Bkj6* z2TQ>Cf;Mw#4#2%V`@tpIBEEE$CrT34p(#W~*n-YBwKOX`uIb^|H_;gPV*#9qG~{W& zO>nPnAgm5PCEQv~{nRt!pz3Ec=f)10M16KfpSOtbH`@ET~xi z5F<&`a5NtT6K{-VbEtdteS;GmO6}XEpJa&aOh#7RE)QYB3{@)=;?fUj*y^FaW>Ybbwt$b9p3rIJbSZ z1=SUn!Y(Uwd~hom&R*NVYG&DDqfHvrRtr2n%K{spWJ+iL%!dYeac7?NKAYiVgLkbv z*=e0B;jXF*2J3v1YB-JK=}lyA0r4;Hiajix(Im$kMvii0trIM9)}#13k#2z@uTD)8^)92-54f05owP{GYg^k=>?{l zTZlg8ui;d2I=6UYO&Qg1tYOMZ_GXMP&TChP%e7Ov4CUGHZq|UYvfG4{#>AXVL(seW zn4j1jierAK!Lz>Vydxk0ZJqPMsNR^(n`(s>YFVIfzkw^0C!y!{H*h6$gt(yL0J54` zI9L$^WuHB8R)HD}d8@+@jV12cRtM^wnxqRYvH>^Hx_8_k9)t# zfw?4xfBayDJr@n6?9T>a>qcFCvO`5W^Q+(5qn5loys|ngu3u_IEO#H+;Mku91(@Tx zXLI4`)%9F9%Mm{iSG?w-jM%uo6a)Ky0)@6aET4Rd%a+Rl*D&VfuEd}nN^r)d7rSu5 z3P)S%LVLy*-uc@bhi?sr*5i}JF|>R5tO%hjtv!n+kA2*d6i93?;#RuO7;~i?~fQm^NpHO0gEpietoO3|v zkD8$Mz?MC$UC&M8!coM%$cJ?B z4EABNTg>pHR|#D6PUlL~1w`xbY;l|(OQL*#ev}e*zgF^{J0omdw({^NjU%m zqbt~DO9woYIRmQKEaKf1hUzk)o3Z-k_T3AkltD*VXZ$IEuu;jt6dU^J&%-1*cFPnG^=cE77AALNfU<2B(! z)8ys{lp8&=%?Os}SF#%+6Y<~$>QkBP#Rqm0_oFxf9^dd3GPyBa*P6{DBQyAEuT{7? z`8J%|<;H`wO;H$83?E{&+1C33IJJ8p>72j3*^|0a)Zm7vilDm9$;RzDb%Bi6!xeji z(WxntIuo_| z0|%${fQ-pM#OpgL<3PK;@^b?gt0lpct#+{HaG$2Z{+@Vi&I0HuX0qwTrYrGDf!c^U z+?Fz}4+o^f{6WiwiII=t=5HhEoDcZnfjwJ$fLv~Ym{h{>p7UThR1?82_?82S#mBmO#Pg<*{d6a55cNUUsl zMvP@*;G7v5jjqSa;K(Vu6?(X#)__&eHM@XK>@>seRmCv&T`)KA<&N>y-GIsWWLixE zChZw0o%51n#Mz6+LQZ9yw70j^ z#AYdp2lef>{6}{e+;yu6t_1cJZEeeNrr9UBEPJ1M_wd6BqkBR^wGn^e=Y*s6l;Dx4 z92-e_e~ar{;B#yX*CyUq4fWJ_Z?+f5M-ZnjA`))*@L;2z$cH>7i8wh0JoLN`-dvvx zs{K|;dVj0OSEssTPelQYBHd7TPZ#N&KU_u39LhP}_?g4H4D~`>UQw;fH z2@a1B2*HZPy6hybvp;dq4o^kN+7g)fQjKd`Q)fs2Y{)UzW_Mpu_uS=T*tvThpHEt} zzxGcyVbdqci4I$IJ!t?5k5zb;vIWlmDuIvjeOdplrno597k*Da&kq=QqyFtoSUHW0 zPvtG}SNTdf=Iq1H_)>>OXt9)acF;?}{DzP0o~<71GR+Pz=?{Sk_LaP_loZs?5=VaH@{8ZC!;q~ zzvbC{Tb%9igZMF%*|M@psI@{JJa6Rlq+)YarXH4R^me7p z{8T;E&Irb@j#H#QoH*(g)pzxQsG5^PrK&ON<;H-uvdG_0^~O_A%fPaAkJx@%z}%%} zPxp^>-C@_k0`U$pD@4UX#4w3u zovvP(T4xEW)fpU1~7K5qt^^e=~{*UZG^Cx8oC4j9eLV6$$Tp+|cWtf~#>4~gB~ z<5wpu-O-Ibc`hLPI{=mq*}3?O&mWO3{VBlN5{hcdlL*3-ZN*Ds2KPYtDf zN~j~MT}Xw>Lw1rbi|sMDC?D?CUSL(ni*Rz%D|j$JgMaB_jeSqNXEobau#KtIX*EL) z{zuYzhhyD;aa=>RlZL2-N)*}q{(jD}_ueyvhA0i~WJI!QQ7SD>Z56&BPrIa{p((WY z-pTKD|NiTGx~?AMzR!KW=e*DB1-GNPOu8|8wWz_!=-ooUh2|LNFM#pWRxaNVg=-$A z!LABT?m58%ug51r#b*_Ev8yTitENj?XV1r2<2bESI49Forz$ytI~}INUY~GicOzd0 z-3lc?*5<2;r4#*0U0UbmDd&9bpa6$oZs*hI(5-q|Jp5R4MpU7j^u@R0;Z>RgJMa#$ z!*LZHo07*5O!UP6+_zI!vsqHzB9B*QS2A_GXZ*abI}YD64D9q@isP!>(Zb0XdTBVZ z*Qx$k{xJ|#o^IuR&jU8tg@Js%uK1!K-OM_!fSFIDx#J^ZM%9*r$E8x?&<*-b$$iHT z@I$<^!wJ)t4}oVFmWtyqn4p&TC@4{w#ELS=Rod(hWtypcsf9Tfm-)gz!@X8}`kT^T zdpdln+0QQ8uEECjx523_Y8n{jg`WR zJ=(bP&|qn84~p(cer=gm?|e^2*(+Zm%`C|Q`w0%#1P1s2V?H!aXd-$jpteLZe^h)e!vb4%jk-;skSy1xMIVZ z-)xA<#=2jw0&Z#O3jxtNY?h1{mU@}O`LJL(F*=wnJ3yt$iUXkeCcx`v$fexs;l%V~y)1HDuJ0?K>$+jNzYj ziD91M3Xxmug)x**sJEE{I?f`Wy~YtoTjs+D-#y}wew2IsyasZ9M>DNqp7^|<3?%gZ zE(TG4zV>V{>CIGPlq=R8c8AKNLu!&teDHii5<~`NGbJa)0&?{HtL<%+lQ|Qc4st)! zgr2MoSWkUeTlA7^efGqDt7Yi6qCkXJ+CvS|0ILVfS(2X@YHcuuIuIj-Zx%;9~i6NeAGlca0#_Wr+1?s%;keg3;vL2cH$4#Y$40ErjxVgU>`^b-_K78 zHuw;&9vAx?N%_h|T(x`sQ_t$qHtEclw}BT=E+{^-pr2r+DA zHF`zpsQHBUGPHZ8-fVR7Yv${}l09|v!I9%s;FU`xPoo}tfG`sDZTATG51ZqvI&KRaQSB1&OOSr#HM-k zU}0w#mjoN*$B)Bda%EQ*MZe#g(H77uyMxy)F~LQJQ$X#418cs6$PHFP#OXZVF^&3` z;p?G1?UJPCKY473+a|q@ieBc1H^vT;`ebiW%`~qX2`^q4FpZ^w_`W6pa&5NrSBlnn z^i~M`te+@G6UTVHRzghQ(DjWQ9pKcTRyy){YmH^N-h$YPF8p$j@Qh$#%QH}@b-J9aP+b^8hI*8 z>v_s?YrN6Z8f<5t6Hkx_t@yn^&Ebc#ho!WWwVENV=Mp(rOdvL?T(F!tou2V$gl~X( zmkZh1-L!LTmIZ|zOJ3_B;3WCppom@BIbw!b>{ADsmR-DvW~66R?Z^S=BAO7ND!8{7 zD37yd3*_iVH8lfNrf=ZB$>fxIQw-~_luKUiD#vU0zJY?o815|!!Aozu!RR%Wb%*J` zPtmsz$ga(0?~Z$+ZMzZZMg;R-lMQKaWdJAm5h3p37}(Wn$vn?)<{g8gaN)6h7^SGj zpWU;>>|NReMMj$SHb_vy5L2HFYNNZ?~;P=c6dzG21n!J{I-HAZk%BP zcPe|a+vNCm^Y)PT>Ro)|Ft>Lx4Ap58bMKkqhwN0?mgUWs+?3$py~SW>lg$%$2zW#P zDf>8SJo`M-3yUr*!QsB!_&RU8Wqvgte($(fdyaf|*XNl_d-e2(w%F}&IBXv~k9T`! zhMo%3!JWkmAE!h>$k~mICc%8_cTen0x|8c+W!6S9 zv%4KGzWauqzP*7jSW3ACdY!lK@vr+#^B)bSA-#328RCK8Lfv8Jc5iN*V1hx!(dt+1 zA-FXeLyKk{W3`!F{dgE2E8YO%)0Ox>T^qWsUJJdd4cVv*fhgnN6`ZFP^6J;&_^3@C zZm%3IOmlLwK3t}Q_r1pB!>@k$&e#tUoHh8dz9#s~#9i8-Ur07W-^3VrBQJ7R?T95} zF08TGBOY93i;JGFgFPKnn9p24T<0zW-5onbf%;(^8+kYqs>^Ofl6$Da7akams98-M zg-cO0LE#bkQEC|uJx%vqH>UG5G{^Q@k_LA}(uKYETjAPkUC_Aqf}c3zjT-J9?BBdS zWS;{Ld!_&(7vov!5^sFE${1>OvUu;;W~gmv2Iq~<1sBTxwV8WEdH6Q=bqu0g-drfo zw&Z7y8e^$<3OIjzB+Ps^5j!X!p49UI*Ulzxp4xY&Zn0DFk5$IaUt6U8`5F4X{5U!e zb_h2`?OF>gm~I9G&sedRFXm|R#S;|zY~$B<*yF+D3!&e06;V~k4hMQ=!wA`Irg6vu zEBp#T#X6if@AkpXS-;qql%DL|I)--*dV%bW{XDhA2{(Qk4-X+$OeQDDlX^o~HY=71 z;V!r}Y%+N0uje5ywzzN|G3r%OQh3x6qpEY@tj9GrYd|rcw|flv6SDYndmEg6?-~2Y zrR)r)K4iU~iVpqK+I7!c{rh6^1=&C9tkC0=SVS&(K z3Vqaf@R`ZPho>3cfjtePzAimGJ5L3_G-vjR`2Vls={cGlf}7=tyA`wrawN@?@U8Or zEN`vAA041MYOjIN$2~?IFJWk38lJOTe*W66X%u!G^W;eed>w=4JP=9XaDNeH?_I|Sq^eSTP#|%Jz zYnGHhZ0nEsaA+nZPbrcZ_SuHVPyT^7V=Q5_mkTa^`Hnppx}k2wL|YUq`#@Aq0Xri4 z;e6r`$j62AUndQ)g1FhM-yaqd={Cdhtr=5S-OO*7lAk7?Qfojubp9q! znVuz9>lMH|*)9CdMrZ1^-m!iCzf1PJIAH83Ef_gw1RqVWu^Xv|Qs!{)EvEQ2+zr&) zFY}H+l=)n{7>30k6Z>5RG&s5fE_;Nql}iMysVRcyf^2TqDPU_tD^n>O&uov;TzY;# z2xutd%g)*3q^fan;_2PmN46GN`qxBS&qb>9A#cLrNymIXX}%41shkV0OBV=gGb6xt z)CTFT>-kw8_~#ONMXh`CGldKlRod9eCm~GZjW5dVQiAnka(G-9>Ya2o;nq)WK}*dE zGe1s(Q3oA()GPYDSda{XdXI&<^9(RJc7e2>?@YGGQ?2X3qHDQ$M6|gJhAu)KH_L@O1u+qqtNuEh{{Yv?cSk{ zhIFrWkyy|jUd~X|YXl!j{OYwg-C=C*dEv}gVh2r+hNZzGpONf{dWtzP@%nBtb&-JM zPZmK&S|p2(2*%H@GSGi%7yjgjIZpML1?zJNDPOe#$(y z>?yf#^ydK_n91kJnBaoIrQmI`Tu9l_25}d4q;vJ1Zr-?ZB+a1i6^P&MY;bj#KJYj` zj!h(%U3IyMbgn*3F9i4d1;F~?5TTRi`5P~JN*QH8<(yDu`(oJFVa**Ln~)o58St@f z!rX~^c>h?Ybl$>R+)-!nXZFt_C7Y;>j-m>UcKDJ!4t*nUiq}@!;EiDbUCQj( z_Dpk}u*?G@Hg4s;{j9Ood=6O5Q4;TDxZqP`Vn@g3vG&L03)9Pohx(K^P@c%a2H4uw)L~rAr((Ni_WIvYtm#hSqA%BKUd1R?^p3f{o5J zgPL)Mt@0|umDAeb@(kMPXCaQ7_Ly}I&0-B-ys$892>E;?_*O4_Galf@IlM?-S8 zyfuMP{Wkvmb}%Z`)7R;!#+4WNu?K41R)9j^S7MwR;_yLgkeg-6 z)C>Ia^F|LyNZ-okG<|XNplML^9~1kvnvz>&G7N~G&mtTpxcGc3xaLmgM_1DKsGkRI zgNlUt1=e^#@e#|@Jj@e^6J!6?K+xZsCYF#dcoF65tD~l|?^QIPf9L}BwHbUI^~UE% zM8YJsI;*$jXi(u(pe5oEdqVqV{juv|_ysTC{FPX>y$Ync#{e-9w=Dm`94E!|*w?-| zX)UoY&K?&s$B#$JX?h>+dd%A|dEnInP9QtwhA6k%4bR<-g6?h_Ot}l?_r^|<_T-zQ zJkk1BKD>L`Q*_yEj=fWIp}~pxa&3XQXx9%md5Hdth??-_M>1oSZ4 z&4)g6#~l+KVP~0-=yci`&*acu!+n7jb+f^dN=fkZO#%Pg?1dJ83SfM7x#Vw5IfgCy zNIWhhaBn1k%AS`jGipQKA~TxF1onVCjX7-oGxA&ymMem`k)s%=-^F960w^o1;2+O8;XME6%=r0NiBhy1 zD!7dY=bLKWhFp!!ZuZdhO_{m0nBtO0&QS81W-MytUXRIyDQC`#n$)ueloZ1LxJ0&= zvQOc0`5@Vq#jgx@M~TxLmaSmUdJb_w&quvse+T&m@?CMs25ophu(j6WjRi5bjNs^` zQufo6dLG#@n9{L;moK#^Zu2~NptwZXvz0P*#$`-zUl!lFuZVbekEGoAYJK7t?QCIc z4dG1XfIlYQ8Up*xa=9w_VYdhR;QGN#upZ)JEg$8G(?TZWubYl2zcvhHjp(L{7+K{! z3Ld943HEgc2p#nQsyWKP5!-Oi%C!*FuUwQbwa4Q}9<#9@H}WRRtBhDR5VE%f)y+4z z#zP%y(EMl(Grvu_+)r+>TP={!rhew;W(Sa8;3hoSV*=~WMzP_8viRchLD;*`8u7dpd{rnABsC1ad;eUfy>Qe)@SGYD&hwV5<-i-wo@V%~Y%^}L(&%QYcjD}>eDQ4FALS+^#4Nu^b zN%Z`_Wg)EJoFe#+X$R}*3DOzMICc8jhJRsiP8Nw*e|h2N6^h_=cs?u74!{X#4dJY? zihmhFe3i?@h8<=jh_vrMUG53n)OWJAOPz3+#zHW&AlAe=Q(W#)(9uc0JDr4@oThbXz4&B!b^Hqb{bbDBO&k8->8o{#F0^39HeIq0Gs>E z!q=nw`6L$`Vz7^bKprmkkfEKNhL>jeK6nXie!qz?Ft^2^xDp6^ z-c)yhb}rRD2SJxfy1aujDso4LK=->1sa{61s={~X_o)qPMVJ{D$vy(E76Yl;%> zD0qL~kv%5X=;Y;TQ1>Z^U%lalYs<=E`Qm0t%^G>^IJQpeejVdP@8#+N(2cznHxV1W z*=+<2w688<_=QHqPtobp{yZUn z1HPa52I|xd;K?B$v^)5QnTJ)>9dShL)m;`2TIDg_MlU?@cD$5PuzHOVx+_kQG78pR z91EW^jG4007QSmx1bUt(@579dd?&HB3lA-Z^uuawEb&Y4@5qBLP{EhRxe{CB32W^5 zAvq)Gf_jl-VbXn7zFmg+W<}cdEf)3r4U?IBQ~ho;9cho zkeeCCf|QBN7n2VgUlC)l#F_f2cDD1TG3#UJfUDJef?cl-+p$CL+sqcWbaXjiaf@z# ztNVk=>7Y9OcMOXhN5F_bCG1%@KXm`;EUoQ&XN=92;ZR>D@|&aF(05c0IEC*QZ$1OeqPcX$ z*=W{zJ{V_h_`+ICyYT9{miVCk>w3bXO$*qYQ4Z)e zZVtGq&Eb7}TcYQxWpHV6x^N}G9eke>7xdsuKJ3bV%2(TfU*QL_P0I_nf9wyztCLyu zKp)g6Pg#t079VD9j>#+Z;Qe58p)Ov)W6T4lYFDy}QO?+9?0l$hwc#$;D5s>h2!4xg z!YaBc&`-#K0KWs=aK|)ErLS{9dyU{tz53U^*O|?^CwyTq%1~V%Nu25?aluD&RgX6W zs}+o$rYwzxlausb)ipE$k9{hDhjT5UEoOn!=gS;sJMV$u8Lz?Bi<{Edn|N^h0%Vq#@x6i5@ZGdL z7;r5{a*Vz&v);?$`I|Frre!hqSnvS0U(Dn!=NO_-6MOl71-tgy7b|f9WTr&%0SQ(( zAyf(0sT~li{q#}i>zKpXFGm59O3DKPc!M4n4`Pw`Q)@UDFX`)z80-G#+a^=LD< z_-2dllZ!!p`i;8Igdl8GR|L(+dR(Q8DfVqvga^spSVj)z;g{;c?ae#*qW(0GJ?Rd2 zl8%d)e>&kQ-MLVx9m?nw38Sv3LjTHKo;odv?gc7f>z@|Mg-m%oe!7I6P<_fhUU_5o zNUDw3-im3yf%KlCJ=ZBOR({YLL${m2%TXmf#>){~x&=UNwUM~(v;;-EgL7?I#)|ez zuxe-u>{vLNe>hFtSJiyDbbhrE)Mky10XL(LY2ECDx)N3Z2 zQtFMWMRs5`FM~VMGl+r25wuJ9S{*%Ufj^a_;F|qGru=OU9(mdT3R!vFcDET8H?4$V z!;b<6`C(Y{3pP1v3jel;oVGW*z|YPdLh6a}SYXi$LI*zK?dk65T8HrK)OB&Jwh<~t zA>6;+k2&ABz!}z2;B~%&-`^LF<4&!I&)!4C1T4c|{5k0MZe`C`M4{J>Z>(dwz~6fN zW9GC0P!}?gIeeF3@=GOYZO_s7$EXjE(oDPQCo}w!W)A_kkd3|JfWhBp!8hF!-k^#& zHa->3A1{=s>zCsYwKs5xW_GES+x-C2CB0M@e=GeDHn#i zRq(-sBXHrs&us1$Iib?Z1;?+`0GSu6yrWuzIluIw!n8lrq?~8gL-K1-ZTF}{?6Phe z?6$8GGtQdefd}&-Zh{9p`&hu1WMU1uXY&AZNKIb)fPGwL%qp7fvFwMe^j@iVV+0-@ zV+0p3f2sBJ0z5vA{#;njWP)5U$~G9*I4|LbvewxD{WMU%GfyzP6Apn(*GRd+jv+31 z?JRj}WP9)%8vv~zU1v$BL)q0){&>o90BBU@@MW#USwEu#uRd7_gQK;r+nZI4ERl*9}eema5dpLH*pO2t@{pjoVaN~=Y(DcF#?mUZ- z=3btkn}pLZuZ6se!??yhav~qi1`7*qR(vK9RrTMn`6CN?AL?6f&+Y@&3x^5c`ng-L zemDk?w(8=A%P}~)BmlNF=<<>>19Uvb04LN7?H7$PK{Zrb+ba^>unXNO%$vSnEbb0C z)gvG55~A3kieQ{-{!ZGr|DI)uf6M-`ez$bl``=cm=1lIJGrejGqlqti#}-BnOJt9h z*xU-o@OW8|0{x- zYlmReG(E70%H=WU=BRmE2gW}$6J)pB;PFl`XxOlqbud>{^iGDz1$O+4n<;)PNrsAh ztwNisKHk?)m)7=UX@0nQ`wO<_-EJW=QyD+9Yvd((!i$|8(0$q{n4NJ;G%9z&;_eK( zpd0JsVSzEf9N_p(%6qR4#QCGh`y8qzPR$_xXLUMQcU{T0J6Yn6^Q&O_&oF-LsXZng zzr&zYhK;%mXi0pVO6@A%dxQhAK}Nx;CsAU2un`98Yr%k3(QI?QCvoW~L3;fLeuG%| z%_FBmmpUs+s|mv&YRjS5-m`4}<6?ZlAHWy?EIvTX88hr3u-E2!>`9(KzAqX;`_{>P zH@TK78iz{f>PKoUFpq8`{`Kv;{;{~&inzG8THI+rWfYCVKt^7P#l1Agxyrz++1^x6uRp=R0`z6i@tlC<5Y# zUl5mebHgjbd@xLiVB?$xR7p*NgjuWjT^hwV6y?EM znCgdnH0@xQekO0DJCSL`=NaR2*vfG*-37EwlFnpGQp550$`atWz4)CAW>`KeOWL>d z93Q;0q?P?+&P-fKya?I9e#1bX}+4$l^2jFkX%Z|TpH zc9`R-A7OAkZwr^*;)td1GNi2F_Cu8S8@Uo<$jkPVvL*93zGJcPtoSLfXzcrPFw7fG z`|GI!x>1Hlv2{1U=U|WPhnm6>FK4k~ryu?|XBl+2FXz!TqkE#i9A4iqlync-h>Ig% zkf*}{)OLHKOu|E!)4r)LXR!p^U;kvj4y#!G2_N#$YC_MwA^bp;5ut&`!kNw^f>rBS zIJikq${aAVr@QRlv%#p}0N%005lx#jK&M5Q-CrWX7;<#p98Ftk^ED3c`c{dT6p78HM0|iT z?(84`t(4~W4U1OtwTsAk(Q$`4hM6+$R(tHH*$t-Vl=1(9{BivZEjZ!&s@AB3{yQh{ z(fh4TSnq;&mjr+$d;>uTO zSmDA?li;NK9bt8zA^tp>2&Y~h<%-XP$+@-#9)#`_`yIB&hxeM;Ki`M@O